From 5d97a8f9ae63f199b6c01fd71871c26fb52a5759 Mon Sep 17 00:00:00 2001 From: Xinjie Yao Date: Wed, 3 Dec 2025 13:33:48 -0800 Subject: [PATCH 01/26] Add CPU option to run policy closedloop (#254) ## Summary Closedloop GN1.5 observed low SR in multi-episode rollout, esp in parallel-env where more contacts are being introduced / more episodes are being observed. ## Detailed description ### Static manip - Issue: At the beginning of episode, hands have close-open motions in recorded trajectories. Given microwave joint is not stiff enough, small deviations during first few inferences cause the door closed by mistake. And this closed door is hard to pull with static GR1, causing it to fail the task. [Screencast from 12-02-2025 03:16:36 PM.webm](https://github.com/user-attachments/assets/da06de60-8f01-47e7-ae26-a48e08cb523f) - Fix: a. Shorten task_episode_length_s to introduce more frequent resets once the door is closed. Tradeoff is introducing more episodes. b. Also tried with shorter `action_horizon` but ended up getting worse SR. My hypothesis is that it's hard for VLA to tell from visuals/states whether the door is closed to 0.2 (success) vs 0.21 (fail). > 16 -- Metrics: {'success_rate': 0.605, 'door_moved_rate': 0.955, 'num_episodes': 200} > 8 -- Metrics: {'success_rate': 0.225, 'door_moved_rate': 0.615, 'num_episodes': 200} > 1 -- Metrics: {'success_rate': 0.0, 'door_moved_rate': 0.985, 'num_episodes': 200} c. Switching to CPU PhyX does not solve above issues. So keep it on GPU for faster parallelization (in theory). ### Loco manip - Issue: After each reset, the left arm tends to have fast motions and the box is tilted. Also observed significant penetration among fingers. See 00:15 VS 0:30 for 5 parallel env closedloop in below video. [Screencast from 11-25-2025 03:42:36 PM.webm](https://github.com/user-attachments/assets/c4934817-65fa-412f-a88c-af143d25d7c2) - Fix: switch to CPU phyX, keep the policy on GPU Arms open first and G1 starts moving, box is placed with expected pose. [Screencast from 12-02-2025 10:15:59 PM.webm](https://github.com/user-attachments/assets/4a02e6cd-7baf-441b-8c0f-7146051e5c9a) ### Minor fixes Update doc on cmds & metrics. --- .../locomanipulation/step_4_evaluation.rst | 16 ++++++++++++---- .../static_manipulation/step_5_evaluation.rst | 4 ++-- ...eo_g1_locomanip_pick_and_place_environment.py | 2 +- .../gr1_open_microwave_environment.py | 2 +- isaaclab_arena/examples/policy_runner_cli.py | 8 +++++++- .../g1_locomanip_gr00t_closedloop_config.yaml | 2 ++ isaaclab_arena_gr00t/gr00t_closedloop_policy.py | 2 +- .../gr1_manip_gr00t_closedloop_config.yaml | 3 +++ 8 files changed, 29 insertions(+), 10 deletions(-) diff --git a/docs/pages/example_workflows/locomanipulation/step_4_evaluation.rst b/docs/pages/example_workflows/locomanipulation/step_4_evaluation.rst index 87bca83c..40a8c205 100644 --- a/docs/pages/example_workflows/locomanipulation/step_4_evaluation.rst +++ b/docs/pages/example_workflows/locomanipulation/step_4_evaluation.rst @@ -111,25 +111,28 @@ Test the policy in 5 parallel environments with visualization via the GUI run: --num_steps 1200 \ --num_envs 5 \ --enable_cameras \ + --device cpu \ + --policy_device cuda \ galileo_g1_locomanip_pick_and_place \ --object brown_box \ --embodiment g1_wbc_joint And during the evaluation, you should see the following output on the console at the end of the evaluation -indicating which environments are terminated (task-specific conditions like the brown box is placed into the blue bin), +indicating which environments are terminated (task-specific conditions like the brown box is placed into the blue bin, +or the episode length is exceeded by 30 seconds), or truncated (if timeouts are enabled, like the maximum episode length is exceeded). .. code-block:: text - Resetting policy for terminated env_ids: tensor([4], device='cuda:0') and truncated env_ids: tensor([], device='cuda:0', dtype=torch.int64) + Resetting policy for terminated env_ids: tensor([3], device='cuda:0') and truncated env_ids: tensor([], device='cuda:0', dtype=torch.int64) At the end of the evaluation, you should see the following output on the console indicating the metrics. -You can see that the success rate is no longer 1.0 as more trials are being evaluated and randomizations are being introduced, +You can see that the success rate might not be 1.0 as more trials are being evaluated and randomizations are being introduced, and the number of episodes is more than the single environment evaluation because of the parallelization. .. code-block:: text - Metrics: {'success_rate': 0.2, 'num_episodes': 5} + Metrics: {'success_rate': 1.0, 'num_episodes': 4} .. note:: @@ -139,3 +142,8 @@ and the number of episodes is more than the single environment evaluation becaus which are realized by using the PINK IK controller, and the lower body is controlled via a WBC policy. GR00T N1.5 policy is trained on upper body joint positions and lower body WBC policy inputs, so we use ``g1_wbc_joint`` for closed-loop policy inference. + +.. note:: + + The policy was trained on datasets generated using CPU-based physics, therefore the evaluation uses ``--device cpu`` to ensure physics reproducibility. + If you have GPU-generated datasets, you can switch to using GPU-based physics for evaluation by providing the ``--device cuda`` flag. diff --git a/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst b/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst index a4b7b354..a01f77b6 100644 --- a/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst +++ b/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst @@ -133,12 +133,12 @@ or truncated (if timeouts are enabled, like the maximum episode length is exceed Resetting policy for terminated env_ids: tensor([7], device='cuda:0') and truncated env_ids: tensor([], device='cuda:0', dtype=torch.int64) At the end of the evaluation, you should see the following output on the console indicating the metrics. -You can see that the success rate is no longer 1.0 as more trials are being evaluated, and the number of episodes is more +You can see that the success rate and door moved rate might not be 1.0 as more trials are being evaluated, and the number of episodes is more than the single environment evaluation because of the parallel evaluation. .. code-block:: text - Metrics: {'success_rate': 0.5833333333333334, 'door_moved_rate': 1.0, 'num_episodes': 120} + Metrics: {'success_rate': 0.605, 'door_moved_rate': 0.955, 'num_episodes': 200} .. note:: diff --git a/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py b/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py index e2e6a4ae..be5ab7fa 100644 --- a/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py +++ b/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py @@ -69,7 +69,7 @@ def get_env(self, args_cli: argparse.Namespace): name=self.name, embodiment=embodiment, scene=scene, - task=G1LocomanipPickAndPlaceTask(pick_up_object, blue_sorting_bin, background, episode_length_s=20.0), + task=G1LocomanipPickAndPlaceTask(pick_up_object, blue_sorting_bin, background, episode_length_s=30.0), teleop_device=teleop_device, ) return isaaclab_arena_environment diff --git a/isaaclab_arena/examples/example_environments/gr1_open_microwave_environment.py b/isaaclab_arena/examples/example_environments/gr1_open_microwave_environment.py index ecac5c08..d2161181 100644 --- a/isaaclab_arena/examples/example_environments/gr1_open_microwave_environment.py +++ b/isaaclab_arena/examples/example_environments/gr1_open_microwave_environment.py @@ -62,7 +62,7 @@ def get_env(self, args_cli: argparse.Namespace): # -> IsaacLabArenaEnvironment: name=self.name, embodiment=embodiment, scene=scene, - task=OpenDoorTask(microwave, openness_threshold=0.8, reset_openness=0.2, episode_length_s=5.0), + task=OpenDoorTask(microwave, openness_threshold=0.8, reset_openness=0.2, episode_length_s=2.0), teleop_device=teleop_device, ) diff --git a/isaaclab_arena/examples/policy_runner_cli.py b/isaaclab_arena/examples/policy_runner_cli.py index e9022d60..9103929d 100644 --- a/isaaclab_arena/examples/policy_runner_cli.py +++ b/isaaclab_arena/examples/policy_runner_cli.py @@ -75,6 +75,12 @@ def add_gr00t_closedloop_arguments(parser: argparse.ArgumentParser) -> None: type=str, help="Path to the Gr00t closedloop policy config YAML file (required with --policy_type gr00t_closedloop)", ) + gr00t_closedloop_group.add_argument( + "--policy_device", + type=str, + default="cuda", + help="Device to use for the policy-related operations (only used with --policy_type gr00t_closedloop)", + ) def setup_policy_argument_parser(args_parser: argparse.ArgumentParser | None = None) -> argparse.ArgumentParser: @@ -133,7 +139,7 @@ def create_policy(args: argparse.Namespace) -> tuple[PolicyBase, int]: elif args.policy_type == "gr00t_closedloop": from isaaclab_arena_gr00t.gr00t_closedloop_policy import Gr00tClosedloopPolicy - policy = Gr00tClosedloopPolicy(args.policy_config_yaml_path, num_envs=args.num_envs, device=args.device) + policy = Gr00tClosedloopPolicy(args.policy_config_yaml_path, num_envs=args.num_envs, device=args.policy_device) num_steps = args.num_steps else: raise ValueError(f"Unknown policy type: {args.type}") diff --git a/isaaclab_arena_gr00t/g1_locomanip_gr00t_closedloop_config.yaml b/isaaclab_arena_gr00t/g1_locomanip_gr00t_closedloop_config.yaml index 2b7581ab..c48e41df 100644 --- a/isaaclab_arena_gr00t/g1_locomanip_gr00t_closedloop_config.yaml +++ b/isaaclab_arena_gr00t/g1_locomanip_gr00t_closedloop_config.yaml @@ -7,6 +7,7 @@ # NOTE(alexmillane, 2025-10-31): The model path here aligns with the model used in the static manipulation tutorial. model_path: /models/isaaclab_arena/locomanipulation_tutorial/checkpoint-20000 language_instruction: "Pick up the brown box from the shelf, and place it into the blue bin on the table located at the right of the shelf." +# Action horizon is the number of actions predicted by the policy per inference rollout, defined in the GN1.5 policy data_config 'unitree_g1_sim_wbc'. action_horizon: 16 embodiment_tag: new_embodiment video_backend: decord @@ -16,6 +17,7 @@ policy_joints_config_path: isaaclab_arena_gr00t/config/g1/gr00t_43dof_joint_spac action_joints_config_path: isaaclab_arena_gr00t/config/g1/43dof_joint_space.yaml state_joints_config_path: isaaclab_arena_gr00t/config/g1/43dof_joint_space.yaml +# Action chunk length is the number of actions executed per inference rollout, could be less than action_horizon. action_chunk_length: 16 pov_cam_name_sim: "robot_head_cam_rgb" diff --git a/isaaclab_arena_gr00t/gr00t_closedloop_policy.py b/isaaclab_arena_gr00t/gr00t_closedloop_policy.py index 645b60f6..51e10e85 100644 --- a/isaaclab_arena_gr00t/gr00t_closedloop_policy.py +++ b/isaaclab_arena_gr00t/gr00t_closedloop_policy.py @@ -54,7 +54,7 @@ def __init__(self, policy_config_yaml_path: Path, num_envs: int = 1, device: str self.action_dim += NUM_NAVIGATE_CMD + NUM_BASE_HEIGHT_CMD + NUM_TORSO_ORIENTATION_RPY_CMD self.current_action_chunk = torch.zeros( - (num_envs, self.action_chunk_length, self.action_dim), + (num_envs, self.policy_config.action_horizon, self.action_dim), dtype=torch.float, device=device, ) diff --git a/isaaclab_arena_gr00t/gr1_manip_gr00t_closedloop_config.yaml b/isaaclab_arena_gr00t/gr1_manip_gr00t_closedloop_config.yaml index 89f5edb0..3ce39bb8 100644 --- a/isaaclab_arena_gr00t/gr1_manip_gr00t_closedloop_config.yaml +++ b/isaaclab_arena_gr00t/gr1_manip_gr00t_closedloop_config.yaml @@ -7,6 +7,7 @@ # NOTE(alexmillane, 2025-10-31): The model path here aligns with the model used in the static manipulation tutorial. model_path: /models/isaaclab_arena/static_manipulation_tutorial/checkpoint-20000 language_instruction: "Reach out to the microwave and open it." +# Action horizon is the number of actions predicted by the policy per inference rollout, defined in the GN1.5 policy data_config 'fourier_gr1_arms_only'. action_horizon: 16 embodiment_tag: gr1 video_backend: decord @@ -15,6 +16,8 @@ data_config: fourier_gr1_arms_only policy_joints_config_path: isaaclab_arena_gr00t/config/gr1/gr00t_26dof_joint_space.yaml action_joints_config_path: isaaclab_arena_gr00t/config/gr1/36dof_joint_space.yaml state_joints_config_path: isaaclab_arena_gr00t/config/gr1/54dof_joint_space.yaml + +# Action chunk length is the number of actions executed per inference rollout, could be less than action_horizon. action_chunk_length: 16 task_mode_name: gr1_tabletop_manipulation From 553d4ea9c253cc45ffbc2b28d1f2bcf1595a70cf Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Thu, 4 Dec 2025 11:18:17 +0100 Subject: [PATCH 02/26] expose the env spacing parameter (#260) ## Summary expose env spacing parameter --- isaaclab_arena/cli/isaaclab_arena_cli.py | 1 + 1 file changed, 1 insertion(+) diff --git a/isaaclab_arena/cli/isaaclab_arena_cli.py b/isaaclab_arena/cli/isaaclab_arena_cli.py index 25d31108..3cc11fbf 100644 --- a/isaaclab_arena/cli/isaaclab_arena_cli.py +++ b/isaaclab_arena/cli/isaaclab_arena_cli.py @@ -29,6 +29,7 @@ def add_isaac_lab_cli_args(parser: argparse.ArgumentParser) -> None: "--seed", type=int, default=None, help="Optional seed for the random number generator." ) isaac_lab_group.add_argument("--num_envs", type=int, default=1, help="Number of environments to simulate.") + isaac_lab_group.add_argument("--env_spacing", type=float, default=30.0, help="Spacing between environments.") # NOTE(alexmillane, 2025.07.25): Unlike base isaaclab, we enable pinocchio by default. isaac_lab_group.add_argument( "--disable_pinocchio", From 6c305d4f31776a89b6247327d1c787b0f81079d4 Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Thu, 4 Dec 2025 11:23:30 +0100 Subject: [PATCH 03/26] Add comment to show that this is manual annotation (#257) ## Summary Modify docs to show that this is manual annotation --- .../static_manipulation/step_3_data_generation.rst | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/docs/pages/example_workflows/static_manipulation/step_3_data_generation.rst b/docs/pages/example_workflows/static_manipulation/step_3_data_generation.rst index 795369f7..0e83bbf8 100644 --- a/docs/pages/example_workflows/static_manipulation/step_3_data_generation.rst +++ b/docs/pages/example_workflows/static_manipulation/step_3_data_generation.rst @@ -22,9 +22,12 @@ below. Step 1: Annotate Demonstrations ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ -This step describes how to annotate the demonstrations recorded in the preceding step -such that they can be used by Isaac Lab Mimic. -The process of annotation involves segmenting demonstrations into subtasks (reach, grasp, pull): +This step describes how to manually annotate the demonstrations recorded in the preceding step +such that they can be used by Isaac Lab Mimic. For automatic annotation the user needs to define +subtasks in their task definition, we do not show how to do this in this tutorial. +The process of annotation involves segmenting demonstrations into two subtasks (reach, open door): +For more details on mimic annotation, please refer to the +`Isaac Lab Mimic documentation `_. To skip this step, you can download the pre-annotated dataset from Hugging Face as described below. From 778177dfc1f3c498f98099c723ec748a2d202815 Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Thu, 4 Dec 2025 14:46:09 +0100 Subject: [PATCH 04/26] Add/ground plane anbd light (#253) ## Summary Add ground plane and light objects --- isaaclab_arena/assets/asset.py | 1 + isaaclab_arena/assets/object.py | 16 ++++- isaaclab_arena/assets/object_base.py | 7 +++ isaaclab_arena/assets/object_library.py | 50 ++++++++++++++- isaaclab_arena/assets/object_reference.py | 2 + isaaclab_arena/tests/test_asset_registry.py | 67 +++++++++++++++++++++ isaaclab_arena/utils/usd_helpers.py | 20 +++++- 7 files changed, 160 insertions(+), 3 deletions(-) diff --git a/isaaclab_arena/assets/asset.py b/isaaclab_arena/assets/asset.py index 2e26f0a1..c2cee770 100644 --- a/isaaclab_arena/assets/asset.py +++ b/isaaclab_arena/assets/asset.py @@ -15,6 +15,7 @@ def __init__(self, name: str, tags: list[str] | None = None, **kwargs): # multiple inheritance of inheriting classes. super().__init__(**kwargs) # self.name = name + assert name is not None, "Name is required for all assets" self._name = name self.tags = tags diff --git a/isaaclab_arena/assets/object.py b/isaaclab_arena/assets/object.py index d08d9cb6..30322177 100644 --- a/isaaclab_arena/assets/object.py +++ b/isaaclab_arena/assets/object.py @@ -9,6 +9,7 @@ from isaaclab_arena.assets.object_base import ObjectBase, ObjectType from isaaclab_arena.assets.object_utils import detect_object_type from isaaclab_arena.utils.pose import Pose +from isaaclab_arena.utils.usd_helpers import has_light, open_stage class Object(ObjectBase): @@ -26,7 +27,8 @@ def __init__( initial_pose: Pose | None = None, **kwargs, ): - assert name is not None and usd_path is not None + if object_type is not ObjectType.SPAWNER: + assert usd_path is not None # Detect object type if not provided if object_type is None: object_type = detect_object_type(usd_path=usd_path) @@ -75,6 +77,9 @@ def _generate_articulation_cfg(self) -> ArticulationCfg: def _generate_base_cfg(self) -> AssetBaseCfg: assert self.object_type == ObjectType.BASE + with open_stage(self.usd_path) as stage: + if has_light(stage): + print("WARNING: Base object has lights, this may cause issues when using with multiple environments.") object_cfg = AssetBaseCfg( prim_path="{ENV_REGEX_NS}/" + self.name, spawn=UsdFileCfg(usd_path=self.usd_path, scale=self.scale), @@ -82,6 +87,15 @@ def _generate_base_cfg(self) -> AssetBaseCfg: object_cfg = self._add_initial_pose_to_cfg(object_cfg) return object_cfg + def _generate_spawner_cfg(self) -> AssetBaseCfg: + assert self.object_type == ObjectType.SPAWNER + object_cfg = AssetBaseCfg( + prim_path=self.prim_path, + spawn=self.spawner_cfg, + ) + object_cfg = self._add_initial_pose_to_cfg(object_cfg) + return object_cfg + def _add_initial_pose_to_cfg( self, object_cfg: RigidObjectCfg | ArticulationCfg | AssetBaseCfg ) -> RigidObjectCfg | ArticulationCfg | AssetBaseCfg: diff --git a/isaaclab_arena/assets/object_base.py b/isaaclab_arena/assets/object_base.py index c2044b1b..39ddbdaf 100644 --- a/isaaclab_arena/assets/object_base.py +++ b/isaaclab_arena/assets/object_base.py @@ -19,6 +19,7 @@ class ObjectType(Enum): BASE = "base" RIGID = "rigid" ARTICULATION = "articulation" + SPAWNER = "spawner" class ObjectBase(Asset, ABC): @@ -53,6 +54,8 @@ def _init_object_cfg(self) -> RigidObjectCfg | ArticulationCfg | AssetBaseCfg: object_cfg = self._generate_articulation_cfg() elif self.object_type == ObjectType.BASE: object_cfg = self._generate_base_cfg() + elif self.object_type == ObjectType.SPAWNER: + object_cfg = self._generate_spawner_cfg() else: raise ValueError(f"Invalid object type: {self.object_type}") return object_cfg @@ -103,3 +106,7 @@ def _generate_articulation_cfg(self) -> ArticulationCfg: def _generate_base_cfg(self) -> AssetBaseCfg: # Subclasses must implement this method pass + + def _generate_spawner_cfg(self) -> AssetBaseCfg: + # Object Subclasses must implement this method + pass diff --git a/isaaclab_arena/assets/object_library.py b/isaaclab_arena/assets/object_library.py index 7618fd92..66b75edb 100644 --- a/isaaclab_arena/assets/object_library.py +++ b/isaaclab_arena/assets/object_library.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: Apache-2.0 +import isaaclab.sim as sim_utils +from isaaclab.sim.spawners.from_files.from_files_cfg import GroundPlaneCfg from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR from isaaclab_arena.affordances.openable import Openable @@ -21,7 +23,7 @@ class LibraryObject(Object): name: str tags: list[str] - usd_path: str + usd_path: str | None = None object_type: ObjectType = ObjectType.RIGID scale: tuple[float, float, float] = (1.0, 1.0, 1.0) @@ -230,3 +232,49 @@ class BrownBox(LibraryObject): def __init__(self, prim_path: str | None = None, initial_pose: Pose | None = None): super().__init__(prim_path=prim_path, initial_pose=initial_pose) + + +@register_asset +class GroundPlane(LibraryObject): + """ + A ground plane. + """ + + name = "ground_plane" + tags = ["ground_plane"] + # Setting a global prim path for the ground plane. Will not get repeated for each environment. + default_prim_path = "/World/GroundPlane" + object_type = ObjectType.SPAWNER + default_spawner_cfg = GroundPlaneCfg() + + def __init__( + self, + prim_path: str | None = default_prim_path, + initial_pose: Pose | None = None, + spawner_cfg: sim_utils.GroundPlaneCfg = default_spawner_cfg, + ): + self.spawner_cfg = spawner_cfg + super().__init__(prim_path=prim_path, initial_pose=initial_pose) + + +@register_asset +class Light(LibraryObject): + """ + A dome light. + """ + + name = "light" + tags = ["light"] + # Setting a global prim path for the dome light. Will not get repeated for each environment. + default_prim_path = "/World/Light" + object_type = ObjectType.SPAWNER + default_spawner_cfg = sim_utils.DomeLightCfg(color=(0.75, 0.75, 0.75), intensity=3000.0) + + def __init__( + self, + prim_path: str | None = default_prim_path, + initial_pose: Pose | None = None, + spawner_cfg: sim_utils.LightCfg = default_spawner_cfg, + ): + self.spawner_cfg = spawner_cfg + super().__init__(prim_path=prim_path, initial_pose=initial_pose) diff --git a/isaaclab_arena/assets/object_reference.py b/isaaclab_arena/assets/object_reference.py index feb32d11..2b27716d 100644 --- a/isaaclab_arena/assets/object_reference.py +++ b/isaaclab_arena/assets/object_reference.py @@ -23,6 +23,8 @@ def __init__(self, parent_asset: Asset, **kwargs): super().__init__(**kwargs) self.initial_pose_relative_to_parent = self._get_referenced_prim_pose_relative_to_parent(parent_asset) self.parent_asset = parent_asset + # Check that the object reference is not a spawner. + assert self.object_type != ObjectType.SPAWNER, "Object reference cannot be a spawner" self.object_cfg = self._init_object_cfg() def get_initial_pose(self) -> Pose: diff --git a/isaaclab_arena/tests/test_asset_registry.py b/isaaclab_arena/tests/test_asset_registry.py index a6e1c2b5..58d59ba3 100644 --- a/isaaclab_arena/tests/test_asset_registry.py +++ b/isaaclab_arena/tests/test_asset_registry.py @@ -26,6 +26,12 @@ def _test_default_assets_registered(simulation_app): num_assets = len(asset_registry.get_assets_by_tag("object")) print(f"Number of pick up object assets registered: {num_assets}") assert num_assets > 0 + num_ground_plane_assets = len(asset_registry.get_assets_by_tag("ground_plane")) + print(f"Number of ground plane assets registered: {num_ground_plane_assets}") + assert num_ground_plane_assets > 0 + num_light_assets = len(asset_registry.get_assets_by_tag("light")) + print(f"Number of light assets registered: {num_light_assets}") + assert num_light_assets > 0 return True @@ -70,6 +76,15 @@ def _test_all_assets_in_registry(simulation_app): asset.set_initial_pose(pose) objects_in_registry.append(asset) objects_in_registry_names.append(asset.name) + # Add lights + for asset_cls in asset_registry.get_assets_by_tag("light"): + asset = asset_cls() + objects_in_registry.append(asset) + objects_in_registry_names.append(asset.name) + # Add ground plane + ground_plane = asset_registry.get_asset_by_name("ground_plane")() + objects_in_registry.append(ground_plane) + objects_in_registry_names.append(ground_plane.name) assert len(objects_in_registry) > 0 scene = Scene(assets=[background, *objects_in_registry]) @@ -117,6 +132,58 @@ def test_all_assets_in_registry(): assert result, "Test failed" +def _test_multi_light_in_scene(simulation_app): + from pxr import UsdLux + + from isaaclab_arena.assets.asset_registry import AssetRegistry + from isaaclab_arena.embodiments.franka.franka import FrankaEmbodiment + from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder + from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment + from isaaclab_arena.scene.scene import Scene + from isaaclab_arena.tasks.dummy_task import DummyTask + from isaaclab_arena.utils.usd_helpers import get_all_prims + + asset_registry = AssetRegistry() + light = asset_registry.get_asset_by_name("light")() + light_duplicate = asset_registry.get_asset_by_name("light")() + ground_plane = asset_registry.get_asset_by_name("ground_plane")() + ground_plane_duplicate = asset_registry.get_asset_by_name("ground_plane")() + scene = Scene(assets=[light, light_duplicate, ground_plane, ground_plane_duplicate]) + isaaclab_arena_environment = IsaacLabArenaEnvironment( + name="dummy_task", + embodiment=FrankaEmbodiment(), + scene=scene, + task=DummyTask(), + ) + # Compile the environment. + args_parser = get_isaaclab_arena_cli_parser() + args_cli = args_parser.parse_args(["--num_envs", "2"]) + + builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) + env = builder.make_registered() + env.reset() + for _ in tqdm.tqdm(range(NUM_STEPS)): + with torch.inference_mode(): + actions = torch.zeros(env.action_space.shape, device=env.unwrapped.device) + env.step(actions) + all_prims_in_stage = get_all_prims(env.scene.stage) + # Check that there is only one light in the stage + # We dont add lights from anywhere else in this scene. + light_prims = [prim for prim in all_prims_in_stage if prim.IsA(UsdLux.DomeLight)] + assert len(light_prims) == 1 + env.close() + return True + + +def test_multi_light_in_scene(): + result = run_simulation_app_function( + _test_multi_light_in_scene, + headless=HEADLESS, + ) + assert result, "Test failed" + + if __name__ == "__main__": test_default_assets_registered() test_all_assets_in_registry() + test_multi_light_in_scene() diff --git a/isaaclab_arena/utils/usd_helpers.py b/isaaclab_arena/utils/usd_helpers.py index 5ec0e447..f9661f86 100644 --- a/isaaclab_arena/utils/usd_helpers.py +++ b/isaaclab_arena/utils/usd_helpers.py @@ -5,7 +5,7 @@ from contextlib import contextmanager -from pxr import Usd, UsdPhysics +from pxr import Usd, UsdLux, UsdPhysics def get_all_prims( @@ -34,6 +34,24 @@ def get_all_prims( return prims_list +def has_light(stage: Usd.Stage) -> bool: + """Check if the stage has a light""" + LIGHT_TYPES = ( + UsdLux.SphereLight, + UsdLux.RectLight, + UsdLux.DomeLight, + UsdLux.DistantLight, + UsdLux.DiskLight, + ) + has_light = False + all_prims = get_all_prims(stage) + for prim in all_prims: + if any(prim.IsA(t) for t in LIGHT_TYPES): + has_light = True + break + return has_light + + def is_articulation_root(prim: Usd.Prim) -> bool: """Check if prim is articulation root""" return prim.HasAPI(UsdPhysics.ArticulationRootAPI) From fdc26acece7a51a3cc9ee25cd4aa4cbe0fc27205 Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Thu, 4 Dec 2025 14:57:32 +0100 Subject: [PATCH 05/26] Add env cfg callback to modify env cfg (#259) ## Summary Users might want to modify env cfg components such as sim config. This lets them do it. --- isaaclab_arena/environments/arena_env_builder.py | 5 +++++ isaaclab_arena/environments/isaaclab_arena_environment.py | 5 +++++ 2 files changed, 10 insertions(+) diff --git a/isaaclab_arena/environments/arena_env_builder.py b/isaaclab_arena/environments/arena_env_builder.py index cd552f7a..436f0481 100644 --- a/isaaclab_arena/environments/arena_env_builder.py +++ b/isaaclab_arena/environments/arena_env_builder.py @@ -169,6 +169,11 @@ def compose_manager_cfg(self) -> IsaacLabArenaManagerBasedRLEnvCfg: viewer=viewer_cfg, ) + # Apply the environment configuration callback if it is set + # This can be used to modify the simulation configuration, etc. + if self.arena_env.env_cfg_callback is not None: + env_cfg = self.arena_env.env_cfg_callback(env_cfg) + return env_cfg def get_entry_point(self) -> str | type[ManagerBasedRLMimicEnv]: diff --git a/isaaclab_arena/environments/isaaclab_arena_environment.py b/isaaclab_arena/environments/isaaclab_arena_environment.py index 9f7553a5..19c93dad 100644 --- a/isaaclab_arena/environments/isaaclab_arena_environment.py +++ b/isaaclab_arena/environments/isaaclab_arena_environment.py @@ -5,6 +5,7 @@ from __future__ import annotations +from collections.abc import Callable from dataclasses import MISSING from typing import TYPE_CHECKING @@ -12,6 +13,7 @@ if TYPE_CHECKING: from isaaclab_arena.embodiments.embodiment_base import EmbodimentBase + from isaaclab_arena.environments.isaaclab_arena_manager_based_env import IsaacLabArenaManagerBasedRLEnvCfg from isaaclab_arena.orchestrator.orchestrator_base import OrchestratorBase from isaaclab_arena.scene.scene import Scene from isaaclab_arena.tasks.task_base import TaskBase @@ -39,3 +41,6 @@ class IsaacLabArenaEnvironment: orchestrator: OrchestratorBase | None = None """The orchestrator to use in the environment.""" + + env_cfg_callback: Callable[IsaacLabArenaManagerBasedRLEnvCfg] | None = None + """A callback function that modifies the environment configuration.""" From 0ed52f833f9493c7300f22de1e55c82c739756a7 Mon Sep 17 00:00:00 2001 From: Alex Millane Date: Fri, 5 Dec 2025 06:30:22 -0800 Subject: [PATCH 06/26] Move to public CI (#250) ## Summary Move our CI infra to public runners ## Detailed description - As part of our open-source release, we can no longer run on internal infra. - This MR moves our runners to public runners. - I also took the chance to refactor and modularize the workflow file. --- .github/workflows/ci.yml | 98 +++++++++++++------ docker/run_docker.sh | 2 + .../test_replay_lerobot_action_policy.py | 4 + 3 files changed, 72 insertions(+), 32 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index faac553b..9363579b 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -28,16 +28,18 @@ env: jobs: - test: - name: Run pre commit checks and tests - runs-on: [self-hosted, zurich] - timeout-minutes: 45 + + pre_commit: + name: Pre-commit + runs-on: [gpu] + timeout-minutes: 30 container: - image: nvcr.io/nvstaging/isaac-amr/isaaclab_arena:latest - credentials: - username: $oauthtoken - password: ${{ env.NGC_API_KEY }} + image: python:3.11-slim + + env: + # We're getting issues with the markers on the checked out files. + SKIP: check-executables-have-shebangs steps: - &install_git_step @@ -54,25 +56,23 @@ jobs: name: Clean up symlinks in submodules directory run: | rm -f .git/modules/submodules/IsaacLab/index.lock || true - rm -rf submodules/IsaacLab || true + rm -rf submodules/* || true + + # Fix "detected dubious ownership in repository" inside containers + - &mark_repo_safe_step + name: Mark repo as safe for git + run: git config --global --add safe.directory "$PWD" # Checkout Code - &checkout_step name: Checkout Code uses: actions/checkout@v4 with: - fetch-depth: 0 - clean: true submodules: true # LFS checkout here somehow causes issues when LFS stuff changes over time. # So I do LFS manually in a step after. # lfs: true - # Fix "detected dubious ownership in repository" inside containers - - &mark_repo_safe_step - name: Mark repo as safe for git - run: git config --global --add safe.directory "$PWD" - # Pull LFS files explicitly (in case checkout didn't get them all) - &git_lfs_step name: Git LFS @@ -81,9 +81,39 @@ jobs: git lfs install --local git lfs pull - - &setup_python_step - name: Setup Python - uses: actions/setup-python@v3 + - name: git status + run: | + git status + + - name: Run pre-commit + uses: pre-commit/action@v3.0.1 + with: + extra_args: --verbose + + test: + name: Run tests + runs-on: [gpu] + timeout-minutes: 60 + needs: [pre_commit] + + container: + image: nvcr.io/nvstaging/isaac-amr/isaaclab_arena:latest + credentials: + username: $oauthtoken + password: ${{ env.NGC_API_KEY }} + + steps: + # nvidia-smi + - &nvidia_smi + name: nvidia-smi + run: nvidia-smi + + # Setup + - *install_git_step + - *cleanup_step + - *mark_repo_safe_step + - *checkout_step + - *git_lfs_step - &install_project_step name: Install project and link isaac-sim @@ -91,21 +121,19 @@ jobs: pip install --no-cache-dir -e . [ -e ./submodules/IsaacLab/_isaac_sim ] || ln -s /isaac-sim ./submodules/IsaacLab/_isaac_sim - - name: Run pre-commit - run: | - pip install --no-cache-dir --upgrade pip pre-commit - pre-commit run --all-files - + # Run the tests (excluding the gr00t related tests) - name: Run pytest excluding policy-related tests. First we run all tests without cameras. run: /isaac-sim/python.sh -m pytest -sv -m "not with_cameras" isaaclab_arena/tests/ --ignore=isaaclab_arena/tests/policy/ - name: Run pytest excluding policy-related tests. Now we run all tests with cameras. run: /isaac-sim/python.sh -m pytest -sv -m with_cameras isaaclab_arena/tests/ --ignore=isaaclab_arena/tests/policy/ + test_policy: name: Run policy-related tests with GR00T & cuda12_8 deps - runs-on: [self-hosted, zurich] - timeout-minutes: 30 + runs-on: [gpu] + timeout-minutes: 60 + needs: [pre_commit] container: image: nvcr.io/nvstaging/isaac-amr/isaaclab_arena:cuda_gr00t @@ -113,22 +141,27 @@ jobs: username: $oauthtoken password: ${{ env.NGC_API_KEY }} steps: + # nvidia-smi + - *nvidia_smi + # Setup. - *install_git_step - *cleanup_step - - *checkout_step - *mark_repo_safe_step + - *checkout_step - *git_lfs_step - - *setup_python_step - *install_project_step + # Run the policy (GR00T) related tests. - name: Run policy-related pytest run: /isaac-sim/python.sh -m pytest -sv isaaclab_arena/tests/policy/ + build_docs_pre_merge: name: Build the docs (pre-merge) - runs-on: [self-hosted, zurich] + runs-on: [gpu] timeout-minutes: 30 + needs: [pre_commit] container: image: python:3.11-slim @@ -147,11 +180,12 @@ jobs: make SPHINXOPTS=-W html touch ./_build/html/.nojekyll + build_and_push_image_post_merge: name: Build & push NGC image (post-merge) - runs-on: [self-hosted, zurich] - timeout-minutes: 60 - needs: [test, test_policy, build_docs_pre_merge] # only push if tests passed + runs-on: [gpu] + timeout-minutes: 90 + needs: [test, test_policy] # only push if tests passed if: github.event_name == 'push' && github.ref == 'refs/heads/main' container: diff --git a/docker/run_docker.sh b/docker/run_docker.sh index 87da931e..b4fb6cef 100755 --- a/docker/run_docker.sh +++ b/docker/run_docker.sh @@ -139,6 +139,8 @@ else "-v" "./isaaclab_arena:${WORKDIR}/isaaclab_arena" "-v" "./isaaclab_arena_g1:${WORKDIR}/isaaclab_arena_g1" "-v" "./isaaclab_arena_gr00t:${WORKDIR}/isaaclab_arena_gr00t" + "-v" "./docker:${WORKDIR}/docker" + "-v" "./.github:${WORKDIR}/.github" "-v" "./submodules/IsaacLab:${WORKDIR}/submodules/IsaacLab" $(add_volume_if_it_exists $DATASETS_HOST_MOUNT_DIRECTORY /datasets) $(add_volume_if_it_exists $MODELS_HOST_MOUNT_DIRECTORY /models) diff --git a/isaaclab_arena/tests/policy/test_replay_lerobot_action_policy.py b/isaaclab_arena/tests/policy/test_replay_lerobot_action_policy.py index 196aeafe..85fe0bb3 100644 --- a/isaaclab_arena/tests/policy/test_replay_lerobot_action_policy.py +++ b/isaaclab_arena/tests/policy/test_replay_lerobot_action_policy.py @@ -3,6 +3,8 @@ # # SPDX-License-Identifier: Apache-2.0 +import pytest + from isaaclab_arena.tests.utils.constants import TestConstants from isaaclab_arena.tests.utils.subprocess import run_subprocess @@ -36,6 +38,7 @@ def test_g1_locomanip_replay_lerobot_policy_runner_single_env(): run_subprocess(args) +@pytest.mark.skip(reason="Fails on CI for reasons under investigation.") def test_gr1_manip_replay_lerobot_policy_runner_single_env(): args = [TestConstants.python_path, f"{TestConstants.examples_dir}/policy_runner.py"] args.append("--policy_type") @@ -61,3 +64,4 @@ def test_gr1_manip_replay_lerobot_policy_runner_single_env(): if __name__ == "__main__": test_g1_locomanip_replay_lerobot_policy_runner_single_env() + test_gr1_manip_replay_lerobot_policy_runner_single_env() From c7b70779f103e10d690d1a13863e8d77da7fc782 Mon Sep 17 00:00:00 2001 From: Alex Millane Date: Mon, 8 Dec 2025 04:14:21 -0800 Subject: [PATCH 07/26] Update docs link in the README. (#270) ## Summary Update link to the docs in README.md to the new public location. ## Detailed description - Docs url has changed now that the repo is public. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index dff15fdb..85a6e1db 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ Isaac-Lab Arena is a comprehensive robotics simulation framework that enhances NVIDIA Isaac Lab by providing a composable, scalable system for creating diverse simulation environments and evaluating robot learning policies. The framework enables researchers and developers to rapidly prototype and test robotic tasks with various robot embodiments, objects, and environments. -To get started with Isaac-Lab Arena, see our [documentation site](https://fictional-disco-qm1zq12.pages.github.io/html/index.html). +To get started with Isaac-Lab Arena, see our [documentation site](https://isaac-sim.github.io/IsaacLab-Arena/html/index.html).
From e544861f028ed3d1e4ba942b3dd9a93e81e46b8b Mon Sep 17 00:00:00 2001 From: Alex Millane Date: Tue, 9 Dec 2025 23:09:25 +0100 Subject: [PATCH 08/26] Correct public CI tags. (#276) ## Summary Fixes an issue that our tags requesting for public CI were incorrect. ## Detailed description - Corrects the tag `[gpu]` -> `[self-hosted, gpu]` --- .github/workflows/ci.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 9363579b..99685700 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -31,7 +31,7 @@ jobs: pre_commit: name: Pre-commit - runs-on: [gpu] + runs-on: [self-hosted, gpu] timeout-minutes: 30 container: @@ -92,7 +92,7 @@ jobs: test: name: Run tests - runs-on: [gpu] + runs-on: [self-hosted, gpu] timeout-minutes: 60 needs: [pre_commit] @@ -131,7 +131,7 @@ jobs: test_policy: name: Run policy-related tests with GR00T & cuda12_8 deps - runs-on: [gpu] + runs-on: [self-hosted, gpu] timeout-minutes: 60 needs: [pre_commit] @@ -159,7 +159,7 @@ jobs: build_docs_pre_merge: name: Build the docs (pre-merge) - runs-on: [gpu] + runs-on: [self-hosted, gpu] timeout-minutes: 30 needs: [pre_commit] @@ -183,7 +183,7 @@ jobs: build_and_push_image_post_merge: name: Build & push NGC image (post-merge) - runs-on: [gpu] + runs-on: [self-hosted, gpu] timeout-minutes: 90 needs: [test, test_policy] # only push if tests passed if: github.event_name == 'push' && github.ref == 'refs/heads/main' From 3c3c789c6e7a1ee27cc37f0e38b398b9be298c0c Mon Sep 17 00:00:00 2001 From: Alex Millane Date: Wed, 10 Dec 2025 15:56:25 +0100 Subject: [PATCH 09/26] Move back to mapping the whole repo. (#275) ## Summary Revert to mapping the whole repo in the dev docker. ## Detailed description - Previously we changed to mapping only specific folders in the repo. - This was done for docker build speed (I believe?) - The issue is that we want (even if occasionally) to work on all folders in the repo, within the dev docker. - This reverts to mapping the whole repo. --- docker/run_docker.sh | 8 +------- 1 file changed, 1 insertion(+), 7 deletions(-) diff --git a/docker/run_docker.sh b/docker/run_docker.sh index b4fb6cef..49f6d60a 100755 --- a/docker/run_docker.sh +++ b/docker/run_docker.sh @@ -135,13 +135,7 @@ else "--net=host" "--runtime=nvidia" "--gpus=all" - "-v" "./docs:${WORKDIR}/docs" - "-v" "./isaaclab_arena:${WORKDIR}/isaaclab_arena" - "-v" "./isaaclab_arena_g1:${WORKDIR}/isaaclab_arena_g1" - "-v" "./isaaclab_arena_gr00t:${WORKDIR}/isaaclab_arena_gr00t" - "-v" "./docker:${WORKDIR}/docker" - "-v" "./.github:${WORKDIR}/.github" - "-v" "./submodules/IsaacLab:${WORKDIR}/submodules/IsaacLab" + "-v" ".:${WORKDIR}" $(add_volume_if_it_exists $DATASETS_HOST_MOUNT_DIRECTORY /datasets) $(add_volume_if_it_exists $MODELS_HOST_MOUNT_DIRECTORY /models) $(add_volume_if_it_exists $EVAL_HOST_MOUNT_DIRECTORY /eval) From 4b9472386a566372b08be4c212b7ccd5bed74dce Mon Sep 17 00:00:00 2001 From: Alex Millane Date: Thu, 11 Dec 2025 13:52:06 +0100 Subject: [PATCH 10/26] Reenable pre-commit. (#278) ## Summary Re-enables pre-commit in CI. ## Detailed description - During the refactoring and switch to public CI, `pre-commit` was broken. - This MR fixes it. --- .github/workflows/ci.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 99685700..5e968a73 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -88,7 +88,7 @@ jobs: - name: Run pre-commit uses: pre-commit/action@v3.0.1 with: - extra_args: --verbose + extra_args: --all-files --verbose test: name: Run tests From 587600dd60d9be427d3142e576ff9d80a805adec Mon Sep 17 00:00:00 2001 From: Xinjie Yao Date: Thu, 11 Dec 2025 09:10:37 -0800 Subject: [PATCH 11/26] Policy consumes task description from Task (#280) ## Summary Language prompts are fetched from Task's data member, populated from ArenaEnv creation. ## Detailed description - `task_description` is automatically populated into atomic task, and users have the freedom to overwrite it when instantiating the task class - `Policy` sets its `task_description` attribute thru a setter func - `Policy_runner.py` connects the `task_description` from Task to `task_description` setter in `Policy` - GR00T consumes description either thru `task_description` data member or `policy_config` --- ...ileo_g1_locomanip_pick_and_place_environment.py | 11 ++++++++++- isaaclab_arena/examples/policy_runner.py | 3 +++ isaaclab_arena/policy/policy_base.py | 7 ++++++- .../tasks/g1_locomanip_pick_and_place_task.py | 9 ++++++--- isaaclab_arena/tasks/open_door_task.py | 7 ++++--- isaaclab_arena/tasks/pick_and_place_task.py | 9 ++++++--- isaaclab_arena/tasks/press_button_task.py | 4 ++++ isaaclab_arena/tasks/task_base.py | 10 +++++----- isaaclab_arena_gr00t/gr00t_closedloop_policy.py | 14 +++++++++++++- 9 files changed, 57 insertions(+), 17 deletions(-) diff --git a/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py b/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py index be5ab7fa..8930bf16 100644 --- a/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py +++ b/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py @@ -69,7 +69,16 @@ def get_env(self, args_cli: argparse.Namespace): name=self.name, embodiment=embodiment, scene=scene, - task=G1LocomanipPickAndPlaceTask(pick_up_object, blue_sorting_bin, background, episode_length_s=30.0), + task=G1LocomanipPickAndPlaceTask( + pick_up_object, + blue_sorting_bin, + background, + episode_length_s=30.0, + task_description=( + "Pick up the brown box from the shelf, and place it into the blue bin on the table located at the" + " right of the shelf." + ), + ), teleop_device=teleop_device, ) return isaaclab_arena_environment diff --git a/isaaclab_arena/examples/policy_runner.py b/isaaclab_arena/examples/policy_runner.py index ce7365b1..8c29b71c 100644 --- a/isaaclab_arena/examples/policy_runner.py +++ b/isaaclab_arena/examples/policy_runner.py @@ -42,6 +42,9 @@ def main(): # app. Given current SimulationAppContext setup, use lazy import to handle policy-related # deps inside create_policy() function to bringup sim app. policy, num_steps = create_policy(args_cli) + # set task description (could be None) from the task being evaluated + policy.set_task_description(env.cfg.isaaclab_arena_env.task.get_task_description()) + # NOTE(xinjieyao, 2025-10-07): lazy import to prevent app stalling caused by omni.kit from isaaclab_arena.metrics.metrics import compute_metrics diff --git a/isaaclab_arena/policy/policy_base.py b/isaaclab_arena/policy/policy_base.py index 4052d138..c6550cfc 100644 --- a/isaaclab_arena/policy/policy_base.py +++ b/isaaclab_arena/policy/policy_base.py @@ -27,10 +27,15 @@ def get_action(self, env: gym.Env, observation: GymSpacesDict) -> torch.Tensor: Returns: torch.Tensor: The action to take. """ - pass + raise NotImplementedError("Function not implemented yet.") def reset(self, env_ids: torch.Tensor | None = None) -> None: """ Reset the policy. """ pass + + def set_task_description(self, task_description: str | None) -> str: + """Set the task description of the task being evaluated.""" + self.task_description = task_description + return self.task_description diff --git a/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py b/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py index c203ea65..a4117709 100644 --- a/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py +++ b/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py @@ -31,11 +31,17 @@ def __init__( destination_bin: Asset, background_scene: Asset, episode_length_s: float | None = None, + task_description: str | None = None, ): super().__init__(episode_length_s=episode_length_s) self.pick_up_object = pick_up_object self.background_scene = background_scene self.destination_bin = destination_bin + self.task_description = ( + f"Pick up the {pick_up_object.name}, and place it into the {destination_bin.name}" + if task_description is None + else task_description + ) def get_scene_cfg(self): pass @@ -66,9 +72,6 @@ def get_termination_cfg(self): def get_events_cfg(self): return EventsCfg(pick_up_object=self.pick_up_object) - def get_prompt(self): - raise NotImplementedError("Function not implemented yet.") - def get_mimic_env_cfg(self, embodiment_name: str): return G1LocomanipPickPlaceMimicEnvCfg() diff --git a/isaaclab_arena/tasks/open_door_task.py b/isaaclab_arena/tasks/open_door_task.py index 1eb7ed12..035188c8 100644 --- a/isaaclab_arena/tasks/open_door_task.py +++ b/isaaclab_arena/tasks/open_door_task.py @@ -28,6 +28,7 @@ def __init__( openness_threshold: float | None = None, reset_openness: float | None = None, episode_length_s: float | None = None, + task_description: str | None = None, ): super().__init__(episode_length_s=episode_length_s) assert isinstance(openable_object, Openable), "Openable object must be an instance of Openable" @@ -37,6 +38,9 @@ def __init__( self.scene_config = None self.events_cfg = OpenDoorEventCfg(self.openable_object, reset_openness=self.reset_openness) self.termination_cfg = self.make_termination_cfg() + self.task_description = ( + f"Reach out to the {openable_object.name} and open it." if task_description is None else task_description + ) def get_scene_cfg(self): return self.scene_config @@ -57,9 +61,6 @@ def make_termination_cfg(self): def get_events_cfg(self): return self.events_cfg - def get_prompt(self): - raise NotImplementedError("Function not implemented yet.") - def get_mimic_env_cfg(self, embodiment_name: str): return OpenDoorMimicEnvCfg( embodiment_name=embodiment_name, diff --git a/isaaclab_arena/tasks/pick_and_place_task.py b/isaaclab_arena/tasks/pick_and_place_task.py index 59a72ec7..b1b9fdbd 100644 --- a/isaaclab_arena/tasks/pick_and_place_task.py +++ b/isaaclab_arena/tasks/pick_and_place_task.py @@ -31,6 +31,7 @@ def __init__( destination_location: Asset, background_scene: Asset, episode_length_s: float | None = None, + task_description: str | None = None, ): super().__init__(episode_length_s=episode_length_s) self.pick_up_object = pick_up_object @@ -43,6 +44,11 @@ def __init__( ) self.events_cfg = EventsCfg(pick_up_object=self.pick_up_object) self.termination_cfg = self.make_termination_cfg() + self.task_description = ( + f"Pick up the {pick_up_object.name}, and place it into the {destination_location.name}" + if task_description is None + else task_description + ) def get_scene_cfg(self): return self.scene_config @@ -75,9 +81,6 @@ def make_termination_cfg(self): def get_events_cfg(self): return self.events_cfg - def get_prompt(self): - raise NotImplementedError("Function not implemented yet.") - def get_mimic_env_cfg(self, embodiment_name: str): return PickPlaceMimicEnvCfg( embodiment_name=embodiment_name, diff --git a/isaaclab_arena/tasks/press_button_task.py b/isaaclab_arena/tasks/press_button_task.py index 9246155e..6929187e 100644 --- a/isaaclab_arena/tasks/press_button_task.py +++ b/isaaclab_arena/tasks/press_button_task.py @@ -25,12 +25,16 @@ def __init__( pressedness_threshold: float | None = None, reset_pressedness: float | None = None, episode_length_s: float | None = None, + task_description: str | None = None, ): super().__init__(episode_length_s=episode_length_s) assert isinstance(pressable_object, Pressable), "Pressable object must be an instance of Pressable" self.pressable_object = pressable_object self.pressedness_threshold = pressedness_threshold self.reset_pressedness = reset_pressedness + self.task_description = ( + f"Press the {pressable_object.name} button" if task_description is None else task_description + ) def get_scene_cfg(self): pass diff --git a/isaaclab_arena/tasks/task_base.py b/isaaclab_arena/tasks/task_base.py index 9ee4e1af..0a02edc5 100644 --- a/isaaclab_arena/tasks/task_base.py +++ b/isaaclab_arena/tasks/task_base.py @@ -15,8 +15,9 @@ class TaskBase(ABC): - def __init__(self, episode_length_s: float | None = None): + def __init__(self, episode_length_s: float | None = None, task_description: str | None = None): self.episode_length_s = episode_length_s + self.task_description = task_description @abstractmethod def get_scene_cfg(self) -> Any: @@ -30,10 +31,6 @@ def get_termination_cfg(self) -> Any: def get_events_cfg(self) -> Any: raise NotImplementedError("Function not implemented yet.") - @abstractmethod - def get_prompt(self) -> str: - raise NotImplementedError("Function not implemented yet.") - @abstractmethod def get_mimic_env_cfg(self, embodiment_name: str) -> Any: raise NotImplementedError("Function not implemented yet.") @@ -65,3 +62,6 @@ def get_viewer_cfg(self) -> ViewerCfg: def get_episode_length_s(self) -> float | None: return self.episode_length_s + + def get_task_description(self) -> str | None: + return self.task_description diff --git a/isaaclab_arena_gr00t/gr00t_closedloop_policy.py b/isaaclab_arena_gr00t/gr00t_closedloop_policy.py index 51e10e85..ea6d088c 100644 --- a/isaaclab_arena_gr00t/gr00t_closedloop_policy.py +++ b/isaaclab_arena_gr00t/gr00t_closedloop_policy.py @@ -64,6 +64,9 @@ def __init__(self, policy_config_yaml_path: Path, num_envs: int = 1, device: str self.current_action_index = torch.zeros(num_envs, dtype=torch.int32, device=device) + # task description of task being evaluated. It will be set by the task being evaluated. + self.task_description: str | None = None + def load_policy_joints_config(self, policy_config_path: Path) -> dict[str, Any]: """Load the GR00T policy joint config from the data config.""" return load_robot_joints_config_from_yaml(policy_config_path) @@ -101,6 +104,13 @@ def load_policy(self) -> Gr00tPolicy: device=self.policy_config.policy_device, ) + def set_task_description(self, task_description: str | None) -> str: + """Set the language instruction of the task being evaluated.""" + if task_description is None: + task_description = self.policy_config.language_instruction + self.task_description = task_description + return self.task_description + def get_observations(self, observation: dict[str, Any], camera_name: str = "robot_head_cam_rgb") -> dict[str, Any]: rgb = observation["camera_obs"][camera_name] # gr00t uses numpy arrays @@ -117,8 +127,10 @@ def get_observations(self, observation: dict[str, Any], camera_name: str = "robo joint_pos_state_policy = remap_sim_joints_to_policy_joints(joint_pos_state_sim, self.policy_joints_config) # Pack inputs to dictionary and run the inference + assert self.task_description is not None, "Task description is not set" policy_observations = { - "annotation.human.task_description": [self.policy_config.language_instruction] * self.num_envs, + # TODO(xinejiayao, 2025-12-10): when multi-task with parallel envs feature is enabled, we need to pass in a list of task descriptions. + "annotation.human.task_description": [self.task_description] * self.num_envs, "video.ego_view": rgb.reshape( self.num_envs, 1, From 43ed13fb7512b52ae592706a9c7c76d67deea1ac Mon Sep 17 00:00:00 2001 From: Xinjie Yao Date: Thu, 11 Dec 2025 10:49:09 -0800 Subject: [PATCH 12/26] Package example_environments into isaaclab_arena_environments (#281) ## Summary All example environments.py are repackaged into isaaclab_arena_environments ## Reason In prep for multi-task evaluation, as we may introduce more example envs. --- docker/Dockerfile.isaaclab_arena | 1 + isaaclab_arena/examples/example_env_notebook.py | 7 ++----- isaaclab_arena/examples/policy_runner.py | 2 +- isaaclab_arena/examples/policy_runner_cli.py | 4 ++-- isaaclab_arena/scripts/annotate_demos.py | 5 +---- isaaclab_arena/scripts/generate_dataset.py | 5 +---- isaaclab_arena/scripts/record_demos.py | 5 +---- isaaclab_arena/scripts/replay_demos.py | 5 +---- isaaclab_arena/scripts/teleop.py | 5 +---- .../__init__.py | 0 .../cli.py | 16 ++++++---------- .../example_environment_base.py | 0 ...eo_g1_locomanip_pick_and_place_environment.py | 2 +- .../galileo_pick_and_place_environment.py | 2 +- .../gr1_open_microwave_environment.py | 2 +- .../kitchen_pick_and_place_environment.py | 2 +- .../press_button_environment.py | 2 +- setup.py | 4 +++- 18 files changed, 25 insertions(+), 44 deletions(-) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/__init__.py (100%) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/cli.py (86%) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/example_environment_base.py (100%) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/galileo_g1_locomanip_pick_and_place_environment.py (97%) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/galileo_pick_and_place_environment.py (96%) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/gr1_open_microwave_environment.py (96%) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/kitchen_pick_and_place_environment.py (96%) rename {isaaclab_arena/examples/example_environments => isaaclab_arena_environments}/press_button_environment.py (95%) diff --git a/docker/Dockerfile.isaaclab_arena b/docker/Dockerfile.isaaclab_arena index 8384ee3f..2c4bcdf4 100644 --- a/docker/Dockerfile.isaaclab_arena +++ b/docker/Dockerfile.isaaclab_arena @@ -115,6 +115,7 @@ COPY *.* ${WORKDIR}/ COPY isaaclab_arena ${WORKDIR}/isaaclab_arena COPY isaaclab_arena_g1 ${WORKDIR}/isaaclab_arena_g1 COPY isaaclab_arena_gr00t ${WORKDIR}/isaaclab_arena_gr00t +COPY isaaclab_arena_environments ${WORKDIR}/isaaclab_arena_environments COPY docs ${WORKDIR}/docs # Install IsaacLab Arena diff --git a/isaaclab_arena/examples/example_env_notebook.py b/isaaclab_arena/examples/example_env_notebook.py index ad03a595..2fa520df 100644 --- a/isaaclab_arena/examples/example_env_notebook.py +++ b/isaaclab_arena/examples/example_env_notebook.py @@ -19,12 +19,9 @@ from isaaclab_arena.utils.reload_modules import reload_arena_modules reload_arena_modules() -from isaaclab_arena.examples.example_environments.cli import ( - get_arena_builder_from_cli, - get_isaaclab_arena_example_environment_cli_parser, -) +from isaaclab_arena_environments.cli import get_arena_builder_from_cli, get_isaaclab_arena_environments_cli_parser -args_parser = get_isaaclab_arena_example_environment_cli_parser() +args_parser = get_isaaclab_arena_environments_cli_parser() # GR1 Open Microwave args_cli = args_parser.parse_args([ diff --git a/isaaclab_arena/examples/policy_runner.py b/isaaclab_arena/examples/policy_runner.py index 8c29b71c..4d42e06d 100644 --- a/isaaclab_arena/examples/policy_runner.py +++ b/isaaclab_arena/examples/policy_runner.py @@ -9,9 +9,9 @@ import tqdm from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.examples.example_environments.cli import get_arena_builder_from_cli from isaaclab_arena.examples.policy_runner_cli import create_policy, setup_policy_argument_parser from isaaclab_arena.utils.isaaclab_utils.simulation_app import SimulationAppContext +from isaaclab_arena_environments.cli import get_arena_builder_from_cli def main(): diff --git a/isaaclab_arena/examples/policy_runner_cli.py b/isaaclab_arena/examples/policy_runner_cli.py index 9103929d..1c9f2921 100644 --- a/isaaclab_arena/examples/policy_runner_cli.py +++ b/isaaclab_arena/examples/policy_runner_cli.py @@ -5,10 +5,10 @@ import argparse -from isaaclab_arena.examples.example_environments.cli import get_isaaclab_arena_example_environment_cli_parser from isaaclab_arena.policy.policy_base import PolicyBase from isaaclab_arena.policy.replay_action_policy import ReplayActionPolicy from isaaclab_arena.policy.zero_action_policy import ZeroActionPolicy +from isaaclab_arena_environments.cli import get_isaaclab_arena_environments_cli_parser def add_zero_action_arguments(parser: argparse.ArgumentParser) -> None: @@ -86,7 +86,7 @@ def add_gr00t_closedloop_arguments(parser: argparse.ArgumentParser) -> None: def setup_policy_argument_parser(args_parser: argparse.ArgumentParser | None = None) -> argparse.ArgumentParser: """Set up and configure the argument parser with all policy-related arguments.""" # Get the base parser from IsaacLab Arena - args_parser = get_isaaclab_arena_example_environment_cli_parser(args_parser) + args_parser = get_isaaclab_arena_environments_cli_parser(args_parser) args_parser.add_argument( "--policy_type", diff --git a/isaaclab_arena/scripts/annotate_demos.py b/isaaclab_arena/scripts/annotate_demos.py index 23ccbe98..66c0ed55 100644 --- a/isaaclab_arena/scripts/annotate_demos.py +++ b/isaaclab_arena/scripts/annotate_demos.py @@ -19,10 +19,7 @@ from isaaclab.app import AppLauncher from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.examples.example_environments.cli import ( - add_example_environments_cli_args, - get_arena_builder_from_cli, -) +from isaaclab_arena_environments.cli import add_example_environments_cli_args, get_arena_builder_from_cli # Launching Isaac Sim Simulator first. diff --git a/isaaclab_arena/scripts/generate_dataset.py b/isaaclab_arena/scripts/generate_dataset.py index 906244a0..a865ae1d 100644 --- a/isaaclab_arena/scripts/generate_dataset.py +++ b/isaaclab_arena/scripts/generate_dataset.py @@ -22,10 +22,7 @@ from isaaclab.app import AppLauncher from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.examples.example_environments.cli import ( - add_example_environments_cli_args, - get_arena_builder_from_cli, -) +from isaaclab_arena_environments.cli import add_example_environments_cli_args, get_arena_builder_from_cli # add argparse arguments parser = get_isaaclab_arena_cli_parser() diff --git a/isaaclab_arena/scripts/record_demos.py b/isaaclab_arena/scripts/record_demos.py index 0ca3af33..63a56fdf 100644 --- a/isaaclab_arena/scripts/record_demos.py +++ b/isaaclab_arena/scripts/record_demos.py @@ -35,10 +35,7 @@ from isaaclab.app import AppLauncher from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.examples.example_environments.cli import ( - add_example_environments_cli_args, - get_arena_builder_from_cli, -) +from isaaclab_arena_environments.cli import add_example_environments_cli_args, get_arena_builder_from_cli # add argparse arguments parser = get_isaaclab_arena_cli_parser() diff --git a/isaaclab_arena/scripts/replay_demos.py b/isaaclab_arena/scripts/replay_demos.py index 63039090..f4d36869 100644 --- a/isaaclab_arena/scripts/replay_demos.py +++ b/isaaclab_arena/scripts/replay_demos.py @@ -15,10 +15,7 @@ from isaaclab.app import AppLauncher from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.examples.example_environments.cli import ( - add_example_environments_cli_args, - get_arena_builder_from_cli, -) +from isaaclab_arena_environments.cli import add_example_environments_cli_args, get_arena_builder_from_cli # add argparse arguments parser = get_isaaclab_arena_cli_parser() diff --git a/isaaclab_arena/scripts/teleop.py b/isaaclab_arena/scripts/teleop.py index a3b31a57..67275008 100644 --- a/isaaclab_arena/scripts/teleop.py +++ b/isaaclab_arena/scripts/teleop.py @@ -18,10 +18,7 @@ from isaaclab.app import AppLauncher from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.examples.example_environments.cli import ( - add_example_environments_cli_args, - get_arena_builder_from_cli, -) +from isaaclab_arena_environments.cli import add_example_environments_cli_args, get_arena_builder_from_cli # add argparse arguments parser = get_isaaclab_arena_cli_parser() diff --git a/isaaclab_arena/examples/example_environments/__init__.py b/isaaclab_arena_environments/__init__.py similarity index 100% rename from isaaclab_arena/examples/example_environments/__init__.py rename to isaaclab_arena_environments/__init__.py diff --git a/isaaclab_arena/examples/example_environments/cli.py b/isaaclab_arena_environments/cli.py similarity index 86% rename from isaaclab_arena/examples/example_environments/cli.py rename to isaaclab_arena_environments/cli.py index 3e476bc6..1f25b243 100644 --- a/isaaclab_arena/examples/example_environments/cli.py +++ b/isaaclab_arena_environments/cli.py @@ -8,17 +8,13 @@ from typing import Any from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.examples.example_environments.galileo_g1_locomanip_pick_and_place_environment import ( +from isaaclab_arena_environments.galileo_g1_locomanip_pick_and_place_environment import ( GalileoG1LocomanipPickAndPlaceEnvironment, ) -from isaaclab_arena.examples.example_environments.galileo_pick_and_place_environment import ( - GalileoPickAndPlaceEnvironment, -) -from isaaclab_arena.examples.example_environments.gr1_open_microwave_environment import Gr1OpenMicrowaveEnvironment -from isaaclab_arena.examples.example_environments.kitchen_pick_and_place_environment import ( - KitchenPickAndPlaceEnvironment, -) -from isaaclab_arena.examples.example_environments.press_button_environment import PressButtonEnvironment +from isaaclab_arena_environments.galileo_pick_and_place_environment import GalileoPickAndPlaceEnvironment +from isaaclab_arena_environments.gr1_open_microwave_environment import Gr1OpenMicrowaveEnvironment +from isaaclab_arena_environments.kitchen_pick_and_place_environment import KitchenPickAndPlaceEnvironment +from isaaclab_arena_environments.press_button_environment import PressButtonEnvironment # NOTE(alexmillane, 2025.09.04): There is an issue with type annotation in this file. # We cannot annotate types which require the simulation app to be started in order to @@ -78,7 +74,7 @@ def add_example_environments_cli_args(args_parser: argparse.ArgumentParser) -> a return args_parser -def get_isaaclab_arena_example_environment_cli_parser( +def get_isaaclab_arena_environments_cli_parser( args_parser: argparse.ArgumentParser | None = None, ) -> argparse.ArgumentParser: if args_parser is None: diff --git a/isaaclab_arena/examples/example_environments/example_environment_base.py b/isaaclab_arena_environments/example_environment_base.py similarity index 100% rename from isaaclab_arena/examples/example_environments/example_environment_base.py rename to isaaclab_arena_environments/example_environment_base.py diff --git a/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py b/isaaclab_arena_environments/galileo_g1_locomanip_pick_and_place_environment.py similarity index 97% rename from isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py rename to isaaclab_arena_environments/galileo_g1_locomanip_pick_and_place_environment.py index 8930bf16..0e016d13 100644 --- a/isaaclab_arena/examples/example_environments/galileo_g1_locomanip_pick_and_place_environment.py +++ b/isaaclab_arena_environments/galileo_g1_locomanip_pick_and_place_environment.py @@ -5,7 +5,7 @@ import argparse -from isaaclab_arena.examples.example_environments.example_environment_base import ExampleEnvironmentBase +from isaaclab_arena_environments.example_environment_base import ExampleEnvironmentBase class GalileoG1LocomanipPickAndPlaceEnvironment(ExampleEnvironmentBase): diff --git a/isaaclab_arena/examples/example_environments/galileo_pick_and_place_environment.py b/isaaclab_arena_environments/galileo_pick_and_place_environment.py similarity index 96% rename from isaaclab_arena/examples/example_environments/galileo_pick_and_place_environment.py rename to isaaclab_arena_environments/galileo_pick_and_place_environment.py index 7e4a1ae5..eba4a66c 100644 --- a/isaaclab_arena/examples/example_environments/galileo_pick_and_place_environment.py +++ b/isaaclab_arena_environments/galileo_pick_and_place_environment.py @@ -5,7 +5,7 @@ import argparse -from isaaclab_arena.examples.example_environments.example_environment_base import ExampleEnvironmentBase +from isaaclab_arena_environments.example_environment_base import ExampleEnvironmentBase # NOTE(alexmillane, 2025.09.04): There is an issue with type annotation in this file. # We cannot annotate types which require the simulation app to be started in order to diff --git a/isaaclab_arena/examples/example_environments/gr1_open_microwave_environment.py b/isaaclab_arena_environments/gr1_open_microwave_environment.py similarity index 96% rename from isaaclab_arena/examples/example_environments/gr1_open_microwave_environment.py rename to isaaclab_arena_environments/gr1_open_microwave_environment.py index d2161181..4d87e0be 100644 --- a/isaaclab_arena/examples/example_environments/gr1_open_microwave_environment.py +++ b/isaaclab_arena_environments/gr1_open_microwave_environment.py @@ -5,7 +5,7 @@ import argparse -from isaaclab_arena.examples.example_environments.example_environment_base import ExampleEnvironmentBase +from isaaclab_arena_environments.example_environment_base import ExampleEnvironmentBase # NOTE(alexmillane, 2025.09.04): There is an issue with type annotation in this file. # We cannot annotate types which require the simulation app to be started in order to diff --git a/isaaclab_arena/examples/example_environments/kitchen_pick_and_place_environment.py b/isaaclab_arena_environments/kitchen_pick_and_place_environment.py similarity index 96% rename from isaaclab_arena/examples/example_environments/kitchen_pick_and_place_environment.py rename to isaaclab_arena_environments/kitchen_pick_and_place_environment.py index 902d320d..bf183c1e 100644 --- a/isaaclab_arena/examples/example_environments/kitchen_pick_and_place_environment.py +++ b/isaaclab_arena_environments/kitchen_pick_and_place_environment.py @@ -5,7 +5,7 @@ import argparse -from isaaclab_arena.examples.example_environments.example_environment_base import ExampleEnvironmentBase +from isaaclab_arena_environments.example_environment_base import ExampleEnvironmentBase # NOTE(alexmillane, 2025.09.04): There is an issue with type annotation in this file. # We cannot annotate types which require the simulation app to be started in order to diff --git a/isaaclab_arena/examples/example_environments/press_button_environment.py b/isaaclab_arena_environments/press_button_environment.py similarity index 95% rename from isaaclab_arena/examples/example_environments/press_button_environment.py rename to isaaclab_arena_environments/press_button_environment.py index 01851709..ad84cbbf 100644 --- a/isaaclab_arena/examples/example_environments/press_button_environment.py +++ b/isaaclab_arena_environments/press_button_environment.py @@ -5,7 +5,7 @@ import argparse -from isaaclab_arena.examples.example_environments.example_environment_base import ExampleEnvironmentBase +from isaaclab_arena_environments.example_environment_base import ExampleEnvironmentBase # NOTE(alexmillane, 2025.09.04): There is an issue with type annotation in this file. # We cannot annotate types which require the simulation app to be started in order to diff --git a/setup.py b/setup.py index efd26a65..dd50ac36 100644 --- a/setup.py +++ b/setup.py @@ -12,7 +12,9 @@ name="isaaclab_arena", version=ISAACLAB_ARENA_VERSION_NUMBER, description="Isaac Lab - Arena. An Isaac Lab extension for robotic policy evaluation. ", - packages=find_packages(include=["isaaclab_arena*", "isaaclab_arena_g1*", "isaaclab_arena_gr00t*"]), + packages=find_packages( + include=["isaaclab_arena*", "isaaclab_arena_environments*", "isaaclab_arena_g1*", "isaaclab_arena_gr00t*"] + ), python_requires=">=3.10", zip_safe=False, ) From e92e000dc94a19e344536f215886e7cba80ad559 Mon Sep 17 00:00:00 2001 From: Alex Millane Date: Thu, 11 Dec 2025 22:06:54 +0100 Subject: [PATCH 13/26] multi-versioned docs (#272) ## Summary Move the multi-versioned docs now that we have multiple version of Isaac Lab Arena. ## Detailed description - Means users can read the version of the docs that shipped the release that they're using. version_sidebar --- .github/workflows/ci.yml | 15 +++++++++++---- .github/workflows/gh-pages.yml | 6 +++--- docs/Makefile | 10 ++++++++-- docs/_redirect/index.html | 2 +- docs/_templates/versioning.html | 21 +++++++++++++++++++++ docs/conf.py | 16 ++++++++-------- docs/requirements.txt | 1 + 7 files changed, 53 insertions(+), 18 deletions(-) create mode 100644 docs/_templates/versioning.html diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 5e968a73..5336b827 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -169,16 +169,23 @@ jobs: steps: # Setup. - *install_git_step + - *mark_repo_safe_step - *cleanup_step - - *checkout_step + + # Checkout all branches, and tags, such that sphinx-multiversion can build the docs for all versions. + - name: Checkout Code + uses: actions/checkout@v4 + with: + fetch-depth: 0 + fetch-tags: true # Build docs - name: Build docs + working-directory: ./docs run: | - cd docs pip3 install -r requirements.txt - make SPHINXOPTS=-W html - touch ./_build/html/.nojekyll + make SPHINXOPTS=-W multi-docs + touch ./_build/.nojekyll build_and_push_image_post_merge: diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index d2e9326d..60f5e7ba 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -28,7 +28,7 @@ env: jobs: deploy_docs: name: Deploy the docs - runs-on: [self-hosted, zurich] + runs-on: [self-hosted, gpu] timeout-minutes: 30 container: @@ -54,8 +54,8 @@ jobs: run: | cd docs pip3 install -r requirements.txt - make SPHINXOPTS=-W html - touch ./_build/html/.nojekyll + make SPHINXOPTS=-W multi-docs + touch ./_build/.nojekyll - name: Copy redirect file run: | diff --git a/docs/Makefile b/docs/Makefile index 7628ba03..fcf55618 100644 --- a/docs/Makefile +++ b/docs/Makefile @@ -10,12 +10,18 @@ BUILDDIR = _build # Put it first so that "make" without argument is like "make help". +.PHONY: help Makefile help: @$(SPHINXBUILD) -M help "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) -.PHONY: help Makefile + +.PHONY: multi-docs +multi-docs: + @sphinx-multiversion --verbose "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) + @cp _redirect/index.html $(BUILDDIR)/index.html + # Catch-all target: route all unknown targets to Sphinx using the new # "make mode" option. $(O) is meant as a shortcut for $(SPHINXOPTS). %: Makefile - @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)" $(SPHINXOPTS) $(O) + @$(SPHINXBUILD) -M $@ "$(SOURCEDIR)" "$(BUILDDIR)/current" $(SPHINXOPTS) $(O) diff --git a/docs/_redirect/index.html b/docs/_redirect/index.html index eeb3b9f5..c6758313 100644 --- a/docs/_redirect/index.html +++ b/docs/_redirect/index.html @@ -3,6 +3,6 @@ Redirecting to the latest Isaac Lab Arena documentation - + diff --git a/docs/_templates/versioning.html b/docs/_templates/versioning.html new file mode 100644 index 00000000..eb67be60 --- /dev/null +++ b/docs/_templates/versioning.html @@ -0,0 +1,21 @@ +{% if versions %} + +{% endif %} diff --git a/docs/conf.py b/docs/conf.py index b2b3b285..6c26a8cc 100644 --- a/docs/conf.py +++ b/docs/conf.py @@ -66,6 +66,7 @@ "sphinx_tabs.tabs", "sphinx_design", "sphinx_copybutton", + "sphinx_multiversion", "isaaclab_arena_doc_tools", ] @@ -87,7 +88,7 @@ # List of patterns, relative to source directory, that match files and # directories to ignore when looking for source files. # This pattern also affects html_static_path and html_extra_path. -exclude_patterns = ["_build", "Thumbs.db", ".DS_Store", "venv_docs"] +exclude_patterns = ["_build", "_templates", "Thumbs.db", ".DS_Store", "venv_docs"] # Be picky about missing references nitpicky = True # warns on broken references @@ -119,20 +120,19 @@ # Add any paths that contain custom static files (such as style sheets) here, # relative to this directory. They are copied after the builtin static files, # so a file named "default.css" will overwrite the builtin "default.css". -# html_static_path = [] html_static_path = ["_static"] html_css_files = ["custom.css"] +# Versioning +smv_remote_whitelist = r"^.*$" +smv_branch_whitelist = r"^(main|release/.*)$" +smv_tag_whitelist = r"^v.*$" +html_sidebars = {"**": ["versioning.html", "sidebar-nav-bs"]} # Todos todo_include_todos = True # Linkcheck -# NOTE(alexmillane, 2025-05-09): The links in the main example page are relative links -# which are only valid post-build. linkcheck doesn't like this. So here we ignore -# links to the example pages via html. -linkcheck_ignore = [ - # r'pages/torch_examples_.*\.html', # Ignore all pages/torch_examples_*.html links -] +linkcheck_ignore = [] temporary_linkcheck_ignore = [ # TemporaryLinkcheckIgnore( diff --git a/docs/requirements.txt b/docs/requirements.txt index 355ec9d9..05ddcc95 100644 --- a/docs/requirements.txt +++ b/docs/requirements.txt @@ -1,4 +1,5 @@ sphinx==8.2.3 +sphinx-multiversion==0.2.4 sphinx_copybutton==0.5.2 sphinx_tabs==3.4.7 nvidia-sphinx-theme==0.0.8 From 4c267fbd43998f9caae5c27be5e383ed42cfc5dc Mon Sep 17 00:00:00 2001 From: Xinjie Yao Date: Fri, 12 Dec 2025 01:52:55 -0800 Subject: [PATCH 14/26] Refactor tear down func for persistent app (#282) ## Summary Tear down simulation app func could be useful both in core & tests. Prep for it to be consumed. ## Detailed description - Add USD `get_new_stage()` to jupyter notebook example, resolving issue where USDs from previous run are not removed - Add optional `suppress_exception `to let exception raised by default, or ignored in tests - Move this func to `isaaclab_utils` --- .../examples/example_env_notebook.py | 12 +---- isaaclab_arena/tests/test_device_registry.py | 5 +- isaaclab_arena/tests/utils/subprocess.py | 43 +--------------- .../utils/isaaclab_utils/simulation_app.py | 50 +++++++++++++++++++ 4 files changed, 57 insertions(+), 53 deletions(-) diff --git a/isaaclab_arena/examples/example_env_notebook.py b/isaaclab_arena/examples/example_env_notebook.py index 2fa520df..a56d5d72 100644 --- a/isaaclab_arena/examples/example_env_notebook.py +++ b/isaaclab_arena/examples/example_env_notebook.py @@ -55,14 +55,6 @@ env.step(actions) # %% +from isaaclab_arena.utils.isaaclab_utils.simulation_app import teardown_simulation_app -from isaaclab.sim import SimulationContext - -simulation_context = SimulationContext.instance() -simulation_context._disable_app_control_on_stop_handle = True -simulation_context.stop() -simulation_context.clear_instance() -env.close() -import omni.timeline - -omni.timeline.get_timeline_interface().stop() +teardown_simulation_app(suppress_exceptions=False, make_new_stage=True) diff --git a/isaaclab_arena/tests/test_device_registry.py b/isaaclab_arena/tests/test_device_registry.py index 03bb34f3..c4a9a3e7 100644 --- a/isaaclab_arena/tests/test_device_registry.py +++ b/isaaclab_arena/tests/test_device_registry.py @@ -8,7 +8,8 @@ import tqdm from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function, safe_teardown +from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function +from isaaclab_arena.utils.isaaclab_utils.simulation_app import teardown_simulation_app NUM_STEPS = 2 HEADLESS = True @@ -63,7 +64,7 @@ def _test_all_devices_in_registry(simulation_app): # Close the environment using safe teardown # Also creates a new stage for the next test - safe_teardown() + teardown_simulation_app(suppress_exceptions=True, make_new_stage=True) return True diff --git a/isaaclab_arena/tests/utils/subprocess.py b/isaaclab_arena/tests/utils/subprocess.py index 671a41be..081e3ed2 100644 --- a/isaaclab_arena/tests/utils/subprocess.py +++ b/isaaclab_arena/tests/utils/subprocess.py @@ -8,13 +8,12 @@ import subprocess import sys from collections.abc import Callable -from contextlib import suppress from isaaclab.app import AppLauncher from isaacsim import SimulationApp from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.utils.isaaclab_utils.simulation_app import get_app_launcher +from isaaclab_arena.utils.isaaclab_utils.simulation_app import get_app_launcher, teardown_simulation_app _PERSISTENT_SIM_APP_LAUNCHER: AppLauncher | None = None _PERSISTENT_INIT_ARGS = None # store (headless, enable_cameras) used at first init @@ -57,44 +56,6 @@ def __exit__(self, exc_type, exc, tb): sys.argv = self._old -def safe_teardown(make_new_stage: bool = True) -> None: - """ - Best-effort reset so the persistent SimulationApp can accept the next test. - Runs even if a test fails or raises. - """ - with suppress(Exception): - # Local import to avoid loading Isaac/Kit unless needed. - from isaaclab.sim import SimulationContext - - sim = None - with suppress(Exception): - sim = SimulationContext.instance() - - # Stop the simulation app - if sim is not None: - with suppress(Exception): - # Some versions gate shutdown on this flag. - sim._disable_app_control_on_stop_handle = True # noqa: SLF001 (intentional private attr) - with suppress(Exception): - sim.stop() - with suppress(Exception): - sim.clear_instance() - - # Stop the timeline - with suppress(Exception): - import omni.timeline - - with suppress(Exception): - omni.timeline.get_timeline_interface().stop() - - # Finally, start a fresh USD stage for the next test - if make_new_stage: - with suppress(Exception): - import omni.usd - - omni.usd.get_context().new_stage() - - def _close_persistent(): global _PERSISTENT_SIM_APP_LAUNCHER if _PERSISTENT_SIM_APP_LAUNCHER is not None: @@ -165,4 +126,4 @@ def run_simulation_app_function( return False finally: # **Always** clean up the SimulationContext/timeline between tests - safe_teardown() + teardown_simulation_app(suppress_exceptions=True, make_new_stage=True) diff --git a/isaaclab_arena/utils/isaaclab_utils/simulation_app.py b/isaaclab_arena/utils/isaaclab_utils/simulation_app.py index 33a737c6..08cc6470 100644 --- a/isaaclab_arena/utils/isaaclab_utils/simulation_app.py +++ b/isaaclab_arena/utils/isaaclab_utils/simulation_app.py @@ -7,6 +7,7 @@ import os import sys import traceback +from contextlib import nullcontext, suppress import omni.kit.app from isaaclab.app import AppLauncher @@ -31,6 +32,55 @@ def get_app_launcher(args: argparse.Namespace) -> AppLauncher: return app_launcher +def teardown_simulation_app(suppress_exceptions: bool = False, make_new_stage: bool = True) -> None: + """ + Tear down the SimulationApp and start a fresh USD stage preparing for the next content. + Useful for loading new content into the SimulationApp without restarting the app. + + Args: + suppress_exceptions: Whether to suppress exceptions. If True, the exception will be caught and the execution will continue. If False, the exception will be propagated. + make_new_stage: Whether to make a new USD stage. If True, a new USD stage will be created. If False, the current USD stage will be used. + """ + if suppress_exceptions: + # silently caught exceptions and continue the execution. + error_manager = suppress(Exception) + else: + # Do nothing and let the exception to be raised. + error_manager = nullcontext() + + with error_manager: + # Local import to avoid loading Isaac/Kit unless needed. + from isaaclab.sim import SimulationContext + + sim = None + with error_manager: + sim = SimulationContext.instance() + + # Stop the simulation app + if sim is not None: + with error_manager: + # Some versions gate shutdown on this flag. + sim._disable_app_control_on_stop_handle = True # noqa: SLF001 (intentional private attr) + with error_manager: + sim.stop() + with error_manager: + sim.clear_instance() + + # Stop the timeline + with error_manager: + import omni.timeline + + with error_manager: + omni.timeline.get_timeline_interface().stop() + + # Finally, start a fresh USD stage for the next test + if make_new_stage: + with error_manager: + import omni.usd + + omni.usd.get_context().new_stage() + + class SimulationAppContext: """Context manager for launching and closing a simulation app.""" From deb3913c9426c2d9af23e1450baada94a1fad3d6 Mon Sep 17 00:00:00 2001 From: Alex Millane Date: Fri, 12 Dec 2025 13:28:28 +0100 Subject: [PATCH 15/26] Fix git ownership issues in deployment pipeline. (#284) ## Summary Fix git ownership issues in deployment pipeline. ## Detailed description - Multi-version docs now require git during documentation build. - This revealed git ownership issues in the page deployment pipeline (previously seen in our pre-merge pipeline) - This MR applies the same fix that's used in pre-merge. --- .github/workflows/gh-pages.yml | 19 +++++-------------- 1 file changed, 5 insertions(+), 14 deletions(-) diff --git a/.github/workflows/gh-pages.yml b/.github/workflows/gh-pages.yml index 60f5e7ba..59f1db41 100644 --- a/.github/workflows/gh-pages.yml +++ b/.github/workflows/gh-pages.yml @@ -48,6 +48,11 @@ jobs: with: clean: true fetch-depth: 0 + fetch-tags: true + + # Fix "detected dubious ownership in repository" inside containers + - name: Mark repo as safe for git + run: git config --global --add safe.directory "$PWD" # Build docs - name: Build docs @@ -61,20 +66,6 @@ jobs: run: | cp ./docs/_redirect/index.html ./docs/_build/index.html - # Upload docs artifact - - name: Upload docs artifact - uses: actions/upload-artifact@v4 - with: - name: docs-html - path: ./docs/_build - - # Download docs artifact - - name: Download docs artifact - uses: actions/download-artifact@v4 - with: - name: docs-html - path: ./docs/_build - # Deploy to gh-pages - name: Deploy to gh-pages uses: peaceiris/actions-gh-pages@v3 From dba09956588dddae52897820686efd329d85da12 Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Fri, 12 Dec 2025 17:26:28 +0100 Subject: [PATCH 16/26] Update README.md (#288) --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 85a6e1db..004484dc 100644 --- a/README.md +++ b/README.md @@ -6,7 +6,7 @@ Isaac-Lab Arena is a comprehensive robotics simulation framework that enhances NVIDIA Isaac Lab by providing a composable, scalable system for creating diverse simulation environments and evaluating robot learning policies. The framework enables researchers and developers to rapidly prototype and test robotic tasks with various robot embodiments, objects, and environments. -To get started with Isaac-Lab Arena, see our [documentation site](https://isaac-sim.github.io/IsaacLab-Arena/html/index.html). +To get started with Isaac-Lab Arena, see our [documentation site](https://isaac-sim.github.io/IsaacLab-Arena/main/index.html).
From b4feca387f280e3d2d08ed3c4825f7877ab709f4 Mon Sep 17 00:00:00 2001 From: peterd-NV Date: Mon, 15 Dec 2025 13:57:28 -0800 Subject: [PATCH 17/26] Update object library paths to use ISAAC_NUCLEUS_DIR prefix (#291) ## Summary Update object library to use ISAAC_NUCLEUS_DIR prefix for YCB object usd paths --- isaaclab_arena/assets/object_library.py | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/isaaclab_arena/assets/object_library.py b/isaaclab_arena/assets/object_library.py index 66b75edb..1e4e5c15 100644 --- a/isaaclab_arena/assets/object_library.py +++ b/isaaclab_arena/assets/object_library.py @@ -5,7 +5,7 @@ import isaaclab.sim as sim_utils from isaaclab.sim.spawners.from_files.from_files_cfg import GroundPlaneCfg -from isaaclab.utils.assets import ISAACLAB_NUCLEUS_DIR +from isaaclab.utils.assets import ISAAC_NUCLEUS_DIR, ISAACLAB_NUCLEUS_DIR from isaaclab_arena.affordances.openable import Openable from isaaclab_arena.affordances.pressable import Pressable @@ -40,8 +40,6 @@ def __init__(self, prim_path: str | None = None, initial_pose: Pose | None = Non ) -# TODO(peterd, 2025.11.05): Update all OV drive paths to use {ISAACLAB_NUCLEUS_DIR} -# alias prior to public release once assets are synced to S3 @register_asset class CrackerBox(LibraryObject): """ @@ -50,7 +48,7 @@ class CrackerBox(LibraryObject): name = "cracker_box" tags = ["object"] - usd_path = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/4.5/Isaac/Props/YCB/Axis_Aligned_Physics/003_cracker_box.usd" + usd_path = f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/003_cracker_box.usd" def __init__(self, prim_path: str | None = None, initial_pose: Pose | None = None): super().__init__(prim_path=prim_path, initial_pose=initial_pose) @@ -64,7 +62,7 @@ class MustardBottle(LibraryObject): name = "mustard_bottle" tags = ["object"] - usd_path = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/4.5/Isaac/Props/YCB/Axis_Aligned_Physics/006_mustard_bottle.usd" + usd_path = f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/006_mustard_bottle.usd" def __init__(self, prim_path: str | None = None, initial_pose: Pose | None = None): super().__init__(prim_path=prim_path, initial_pose=initial_pose) @@ -78,7 +76,7 @@ class SugarBox(LibraryObject): name = "sugar_box" tags = ["object"] - usd_path = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/4.5/Isaac/Props/YCB/Axis_Aligned_Physics/004_sugar_box.usd" + usd_path = f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/004_sugar_box.usd" def __init__(self, prim_path: str | None = None, initial_pose: Pose | None = None): super().__init__(prim_path=prim_path, initial_pose=initial_pose) @@ -92,7 +90,7 @@ class TomatoSoupCan(LibraryObject): name = "tomato_soup_can" tags = ["object"] - usd_path = "https://omniverse-content-production.s3-us-west-2.amazonaws.com/Assets/Isaac/4.5/Isaac/Props/YCB/Axis_Aligned_Physics/005_tomato_soup_can.usd" + usd_path = f"{ISAAC_NUCLEUS_DIR}/Props/YCB/Axis_Aligned_Physics/005_tomato_soup_can.usd" def __init__(self, prim_path: str | None = None, initial_pose: Pose | None = None): super().__init__(prim_path=prim_path, initial_pose=initial_pose) From 415a327670071bdca911d2a2432ef960328770ad Mon Sep 17 00:00:00 2001 From: Rebecca Zhang <168459200+rebeccazhang0707@users.noreply.github.com> Date: Tue, 16 Dec 2025 11:47:28 +0800 Subject: [PATCH 18/26] Refactors mimic_env_cfg building logic in arena_env_builder (#273) ## Summary Refactor `mimic_env_cfg` building logic in `arena_env_builder`. ## Detailed description - What was the reason for the change? - Originally we need to maintain a list of embodiment_names in each task's MimicEnvCfg, given its single_arm or dual_arm. It is not efficient and scalable. - What has been changed? - creates a new enum class `MimicArmMode` to represent the arm mode for the mimic environment: can select from ["single_arm", "dual_arm", "left", "right"] - assigns a property of 'mimic_arm_mode' to embodiment_base - changes task.get_mimic_env_cfg() method's input from 'embodiment_name' to 'mimic_arm_mode' - refactors the SubTaskConfigs configuration logic in each MimicEnvCfg based on embodiment.mimic_arm_mode - What is the impact of this change? - all existing embodiments and tasks with MimicEnvCfg. --- .../concepts/concept_embodiment_design.rst | 62 ++++++++++++++++++- docs/pages/concepts/concept_tasks_design.rst | 2 +- .../embodiments/common/mimic_arm_mode.py | 27 ++++++++ isaaclab_arena/embodiments/embodiment_base.py | 10 ++- isaaclab_arena/embodiments/franka/franka.py | 8 ++- isaaclab_arena/embodiments/g1/g1.py | 8 ++- isaaclab_arena/embodiments/gr1t2/gr1t2.py | 8 ++- .../environments/arena_env_builder.py | 4 +- isaaclab_arena/tasks/dummy_task.py | 3 +- .../tasks/g1_locomanip_pick_and_place_task.py | 6 +- isaaclab_arena/tasks/open_door_task.py | 20 +++--- isaaclab_arena/tasks/pick_and_place_task.py | 20 +++--- isaaclab_arena/tasks/press_button_task.py | 3 +- isaaclab_arena/tasks/task_base.py | 7 ++- 14 files changed, 158 insertions(+), 30 deletions(-) create mode 100644 isaaclab_arena/embodiments/common/mimic_arm_mode.py diff --git a/docs/pages/concepts/concept_embodiment_design.rst b/docs/pages/concepts/concept_embodiment_design.rst index 622c0b8a..c3b78d9e 100644 --- a/docs/pages/concepts/concept_embodiment_design.rst +++ b/docs/pages/concepts/concept_embodiment_design.rst @@ -13,8 +13,9 @@ Embodiments use the ``EmbodimentBase`` abstract class that extends the asset sys class EmbodimentBase(Asset): name: str | None = None tags: list[str] = ["embodiment"] + mimic_arm_mode: MimicArmMode | None = None - def __init__(self, enable_cameras: bool = False, initial_pose: Pose | None = None): + def __init__(self, enable_cameras: bool = False, initial_pose: Pose | None = None, mimic_arm_mode: MimicArmMode | None = None): self.scene_config: Any | None = None self.action_config: Any | None = None self.observation_config: Any | None = None @@ -42,6 +43,7 @@ Embodiments in Detail - **XR Configuration**: XR device locations for teleop integration (optional) - **Mimic Configuration**: Mimic environment support for demonstration (optional) + **Available Embodiments** Robot assets with different capabilities and control modes: @@ -53,6 +55,64 @@ Embodiments in Detail **Camera Integration** Optional camera systems that add observation terms when enabled, supporting both manipulation and perception tasks with head-mounted or external cameras. + +**Mimic Arm Mode** + Embodiments expose an ``mimic_arm_mode`` attribute that declares which arms are + movable for demonstration playback. This attribute uses the + ``MimicArmMode`` enum from ``isaaclab_arena.embodiments.common.mimic_arm_mode``: + + - **SINGLE_ARM** – the robot has only one arm. + - **DUAL_ARM** – bimanual robot, task is performed with both arms in the demonstration. + - **LEFT** – bimanual robot, task is performed with the left arm and right arm is idle. + - **RIGHT** – bimanual robot, task is performed with the right arm and left arm is idle. + + Tasks and mimic environment builders consult this property to request the correct + subtask configurations, ensuring that mimic environments match the + capabilities of the selected embodiment. + + .. code-block:: python + + class PickAndPlaceTask(TaskBase): + """ Task class """ + + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): + # gets the mimic environment configuration based on embodiment's mimic arm mode. + return PickPlaceMimicEnvCfg( + arm_mode=arm_mode, + pick_up_object_name=self.pick_up_object.name, + destination_location_name=self.destination_location.name, + ) + + @configclass + class PickPlaceMimicEnvCfg(MimicEnvCfg): + """Mimic environment configuration class""" + + arm_mode: MimicArmMode = MimicArmMode.SINGLE_ARM + + def __post_init__(self): + super().__post_init__() + + # defines the subtask configurations based on the mimic arm mode. + if self.arm_mode == "single_arm": + # single arm subtask configuration + elif self.arm_mode in ["left", "right"]: + # bimanual robot with one arm idle subtask configuration + elif self.arm_mode == "dual_arm": + # dual arm subtask configuration + else: + # raise error for unsupported mimic arm mode + + class ArenaEnvBuilder: + """ ArenaEnvBuilder class """ + + def compose_manager_cfg(self): + # composes the mimic environment configuration based on embodiment's mimic arm mode. + task_mimic_env_cfg = self.arena_env.task.get_mimic_env_cfg( + arm_mode=self.arena_env.embodiment.mimic_arm_mode + ) + return task_mimic_env_cfg + + Environment Integration ----------------------- diff --git a/docs/pages/concepts/concept_tasks_design.rst b/docs/pages/concepts/concept_tasks_design.rst index bac92791..a3e94d08 100644 --- a/docs/pages/concepts/concept_tasks_design.rst +++ b/docs/pages/concepts/concept_tasks_design.rst @@ -28,7 +28,7 @@ Tasks use the ``TaskBase`` abstract class: """Performance evaluation metrics.""" @abstractmethod - def get_mimic_env_cfg(self, embodiment_name: str) -> Any: + def get_mimic_env_cfg(self, arm_mode: MimicArmMode) -> Any: """Demonstration generation configuration.""" Tasks in Detail diff --git a/isaaclab_arena/embodiments/common/mimic_arm_mode.py b/isaaclab_arena/embodiments/common/mimic_arm_mode.py new file mode 100644 index 00000000..e6bfc2d6 --- /dev/null +++ b/isaaclab_arena/embodiments/common/mimic_arm_mode.py @@ -0,0 +1,27 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +from enum import Enum + + +class MimicArmMode(str, Enum): + """ + The arm mode for the mimic environment configuration. + + Attributes: + SINGLE_ARM: Single arm mode (the robot has only one arm). + DUAL_ARM: Dual arm mode (bimanual robot, task is performed with both arms in the demonstration). + LEFT: Left arm mode (bimanual robot, task is performed with the left arm in the demonstration, right arm is idle). + RIGHT: Right arm mode (bimanual robot, task is performed with the right arm in the demonstration, left arm is idle). + """ + + SINGLE_ARM = "single_arm" + DUAL_ARM = "dual_arm" + LEFT = "left" + RIGHT = "right" + + def get_other_arm(self) -> str: + assert self in [MimicArmMode.LEFT, MimicArmMode.RIGHT], f"Arm mode {self} is not a bimanual arm mode" + return MimicArmMode.RIGHT if self == MimicArmMode.LEFT else MimicArmMode.LEFT diff --git a/isaaclab_arena/embodiments/embodiment_base.py b/isaaclab_arena/embodiments/embodiment_base.py index e5be80de..c7bc56e2 100644 --- a/isaaclab_arena/embodiments/embodiment_base.py +++ b/isaaclab_arena/embodiments/embodiment_base.py @@ -9,6 +9,7 @@ from isaaclab.managers.recorder_manager import RecorderManagerBaseCfg from isaaclab_arena.assets.asset import Asset +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.environments.isaaclab_arena_manager_based_env import IsaacLabArenaManagerBasedRLEnvCfg from isaaclab_arena.utils.cameras import make_camera_observation_cfg from isaaclab_arena.utils.configclass import combine_configclass_instances @@ -19,10 +20,14 @@ class EmbodimentBase(Asset): name: str | None = None tags: list[str] = ["embodiment"] + default_mimic_arm_mode: MimicArmMode | None = None - def __init__(self, enable_cameras: bool = False, initial_pose: Pose | None = None): + def __init__( + self, enable_cameras: bool = False, initial_pose: Pose | None = None, mimic_arm_mode: MimicArmMode | None = None + ): self.enable_cameras = enable_cameras self.initial_pose = initial_pose + self.mimic_arm_mode = mimic_arm_mode or self.default_mimic_arm_mode # These should be filled by the subclass self.scene_config: Any | None = None self.camera_config: Any | None = None @@ -101,3 +106,6 @@ def get_termination_cfg(self) -> Any: def modify_env_cfg(self, env_cfg: IsaacLabArenaManagerBasedRLEnvCfg) -> IsaacLabArenaManagerBasedRLEnvCfg: return env_cfg + + def get_mimic_arm_mode(self) -> MimicArmMode: + return self.mimic_arm_mode diff --git a/isaaclab_arena/embodiments/franka/franka.py b/isaaclab_arena/embodiments/franka/franka.py index 9e2a5855..be443301 100644 --- a/isaaclab_arena/embodiments/franka/franka.py +++ b/isaaclab_arena/embodiments/franka/franka.py @@ -28,6 +28,7 @@ from isaaclab_tasks.manager_based.manipulation.stack.mdp.observations import ee_frame_pos, ee_frame_quat from isaaclab_arena.assets.register import register_asset +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.embodiments.common.mimic_utils import get_rigid_and_articulated_object_poses from isaaclab_arena.embodiments.embodiment_base import EmbodimentBase from isaaclab_arena.embodiments.franka.observations import gripper_pos @@ -39,9 +40,12 @@ class FrankaEmbodiment(EmbodimentBase): """Embodiment for the Franka robot.""" name = "franka" + default_mimic_arm_mode = MimicArmMode.SINGLE_ARM - def __init__(self, enable_cameras: bool = False, initial_pose: Pose | None = None): - super().__init__(enable_cameras, initial_pose) + def __init__( + self, enable_cameras: bool = False, initial_pose: Pose | None = None, mimic_arm_mode: MimicArmMode | None = None + ): + super().__init__(enable_cameras, initial_pose, mimic_arm_mode) self.scene_config = FrankaSceneCfg() self.action_config = FrankaActionsCfg() self.observation_config = FrankaObservationsCfg() diff --git a/isaaclab_arena/embodiments/g1/g1.py b/isaaclab_arena/embodiments/g1/g1.py index 48fbc9bb..ba7f3bd6 100644 --- a/isaaclab_arena/embodiments/g1/g1.py +++ b/isaaclab_arena/embodiments/g1/g1.py @@ -26,6 +26,7 @@ import isaaclab_arena.terms.transforms as transforms_terms from isaaclab_arena.assets.register import register_asset +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.embodiments.embodiment_base import EmbodimentBase from isaaclab_arena.utils.isaaclab_utils.resets import reset_all_articulation_joints from isaaclab_arena.utils.pose import Pose @@ -39,9 +40,12 @@ class G1EmbodimentBase(EmbodimentBase): """Embodiment for the G1 robot.""" name = "g1" + default_mimic_arm_mode = MimicArmMode.DUAL_ARM - def __init__(self, enable_cameras: bool = False, initial_pose: Pose | None = None): - super().__init__(enable_cameras, initial_pose) + def __init__( + self, enable_cameras: bool = False, initial_pose: Pose | None = None, mimic_arm_mode: MimicArmMode | None = None + ): + super().__init__(enable_cameras, initial_pose, mimic_arm_mode) # Configuration structs self.scene_config = G1SceneCfg() self.camera_config = G1CameraCfg() diff --git a/isaaclab_arena/embodiments/gr1t2/gr1t2.py b/isaaclab_arena/embodiments/gr1t2/gr1t2.py index 4eaaa5e3..b2f3b316 100644 --- a/isaaclab_arena/embodiments/gr1t2/gr1t2.py +++ b/isaaclab_arena/embodiments/gr1t2/gr1t2.py @@ -28,6 +28,7 @@ from isaaclab_tasks.manager_based.manipulation.pick_place.pickplace_gr1t2_env_cfg import ActionsCfg as GR1T2ActionsCfg from isaaclab_arena.assets.register import register_asset +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.embodiments.common.mimic_utils import get_rigid_and_articulated_object_poses from isaaclab_arena.embodiments.embodiment_base import EmbodimentBase from isaaclab_arena.utils.isaaclab_utils.resets import reset_all_articulation_joints @@ -83,9 +84,12 @@ class GR1T2EmbodimentBase(EmbodimentBase): """Embodiment for the GR1T2 robot.""" name = "gr1" + default_mimic_arm_mode = MimicArmMode.RIGHT - def __init__(self, enable_cameras: bool = False, initial_pose: Pose | None = None): - super().__init__(enable_cameras, initial_pose) + def __init__( + self, enable_cameras: bool = False, initial_pose: Pose | None = None, mimic_arm_mode: MimicArmMode | None = None + ): + super().__init__(enable_cameras, initial_pose, mimic_arm_mode) # Configuration structs self.scene_config = GR1T2SceneCfg() self.observation_config = GR1T2ObservationsCfg() diff --git a/isaaclab_arena/environments/arena_env_builder.py b/isaaclab_arena/environments/arena_env_builder.py index 436f0481..420b138f 100644 --- a/isaaclab_arena/environments/arena_env_builder.py +++ b/isaaclab_arena/environments/arena_env_builder.py @@ -145,7 +145,9 @@ def compose_manager_cfg(self) -> IsaacLabArenaManagerBasedRLEnvCfg: if episode_length_s is not None: env_cfg.episode_length_s = episode_length_s else: - task_mimic_env_cfg = self.arena_env.task.get_mimic_env_cfg(embodiment_name=self.arena_env.embodiment.name) + task_mimic_env_cfg = self.arena_env.task.get_mimic_env_cfg( + arm_mode=self.arena_env.embodiment.mimic_arm_mode + ) env_cfg = IsaacArenaManagerBasedMimicEnvCfg( observations=observation_cfg, actions=actions_cfg, diff --git a/isaaclab_arena/tasks/dummy_task.py b/isaaclab_arena/tasks/dummy_task.py index 8d2ba948..ff319ebf 100644 --- a/isaaclab_arena/tasks/dummy_task.py +++ b/isaaclab_arena/tasks/dummy_task.py @@ -5,6 +5,7 @@ from isaaclab.envs.common import ViewerCfg +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.tasks.task_base import TaskBase @@ -24,7 +25,7 @@ def get_events_cfg(self): def get_prompt(self): pass - def get_mimic_env_cfg(self, embodiment_name: str): + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): pass def get_metrics(self): diff --git a/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py b/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py index a4117709..3ac8ff56 100644 --- a/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py +++ b/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py @@ -16,6 +16,7 @@ from isaaclab_tasks.manager_based.manipulation.stack.mdp import franka_stack_events from isaaclab_arena.assets.asset import Asset +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.metrics.metric_base import MetricBase from isaaclab_arena.metrics.success_rate import SuccessRateMetric from isaaclab_arena.tasks.task_base import TaskBase @@ -72,7 +73,10 @@ def get_termination_cfg(self): def get_events_cfg(self): return EventsCfg(pick_up_object=self.pick_up_object) - def get_mimic_env_cfg(self, embodiment_name: str): + def get_prompt(self): + raise NotImplementedError("Function not implemented yet.") + + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): return G1LocomanipPickPlaceMimicEnvCfg() def get_metrics(self) -> list[MetricBase]: diff --git a/isaaclab_arena/tasks/open_door_task.py b/isaaclab_arena/tasks/open_door_task.py index 035188c8..942b09ba 100644 --- a/isaaclab_arena/tasks/open_door_task.py +++ b/isaaclab_arena/tasks/open_door_task.py @@ -13,6 +13,7 @@ from isaaclab.utils import configclass from isaaclab_arena.affordances.openable import Openable +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.metrics.door_moved_rate import DoorMovedRateMetric from isaaclab_arena.metrics.metric_base import MetricBase from isaaclab_arena.metrics.success_rate import SuccessRateMetric @@ -61,9 +62,12 @@ def make_termination_cfg(self): def get_events_cfg(self): return self.events_cfg - def get_mimic_env_cfg(self, embodiment_name: str): + def get_prompt(self): + raise NotImplementedError("Function not implemented yet.") + + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): return OpenDoorMimicEnvCfg( - embodiment_name=embodiment_name, + arm_mode=arm_mode, openable_object_name=self.openable_object.name, ) @@ -127,7 +131,7 @@ class OpenDoorMimicEnvCfg(MimicEnvCfg): Isaac Lab Mimic environment config class for Open Door env. """ - embodiment_name: str = "franka" + arm_mode: MimicArmMode = MimicArmMode.SINGLE_ARM openable_object_name: str = "openable_object" @@ -200,11 +204,11 @@ def __post_init__(self): apply_noise_during_interpolation=False, ) ) - if self.embodiment_name == "franka": + if self.arm_mode == MimicArmMode.SINGLE_ARM: self.subtask_configs["robot"] = subtask_configs # We need to add the left and right subtasks for GR1. - elif self.embodiment_name == "gr1_pink": - self.subtask_configs["right"] = subtask_configs + elif self.arm_mode in [MimicArmMode.LEFT, MimicArmMode.RIGHT]: + self.subtask_configs[self.arm_mode] = subtask_configs # EEF on opposite side (arm is static) subtask_configs = [] subtask_configs.append( @@ -229,7 +233,7 @@ def __post_init__(self): apply_noise_during_interpolation=False, ) ) - self.subtask_configs["left"] = subtask_configs + self.subtask_configs[self.arm_mode.get_other_arm()] = subtask_configs else: - raise ValueError(f"Embodiment name {self.embodiment_name} not supported") + raise ValueError(f"Embodiment arm mode {self.arm_mode} not supported") diff --git a/isaaclab_arena/tasks/pick_and_place_task.py b/isaaclab_arena/tasks/pick_and_place_task.py index b1b9fdbd..a22b3099 100644 --- a/isaaclab_arena/tasks/pick_and_place_task.py +++ b/isaaclab_arena/tasks/pick_and_place_task.py @@ -14,6 +14,7 @@ from isaaclab.utils import configclass from isaaclab_arena.assets.asset import Asset +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.metrics.metric_base import MetricBase from isaaclab_arena.metrics.object_moved import ObjectMovedRateMetric from isaaclab_arena.metrics.success_rate import SuccessRateMetric @@ -81,9 +82,12 @@ def make_termination_cfg(self): def get_events_cfg(self): return self.events_cfg - def get_mimic_env_cfg(self, embodiment_name: str): + def get_prompt(self): + raise NotImplementedError("Function not implemented yet.") + + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): return PickPlaceMimicEnvCfg( - embodiment_name=embodiment_name, + arm_mode=arm_mode, pick_up_object_name=self.pick_up_object.name, destination_location_name=self.destination_location.name, ) @@ -147,7 +151,7 @@ class PickPlaceMimicEnvCfg(MimicEnvCfg): Isaac Lab Mimic environment config class for Pick and Place env. """ - embodiment_name: str = "franka" + arm_mode: MimicArmMode = MimicArmMode.SINGLE_ARM pick_up_object_name: str = "pick_up_object" @@ -222,11 +226,11 @@ def __post_init__(self): apply_noise_during_interpolation=False, ) ) - if self.embodiment_name == "franka": + if self.arm_mode == MimicArmMode.SINGLE_ARM: self.subtask_configs["robot"] = subtask_configs # We need to add the left and right subtasks for GR1. - elif self.embodiment_name == "gr1_pink": - self.subtask_configs["right"] = subtask_configs + elif self.arm_mode in [MimicArmMode.LEFT, MimicArmMode.RIGHT]: + self.subtask_configs[self.arm_mode] = subtask_configs # EEF on opposite side (arm is static) subtask_configs = [] subtask_configs.append( @@ -251,7 +255,7 @@ def __post_init__(self): apply_noise_during_interpolation=False, ) ) - self.subtask_configs["left"] = subtask_configs + self.subtask_configs[self.arm_mode.get_other_arm()] = subtask_configs else: - raise ValueError(f"Embodiment name {self.embodiment_name} not supported") + raise ValueError(f"Embodiment arm mode {self.arm_mode} not supported") diff --git a/isaaclab_arena/tasks/press_button_task.py b/isaaclab_arena/tasks/press_button_task.py index 6929187e..a08e35f0 100644 --- a/isaaclab_arena/tasks/press_button_task.py +++ b/isaaclab_arena/tasks/press_button_task.py @@ -12,6 +12,7 @@ from isaaclab.utils import configclass from isaaclab_arena.affordances.pressable import Pressable +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.metrics.metric_base import MetricBase from isaaclab_arena.metrics.success_rate import SuccessRateMetric from isaaclab_arena.tasks.task_base import TaskBase @@ -55,7 +56,7 @@ def get_events_cfg(self): def get_prompt(self): raise NotImplementedError("Function not implemented yet.") - def get_mimic_env_cfg(self, embodiment_name: str): + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): raise NotImplementedError("Function not implemented yet.") def get_metrics(self) -> list[MetricBase]: diff --git a/isaaclab_arena/tasks/task_base.py b/isaaclab_arena/tasks/task_base.py index 0a02edc5..a3eef38e 100644 --- a/isaaclab_arena/tasks/task_base.py +++ b/isaaclab_arena/tasks/task_base.py @@ -9,6 +9,7 @@ from isaaclab.envs.common import ViewerCfg from isaaclab.managers.recorder_manager import RecorderManagerBaseCfg +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode from isaaclab_arena.environments.isaaclab_arena_manager_based_env import IsaacLabArenaManagerBasedRLEnvCfg from isaaclab_arena.metrics.metric_base import MetricBase @@ -32,7 +33,11 @@ def get_events_cfg(self) -> Any: raise NotImplementedError("Function not implemented yet.") @abstractmethod - def get_mimic_env_cfg(self, embodiment_name: str) -> Any: + def get_prompt(self) -> str: + raise NotImplementedError("Function not implemented yet.") + + @abstractmethod + def get_mimic_env_cfg(self, arm_mode: MimicArmMode) -> Any: raise NotImplementedError("Function not implemented yet.") @abstractmethod From 3bb3ede2e5468680d3ea549639a4a2a0b445d0de Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Tue, 16 Dec 2025 15:31:14 +0100 Subject: [PATCH 19/26] add settings file to pick up packages for easier development (#294) ## Summary Add settings file --- .vscode/settings.json | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) create mode 100644 .vscode/settings.json diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 00000000..8e4075da --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,18 @@ +{ + "python.analysis.extraPaths": [ + "${workspaceFolder}", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_assets", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_rl", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_mimic", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_tasks", + ], + "cursorpyright.analysis.extraPaths": [ + "${workspaceFolder}", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_assets", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_rl", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_mimic", + "${workspaceFolder}/submodules/IsaacLab/source/isaaclab_tasks", + ] +} From d2c40d955a1f290b9ebbd1f66743b9745667ed3f Mon Sep 17 00:00:00 2001 From: Xinjie Yao Date: Tue, 16 Dec 2025 12:19:40 -0800 Subject: [PATCH 20/26] Add RigidObjectSet class to enable multi-object spawning (#290) ## Summary `RigidObjectSet` inherited from `Object` to enable users provide a list of assets, and sim app spawn each `env_id` with one obj from this set. ## Detailed description - Introduced `RigidObjectSet(Obejct)` class for handle rigid body object set construction - The order of each obj in the set to load in each env_id could be configured as following func args order, or being random. - Introduced `--object_set` in `kitchen_pick_and_place.py` cli to allow spawning for each env_id - Added tests for empty/single/multi object sets & checker each env_id's usd is referenced in expected sequence ## TODO - Pipe clean & verify other task-centered obj metrics/ attributes access (Done in test) - Introduce this concept in other sample envs & multi-task eval ## Note - Naming to `set` instead of `collection` is to differentiate what [`RigidBodyCollection`](https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab/isaaclab/assets/rigid_object_collection/rigid_object_collection_data.py) from IssacLab provides. In our use case, we need to spawn 1 obj from N objs, where `RigidBodyCollection` API is to spawn all N objs for each id. - MultiAssetSpawnerCfg for articulated objs will be tricky (/buggy) as PhyX APIs require it has the same joint prim path. It puts too much constraints on what could be added into the set - [MultiAssetSpawnerCfg](https://github.com/isaac-sim/IsaacLab/blob/main/source/isaaclab/isaaclab/sim/spawners/wrappers/wrappers_cfg.py#L16) for rigid objs require the same type of collision meshes, as written in Lab's doc. image --- isaaclab_arena/assets/object_set.py | 87 ++++++ isaaclab_arena/scene/scene.py | 23 +- isaaclab_arena/tests/test_object_set.py | 288 ++++++++++++++++++ isaaclab_arena/utils/usd_helpers.py | 24 ++ .../kitchen_pick_and_place_environment.py | 23 +- 5 files changed, 434 insertions(+), 11 deletions(-) create mode 100644 isaaclab_arena/assets/object_set.py create mode 100644 isaaclab_arena/tests/test_object_set.py diff --git a/isaaclab_arena/assets/object_set.py b/isaaclab_arena/assets/object_set.py new file mode 100644 index 00000000..217198b0 --- /dev/null +++ b/isaaclab_arena/assets/object_set.py @@ -0,0 +1,87 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +import isaaclab.sim as sim_utils +from isaaclab.assets import RigidObjectCfg + +from isaaclab_arena.assets.object import Object +from isaaclab_arena.assets.object_base import ObjectBase, ObjectType +from isaaclab_arena.assets.object_utils import detect_object_type +from isaaclab_arena.utils.pose import Pose + + +class RigidObjectSet(Object): + """ + A set of rigid objects. + """ + + def __init__( + self, + name: str, + objects: list[Object], + prim_path: str | None = None, + scale: tuple[float, float, float] = (1.0, 1.0, 1.0), + random_choice: bool = False, + initial_pose: Pose | None = None, + **kwargs, + ): + """ + Args: + name: The name of the object set. + objects: The list of objects to be included in the object set. + prim_path: The prim path of the object set. Note that for all environments, the object set + prim path must be the same. + scale: The scale of the object set. Note all objects can only have the same scale, if + different scales are needed, considering scaling the object USD file. + random_choice: Whether to randomly choose an object from the object set to spawn in + each environment. If False, object is spawned based on the order of objects in the list. + initial_pose: The initial pose of the object from this object set. + """ + if not self._are_all_objects_type_rigid(objects): + raise ValueError(f"Object set {name} must contain only rigid objects.") + + self.object_usd_paths = [object.usd_path for object in objects] + self.random_choice = random_choice + + # Set default prim_path if not provided + if prim_path is None: + prim_path = f"{{ENV_REGEX_NS}}/{name}" + + super().__init__( + name=name, + object_type=ObjectType.RIGID, + usd_path="", + prim_path=prim_path, + scale=scale, + initial_pose=initial_pose, + **kwargs, + ) + + def _are_all_objects_type_rigid(self, objects: list[ObjectBase]) -> bool: + if objects is None or len(objects) == 0: + raise ValueError(f"Object set {self.name} must contain at least 1 object.") + return all(detect_object_type(usd_path=object.usd_path) == ObjectType.RIGID for object in objects) + + def _generate_rigid_cfg(self) -> RigidObjectCfg: + assert self.object_type == ObjectType.RIGID + object_cfg = RigidObjectCfg( + prim_path=self.prim_path, + spawn=sim_utils.MultiUsdFileCfg( + usd_path=self.object_usd_paths, + random_choice=self.random_choice, + activate_contact_sensors=True, + ), + ) + object_cfg = self._add_initial_pose_to_cfg(object_cfg) + return object_cfg + + def _generate_articulation_cfg(self): + raise NotImplementedError("Articulation configuration is not supported for object sets") + + def _generate_base_cfg(self): + raise NotImplementedError("Base configuration is not supported for object sets") + + def _generate_spawner_cfg(self): + raise NotImplementedError("Spawner configuration is not supported for object sets") diff --git a/isaaclab_arena/scene/scene.py b/isaaclab_arena/scene/scene.py index 66650785..029fcaf3 100644 --- a/isaaclab_arena/scene/scene.py +++ b/isaaclab_arena/scene/scene.py @@ -14,6 +14,7 @@ from isaaclab_arena.assets.asset import Asset from isaaclab_arena.assets.object import Object from isaaclab_arena.assets.object_base import ObjectType +from isaaclab_arena.assets.object_set import RigidObjectSet from isaaclab_arena.environments.isaaclab_arena_manager_based_env import IsaacLabArenaManagerBasedRLEnvCfg from isaaclab_arena.utils.configclass import make_configclass from isaaclab_arena.utils.phyx_utils import add_contact_report @@ -23,8 +24,8 @@ class Scene: - def __init__(self, assets: list[Asset] | None = None): - self.assets: dict[str, Asset] = {} + def __init__(self, assets: list[Asset, RigidObjectSet] | None = None): + self.assets: dict[str, Asset | RigidObjectSet] = {} # We add these here so a user can override them if they want. self.observation_cfg = None self.events_cfg = None @@ -35,11 +36,23 @@ def __init__(self, assets: list[Asset] | None = None): if assets is not None: self.add_assets(assets) - def add_asset(self, asset: Asset): - assert asset.name is not None, "Asset with the same name already exists" + def add_asset(self, asset: Asset | RigidObjectSet): + """Add an asset to the scene. + + Args: + asset: An Asset instance or a dictionary of Assets. If a dictionary is provided, + the keys will be used as the names of the assets and the values will be the list of assets. + """ + if not isinstance(asset, Asset | RigidObjectSet): + raise ValueError(f"Invalid asset type: {type(asset)}") + + if asset.name is None: + print("Asset name is None. Skipping asset.") + return + # if name already exists, overwrite self.assets[asset.name] = asset - def add_assets(self, assets: list[Asset]): + def add_assets(self, assets: list[Asset | RigidObjectSet]): for asset in assets: self.add_asset(asset) diff --git a/isaaclab_arena/tests/test_object_set.py b/isaaclab_arena/tests/test_object_set.py new file mode 100644 index 00000000..19ef91d6 --- /dev/null +++ b/isaaclab_arena/tests/test_object_set.py @@ -0,0 +1,288 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function + +HEADLESS = True +NUM_ENVS = 3 +OBJECT_SET_1_PRIM_PATH = "/World/envs/env_.*/ObjectSet_1" +OBJECT_SET_2_PRIM_PATH = "/World/envs/env_.*/ObjectSet_2" + + +def _test_empty_object_set(simulation_app): + from isaaclab_arena.assets.object_set import RigidObjectSet + + try: + RigidObjectSet(name="empty_object_set", objects=[]) + except Exception: + return True + return False + + +def _test_articulation_object_set(simulation_app): + from isaaclab_arena.assets.asset_registry import AssetRegistry + from isaaclab_arena.assets.object_set import RigidObjectSet + + asset_registry = AssetRegistry() + microwave = asset_registry.get_asset_by_name("microwave")() + try: + RigidObjectSet(name="articulation_object_set", objects=[microwave]) + except Exception: + return True + return False + + +def _test_single_object_in_one_object_set(simulation_app): + from isaacsim.core.utils.stage import get_current_stage + + from isaaclab_arena.assets.asset_registry import AssetRegistry + from isaaclab_arena.assets.object_reference import ObjectReference + from isaaclab_arena.assets.object_set import RigidObjectSet + from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser + from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder + from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment + from isaaclab_arena.scene.scene import Scene + from isaaclab_arena.tasks.pick_and_place_task import PickAndPlaceTask + from isaaclab_arena.utils.pose import Pose + from isaaclab_arena.utils.usd_helpers import get_asset_usd_path_from_prim_path + + asset_registry = AssetRegistry() + background = asset_registry.get_asset_by_name("kitchen")() + embodiment = asset_registry.get_asset_by_name("franka")() + cracker_box = asset_registry.get_asset_by_name("cracker_box")() + destination_location = ObjectReference( + name="destination_location", + prim_path="{ENV_REGEX_NS}/kitchen/Cabinet_B_02", + parent_asset=background, + ) + obj_set = RigidObjectSet( + name="single_object_set", objects=[cracker_box, cracker_box], prim_path=OBJECT_SET_1_PRIM_PATH + ) + obj_set.set_initial_pose(Pose(position_xyz=(0.1, 0.0, 0.1), rotation_wxyz=(1.0, 0.0, 0.0, 0.0))) + scene = Scene(assets=[background, obj_set]) + isaaclab_arena_environment = IsaacLabArenaEnvironment( + name="single_object_set_test", + embodiment=embodiment, + scene=scene, + task=PickAndPlaceTask( + pick_up_object=obj_set, destination_location=destination_location, background_scene=background + ), + teleop_device=None, + ) + args_cli = get_isaaclab_arena_cli_parser().parse_args([]) + args_cli.num_envs = NUM_ENVS + args_cli.headless = HEADLESS + env_builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) + env = env_builder.make_registered() + env.reset() + + try: + for i in range(NUM_ENVS): + # Construct the actual prim path for this environment + path = get_asset_usd_path_from_prim_path( + prim_path=OBJECT_SET_1_PRIM_PATH.replace(".*", str(i)), stage=get_current_stage() + ) + assert path is not None, "Path is None" + assert "cracker_box.usd" in path, "Path does not contain cracker_box.usd" + assert obj_set.get_initial_pose() is not None, "Initial pose is None" + + assert env.scene[obj_set.name].data.root_pose_w is not None, "Root pose is None" + assert ( + env.scene.sensors["pick_up_object_contact_sensor"].data.force_matrix_w is not None + ), "Contact sensor data is None" + except Exception as e: + print(f"Error: {e}") + return False + finally: + env.close() + return True + + +def _test_multi_objects_in_one_object_set(simulation_app): + from isaacsim.core.utils.stage import get_current_stage + + from isaaclab_arena.assets.asset_registry import AssetRegistry + from isaaclab_arena.assets.object_reference import ObjectReference + from isaaclab_arena.assets.object_set import RigidObjectSet + from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser + from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder + from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment + from isaaclab_arena.scene.scene import Scene + from isaaclab_arena.tasks.pick_and_place_task import PickAndPlaceTask + from isaaclab_arena.utils.usd_helpers import get_asset_usd_path_from_prim_path + + asset_registry = AssetRegistry() + background = asset_registry.get_asset_by_name("kitchen")() + embodiment = asset_registry.get_asset_by_name("franka")() + cracker_box = asset_registry.get_asset_by_name("cracker_box")() + sugar_box = asset_registry.get_asset_by_name("sugar_box")() + destination_location = ObjectReference( + name="destination_location", + prim_path="{ENV_REGEX_NS}/kitchen/Cabinet_B_02", + parent_asset=background, + ) + obj_set = RigidObjectSet( + name="multi_object_sets", objects=[cracker_box, sugar_box], prim_path=OBJECT_SET_2_PRIM_PATH + ) + scene = Scene(assets=[background, obj_set]) + isaaclab_arena_environment = IsaacLabArenaEnvironment( + name="multi_objects_in_one_object_set_test", + embodiment=embodiment, + scene=scene, + task=PickAndPlaceTask( + pick_up_object=obj_set, destination_location=destination_location, background_scene=background + ), + teleop_device=None, + ) + args_cli = get_isaaclab_arena_cli_parser().parse_args([]) + args_cli.num_envs = NUM_ENVS + args_cli.headless = HEADLESS + env_builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) + env = env_builder.make_registered() + env.reset() + + assert env.scene[obj_set.name].data.root_pose_w is not None, "Root pose is None" + assert ( + env.scene.sensors["pick_up_object_contact_sensor"].data.force_matrix_w is not None + ), "Contact sensor data is None" + + # replace * in OBJECT_SET_PRIM_PATH with env_index + try: + for i in range(NUM_ENVS): + + path = get_asset_usd_path_from_prim_path( + prim_path=OBJECT_SET_2_PRIM_PATH.replace(".*", str(i)), stage=get_current_stage() + ) + assert path is not None, "Path is None" + if i % 2 == 0: + assert "cracker_box.usd" in path, "Path does not contain cracker_box.usd for env index " + str(i) + else: + assert "sugar_box.usd" in path, "Path does not contain sugar_box.usd for env index " + str(i) + except Exception as e: + print(f"Error: {e}") + return False + finally: + env.close() + return True + + +def _test_multi_object_sets(simulation_app): + from isaacsim.core.utils.stage import get_current_stage + + from isaaclab_arena.assets.asset_registry import AssetRegistry + from isaaclab_arena.assets.object_set import RigidObjectSet + from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser + from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder + from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment + from isaaclab_arena.scene.scene import Scene + from isaaclab_arena.tasks.dummy_task import DummyTask + from isaaclab_arena.utils.usd_helpers import get_asset_usd_path_from_prim_path + + asset_registry = AssetRegistry() + background = asset_registry.get_asset_by_name("packing_table")() + embodiment = asset_registry.get_asset_by_name("franka")() + cracker_box = asset_registry.get_asset_by_name("cracker_box")() + sugar_box = asset_registry.get_asset_by_name("sugar_box")() + mustard_bottle = asset_registry.get_asset_by_name("mustard_bottle")() + + obj_set_1 = RigidObjectSet( + name="multi_object_sets_1", objects=[cracker_box, sugar_box], prim_path=OBJECT_SET_1_PRIM_PATH + ) + obj_set_2 = RigidObjectSet( + name="multi_object_sets_2", objects=[sugar_box, mustard_bottle], prim_path=OBJECT_SET_2_PRIM_PATH + ) + scene = Scene(assets=[background, obj_set_1, obj_set_2]) + isaaclab_arena_environment = IsaacLabArenaEnvironment( + name="multi_object_sets_test", + embodiment=embodiment, + scene=scene, + task=DummyTask(), + teleop_device=None, + ) + args_cli = get_isaaclab_arena_cli_parser().parse_args([]) + args_cli.num_envs = NUM_ENVS + args_cli.headless = HEADLESS + env_builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) + env = env_builder.make_registered() + env.reset() + + try: + for i in range(NUM_ENVS): + + path_1 = get_asset_usd_path_from_prim_path( + prim_path=OBJECT_SET_1_PRIM_PATH.replace(".*", str(i)), stage=get_current_stage() + ) + path_2 = get_asset_usd_path_from_prim_path( + prim_path=OBJECT_SET_2_PRIM_PATH.replace(".*", str(i)), stage=get_current_stage() + ) + + assert path_1 is not None, ( + "Path_1 from Prim Path " + OBJECT_SET_1_PRIM_PATH.replace(".*", str(i)) + " is None" + ) + assert path_2 is not None, ( + "Path_2 from Prim Path " + OBJECT_SET_2_PRIM_PATH.replace(".*", str(i)) + " is None" + ) + if i % 2 == 0: + assert "cracker_box.usd" in path_1, "Path_1 does not contain cracker_box.usd for env index " + str(i) + assert "sugar_box.usd" in path_2, "Path_2 does not contain sugar_box.usd for env index " + str(i) + else: + assert "sugar_box.usd" in path_1, "Path_1 does not contain sugar_box.usd for env index " + str(i) + assert ( + "mustard_bottle.usd" in path_2 + ), "Path_2 does not contain mustard_bottle.usd for env index " + str(i) + except Exception as e: + print(f"Error: {e}") + return False + finally: + env.close() + return True + + +def test_empty_object_set(): + result = run_simulation_app_function( + _test_empty_object_set, + headless=HEADLESS, + ) + assert result, f"Test {_test_empty_object_set.__name__} failed" + + +def test_articulation_object_set(): + result = run_simulation_app_function( + _test_articulation_object_set, + headless=HEADLESS, + ) + assert result, f"Test {_test_articulation_object_set.__name__} failed" + + +def test_single_object_in_one_object_set(): + result = run_simulation_app_function( + _test_single_object_in_one_object_set, + headless=HEADLESS, + ) + assert result, f"Test {_test_single_object_in_one_object_set.__name__} failed" + + +def test_multi_objects_in_one_object_set(): + result = run_simulation_app_function( + _test_multi_objects_in_one_object_set, + headless=HEADLESS, + ) + assert result, f"Test {_test_multi_objects_in_one_object_set.__name__} failed" + + +def test_multi_object_sets(): + result = run_simulation_app_function( + _test_multi_object_sets, + headless=HEADLESS, + ) + assert result, f"Test {_test_multi_object_sets.__name__} failed" + + +if __name__ == "__main__": + test_empty_object_set() + test_articulation_object_set() + test_single_object_in_one_object_set() + test_multi_objects_in_one_object_set() + test_multi_object_sets() diff --git a/isaaclab_arena/utils/usd_helpers.py b/isaaclab_arena/utils/usd_helpers.py index f9661f86..bbf788dd 100644 --- a/isaaclab_arena/utils/usd_helpers.py +++ b/isaaclab_arena/utils/usd_helpers.py @@ -76,3 +76,27 @@ def open_stage(path): finally: # Drop the local reference; Garbage Collection will reclaim once no prim/attr handles remain del stage + + +def get_asset_usd_path_from_prim_path(prim_path: str, stage: Usd.Stage) -> str | None: + """Get the USD path from a prim path, that is referring to an asset.""" + # Note (xinjieyao, 2025.12.12): preferred way to get the composed asset path is to ask the Usd.Prim object itself, + # which handles the entire composition stack. Here it achieved this goal thru root layer due to the USD API limitations. + # It only finds references authored on the root layer. + # If the asset was referenced in an intermediate sublayer, this method would fail to find the asset path. + root_layer = stage.GetRootLayer() + prim_spec = root_layer.GetPrimAtPath(prim_path) + if not prim_spec: + return None + + try: + reference_list = prim_spec.referenceList.GetAddedOrExplicitItems() + except Exception as e: + print(f"Failed to get reference list for prim {prim_path}: {e}") + return None + if len(reference_list) > 0: + for reference_spec in reference_list: + if reference_spec.assetPath: + return reference_spec.assetPath + + return None diff --git a/isaaclab_arena_environments/kitchen_pick_and_place_environment.py b/isaaclab_arena_environments/kitchen_pick_and_place_environment.py index bf183c1e..ab2287dd 100644 --- a/isaaclab_arena_environments/kitchen_pick_and_place_environment.py +++ b/isaaclab_arena_environments/kitchen_pick_and_place_environment.py @@ -21,6 +21,7 @@ class KitchenPickAndPlaceEnvironment(ExampleEnvironmentBase): def get_env(self, args_cli: argparse.Namespace): # -> IsaacLabArenaEnvironment: from isaaclab_arena.assets.object_base import ObjectType from isaaclab_arena.assets.object_reference import ObjectReference + from isaaclab_arena.assets.object_set import RigidObjectSet from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment from isaaclab_arena.scene.scene import Scene from isaaclab_arena.tasks.pick_and_place_task import PickAndPlaceTask @@ -30,11 +31,6 @@ def get_env(self, args_cli: argparse.Namespace): # -> IsaacLabArenaEnvironment: pick_up_object = self.asset_registry.get_asset_by_name(args_cli.object)() embodiment = self.asset_registry.get_asset_by_name(args_cli.embodiment)(enable_cameras=args_cli.enable_cameras) - if args_cli.teleop_device is not None: - teleop_device = self.device_registry.get_device_by_name(args_cli.teleop_device)() - else: - teleop_device = None - pick_up_object.set_initial_pose( Pose( position_xyz=(0.4, 0.0, 0.1), @@ -49,8 +45,22 @@ def get_env(self, args_cli: argparse.Namespace): # -> IsaacLabArenaEnvironment: parent_asset=background, object_type=ObjectType.RIGID, ) + if args_cli.teleop_device is not None: + teleop_device = self.device_registry.get_device_by_name(args_cli.teleop_device)() + else: + teleop_device = None - scene = Scene(assets=[background, pick_up_object, destination_location]) + if args_cli.object_set is not None and len(args_cli.object_set) > 0: + objects = [] + for obj in args_cli.object_set: + obj_from_set = self.asset_registry.get_asset_by_name(obj)() + objects.append(obj_from_set) + object_set = RigidObjectSet(name="object_set", objects=objects) + object_set.set_initial_pose(Pose(position_xyz=(0.4, 0.2, 0.1), rotation_wxyz=(1.0, 0.0, 0.0, 0.0))) + scene = Scene(assets=[background, pick_up_object, destination_location, object_set]) + + else: + scene = Scene(assets=[background, pick_up_object, destination_location]) isaaclab_arena_environment = IsaacLabArenaEnvironment( name=self.name, embodiment=embodiment, @@ -63,6 +73,7 @@ def get_env(self, args_cli: argparse.Namespace): # -> IsaacLabArenaEnvironment: @staticmethod def add_cli_args(parser: argparse.ArgumentParser) -> None: parser.add_argument("--object", type=str, default="cracker_box") + parser.add_argument("--object_set", nargs="+", type=str, default=None) parser.add_argument("--embodiment", type=str, default="franka") # NOTE(alexmillane, 2025.09.04): We need a teleop device argument in order # to be used in the record_demos.py script. From 3b1f31a7e27061e80012399074b07c5a73685fd4 Mon Sep 17 00:00:00 2001 From: peterd-NV Date: Wed, 17 Dec 2025 07:42:56 -0800 Subject: [PATCH 21/26] Add SequentialTaskBase class (#289) ## Summary This PR adds initial support for composite sequential tasks via the SequentialTaskBase class. The SequentialTaskBase class takes a list of atomic tasks (TaskBase) and automatically assembles them into a composite task with unified termination/event configs. Adds: 1. SequentialTaskBase class 2. Test case to validate class methods 3. Test case with example task (sequential open door task) to validate unified success check and events 4. Two new functions in `isaac_arena/utils/configclass.py` to perform config transformation and duplicate checking --- isaaclab_arena/tasks/sequential_task_base.py | 194 +++++++++ .../tests/test_sequential_open_door.py | 394 ++++++++++++++++++ .../tests/test_sequential_task_base.py | 160 +++++++ isaaclab_arena/utils/configclass.py | 68 +++ 4 files changed, 816 insertions(+) create mode 100644 isaaclab_arena/tasks/sequential_task_base.py create mode 100644 isaaclab_arena/tests/test_sequential_open_door.py create mode 100644 isaaclab_arena/tests/test_sequential_task_base.py diff --git a/isaaclab_arena/tasks/sequential_task_base.py b/isaaclab_arena/tasks/sequential_task_base.py new file mode 100644 index 00000000..c1e9c6ac --- /dev/null +++ b/isaaclab_arena/tasks/sequential_task_base.py @@ -0,0 +1,194 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +import copy +import torch +from dataclasses import MISSING +from functools import partial + +from isaaclab.managers import EventTermCfg, TerminationTermCfg +from isaaclab.utils import configclass + +from isaaclab_arena.tasks.task_base import TaskBase +from isaaclab_arena.utils.configclass import ( + check_configclass_field_duplicates, + combine_configclass_instances, + transform_configclass_instance, +) + + +@configclass +class SequentialTaskEventsCfg: + reset_subtask_success_state: EventTermCfg = MISSING + + +@configclass +class TerminationsCfg: + success: TerminationTermCfg = MISSING + + +class SequentialTaskBase(TaskBase): + """ + A base class for composite tasks composed sequentially from multiple subtasks. + The sequential task takes a list of TaskBase instances (subtasks), + and automatically collects configs to form a composite task. + + The sequential task satisfies the following properties: + - Made up of atomic tasks that must be completed in order. + - Once a subtask is complete once (success = True), it's success state can go back to False + without affecting the completeness of the overall sequential task. + """ + + # TODO: peterd - add functions to process Mimic and Metrics configs. + + def __init__(self, subtasks: list[TaskBase], episode_length_s: float | None = None): + super().__init__(episode_length_s) + assert len(subtasks) > 0, "SequentialTaskBase requires at least one subtask" + self.subtasks = subtasks + + @staticmethod + def add_suffix_configclass_transform(fields: list[tuple], suffix: str) -> list[tuple]: + "Config transformation to add a suffix to all field names." + return [(f"{name}{suffix}", ftype, value) for name, ftype, value in fields] + + @staticmethod + def remove_configclass_transform(fields: list[tuple], exclude_fields: set[str]) -> list[tuple]: + "Config transformation to remove all fields in an exclude set." + return [(name, ftype, value) for name, ftype, value in fields if name not in exclude_fields] + + @staticmethod + def sequential_task_success_func( + env, + subtasks: list[TaskBase], + ) -> torch.Tensor: + "Sequential task composite success function." + # Initialize each env's subtask success state to False if not already initialized + if not hasattr(env, "_subtask_success_state"): + env._subtask_success_state = [[False for _ in subtasks] for _ in range(env.num_envs)] + # Initialize each env's current subtask index (state machine) to 0 if not already initialized + if not hasattr(env, "_current_subtask_idx"): + env._current_subtask_idx = [0 for _ in range(env.num_envs)] + + # Check success of current subtask for each env + for env_idx in range(env.num_envs): + current_subtask_idx = env._current_subtask_idx[env_idx] + current_subtask_success_func = subtasks[current_subtask_idx].get_termination_cfg().success.func + current_subtask_success_params = subtasks[current_subtask_idx].get_termination_cfg().success.params + result = current_subtask_success_func(env, **current_subtask_success_params)[env_idx] + + if result: + env._subtask_success_state[env_idx][current_subtask_idx] = True + if current_subtask_idx < len(subtasks) - 1: + env._current_subtask_idx[env_idx] += 1 + + # Compute composite task success state for each env + per_env_success = [all(env_successes) for env_successes in env._subtask_success_state] + success_tensor = torch.tensor(per_env_success, dtype=torch.bool, device=env.device) + + env.extras["subtask_success_state"] = copy.copy(env._subtask_success_state) + + return success_tensor + + @staticmethod + def reset_subtask_success_state( + env, + env_ids, + subtasks: list[TaskBase], + ) -> None: + "Reset subtask success vector and state machine for each environment." + # Initialize each env's subtask success state to False + if not hasattr(env, "_subtask_success_state"): + env._subtask_success_state = [[False for _ in subtasks] for _ in range(env.num_envs)] + else: + for env_id in env_ids: + env._subtask_success_state[env_id] = [False for _ in subtasks] + + # Initialize each env's current subtask index (state machine) to 0 + if not hasattr(env, "_current_subtask_idx"): + env._current_subtask_idx = [0 for _ in range(env.num_envs)] + else: + for env_id in env_ids: + env._current_subtask_idx[env_id] = 0 + + def get_scene_cfg(self) -> configclass: + "Make combined scene cfg from all subtasks." + # Check for duplicate fields across subtask scene configs and warn if found + duplicates = check_configclass_field_duplicates(*(subtask.get_scene_cfg() for subtask in self.subtasks)) + if duplicates: + import warnings + + warnings.warn( + f"\n[WARNING] Duplicate scene config fields found across subtasks: {duplicates}. " + "Duplicates will be ignored.\n", + UserWarning, + ) + + scene_cfg = combine_configclass_instances("SceneCfg", *(subtask.get_scene_cfg() for subtask in self.subtasks)) + return scene_cfg + + def make_sequential_task_events_cfg(self) -> configclass: + "Make event to reset subtask success state." + reset_subtask_success_state = EventTermCfg( + func=self.reset_subtask_success_state, + mode="reset", + params={ + "subtasks": self.subtasks, + }, + ) + + return SequentialTaskEventsCfg( + reset_subtask_success_state=reset_subtask_success_state, + ) + + def get_events_cfg(self) -> configclass: + "Make combined events cfg from all subtasks." + # Collect events_cfgs from subtasks with renamed fields to avoid collisions + renamed_events_cfgs = [] + for i, subtask in enumerate(self.subtasks): + subtask_events_cfg = subtask.get_events_cfg() + renamed_cfg = transform_configclass_instance( + subtask_events_cfg, partial(self.add_suffix_configclass_transform, suffix=f"_subtask_{i}") + ) + if renamed_cfg is not None: + renamed_events_cfgs.append(renamed_cfg) + + # Add reset subtask success state event to the combined events cfgs + events_cfg = combine_configclass_instances( + "EventsCfg", *renamed_events_cfgs, self.make_sequential_task_events_cfg() + ) + + return events_cfg + + def make_sequential_task_termination_cfg(self) -> configclass: + "Make composite success check termination term." + success = TerminationTermCfg( + func=self.sequential_task_success_func, + params={ + "subtasks": self.subtasks, + }, + ) + + return TerminationsCfg( + success=success, + ) + + def get_termination_cfg(self) -> configclass: + "Make combined termination cfg from all subtasks." + # Collect termination cfgs from subtasks with 'success' field removed + subtask_termination_cfgs = [] + for subtask in self.subtasks: + termination_cfg = subtask.get_termination_cfg() + cleaned_cfg = transform_configclass_instance( + termination_cfg, partial(self.remove_configclass_transform, exclude_fields={"success"}) + ) + if cleaned_cfg is not None: + subtask_termination_cfgs.append(cleaned_cfg) + + # Combine subtask terminations with the composite sequential task success + combined_termination_cfg = combine_configclass_instances( + "TerminationsCfg", *subtask_termination_cfgs, self.make_sequential_task_termination_cfg() + ) + + return combined_termination_cfg diff --git a/isaaclab_arena/tests/test_sequential_open_door.py b/isaaclab_arena/tests/test_sequential_open_door.py new file mode 100644 index 00000000..b3e38c84 --- /dev/null +++ b/isaaclab_arena/tests/test_sequential_open_door.py @@ -0,0 +1,394 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +import gymnasium as gym +import torch + +from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function + +NUM_STEPS = 10 +HEADLESS = True + + +def get_test_environment(remove_reset_door_state_event: bool, num_envs: int): + """Returns a scene which we use for these tests.""" + + from isaaclab_arena.assets.asset_registry import AssetRegistry + from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser + from isaaclab_arena.embodiments.franka.franka import FrankaEmbodiment + from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder + from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment + from isaaclab_arena.scene.scene import Scene + from isaaclab_arena.tasks.open_door_task import OpenDoorTask + from isaaclab_arena.tasks.sequential_task_base import SequentialTaskBase + from isaaclab_arena.utils.pose import Pose + + class SequentialOpenDoorTask(SequentialTaskBase): + def __init__( + self, + subtasks, + episode_length_s=None, + ): + super().__init__(subtasks=subtasks, episode_length_s=episode_length_s) + + def get_metrics(self): + return [] + + def get_prompt(self): + return "" + + def get_mimic_env_cfg(self, embodiment_name: str): + return None + + args_parser = get_isaaclab_arena_cli_parser() + args_cli = args_parser.parse_args(["--num_envs", str(num_envs)]) + + asset_registry = AssetRegistry() + background = asset_registry.get_asset_by_name("packing_table")() + microwave_0 = asset_registry.get_asset_by_name("microwave")(prim_path="{ENV_REGEX_NS}/microwave_0") + microwave_1 = asset_registry.get_asset_by_name("microwave")(prim_path="{ENV_REGEX_NS}/microwave_1") + + microwave_0.name = "microwave_0" + microwave_1.name = "microwave_1" + + # Put the microwave on the packing table. + microwave_0.set_initial_pose( + Pose( + position_xyz=(0.6, -0.00586, 0.22773), + rotation_wxyz=(0.7071068, 0, 0, -0.7071068), + ) + ) + microwave_1.set_initial_pose( + Pose( + position_xyz=(0.6, 0.70586, 0.22773), + rotation_wxyz=(0.7071068, 0, 0, -0.7071068), + ) + ) + + subtask_1 = OpenDoorTask(microwave_0) + subtask_2 = OpenDoorTask(microwave_1) + + scene = Scene(assets=[background, microwave_0, microwave_1]) + + isaaclab_arena_environment = IsaacLabArenaEnvironment( + name="sequential_open_door", + embodiment=FrankaEmbodiment(), + scene=scene, + task=SequentialOpenDoorTask([subtask_1, subtask_2]), + ) + + env_builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) + name, cfg = env_builder.build_registered() + if remove_reset_door_state_event: + # Remove the reset door and subtask state events to allow us to inspect the scene without having it reset. + cfg.events.reset_door_state_subtask_0 = None + cfg.events.reset_door_state_subtask_1 = None + cfg.events.reset_subtask_success_state = None + env = gym.make(name, cfg=cfg).unwrapped + env.reset() + + return env, microwave_0, microwave_1 + + +def _test_sequential_open_door_microwave(simulation_app) -> bool: + from isaaclab.envs.manager_based_env import ManagerBasedEnv + + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + # Get the scene + env, microwave_0, microwave_1 = get_test_environment(remove_reset_door_state_event=True, num_envs=1) + + def assert_composite_task_incomplete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([1]) + assert not terminated.item() + if not terminated.item(): + print("Composite task is not completed") + + def assert_composite_task_complete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([1]) + assert terminated.item() + if terminated.item(): + print("Composite task is completed") + + try: + print("Closing both microwaves") + microwave_0.close(env, env_ids=None) + microwave_1.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 0 (completing subtask 0)") + microwave_0.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 1 (completing subtask 1, composite task should be complete)") + microwave_1.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_complete) + + except Exception as e: + print(f"Error: {e}") + return False + + finally: + env.close() + + return True + + +def _test_out_of_order_sequential_open_door_microwave(simulation_app) -> bool: + from isaaclab.envs.manager_based_env import ManagerBasedEnv + + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + # Get the scene + env, microwave_0, microwave_1 = get_test_environment(remove_reset_door_state_event=True, num_envs=1) + + def assert_composite_task_incomplete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([1]) + assert not terminated.item() + if not terminated.item(): + print("Composite task is not completed") + + def assert_composite_task_complete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([1]) + assert terminated.item() + if terminated.item(): + print("Composite task is completed") + + try: + print("Closing both microwaves") + microwave_0.close(env, env_ids=None) + microwave_1.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 1") + microwave_1.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Closing microwave 1") + microwave_1.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 0 (out of order, composite task should remain incomplete)") + microwave_0.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Closing microwave 0") + microwave_0.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 0 (completing subtask 0)") + microwave_0.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 1 (completing subtask 1, composite task should be complete)") + microwave_1.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_complete) + + except Exception as e: + print(f"Error: {e}") + return False + + finally: + env.close() + + return True + + +def _test_sequential_open_door_microwave_multiple_envs(simulation_app) -> bool: + from isaaclab.envs.manager_based_env import ManagerBasedEnv + + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + # Get the scene + env, microwave_0, microwave_1 = get_test_environment(remove_reset_door_state_event=True, num_envs=2) + + def assert_composite_task_incomplete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([2]) + assert not torch.any(terminated) + if not torch.any(terminated): + print("Composite task is not completed") + + def assert_composite_task_complete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([2]) + assert torch.all(terminated) + if torch.all(terminated): + print("Composite task is completed") + + try: + print("Closing both microwaves") + microwave_0.close(env, env_ids=None) + microwave_1.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 0 (completing subtask 0)") + microwave_0.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 1 (completing subtask 1, composite task should be complete)") + microwave_1.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_complete) + + except Exception as e: + print(f"Error: {e}") + return False + + finally: + env.close() + + return True + + +def _test_out_of_order_sequential_open_door_microwave_multiple_envs(simulation_app) -> bool: + from isaaclab.envs.manager_based_env import ManagerBasedEnv + + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + # Get the scene + env, microwave_0, microwave_1 = get_test_environment(remove_reset_door_state_event=True, num_envs=2) + + def assert_composite_task_incomplete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([2]) + assert not torch.any(terminated) + if not torch.any(terminated): + print("Composite task is not completed") + + def assert_composite_task_complete(env: ManagerBasedEnv, terminated: torch.Tensor): + assert terminated.shape == torch.Size([2]) + assert torch.all(terminated) + if torch.all(terminated): + print("Composite task is completed") + + try: + print("Closing both microwaves") + microwave_0.close(env, env_ids=None) + microwave_1.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 1") + microwave_1.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Closing microwave 1") + microwave_1.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 0 (out of order, composite task should remain incomplete)") + microwave_0.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Closing microwave 0") + microwave_0.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 0 (completing subtask 0)") + microwave_0.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_incomplete) + + print("Opening microwave 1 (completing subtask 1, composite task should be complete)") + microwave_1.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_composite_task_complete) + + except Exception as e: + print(f"Error: {e}") + return False + + finally: + env.close() + + return True + + +def _test_sequential_open_door_microwave_reset_condition(simulation_app) -> bool: + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + # Get the scene + env, microwave_0, microwave_1 = get_test_environment(remove_reset_door_state_event=False, num_envs=2) + + try: + print("Closing both microwaves") + microwave_0.close(env, env_ids=None) + microwave_1.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS) + is_open_0 = microwave_0.is_open(env) + is_open_1 = microwave_1.is_open(env) + print(f"expected: [False, False], [False, False]: got: {is_open_0}, {is_open_1}") + assert torch.all(is_open_0 == torch.tensor([False], device=env.device)) + assert torch.all(is_open_1 == torch.tensor([False], device=env.device)) + + print("Opening microwave 0(completing subtask 0)") + microwave_0.open(env, None) + step_zeros_and_call(env, NUM_STEPS) + is_open_0 = microwave_0.is_open(env) + is_open_1 = microwave_1.is_open(env) + print(f"expected: [True, True], [False, False]: got: {is_open_0}, {is_open_1}") + assert torch.all(is_open_0 == torch.tensor([True], device=env.device)) + assert torch.all(is_open_1 == torch.tensor([False], device=env.device)) + + # Check that envs automatically reset to closed. + print("Opening microwave (completing subtask 1)") + microwave_1.open(env, None) + step_zeros_and_call(env, NUM_STEPS) + is_open_0 = microwave_0.is_open(env) + is_open_1 = microwave_1.is_open(env) + print(f"expected: [False, False], [False, False]: got: {is_open_0}, {is_open_1}") + assert torch.all(is_open_0 == torch.tensor([False], device=env.device)) + assert torch.all(is_open_1 == torch.tensor([False], device=env.device)) + + except Exception as e: + print(f"Error: {e}") + return False + + finally: + env.close() + + return True + + +def test_sequential_open_door_microwave(): + result = run_simulation_app_function( + _test_sequential_open_door_microwave, + headless=HEADLESS, + ) + assert result, f"Test {_test_sequential_open_door_microwave.__name__} failed" + + +def test_out_of_order_sequential_open_door_microwave(): + result = run_simulation_app_function( + _test_out_of_order_sequential_open_door_microwave, + headless=HEADLESS, + ) + assert result, f"Test {_test_out_of_order_sequential_open_door_microwave.__name__} failed" + + +def test_sequential_open_door_microwave_multiple_envs(): + result = run_simulation_app_function( + _test_sequential_open_door_microwave_multiple_envs, + headless=HEADLESS, + ) + assert result, f"Test {_test_sequential_open_door_microwave_multiple_envs.__name__} failed" + + +def test_out_of_order_sequential_open_door_microwave_multiple_envs(): + result = run_simulation_app_function( + _test_out_of_order_sequential_open_door_microwave_multiple_envs, + headless=HEADLESS, + ) + assert result, f"Test {_test_out_of_order_sequential_open_door_microwave_multiple_envs.__name__} failed" + + +def test_sequential_open_door_microwave_reset_condition(): + result = run_simulation_app_function( + _test_sequential_open_door_microwave_reset_condition, + headless=HEADLESS, + ) + assert result, f"Test {_test_sequential_open_door_microwave_reset_condition.__name__} failed" + + +if __name__ == "__main__": + test_sequential_open_door_microwave() + test_out_of_order_sequential_open_door_microwave() + test_sequential_open_door_microwave_multiple_envs() + test_out_of_order_sequential_open_door_microwave_multiple_envs() + test_sequential_open_door_microwave_reset_condition() diff --git a/isaaclab_arena/tests/test_sequential_task_base.py b/isaaclab_arena/tests/test_sequential_task_base.py new file mode 100644 index 00000000..2a9f9f2a --- /dev/null +++ b/isaaclab_arena/tests/test_sequential_task_base.py @@ -0,0 +1,160 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function + +HEADLESS = True + + +def _test_add_suffix_configclass_transform(simulation_app) -> bool: + """Test that add_suffix_configclass_transform correctly renames fields with suffix.""" + + from functools import partial + + from isaaclab.utils import configclass + + from isaaclab_arena.tasks.sequential_task_base import SequentialTaskBase + from isaaclab_arena.utils.configclass import transform_configclass_instance + + @configclass + class FooCfg: + int_field: int = 123 + str_field: str = "123" + float_field: float = 1.23 + bool_field: bool = True + + try: + original_cfg = FooCfg() + edited_cfg = transform_configclass_instance( + original_cfg, + partial(SequentialTaskBase.add_suffix_configclass_transform, suffix="_suffix"), + ) + + # Check that new fields exist with suffix + assert hasattr(edited_cfg, "int_field_suffix") + assert hasattr(edited_cfg, "str_field_suffix") + assert hasattr(edited_cfg, "float_field_suffix") + assert hasattr(edited_cfg, "bool_field_suffix") + + # Check that values are preserved + assert edited_cfg.int_field_suffix == 123 + assert edited_cfg.str_field_suffix == "123" + assert edited_cfg.float_field_suffix == 1.23 + assert edited_cfg.bool_field_suffix is True + + # Check types are preserved + assert isinstance(edited_cfg.int_field_suffix, int) + assert isinstance(edited_cfg.str_field_suffix, str) + assert isinstance(edited_cfg.float_field_suffix, float) + assert isinstance(edited_cfg.bool_field_suffix, bool) + + # Check that old field names don't exist + assert not hasattr(edited_cfg, "int_field") + assert not hasattr(edited_cfg, "str_field") + assert not hasattr(edited_cfg, "float_field") + assert not hasattr(edited_cfg, "bool_field") + + # Test None input + edited_cfg = transform_configclass_instance( + None, + partial(SequentialTaskBase.add_suffix_configclass_transform, suffix="_suffix"), + ) + assert edited_cfg is None + + except Exception as e: + print(f"Error: {e}") + return False + + return True + + +def _test_remove_configclass_transform(simulation_app) -> bool: + """Test that remove_configclass_transform correctly removes specified fields.""" + + from functools import partial + + from isaaclab.utils import configclass + + from isaaclab_arena.tasks.sequential_task_base import SequentialTaskBase + from isaaclab_arena.utils.configclass import transform_configclass_instance + + @configclass + class FooCfg: + field_a: int = 123 + field_b: str = "123" + field_c: float = 1.23 + + try: + original_cfg = FooCfg() + edited_cfg = transform_configclass_instance( + original_cfg, + partial(SequentialTaskBase.remove_configclass_transform, exclude_fields={"field_b"}), + ) + + # Check that remaining fields exist + assert hasattr(edited_cfg, "field_a") + assert hasattr(edited_cfg, "field_c") + + # Check that values are preserved + assert edited_cfg.field_a == 123 + assert edited_cfg.field_c == 1.23 + + # Check that removed field doesn't exist + assert not hasattr(edited_cfg, "field_b") + + # Test removing multiple fields + original_cfg = FooCfg() + edited_cfg = transform_configclass_instance( + original_cfg, + partial(SequentialTaskBase.remove_configclass_transform, exclude_fields={"field_a", "field_c"}), + ) + + # Check that only field_b remains + assert hasattr(edited_cfg, "field_b") + assert edited_cfg.field_b == "123" + assert not hasattr(edited_cfg, "field_a") + assert not hasattr(edited_cfg, "field_c") + + # Test None input + edited_cfg = transform_configclass_instance( + None, + partial(SequentialTaskBase.remove_configclass_transform, exclude_fields=set()), + ) + assert edited_cfg is None + + # Test removing all fields returns None + original_cfg = FooCfg() + edited_cfg = transform_configclass_instance( + original_cfg, + partial(SequentialTaskBase.remove_configclass_transform, exclude_fields={"field_a", "field_b", "field_c"}), + ) + assert edited_cfg is None + + except Exception as e: + print(f"Error: {e}") + return False + + return True + + +def test_add_suffix_configclass_transform(): + result = run_simulation_app_function( + _test_add_suffix_configclass_transform, + headless=HEADLESS, + ) + assert result, f"Test {_test_add_suffix_configclass_transform.__name__} failed" + + +def test_remove_configclass_transform(): + result = run_simulation_app_function( + _test_remove_configclass_transform, + headless=HEADLESS, + ) + assert result, f"Test {_test_remove_configclass_transform.__name__} failed" + + +if __name__ == "__main__": + test_add_suffix_configclass_transform() + test_remove_configclass_transform() diff --git a/isaaclab_arena/utils/configclass.py b/isaaclab_arena/utils/configclass.py index 3325307c..48898088 100644 --- a/isaaclab_arena/utils/configclass.py +++ b/isaaclab_arena/utils/configclass.py @@ -201,3 +201,71 @@ def new_post_init(self): post_init(self) return new_post_init + + +def check_configclass_field_duplicates(*input_configclass_instances: Any) -> dict[str, list[str]]: + """Check for duplicate field names in a list of configclass instances. + + Args: + input_configclass_instances: The configclass instances to check. + + Returns: + A dictionary mapping duplicate field names to a list of configclass names + that contain the duplicate. + """ + # Map field name -> list of configclass names that have it + field_sources: dict[str, list[str]] = {} + + for cfg_instance in input_configclass_instances: + if cfg_instance is None: + continue + cfg_name = type(cfg_instance).__name__ + for field in dataclasses.fields(cfg_instance): + if field.name not in field_sources: + field_sources[field.name] = [] + field_sources[field.name].append(cfg_name) + + duplicates = {name: sources for name, sources in field_sources.items() if len(sources) > 1} + return duplicates + + +def transform_configclass_instance( + cfg_instance: Any, + transform: Callable[[list[tuple[str, type, Any]]], list[tuple[str, type, Any]]], +) -> Any: + """Transform a configclass instance by applying a transformation to its fields. + + The transformation callable takes a list of field tuples and returns + a transformed list. This enables generic manipulations like renaming, + filtering, or modifying fields. + + Args: + cfg_instance: The configclass instance to transform. + transform: A callable that takes a list of field tuples and returns + a transformed list of field tuples. + + Returns: + A new configclass instance with the transformed fields, or None if the + the transformation results in no fields. + """ + if cfg_instance is None: + return None + + fields = dataclasses.fields(cfg_instance) + + # Build list of field tuples (name, type, value) + field_tuples = [] + for field in fields: + value = getattr(cfg_instance, field.name) + field_tuples.append((field.name, field.type, value)) + + # Apply transformation + transformed_fields = transform(field_tuples) + + if not transformed_fields: + return None + + # Create a new configclass with transformed fields + field_values = {name: value for name, _, value in transformed_fields} + new_cfg_class = make_configclass(type(cfg_instance).__name__, transformed_fields) + return new_cfg_class(**field_values) From cf797d0d46a0cf186c45c88610211a6ac0a735d3 Mon Sep 17 00:00:00 2001 From: peterd-NV Date: Wed, 17 Dec 2025 13:22:53 -0800 Subject: [PATCH 22/26] Fix mis-named mimic eef in tasks (#297) ## Summary Fixes a typo which caused a misnaming of EEFs in the Mimic Env Configs of tasks. The name of the eefs was being set as an Enum instead of the value of the Enum. This caused data generation to fail using our existing datasets. --- isaaclab_arena/tasks/open_door_task.py | 4 ++-- isaaclab_arena/tasks/pick_and_place_task.py | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/isaaclab_arena/tasks/open_door_task.py b/isaaclab_arena/tasks/open_door_task.py index 942b09ba..119e2ad8 100644 --- a/isaaclab_arena/tasks/open_door_task.py +++ b/isaaclab_arena/tasks/open_door_task.py @@ -208,7 +208,7 @@ def __post_init__(self): self.subtask_configs["robot"] = subtask_configs # We need to add the left and right subtasks for GR1. elif self.arm_mode in [MimicArmMode.LEFT, MimicArmMode.RIGHT]: - self.subtask_configs[self.arm_mode] = subtask_configs + self.subtask_configs[self.arm_mode.value] = subtask_configs # EEF on opposite side (arm is static) subtask_configs = [] subtask_configs.append( @@ -233,7 +233,7 @@ def __post_init__(self): apply_noise_during_interpolation=False, ) ) - self.subtask_configs[self.arm_mode.get_other_arm()] = subtask_configs + self.subtask_configs[self.arm_mode.get_other_arm().value] = subtask_configs else: raise ValueError(f"Embodiment arm mode {self.arm_mode} not supported") diff --git a/isaaclab_arena/tasks/pick_and_place_task.py b/isaaclab_arena/tasks/pick_and_place_task.py index a22b3099..fafb28c8 100644 --- a/isaaclab_arena/tasks/pick_and_place_task.py +++ b/isaaclab_arena/tasks/pick_and_place_task.py @@ -230,7 +230,7 @@ def __post_init__(self): self.subtask_configs["robot"] = subtask_configs # We need to add the left and right subtasks for GR1. elif self.arm_mode in [MimicArmMode.LEFT, MimicArmMode.RIGHT]: - self.subtask_configs[self.arm_mode] = subtask_configs + self.subtask_configs[self.arm_mode.value] = subtask_configs # EEF on opposite side (arm is static) subtask_configs = [] subtask_configs.append( @@ -255,7 +255,7 @@ def __post_init__(self): apply_noise_during_interpolation=False, ) ) - self.subtask_configs[self.arm_mode.get_other_arm()] = subtask_configs + self.subtask_configs[self.arm_mode.get_other_arm().value] = subtask_configs else: raise ValueError(f"Embodiment arm mode {self.arm_mode} not supported") From 12a2e598788dbe53877e2cf833a0e97563b5de6f Mon Sep 17 00:00:00 2001 From: Xinjie Yao Date: Wed, 17 Dec 2025 18:24:16 -0800 Subject: [PATCH 23/26] Refactor OpenDoor task and Introduce CloseDoor Task (#295) ## Summary Implement `OpenDoorTask` and `CloseDoorTask` inherited from `RotateRevoluteJointTask` ## Detailed description - Generalize the task to common articulated objects with revolute joint. E.g. Cabinet door; Window panel (rotate outward or inward relative to the fixed frame using a hinge); Scissor blade at the pivot pin. - Open vs Close Door task differ in terminations & reset events, but share the same underlying logics handling revolute joint. - Add `is_closed` member function to `Openable` affordance, using threshold to decide either open or close. Basically use it as a bi-state object. ## TODO - Test with other articulated objects, than the overly-used microwave --- .../static_manipulation/step_5_evaluation.rst | 6 +- isaaclab_arena/affordances/openable.py | 59 ++-- isaaclab_arena/assets/object_library.py | 4 +- isaaclab_arena/assets/object_reference.py | 4 +- ...d_rate.py => revolute_joint_moved_rate.py} | 46 ++-- isaaclab_arena/tasks/close_door_task.py | 68 +++++ isaaclab_arena/tasks/common/__init__.py | 4 + .../tasks/common/open_close_door_mimic.py | 121 +++++++++ .../tasks/g1_locomanip_pick_and_place_task.py | 3 - isaaclab_arena/tasks/open_door_task.py | 207 ++------------ isaaclab_arena/tasks/pick_and_place_task.py | 3 - isaaclab_arena/tasks/press_button_task.py | 3 - .../tasks/rotate_revolute_joint_task.py | 101 +++++++ isaaclab_arena/tasks/task_base.py | 4 - isaaclab_arena/tests/test_affordance_base.py | 4 +- isaaclab_arena/tests/test_close_door.py | 254 ++++++++++++++++++ isaaclab_arena/tests/test_open_door.py | 2 +- .../tests/test_reference_objects.py | 2 +- ... test_revolute_joint_moved_rate_metric.py} | 14 +- 19 files changed, 650 insertions(+), 259 deletions(-) rename isaaclab_arena/metrics/{door_moved_rate.py => revolute_joint_moved_rate.py} (52%) create mode 100644 isaaclab_arena/tasks/close_door_task.py create mode 100644 isaaclab_arena/tasks/common/__init__.py create mode 100644 isaaclab_arena/tasks/common/open_close_door_mimic.py create mode 100644 isaaclab_arena/tasks/rotate_revolute_joint_task.py create mode 100644 isaaclab_arena/tests/test_close_door.py rename isaaclab_arena/tests/{test_door_moved_rate_metric.py => test_revolute_joint_moved_rate_metric.py} (89%) diff --git a/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst b/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst index a01f77b6..abb2b36a 100644 --- a/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst +++ b/docs/pages/example_workflows/static_manipulation/step_5_evaluation.rst @@ -97,13 +97,13 @@ post-trained policy, the quality of the dataset, and number of steps in the eval .. code-block:: text - Metrics: {'success_rate': 0.8823529411764706, 'door_moved_rate': 1.0, 'num_episodes': 17} + Metrics: {'success_rate': 0.8823529411764706, 'revolute_joint_moved_rate': 1.0, 'num_episodes': 17} .. tab:: Low Hardware Requirements .. code-block:: text - Metrics: {'success_rate': 1.0, 'door_moved_rate': 1.0, 'num_episodes': 19} + Metrics: {'success_rate': 1.0, 'revolute_joint_moved_rate': 1.0, 'num_episodes': 19} Step 2: Run Parallel environments Evaluation @@ -138,7 +138,7 @@ than the single environment evaluation because of the parallel evaluation. .. code-block:: text - Metrics: {'success_rate': 0.605, 'door_moved_rate': 0.955, 'num_episodes': 200} + Metrics: {'success_rate': 0.605, 'revolute_joint_moved_rate': 0.955, 'num_episodes': 200} .. note:: diff --git a/isaaclab_arena/affordances/openable.py b/isaaclab_arena/affordances/openable.py index 8dcbe806..357238af 100644 --- a/isaaclab_arena/affordances/openable.py +++ b/isaaclab_arena/affordances/openable.py @@ -15,11 +15,14 @@ class Openable(AffordanceBase): """Interface for openable objects.""" - def __init__(self, openable_joint_name: str, openable_open_threshold: float = 0.5, **kwargs): + def __init__(self, openable_joint_name: str, openable_threshold: float = 0.5, **kwargs): super().__init__(**kwargs) # TODO(alexmillane, 2025.08.26): We probably want to be able to define the polarity of the joint. self.openable_joint_name = openable_joint_name - self.openable_open_threshold = openable_open_threshold + # For a bistate object, we use a single threshold + # is_open: openness > threshold + # is_closed: openness <= threshold + self.openable_threshold = openable_threshold def get_openness(self, env: ManagerBasedEnv, asset_cfg: SceneEntityCfg | None = None) -> torch.Tensor: """Returns the percentage open that the object is.""" @@ -31,29 +34,57 @@ def get_openness(self, env: ManagerBasedEnv, asset_cfg: SceneEntityCfg | None = def is_open( self, env: ManagerBasedEnv, asset_cfg: SceneEntityCfg | None = None, threshold: float | None = None ) -> torch.Tensor: - """Returns a boolean tensor of whether the object is open.""" - # We allow for overriding the object-level threshold by passing an argument to this - # function explicitly. Otherwise we use the object-level threshold. + """Returns a boolean tensor of whether the object is open. + + For a bistate object, this checks if openness > threshold. + """ if threshold is not None: - openable_open_threshold = threshold + used_threshold = threshold else: - openable_open_threshold = self.openable_open_threshold + used_threshold = self.openable_threshold openness = self.get_openness(env, asset_cfg) - return openness > openable_open_threshold + return openness > used_threshold - def open( + def is_closed( + self, env: ManagerBasedEnv, asset_cfg: SceneEntityCfg | None = None, threshold: float | None = None + ) -> torch.Tensor: + """Returns a boolean tensor of whether the object is closed. + + For a bistate object, this checks if openness <= threshold. + This is the logical inverse of is_open(). + """ + if threshold is not None: + used_threshold = threshold + else: + used_threshold = self.openable_threshold + openness = self.get_openness(env, asset_cfg) + return openness <= used_threshold + + def rotate_revolute_joint( self, env: ManagerBasedEnv, env_ids: torch.Tensor | None, asset_cfg: SceneEntityCfg | None = None, - percentage: float = 1.0, + percentage: float = 0.0, ): - """Open the object (in all the environments).""" + """Rotate the revolute joint of the object to the given percentage (in all the environments).""" + assert percentage >= 0.0 and percentage <= 1.0, "Percentage must be between 0.0 and 1.0" if asset_cfg is None: asset_cfg = SceneEntityCfg(self.name) asset_cfg = self._add_joint_name_to_scene_entity_cfg(asset_cfg) set_normalized_joint_position(env, asset_cfg, percentage, env_ids) + # keep below for backwards compatibility + def open( + self, + env: ManagerBasedEnv, + env_ids: torch.Tensor | None, + asset_cfg: SceneEntityCfg | None = None, + percentage: float = 1.0, + ): + self.rotate_revolute_joint(env, env_ids, asset_cfg, percentage) + + # keep below for backwards compatibility def close( self, env: ManagerBasedEnv, @@ -61,11 +92,7 @@ def close( asset_cfg: SceneEntityCfg | None = None, percentage: float = 0.0, ): - """Close the object (in all the environments).""" - if asset_cfg is None: - asset_cfg = SceneEntityCfg(self.name) - asset_cfg = self._add_joint_name_to_scene_entity_cfg(asset_cfg) - set_normalized_joint_position(env, asset_cfg, percentage, env_ids) + self.rotate_revolute_joint(env, env_ids, asset_cfg, percentage) def _add_joint_name_to_scene_entity_cfg(self, asset_cfg: SceneEntityCfg) -> SceneEntityCfg: asset_cfg.joint_names = [self.openable_joint_name] diff --git a/isaaclab_arena/assets/object_library.py b/isaaclab_arena/assets/object_library.py index 1e4e5c15..d2ed4747 100644 --- a/isaaclab_arena/assets/object_library.py +++ b/isaaclab_arena/assets/object_library.py @@ -127,14 +127,14 @@ class Microwave(LibraryObject, Openable): # Openable affordance parameters openable_joint_name = "microjoint" - openable_open_threshold = 0.5 + openable_threshold = 0.5 # Bistate threshold (open > threshold, closed <= threshold) def __init__(self, prim_path: str | None = None, initial_pose: Pose | None = None): super().__init__( prim_path=prim_path, initial_pose=initial_pose, openable_joint_name=self.openable_joint_name, - openable_open_threshold=self.openable_open_threshold, + openable_threshold=self.openable_threshold, ) diff --git a/isaaclab_arena/assets/object_reference.py b/isaaclab_arena/assets/object_reference.py index 2b27716d..7c2d8926 100644 --- a/isaaclab_arena/assets/object_reference.py +++ b/isaaclab_arena/assets/object_reference.py @@ -129,10 +129,10 @@ def isaaclab_prim_path_to_original_prim_path( class OpenableObjectReference(ObjectReference, Openable): """An object which *refers* to an existing element in the scene and is openable.""" - def __init__(self, openable_joint_name: str, openable_open_threshold: float = 0.5, **kwargs): + def __init__(self, openable_joint_name: str, openable_threshold: float = 0.5, **kwargs): super().__init__( openable_joint_name=openable_joint_name, - openable_open_threshold=openable_open_threshold, + openable_threshold=openable_threshold, object_type=ObjectType.ARTICULATION, **kwargs, ) diff --git a/isaaclab_arena/metrics/door_moved_rate.py b/isaaclab_arena/metrics/revolute_joint_moved_rate.py similarity index 52% rename from isaaclab_arena/metrics/door_moved_rate.py rename to isaaclab_arena/metrics/revolute_joint_moved_rate.py index 0d85e3bf..2b1c82aa 100644 --- a/isaaclab_arena/metrics/door_moved_rate.py +++ b/isaaclab_arena/metrics/revolute_joint_moved_rate.py @@ -15,10 +15,10 @@ from isaaclab_arena.metrics.metric_base import MetricBase -class OpennessRecorder(RecorderTerm): +class RevoluteJointStateRecorder(RecorderTerm): """Records the openness of an object for each sim step of an episode.""" - name = "openness" + name = "revolute_joint_state" def __init__(self, cfg: RecorderTermCfg, env: ManagerBasedEnv): super().__init__(cfg, env) @@ -31,55 +31,55 @@ def record_post_step(self): @configclass class JointStateRecorderCfg(RecorderTermCfg): - class_type: type[RecorderTerm] = OpennessRecorder + class_type: type[RecorderTerm] = RevoluteJointStateRecorder object: ObjectBase = MISSING -class DoorMovedRateMetric(MetricBase): - """Computes the door-moved rate. +class RevoluteJointMovedRateMetric(MetricBase): + """Computes the revolute joint moved rate. - The door-moved rate is the number of episodes in which the door moved, divided + The revolute joint moved rate is the number of episodes in which the revolute joint moved, divided by the total number of episodes. """ - name = "door_moved_rate" - recorder_term_name = OpennessRecorder.name + name = "revolute_joint_moved_rate" + recorder_term_name = RevoluteJointStateRecorder.name - def __init__(self, object: Openable, reset_openness: float, openness_delta_threshold: float = 0.05): + def __init__(self, object: Openable, reset_joint_percentage: float, joint_percentage_delta_threshold: float = 0.05): """Initializes the door-moved rate metric. Args: object(Openable): The door to compute the door-moved rate for. - reset_openness(float): The initial openness of the door (what the door resets to). - openness_delta_threshold(float): The threshold for the door openness to be considered - moved. This is relative to the initial openness of the door. + reset_joint_percentage(float): The initial joint position of the door (what the door resets to). + joint_percentage_delta_threshold(float): The threshold for the door joint percentage to be considered + moved. This is relative to the initial joint position of the door. """ super().__init__() assert isinstance(object, Openable), "Object must be Openable" self.object = object - self.reset_openness = reset_openness - self.openness_delta_threshold = openness_delta_threshold + self.reset_joint_percentage = reset_joint_percentage + self.joint_percentage_delta_threshold = joint_percentage_delta_threshold def get_recorder_term_cfg(self) -> RecorderTermCfg: - """Return the recorder term configuration for the door-moved rate metric.""" + """Return the recorder term configuration for the revolute joint moved rate metric.""" return JointStateRecorderCfg(object=self.object) def compute_metric_from_recording(self, recorded_metric_data: list[np.ndarray]) -> float: - """Computes the door-moved rate from the recorded metric data. + """Computes the revolute joint moved rate from the recorded metric data. Args: - recorded_metric_data(list[np.ndarray]): The recorded door openness per simulated + recorded_metric_data(list[np.ndarray]): The recorded revolute joint percentage per simulated episode. Returns: - The door-moved rate(float). Value between 0 and 1. The proportion of episodes + The revolute joint moved rate(float). Value between 0 and 1. The proportion of episodes in which the door moved. """ if len(recorded_metric_data) == 0: return 0.0 - door_moved_per_demo = [] + revolute_joint_moved_per_demo = [] for episode_data in recorded_metric_data: - openness_threshold = self.reset_openness + self.openness_delta_threshold - door_moved_per_demo.append(np.any(episode_data > openness_threshold)) - door_moved_rate = np.mean(door_moved_per_demo) - return door_moved_rate + revolute_joint_percentage_threshold = self.reset_joint_percentage + self.joint_percentage_delta_threshold + revolute_joint_moved_per_demo.append(np.any(episode_data > revolute_joint_percentage_threshold)) + revolute_joint_moved_rate = np.mean(revolute_joint_moved_per_demo) + return revolute_joint_moved_rate diff --git a/isaaclab_arena/tasks/close_door_task.py b/isaaclab_arena/tasks/close_door_task.py new file mode 100644 index 00000000..081c0899 --- /dev/null +++ b/isaaclab_arena/tasks/close_door_task.py @@ -0,0 +1,68 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +from dataclasses import MISSING + +import isaaclab.envs.mdp as mdp_isaac_lab +from isaaclab.managers import TerminationTermCfg +from isaaclab.utils import configclass + +from isaaclab_arena.affordances.openable import Openable +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode +from isaaclab_arena.tasks.common.open_close_door_mimic import RotateDoorMimicEnvCfg +from isaaclab_arena.tasks.rotate_revolute_joint_task import RotateRevoluteJointTask + + +class CloseDoorTask(RotateRevoluteJointTask): + def __init__( + self, + openable_object: Openable, + closedness_threshold: float | None = None, + reset_openness: float = 1.0, # Start with door OPEN for close task + episode_length_s: float | None = None, + task_description: str | None = None, + ): + super().__init__( + openable_object=openable_object, + target_joint_percentage_threshold=closedness_threshold, + reset_joint_percentage=reset_openness, # Reset to OPEN + episode_length_s=episode_length_s, + task_description=task_description, + ) + + self.termination_cfg = self.make_termination_cfg() + self.task_description = ( + f"Reach out to the {openable_object.name} and close it." if task_description is None else task_description + ) + + def make_termination_cfg(self): + params = {} + if self.target_joint_percentage_threshold is not None: + params["threshold"] = self.target_joint_percentage_threshold + success = TerminationTermCfg( + func=self.openable_object.is_closed, + params=params, + ) + return TerminationsCfg(success=success) + + def get_termination_cfg(self): + return self.termination_cfg + + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): + return RotateDoorMimicEnvCfg( + arm_mode=arm_mode, + openable_object_name=self.openable_object.name, + ) + + +@configclass +class TerminationsCfg: + """Termination terms for the MDP.""" + + time_out: TerminationTermCfg = TerminationTermCfg(func=mdp_isaac_lab.time_out) + + # Dependent on the openable object, so this is passed in from the task at + # construction time. + success: TerminationTermCfg = MISSING diff --git a/isaaclab_arena/tasks/common/__init__.py b/isaaclab_arena/tasks/common/__init__.py new file mode 100644 index 00000000..687b3bcd --- /dev/null +++ b/isaaclab_arena/tasks/common/__init__.py @@ -0,0 +1,4 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 diff --git a/isaaclab_arena/tasks/common/open_close_door_mimic.py b/isaaclab_arena/tasks/common/open_close_door_mimic.py new file mode 100644 index 00000000..91cf9a33 --- /dev/null +++ b/isaaclab_arena/tasks/common/open_close_door_mimic.py @@ -0,0 +1,121 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + + +from isaaclab.envs.mimic_env_cfg import MimicEnvCfg, SubTaskConfig +from isaaclab.utils import configclass + +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode + + +@configclass +class RotateDoorMimicEnvCfg(MimicEnvCfg): + """ + Isaac Lab Mimic environment config class for Open Door env. + """ + + arm_mode: MimicArmMode = MimicArmMode.SINGLE_ARM + + openable_object_name: str = "openable_object" + + def __post_init__(self): + # post init of parents + super().__post_init__() + + # Override the existing values + self.datagen_config.name = "demo_src_rotatedoor_isaac_lab_task_D0" + self.datagen_config.generation_guarantee = True + self.datagen_config.generation_keep_failed = False + self.datagen_config.generation_num_trials = 100 + self.datagen_config.generation_select_src_per_subtask = False + self.datagen_config.generation_select_src_per_arm = False + self.datagen_config.generation_relative = False + self.datagen_config.generation_joint_pos = False + self.datagen_config.generation_transform_first_robot_pose = False + self.datagen_config.generation_interpolate_from_last_target_pose = True + self.datagen_config.max_num_failures = 25 + self.datagen_config.seed = 1 + + # The following are the subtask configurations for the pick and place task. + subtask_configs = [] + subtask_configs.append( + SubTaskConfig( + # Each subtask involves manipulation with respect to a single object frame. + object_ref=self.openable_object_name, + # This key corresponds to the binary indicator in "datagen_info" that signals + # when this subtask is finished (e.g., on a 0 to 1 edge). + subtask_term_signal="grasp_1", + # Specifies time offsets for data generation when splitting a trajectory into + # subtask segments. Random offsets are added to the termination boundary. + subtask_term_offset_range=(10, 20), + # Selection strategy for the source subtask segment during data generation + selection_strategy="nearest_neighbor_object", + # Optional parameters for the selection strategy function + selection_strategy_kwargs={"nn_k": 3}, + # Amount of action noise to apply during this subtask + action_noise=0.005, + # Number of interpolation steps to bridge to this subtask segment + num_interpolation_steps=5, + # Additional fixed steps for the robot to reach the necessary pose + num_fixed_steps=0, + # If True, apply action noise during the interpolation phase and execution + apply_noise_during_interpolation=False, + ) + ) + subtask_configs.append( + SubTaskConfig( + # Each subtask involves manipulation with respect to a single object frame. + object_ref=self.openable_object_name, + # End of final subtask does not need to be detected + subtask_term_signal=None, + # No time offsets for the final subtask + subtask_term_offset_range=(0, 0), + # Selection strategy for source subtask segment + selection_strategy="nearest_neighbor_object", + # Optional parameters for the selection strategy function + selection_strategy_kwargs={"nn_k": 3}, + # Amount of action noise to apply during this subtask + action_noise=0.005, + # Number of interpolation steps to bridge to this subtask segment + num_interpolation_steps=5, + # Additional fixed steps for the robot to reach the necessary pose + num_fixed_steps=0, + # If True, apply action noise during the interpolation phase and execution + apply_noise_during_interpolation=False, + ) + ) + if self.arm_mode == MimicArmMode.SINGLE_ARM: + self.subtask_configs["robot"] = subtask_configs + # We need to add the left and right subtasks for GR1. + elif self.arm_mode in [MimicArmMode.LEFT, MimicArmMode.RIGHT]: + self.subtask_configs[self.arm_mode.value] = subtask_configs + # EEF on opposite side (arm is static) + subtask_configs = [] + subtask_configs.append( + SubTaskConfig( + # Each subtask involves manipulation with respect to a single object frame. + object_ref=self.openable_object_name, + # Corresponding key for the binary indicator in "datagen_info" for completion + subtask_term_signal=None, + # Time offsets for data generation when splitting a trajectory + subtask_term_offset_range=(0, 0), + # Selection strategy for source subtask segment + selection_strategy="nearest_neighbor_object", + # Optional parameters for the selection strategy function + selection_strategy_kwargs={"nn_k": 3}, + # Amount of action noise to apply during this subtask + action_noise=0.005, + # Number of interpolation steps to bridge to this subtask segment + num_interpolation_steps=0, + # Additional fixed steps for the robot to reach the necessary pose + num_fixed_steps=0, + # If True, apply action noise during the interpolation phase and execution + apply_noise_during_interpolation=False, + ) + ) + self.subtask_configs[self.arm_mode.get_other_arm().value] = subtask_configs + + else: + raise ValueError(f"Embodiment arm mode {self.arm_mode} not supported") diff --git a/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py b/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py index 3ac8ff56..ff8e7ecb 100644 --- a/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py +++ b/isaaclab_arena/tasks/g1_locomanip_pick_and_place_task.py @@ -73,9 +73,6 @@ def get_termination_cfg(self): def get_events_cfg(self): return EventsCfg(pick_up_object=self.pick_up_object) - def get_prompt(self): - raise NotImplementedError("Function not implemented yet.") - def get_mimic_env_cfg(self, arm_mode: MimicArmMode): return G1LocomanipPickPlaceMimicEnvCfg() diff --git a/isaaclab_arena/tasks/open_door_task.py b/isaaclab_arena/tasks/open_door_task.py index 119e2ad8..2e79e7f3 100644 --- a/isaaclab_arena/tasks/open_door_task.py +++ b/isaaclab_arena/tasks/open_door_task.py @@ -3,86 +3,59 @@ # # SPDX-License-Identifier: Apache-2.0 -import numpy as np from dataclasses import MISSING import isaaclab.envs.mdp as mdp_isaac_lab -from isaaclab.envs.common import ViewerCfg -from isaaclab.envs.mimic_env_cfg import MimicEnvCfg, SubTaskConfig -from isaaclab.managers import EventTermCfg, SceneEntityCfg, TerminationTermCfg +from isaaclab.managers import TerminationTermCfg from isaaclab.utils import configclass from isaaclab_arena.affordances.openable import Openable from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode -from isaaclab_arena.metrics.door_moved_rate import DoorMovedRateMetric -from isaaclab_arena.metrics.metric_base import MetricBase -from isaaclab_arena.metrics.success_rate import SuccessRateMetric -from isaaclab_arena.tasks.task_base import TaskBase -from isaaclab_arena.terms.events import set_object_pose -from isaaclab_arena.utils.cameras import get_viewer_cfg_look_at_object +from isaaclab_arena.tasks.common.open_close_door_mimic import RotateDoorMimicEnvCfg +from isaaclab_arena.tasks.rotate_revolute_joint_task import RotateRevoluteJointTask -class OpenDoorTask(TaskBase): +class OpenDoorTask(RotateRevoluteJointTask): def __init__( self, openable_object: Openable, openness_threshold: float | None = None, - reset_openness: float | None = None, + reset_openness: float | None = 0.0, episode_length_s: float | None = None, task_description: str | None = None, ): - super().__init__(episode_length_s=episode_length_s) - assert isinstance(openable_object, Openable), "Openable object must be an instance of Openable" - self.openable_object = openable_object - self.openness_threshold = openness_threshold - self.reset_openness = reset_openness - self.scene_config = None - self.events_cfg = OpenDoorEventCfg(self.openable_object, reset_openness=self.reset_openness) + super().__init__( + openable_object=openable_object, + target_joint_percentage_threshold=openness_threshold, + reset_joint_percentage=reset_openness, + episode_length_s=episode_length_s, + task_description=task_description, + ) + self.termination_cfg = self.make_termination_cfg() self.task_description = ( f"Reach out to the {openable_object.name} and open it." if task_description is None else task_description ) - def get_scene_cfg(self): - return self.scene_config - - def get_termination_cfg(self): - return self.termination_cfg - def make_termination_cfg(self): params = {} - if self.openness_threshold is not None: - params["threshold"] = self.openness_threshold + if self.target_joint_percentage_threshold is not None: + params["threshold"] = self.target_joint_percentage_threshold success = TerminationTermCfg( func=self.openable_object.is_open, params=params, ) return TerminationsCfg(success=success) - def get_events_cfg(self): - return self.events_cfg - - def get_prompt(self): - raise NotImplementedError("Function not implemented yet.") + def get_termination_cfg(self): + return self.termination_cfg def get_mimic_env_cfg(self, arm_mode: MimicArmMode): - return OpenDoorMimicEnvCfg( + return RotateDoorMimicEnvCfg( arm_mode=arm_mode, openable_object_name=self.openable_object.name, ) - def get_metrics(self) -> list[MetricBase]: - return [ - SuccessRateMetric(), - DoorMovedRateMetric( - self.openable_object, - reset_openness=self.reset_openness, - ), - ] - - def get_viewer_cfg(self) -> ViewerCfg: - return get_viewer_cfg_look_at_object(lookat_object=self.openable_object, offset=np.array([-1.3, -1.3, 1.3])) - @configclass class TerminationsCfg: @@ -93,147 +66,3 @@ class TerminationsCfg: # Dependent on the openable object, so this is passed in from the task at # construction time. success: TerminationTermCfg = MISSING - - -@configclass -class OpenDoorEventCfg: - """Configuration for Open Door.""" - - reset_door_state: EventTermCfg = MISSING - - reset_openable_object_pose: EventTermCfg = MISSING - - def __init__(self, openable_object: Openable, reset_openness: float | None): - assert isinstance(openable_object, Openable), "Object pose must be an instance of Openable" - params = {} - if reset_openness is not None: - params["percentage"] = reset_openness - self.reset_door_state = EventTermCfg( - func=openable_object.close, - mode="reset", - params=params, - ) - initial_pose = openable_object.get_initial_pose() - if initial_pose is not None: - self.reset_openable_object_pose = EventTermCfg( - func=set_object_pose, - mode="reset", - params={ - "pose": initial_pose, - "asset_cfg": SceneEntityCfg(openable_object.name), - }, - ) - - -@configclass -class OpenDoorMimicEnvCfg(MimicEnvCfg): - """ - Isaac Lab Mimic environment config class for Open Door env. - """ - - arm_mode: MimicArmMode = MimicArmMode.SINGLE_ARM - - openable_object_name: str = "openable_object" - - def __post_init__(self): - # post init of parents - super().__post_init__() - - # Override the existing values - self.datagen_config.name = "demo_src_opendoor_isaac_lab_task_D0" - self.datagen_config.generation_guarantee = True - self.datagen_config.generation_keep_failed = False - self.datagen_config.generation_num_trials = 100 - self.datagen_config.generation_select_src_per_subtask = False - self.datagen_config.generation_select_src_per_arm = False - self.datagen_config.generation_relative = False - self.datagen_config.generation_joint_pos = False - self.datagen_config.generation_transform_first_robot_pose = False - self.datagen_config.generation_interpolate_from_last_target_pose = True - self.datagen_config.max_num_failures = 25 - self.datagen_config.seed = 1 - - # The following are the subtask configurations for the pick and place task. - subtask_configs = [] - subtask_configs.append( - SubTaskConfig( - # Each subtask involves manipulation with respect to a single object frame. - object_ref=self.openable_object_name, - # This key corresponds to the binary indicator in "datagen_info" that signals - # when this subtask is finished (e.g., on a 0 to 1 edge). - subtask_term_signal="grasp_1", - # Specifies time offsets for data generation when splitting a trajectory into - # subtask segments. Random offsets are added to the termination boundary. - subtask_term_offset_range=(10, 20), - # Selection strategy for the source subtask segment during data generation - selection_strategy="nearest_neighbor_object", - # Optional parameters for the selection strategy function - selection_strategy_kwargs={"nn_k": 3}, - # Amount of action noise to apply during this subtask - action_noise=0.005, - # Number of interpolation steps to bridge to this subtask segment - num_interpolation_steps=5, - # Additional fixed steps for the robot to reach the necessary pose - num_fixed_steps=0, - # If True, apply action noise during the interpolation phase and execution - apply_noise_during_interpolation=False, - ) - ) - subtask_configs.append( - SubTaskConfig( - # Each subtask involves manipulation with respect to a single object frame. - # TODO(alexmillane, 2025.09.02): This is currently broken. FIX. - # We need a way to pass in a reference to an object that exists in the - # scene. - object_ref=self.openable_object_name, - # End of final subtask does not need to be detected - subtask_term_signal=None, - # No time offsets for the final subtask - subtask_term_offset_range=(0, 0), - # Selection strategy for source subtask segment - selection_strategy="nearest_neighbor_object", - # Optional parameters for the selection strategy function - selection_strategy_kwargs={"nn_k": 3}, - # Amount of action noise to apply during this subtask - action_noise=0.005, - # Number of interpolation steps to bridge to this subtask segment - num_interpolation_steps=5, - # Additional fixed steps for the robot to reach the necessary pose - num_fixed_steps=0, - # If True, apply action noise during the interpolation phase and execution - apply_noise_during_interpolation=False, - ) - ) - if self.arm_mode == MimicArmMode.SINGLE_ARM: - self.subtask_configs["robot"] = subtask_configs - # We need to add the left and right subtasks for GR1. - elif self.arm_mode in [MimicArmMode.LEFT, MimicArmMode.RIGHT]: - self.subtask_configs[self.arm_mode.value] = subtask_configs - # EEF on opposite side (arm is static) - subtask_configs = [] - subtask_configs.append( - SubTaskConfig( - # Each subtask involves manipulation with respect to a single object frame. - object_ref=self.openable_object_name, - # Corresponding key for the binary indicator in "datagen_info" for completion - subtask_term_signal=None, - # Time offsets for data generation when splitting a trajectory - subtask_term_offset_range=(0, 0), - # Selection strategy for source subtask segment - selection_strategy="nearest_neighbor_object", - # Optional parameters for the selection strategy function - selection_strategy_kwargs={"nn_k": 3}, - # Amount of action noise to apply during this subtask - action_noise=0.005, - # Number of interpolation steps to bridge to this subtask segment - num_interpolation_steps=0, - # Additional fixed steps for the robot to reach the necessary pose - num_fixed_steps=0, - # If True, apply action noise during the interpolation phase and execution - apply_noise_during_interpolation=False, - ) - ) - self.subtask_configs[self.arm_mode.get_other_arm().value] = subtask_configs - - else: - raise ValueError(f"Embodiment arm mode {self.arm_mode} not supported") diff --git a/isaaclab_arena/tasks/pick_and_place_task.py b/isaaclab_arena/tasks/pick_and_place_task.py index fafb28c8..97d146f4 100644 --- a/isaaclab_arena/tasks/pick_and_place_task.py +++ b/isaaclab_arena/tasks/pick_and_place_task.py @@ -82,9 +82,6 @@ def make_termination_cfg(self): def get_events_cfg(self): return self.events_cfg - def get_prompt(self): - raise NotImplementedError("Function not implemented yet.") - def get_mimic_env_cfg(self, arm_mode: MimicArmMode): return PickPlaceMimicEnvCfg( arm_mode=arm_mode, diff --git a/isaaclab_arena/tasks/press_button_task.py b/isaaclab_arena/tasks/press_button_task.py index a08e35f0..5e515ab1 100644 --- a/isaaclab_arena/tasks/press_button_task.py +++ b/isaaclab_arena/tasks/press_button_task.py @@ -53,9 +53,6 @@ def get_termination_cfg(self): def get_events_cfg(self): return PressEventCfg(self.pressable_object, reset_pressedness=self.reset_pressedness) - def get_prompt(self): - raise NotImplementedError("Function not implemented yet.") - def get_mimic_env_cfg(self, arm_mode: MimicArmMode): raise NotImplementedError("Function not implemented yet.") diff --git a/isaaclab_arena/tasks/rotate_revolute_joint_task.py b/isaaclab_arena/tasks/rotate_revolute_joint_task.py new file mode 100644 index 00000000..db5d4eb7 --- /dev/null +++ b/isaaclab_arena/tasks/rotate_revolute_joint_task.py @@ -0,0 +1,101 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +import numpy as np +from dataclasses import MISSING + +from isaaclab.envs.common import ViewerCfg +from isaaclab.managers import EventTermCfg, SceneEntityCfg +from isaaclab.utils import configclass + +from isaaclab_arena.affordances.openable import Openable +from isaaclab_arena.embodiments.common.mimic_arm_mode import MimicArmMode +from isaaclab_arena.metrics.metric_base import MetricBase +from isaaclab_arena.metrics.revolute_joint_moved_rate import RevoluteJointMovedRateMetric +from isaaclab_arena.metrics.success_rate import SuccessRateMetric +from isaaclab_arena.tasks.task_base import TaskBase +from isaaclab_arena.terms.events import set_object_pose +from isaaclab_arena.utils.cameras import get_viewer_cfg_look_at_object + + +class RotateRevoluteJointTask(TaskBase): + def __init__( + self, + openable_object: Openable, + target_joint_percentage_threshold: float, + reset_joint_percentage: float, + episode_length_s: float | None = None, + task_description: str | None = None, + ): + super().__init__(episode_length_s=episode_length_s) + self.openable_object = openable_object + self.target_joint_percentage_threshold = target_joint_percentage_threshold + self.reset_joint_percentage = reset_joint_percentage + self.task_description = ( + f"Rotate the {self.openable_object.name} joint to the target {target_joint_percentage_threshold} joint" + " percentage." + if task_description is None + else task_description + ) + self.events_cfg = RotateRevoluteJointEventCfg( + self.openable_object, reset_openable_object_revolute_joint_percentage=self.reset_joint_percentage + ) + self.scene_config = None + self.termination_cfg = None + self.mimic_env_cfg = None + + def get_scene_cfg(self): + return self.scene_config + + def get_events_cfg(self): + return self.events_cfg + + def get_mimic_env_cfg(self, arm_mode: MimicArmMode): + raise NotImplementedError("Function {self.get_mimic_env_cfg.__name__} not implemented yet.") + + def get_termination_cfg(self): + raise NotImplementedError("Function {self.get_termination_cfg.__name__} not implemented yet.") + + def get_metrics(self) -> list[MetricBase]: + return [ + SuccessRateMetric(), + RevoluteJointMovedRateMetric( + self.openable_object, + reset_joint_percentage=self.reset_joint_percentage, + ), + ] + + def get_viewer_cfg(self) -> ViewerCfg: + return get_viewer_cfg_look_at_object(lookat_object=self.openable_object, offset=np.array([-1.3, -1.3, 1.3])) + + +@configclass +class RotateRevoluteJointEventCfg: + """Configuration for Open Door.""" + + reset_openable_object_revolute_joint_percentage: EventTermCfg = MISSING + + reset_openable_object_pose: EventTermCfg = MISSING + + def __init__(self, openable_object: Openable, reset_openable_object_revolute_joint_percentage: float | None): + assert isinstance(openable_object, Openable), "Object pose must be an instance of Openable" + params = {} + if reset_openable_object_revolute_joint_percentage is not None: + params["percentage"] = reset_openable_object_revolute_joint_percentage + self.reset_openable_object_revolute_joint_percentage = EventTermCfg( + func=openable_object.rotate_revolute_joint, + mode="reset", + params=params, + ) + initial_pose = openable_object.get_initial_pose() + if initial_pose is not None: + self.reset_openable_object_pose = EventTermCfg( + func=set_object_pose, + mode="reset", + params={ + "pose": initial_pose, + "asset_cfg": SceneEntityCfg(openable_object.name), + }, + ) diff --git a/isaaclab_arena/tasks/task_base.py b/isaaclab_arena/tasks/task_base.py index a3eef38e..bf891ac9 100644 --- a/isaaclab_arena/tasks/task_base.py +++ b/isaaclab_arena/tasks/task_base.py @@ -32,10 +32,6 @@ def get_termination_cfg(self) -> Any: def get_events_cfg(self) -> Any: raise NotImplementedError("Function not implemented yet.") - @abstractmethod - def get_prompt(self) -> str: - raise NotImplementedError("Function not implemented yet.") - @abstractmethod def get_mimic_env_cfg(self, arm_mode: MimicArmMode) -> Any: raise NotImplementedError("Function not implemented yet.") diff --git a/isaaclab_arena/tests/test_affordance_base.py b/isaaclab_arena/tests/test_affordance_base.py index e1c7ea5c..b1d6f4b7 100644 --- a/isaaclab_arena/tests/test_affordance_base.py +++ b/isaaclab_arena/tests/test_affordance_base.py @@ -31,10 +31,10 @@ class OpenableNotAnAsset(NotAnAsset, Openable): def __init__(self, **kwargs): super().__init__(**kwargs) - _ = OpenableAsset(name="test_name", openable_joint_name="test_joint_name", openable_open_threshold=0.5) + _ = OpenableAsset(name="test_name", openable_joint_name="test_joint_name", openable_threshold=0.5) with pytest.raises(TypeError) as exception_info: - _ = OpenableNotAnAsset(blah="test_name", openable_joint_name="test_joint_name", openable_open_threshold=0.5) + _ = OpenableNotAnAsset(blah="test_name", openable_joint_name="test_joint_name", openable_threshold=0.5) assert "Can't instantiate abstract class" in str(exception_info.value) return True diff --git a/isaaclab_arena/tests/test_close_door.py b/isaaclab_arena/tests/test_close_door.py new file mode 100644 index 00000000..bdaae350 --- /dev/null +++ b/isaaclab_arena/tests/test_close_door.py @@ -0,0 +1,254 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +import gymnasium as gym +import torch + +from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function + +NUM_STEPS = 10 +HEADLESS = True + + +def get_test_environment(remove_reset_door_state_event: bool, num_envs: int): + """Returns a scene which we use for these tests.""" + + from isaaclab_arena.assets.asset_registry import AssetRegistry + from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser + from isaaclab_arena.embodiments.franka.franka import FrankaEmbodiment + from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder + from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment + from isaaclab_arena.scene.scene import Scene + from isaaclab_arena.tasks.close_door_task import CloseDoorTask + from isaaclab_arena.utils.pose import Pose + + args_parser = get_isaaclab_arena_cli_parser() + args_cli = args_parser.parse_args(["--num_envs", str(num_envs)]) + + asset_registry = AssetRegistry() + background = asset_registry.get_asset_by_name("packing_table")() + microwave = asset_registry.get_asset_by_name("microwave")() + + # Put the microwave on the packing table. + microwave.set_initial_pose( + Pose( + position_xyz=(0.6, -0.00586, 0.22773), + rotation_wxyz=(0.7071068, 0, 0, -0.7071068), + ) + ) + + scene = Scene(assets=[background, microwave]) + + isaaclab_arena_environment = IsaacLabArenaEnvironment( + name="close_door", + embodiment=FrankaEmbodiment(), + scene=scene, + task=CloseDoorTask(microwave), + ) + + env_builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) + name, cfg = env_builder.build_registered() + if remove_reset_door_state_event: + # NOTE: We remove the event to reset the door position, + # to allow us to inspect the scene without having it reset. + cfg.events.reset_openable_object_revolute_joint_percentage = None + env = gym.make(name, cfg=cfg).unwrapped + env.reset() + + return env, microwave + + +def _test_close_door_microwave(simulation_app) -> bool: + + from isaaclab.envs.manager_based_env import ManagerBasedEnv + + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + # Get the scene + env, microwave = get_test_environment(remove_reset_door_state_event=True, num_envs=1) + + def assert_open(env: ManagerBasedEnv, terminated: torch.Tensor): + is_closed = microwave.is_closed(env) + assert is_closed.shape == torch.Size([1]) + assert not is_closed.item() + if not is_closed.item(): + print("Microwave is open") + # Check not terminated. + assert terminated.shape == torch.Size([1]) + assert not terminated.item() + if not terminated.item(): + print("Close door task is not completed") + + def assert_closed(env: ManagerBasedEnv, terminated: torch.Tensor): + is_closed = microwave.is_closed(env) + assert is_closed.shape == torch.Size([1]), "Is closed shape is not correct" + assert is_closed.item(), "The door is not closed when it should be" + if is_closed.item(): + print("Microwave is closed") + # Check terminated. + assert terminated.shape == torch.Size([1]), "Terminated shape is not correct" + assert terminated.item(), "The task didn't terminate when it should have" + if terminated.item(): + print("Close door task is completed") + + try: + + print("Opening microwave") + microwave.open(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_open) + print("Closing microwave") + microwave.close(env, env_ids=None) + step_zeros_and_call(env, NUM_STEPS, assert_closed) + + except Exception as e: + print(f"Error: {e}") + return False + + finally: + env.close() + + return True + + +def _test_close_door_microwave_multiple_envs(simulation_app) -> bool: + + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + env, microwave = get_test_environment(remove_reset_door_state_event=True, num_envs=2) + + try: + + with torch.inference_mode(): + # Open both + microwave.open(env, None) + step_zeros_and_call(env, NUM_STEPS) + is_closed = microwave.is_closed(env) + print(f"expected: [False, False]: got: {is_closed}") + assert torch.all(is_closed == torch.tensor([False, False], device=env.device)) + + # Close both + microwave.close(env, None) + step_zeros_and_call(env, NUM_STEPS) + is_closed = microwave.is_closed(env) + print(f"expected: [True, True]: got: {is_closed}") + assert torch.all(is_closed == torch.tensor([True, True], device=env.device)) + + # Open only env 0 + env_ids = torch.tensor([0], device=env.device) + microwave.open(env, env_ids) + step_zeros_and_call(env, NUM_STEPS) + is_closed = microwave.is_closed(env) + print(f"expected: [False, True]: got: {is_closed}") + assert torch.all(is_closed == torch.tensor([False, True], device=env.device)) + + # Close only env 0 + microwave.close(env, env_ids) + step_zeros_and_call(env, NUM_STEPS) + is_closed = microwave.is_closed(env) + print(f"expected: [True, True]: got: {is_closed}") + assert torch.all(is_closed == torch.tensor([True, True], device=env.device)) + + except Exception as e: + print(f"Error: {e}") + return False + + finally: + env.close() + + return True + + +def _test_close_door_with_reset(simulation_app) -> bool: + """Test that closing the door terminates the env and the env resets with door open.""" + + from isaaclab_arena.tests.utils.simulation import step_zeros_and_call + + # Get the environment WITHOUT removing the reset event + env, microwave = get_test_environment(remove_reset_door_state_event=False, num_envs=1) + + try: + with torch.inference_mode(): + # Initially, the door should be open (from reset event) + initial_openness = microwave.get_openness(env) + print(f"Initial openness after reset: {initial_openness.item()}") + + # Manually open it fully to ensure it's open + microwave.open(env, env_ids=None, percentage=1.0) + step_zeros_and_call(env, NUM_STEPS) + + is_closed = microwave.is_closed(env) + print(f"Door should be open: is_closed = {is_closed.item()}") + assert not is_closed.item(), "Door should be open initially" + + # Close the door - this should trigger task success and termination + print("Closing the door to trigger termination...") + microwave.close(env, env_ids=None, percentage=0.0) + + # Step and wait for termination + terminated = False + for step in range(NUM_STEPS * 2): # Give it more time to detect termination + actions = torch.zeros(env.action_space.shape, device=env.device) + _, _, term, _, _ = env.step(actions) + + is_closed = microwave.is_closed(env) + openness = microwave.get_openness(env) + print( + f"Step {step}: openness={openness.item():.3f}, is_closed={is_closed.item()}," + f" terminated={term.item()}" + ) + + if term.item(): + terminated = True + print(f"āœ“ Environment terminated at step {step}") + break + + assert terminated, "Environment should have terminated when door closed" + + # After termination, env auto-resets. The reset event should open the door again + # Take a few more steps to let the reset settle + for _ in range(5): + actions = torch.zeros(env.action_space.shape, device=env.device) + env.step(actions) + + # Check that door is open again after reset + openness_after_reset = microwave.get_openness(env) + is_closed_after_reset = microwave.is_closed(env) + print(f"After reset: openness={openness_after_reset.item():.3f}, is_closed={is_closed_after_reset.item()}") + + # The reset event should have set the door to the reset percentage + # which for CloseDoorTask should be relatively open + assert not is_closed_after_reset.item(), "Door should be open after reset" + print("āœ“ Environment reset successfully with door open") + + except Exception as e: + print(f"Error: {e}") + import traceback + + traceback.print_exc() + return False + + finally: + env.close() + + return True + + +# Test functions that will be called by pytest +def test_close_door_microwave(): + run_simulation_app_function(_test_close_door_microwave, headless=HEADLESS) + + +def test_close_door_microwave_multiple_envs(): + run_simulation_app_function(_test_close_door_microwave_multiple_envs, headless=HEADLESS) + + +def test_close_door_with_reset(): + run_simulation_app_function(_test_close_door_with_reset, headless=HEADLESS) + + +if __name__ == "__main__": + test_close_door_microwave() + test_close_door_microwave_multiple_envs() + test_close_door_with_reset() diff --git a/isaaclab_arena/tests/test_open_door.py b/isaaclab_arena/tests/test_open_door.py index b29a13f6..bb538bad 100644 --- a/isaaclab_arena/tests/test_open_door.py +++ b/isaaclab_arena/tests/test_open_door.py @@ -53,7 +53,7 @@ def get_test_environment(remove_reset_door_state_event: bool, num_envs: int): if remove_reset_door_state_event: # NOTE(alexmillane, 2025-09-01): We remove the event to reset the door position, # to allow us to inspect the scene without having it reset. - cfg.events.reset_door_state = None + cfg.events.reset_openable_object_revolute_joint_percentage = None env = gym.make(name, cfg=cfg).unwrapped env.reset() diff --git a/isaaclab_arena/tests/test_reference_objects.py b/isaaclab_arena/tests/test_reference_objects.py index e0891251..9e6a8f84 100644 --- a/isaaclab_arena/tests/test_reference_objects.py +++ b/isaaclab_arena/tests/test_reference_objects.py @@ -108,7 +108,7 @@ def _test_reference_objects_with_background_pose(background_pose: Pose, tmp_path prim_path="{ENV_REGEX_NS}/kitchen/microwave", parent_asset=background, openable_joint_name="microjoint", - openable_open_threshold=0.5, + openable_threshold=0.5, ) scene = Scene(assets=[background, cracker_box, microwave]) diff --git a/isaaclab_arena/tests/test_door_moved_rate_metric.py b/isaaclab_arena/tests/test_revolute_joint_moved_rate_metric.py similarity index 89% rename from isaaclab_arena/tests/test_door_moved_rate_metric.py rename to isaaclab_arena/tests/test_revolute_joint_moved_rate_metric.py index b5f7df68..7c2442e6 100644 --- a/isaaclab_arena/tests/test_door_moved_rate_metric.py +++ b/isaaclab_arena/tests/test_revolute_joint_moved_rate_metric.py @@ -23,7 +23,7 @@ EXPECTED_MOVEMENT_RATE_EPS = 1e-6 -def _test_door_moved_rate(simulation_app): +def _test_revolute_joint_moved_rate(simulation_app): """Returns a scene which we use for these tests.""" from isaaclab_arena.assets.asset_registry import AssetRegistry @@ -82,8 +82,8 @@ def _test_door_moved_rate(simulation_app): num_episodes_with_movement = metrics["num_episodes"] - num_episodes_no_movement expected_movement_rate = num_episodes_with_movement / metrics["num_episodes"] print(f"Expected movement rate: {expected_movement_rate}") - print(f"Measured movement rate: {metrics['door_moved_rate']}") - assert abs(metrics["door_moved_rate"] - expected_movement_rate) < EXPECTED_MOVEMENT_RATE_EPS + print(f"Measured movement rate: {metrics['revolute_joint_moved_rate']}") + assert abs(metrics["revolute_joint_moved_rate"] - expected_movement_rate) < EXPECTED_MOVEMENT_RATE_EPS except Exception as e: print(f"Error: {e}") @@ -95,13 +95,13 @@ def _test_door_moved_rate(simulation_app): return True -def test_door_moved_rate_metric(): +def test_revolute_joint_moved_rate_metric(): result = run_simulation_app_function( - _test_door_moved_rate, + _test_revolute_joint_moved_rate, headless=HEADLESS, ) - assert result, f"Test {test_door_moved_rate_metric.__name__} failed" + assert result, f"Test {test_revolute_joint_moved_rate_metric.__name__} failed" if __name__ == "__main__": - test_door_moved_rate_metric() + test_revolute_joint_moved_rate_metric() From 518af836ff550a7060baacc16a24d91ca11c1e85 Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Thu, 18 Dec 2025 08:38:14 +0100 Subject: [PATCH 24/26] Feature/teleop design (#286) ## Summary Simplify device registry and add a retargeter registry --- isaaclab_arena/assets/asset_registry.py | 72 +++++++++++--- isaaclab_arena/assets/device_library.py | 95 +++++++++++++++++++ isaaclab_arena/assets/register.py | 17 +++- isaaclab_arena/assets/retargeter_library.py | 85 +++++++++++++++++ .../environments/arena_env_builder.py | 6 +- .../isaaclab_arena_environment.py | 2 +- isaaclab_arena/teleop_devices/__init__.py | 8 -- .../teleop_devices/avp_handtracking.py | 59 ------------ isaaclab_arena/teleop_devices/keyboard.py | 48 ---------- isaaclab_arena/teleop_devices/spacemouse.py | 48 ---------- .../teleop_devices/teleop_device_base.py | 18 ---- .../test_device_and_retargeter_registry.py | 84 ++++++++++++++++ isaaclab_arena/tests/test_device_registry.py | 78 --------------- 13 files changed, 341 insertions(+), 279 deletions(-) create mode 100644 isaaclab_arena/assets/device_library.py create mode 100644 isaaclab_arena/assets/retargeter_library.py delete mode 100644 isaaclab_arena/teleop_devices/__init__.py delete mode 100644 isaaclab_arena/teleop_devices/avp_handtracking.py delete mode 100644 isaaclab_arena/teleop_devices/keyboard.py delete mode 100644 isaaclab_arena/teleop_devices/spacemouse.py delete mode 100644 isaaclab_arena/teleop_devices/teleop_device_base.py create mode 100644 isaaclab_arena/tests/test_device_and_retargeter_registry.py delete mode 100644 isaaclab_arena/tests/test_device_registry.py diff --git a/isaaclab_arena/assets/asset_registry.py b/isaaclab_arena/assets/asset_registry.py index 2edfb6bd..f7f91da0 100644 --- a/isaaclab_arena/assets/asset_registry.py +++ b/isaaclab_arena/assets/asset_registry.py @@ -10,7 +10,7 @@ if TYPE_CHECKING: from isaaclab_arena.assets.asset import Asset - from isaaclab_arena.teleop_devices.teleop_device_base import TeleopDeviceBase + from isaaclab_arena.assets.teleop_device_base import TeleopDeviceBase # Have to define all classes here in order to avoid circular import. @@ -19,41 +19,53 @@ class Registry(metaclass=SingletonMeta): def __init__(self): self._components = {} - def register(self, component: Any): + def register(self, component: Any, key: str | None = None): """Register an asset with a name. Args: - name (str): The name of the asset. + key (str): The name of the asset. asset (Asset): The asset to register. """ - assert component.name not in self._components, f"component {component.name} already registered" - assert component.name is not None, "component name is not set" - self._components[component.name] = component + assert key not in self._components, f"component {key} already registered" + assert key is not None, "component name is not set" + self._components[key] = component - def is_registered(self, name: str) -> bool: + def is_registered(self, key: str) -> bool: """Check if an component is registered. Args: - name (str): The name of the component. + key (str): The name of the component. """ # For AssetRegistry and DeviceRegistry, ensure assets are registered before checking - if isinstance(self, (AssetRegistry, DeviceRegistry)): + if isinstance(self, (AssetRegistry, DeviceRegistry, RetargeterRegistry)): ensure_assets_registered() - return name in self._components + return key in self._components - def get_component_by_name(self, name: str) -> Any: + def get_component_by_name(self, key: str) -> Any: """Get an component by name. Args: - name (str): The name of the component. + key (str): The name of the component. Returns: Asset: The component. """ # For AssetRegistry and DeviceRegistry, ensure assets are registered before accessing - if isinstance(self, (AssetRegistry, DeviceRegistry)): + if isinstance(self, (AssetRegistry, DeviceRegistry, RetargeterRegistry)): + ensure_assets_registered() + assert key in self._components, f"component {key} not found, please check if requested component is registered" + return self._components[key] + + def get_all_keys(self) -> list[str]: + """Get all the keys of the components. + + Returns: + list[str | tuple[str, str]]: The list of keys. + """ + # For AssetRegistry and DeviceRegistry, ensure assets are registered before accessing + if isinstance(self, (AssetRegistry, DeviceRegistry, RetargeterRegistry)): ensure_assets_registered() - return self._components[name] + return list(self._components.keys()) class AssetRegistry(Registry): @@ -112,6 +124,35 @@ def get_device_by_name(self, name: str) -> type["TeleopDeviceBase"]: ensure_assets_registered() return self.get_component_by_name(name) + def get_teleop_device_cfg(self, device: type["TeleopDeviceBase"], embodiment: object): + from isaaclab.devices.device_base import DevicesCfg + + retargeter_registry = RetargeterRegistry() + retargeter_key = (device.name, embodiment.name) + retargeter_key_str = retargeter_registry.convert_tuple_to_str(retargeter_key) + retargeter = retargeter_registry.get_component_by_name(retargeter_key_str)() + retargeter_cfg = retargeter.get_retargeter_cfg(embodiment, sim_device=device.sim_device) + retargeters = [retargeter_cfg] if retargeter_cfg is not None else [] + device_cfg = device.get_device_cfg(retargeters=retargeters, embodiment=embodiment) + return DevicesCfg( + devices={ + device.name: device_cfg, + } + ) + + +class RetargeterRegistry(Registry): + def __init__(self): + super().__init__() + + def convert_tuple_to_str(self, key: tuple[str, str]) -> str: + # Double underscore is used to separate device and embodiment names. + return f"{key[0]}__{key[1]}" + + def convert_str_to_tuple(self, key: str) -> tuple[str, str]: + # Double underscore is used to separate device and embodiment names. + return (key.split("__")[0], key.split("__")[1]) + # Lazy registration to avoid circular imports _assets_registered = False @@ -123,8 +164,9 @@ def ensure_assets_registered(): if not _assets_registered: # Import modules to trigger asset registration via decorators import isaaclab_arena.assets.background_library # noqa: F401 + import isaaclab_arena.assets.device_library # noqa: F401 import isaaclab_arena.assets.object_library # noqa: F401 + import isaaclab_arena.assets.retargeter_library # noqa: F401 import isaaclab_arena.embodiments # noqa: F401 - import isaaclab_arena.teleop_devices # noqa: F401 _assets_registered = True diff --git a/isaaclab_arena/assets/device_library.py b/isaaclab_arena/assets/device_library.py new file mode 100644 index 00000000..2fbec87e --- /dev/null +++ b/isaaclab_arena/assets/device_library.py @@ -0,0 +1,95 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from abc import ABC, abstractmethod + +from isaaclab.devices.keyboard import Se3KeyboardCfg +from isaaclab.devices.openxr import OpenXRDeviceCfg +from isaaclab.devices.retargeter_base import RetargeterCfg +from isaaclab.devices.spacemouse import Se3SpaceMouseCfg + +from isaaclab_arena.assets.register import register_device + + +class TeleopDeviceBase(ABC): + + name: str | None = None + + def __init__(self, sim_device: str | None = None): + self.sim_device = sim_device + + @abstractmethod + def get_device_cfg(self, retargeters: list[RetargeterCfg] | None = None, embodiment: object | None = None): + raise NotImplementedError + + +@register_device +class OpenXRCfg(TeleopDeviceBase): + name = "openxr" + + def __init__(self, sim_device: str | None = None): + super().__init__(sim_device=sim_device) + + def get_device_cfg( + self, retargeters: list[RetargeterCfg] | None = None, embodiment: object | None = None + ) -> OpenXRDeviceCfg: + return OpenXRDeviceCfg( + retargeters=retargeters, + sim_device=self.sim_device, + xr_cfg=embodiment.get_xr_cfg(), + ) + + +@register_device +class KeyboardCfg(TeleopDeviceBase): + name = "keyboard" + + def __init__(self, sim_device: str | None = None, pos_sensitivity: float = 0.05, rot_sensitivity: float = 0.05): + super().__init__(sim_device=sim_device) + self.pos_sensitivity = pos_sensitivity + self.rot_sensitivity = rot_sensitivity + + def get_device_cfg( + self, retargeters: list[RetargeterCfg] | None = None, embodiment: object | None = None + ) -> Se3KeyboardCfg: + return Se3KeyboardCfg( + retargeters=retargeters, + sim_device=self.sim_device, + pos_sensitivity=self.pos_sensitivity, + rot_sensitivity=self.rot_sensitivity, + ) + + +@register_device +class SpaceMouseCfg(TeleopDeviceBase): + name = "spacemouse" + + def __init__(self, sim_device: str | None = None, pos_sensitivity: float = 0.05, rot_sensitivity: float = 0.05): + super().__init__(sim_device=sim_device) + self.pos_sensitivity = pos_sensitivity + self.rot_sensitivity = rot_sensitivity + + def get_device_cfg( + self, retargeters: list[RetargeterCfg] | None = None, embodiment: object | None = None + ) -> Se3SpaceMouseCfg: + return Se3SpaceMouseCfg( + retargeters=retargeters, + sim_device=self.sim_device, + pos_sensitivity=self.pos_sensitivity, + rot_sensitivity=self.rot_sensitivity, + ) diff --git a/isaaclab_arena/assets/register.py b/isaaclab_arena/assets/register.py index 8cbd755d..64cdf84e 100644 --- a/isaaclab_arena/assets/register.py +++ b/isaaclab_arena/assets/register.py @@ -3,7 +3,7 @@ # # SPDX-License-Identifier: Apache-2.0 -from isaaclab_arena.assets.asset_registry import AssetRegistry, DeviceRegistry +from isaaclab_arena.assets.asset_registry import AssetRegistry, DeviceRegistry, RetargeterRegistry # Decorator to register an asset with the AssetRegistry. @@ -11,7 +11,7 @@ def register_asset(cls): if AssetRegistry().is_registered(cls.name): print(f"WARNING: Asset {cls.name} is already registered. Doing nothing.") else: - AssetRegistry().register(cls) + AssetRegistry().register(cls, cls.name) return cls @@ -20,5 +20,16 @@ def register_device(cls): if DeviceRegistry().is_registered(cls.name): print(f"WARNING: Device {cls.name} is already registered. Doing nothing.") else: - DeviceRegistry().register(cls) + DeviceRegistry().register(cls, cls.name) + return cls + + +# Decorator to register an retargeter with the RetargeterRegistry. +def register_retargeter(cls): + retargeter_key = (cls.device, cls.embodiment) + retargeter_key_str = RetargeterRegistry().convert_tuple_to_str(retargeter_key) + if RetargeterRegistry().is_registered(retargeter_key_str): + print(f"WARNING: Retargeter {cls.device} for {cls.embodiment} is already registered. Doing nothing.") + else: + RetargeterRegistry().register(cls, retargeter_key_str) return cls diff --git a/isaaclab_arena/assets/retargeter_library.py b/isaaclab_arena/assets/retargeter_library.py new file mode 100644 index 00000000..cfceaff6 --- /dev/null +++ b/isaaclab_arena/assets/retargeter_library.py @@ -0,0 +1,85 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from abc import ABC, abstractmethod + +from isaaclab.devices.openxr.retargeters import GR1T2RetargeterCfg +from isaaclab.devices.retargeter_base import RetargeterCfg + +from isaaclab_arena.assets.register import register_retargeter + + +class RetargetterBase(ABC): + device: str + embodiment: str + + @abstractmethod + def get_retargeter_cfg( + self, embodiment: object, sim_device: str, enable_visualization: bool = False + ) -> RetargeterCfg: + raise NotImplementedError + + +@register_retargeter +class GR1T2PinkOpenXRRetargeter(RetargetterBase): + + device = "openxr" + embodiment = "gr1_pink" + num_open_xr_hand_joints = 52 + + def __init__(self): + pass + + def get_retargeter_cfg( + self, gr1t2_embodiment, sim_device: str, enable_visualization: bool = False + ) -> RetargeterCfg: + return GR1T2RetargeterCfg( + enable_visualization=enable_visualization, + # number of joints in both hands + num_open_xr_hand_joints=self.num_open_xr_hand_joints, + sim_device=sim_device, + hand_joint_names=gr1t2_embodiment.get_action_cfg().upper_body_ik.hand_joint_names, + ) + + +@register_retargeter +class FrankaKeyboardRetargeter(RetargetterBase): + device = "keyboard" + embodiment = "franka" + + def __init__(self): + pass + + def get_retargeter_cfg( + self, franka_embodiment, sim_device: str, enable_visualization: bool = False + ) -> RetargeterCfg | None: + return None + + +@register_retargeter +class FrankaSpaceMouseRetargeter(RetargetterBase): + device = "spacemouse" + embodiment = "franka" + + def __init__(self): + pass + + def get_retargeter_cfg( + self, franka_embodiment, sim_device: str, enable_visualization: bool = False + ) -> RetargeterCfg | None: + return None diff --git a/isaaclab_arena/environments/arena_env_builder.py b/isaaclab_arena/environments/arena_env_builder.py index 420b138f..182de7e5 100644 --- a/isaaclab_arena/environments/arena_env_builder.py +++ b/isaaclab_arena/environments/arena_env_builder.py @@ -14,6 +14,7 @@ from isaaclab.scene import InteractiveSceneCfg from isaaclab_tasks.utils import parse_env_cfg +from isaaclab_arena.assets.asset_registry import DeviceRegistry from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment from isaaclab_arena.environments.isaaclab_arena_manager_based_env import ( IsaacArenaManagerBasedMimicEnvCfg, @@ -82,7 +83,10 @@ def compose_manager_cfg(self) -> IsaacLabArenaManagerBasedRLEnvCfg: actions_cfg = self.arena_env.embodiment.get_action_cfg() xr_cfg = self.arena_env.embodiment.get_xr_cfg() if self.arena_env.teleop_device is not None: - teleop_device_cfg = self.arena_env.teleop_device.get_teleop_device_cfg(embodiment=self.arena_env.embodiment) + device_registry = DeviceRegistry() + teleop_device_cfg = device_registry.get_teleop_device_cfg( + self.arena_env.teleop_device, self.arena_env.embodiment + ) else: teleop_device_cfg = None metrics = self.arena_env.task.get_metrics() diff --git a/isaaclab_arena/environments/isaaclab_arena_environment.py b/isaaclab_arena/environments/isaaclab_arena_environment.py index 19c93dad..31def833 100644 --- a/isaaclab_arena/environments/isaaclab_arena_environment.py +++ b/isaaclab_arena/environments/isaaclab_arena_environment.py @@ -12,12 +12,12 @@ from isaaclab.utils import configclass if TYPE_CHECKING: + from isaaclab_arena.assets.teleop_device_base import TeleopDeviceBase from isaaclab_arena.embodiments.embodiment_base import EmbodimentBase from isaaclab_arena.environments.isaaclab_arena_manager_based_env import IsaacLabArenaManagerBasedRLEnvCfg from isaaclab_arena.orchestrator.orchestrator_base import OrchestratorBase from isaaclab_arena.scene.scene import Scene from isaaclab_arena.tasks.task_base import TaskBase - from isaaclab_arena.teleop_devices.teleop_device_base import TeleopDeviceBase @configclass diff --git a/isaaclab_arena/teleop_devices/__init__.py b/isaaclab_arena/teleop_devices/__init__.py deleted file mode 100644 index 99d4b4b3..00000000 --- a/isaaclab_arena/teleop_devices/__init__.py +++ /dev/null @@ -1,8 +0,0 @@ -# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: Apache-2.0 - -from .avp_handtracking import * -from .keyboard import * -from .spacemouse import * diff --git a/isaaclab_arena/teleop_devices/avp_handtracking.py b/isaaclab_arena/teleop_devices/avp_handtracking.py deleted file mode 100644 index 320ab257..00000000 --- a/isaaclab_arena/teleop_devices/avp_handtracking.py +++ /dev/null @@ -1,59 +0,0 @@ -# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: Apache-2.0 - -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from isaaclab.devices.device_base import DevicesCfg -from isaaclab.devices.openxr import OpenXRDeviceCfg -from isaaclab.devices.openxr.retargeters import GR1T2RetargeterCfg - -from isaaclab_arena.assets.register import register_device -from isaaclab_arena.teleop_devices.teleop_device_base import TeleopDeviceBase - - -@register_device -class HandTrackingTeleopDevice(TeleopDeviceBase): - """ - Teleop device for hand tracking. - """ - - name = "avp_handtracking" - - def __init__( - self, sim_device: str | None = None, num_open_xr_hand_joints: int = 52, enable_visualization: bool = True - ): - super().__init__(sim_device=sim_device) - self.num_open_xr_hand_joints = num_open_xr_hand_joints - self.enable_visualization = enable_visualization - - def get_teleop_device_cfg(self, embodiment: object | None = None): - return DevicesCfg( - devices={ - "avp_handtracking": OpenXRDeviceCfg( - retargeters=[ - GR1T2RetargeterCfg( - enable_visualization=self.enable_visualization, - # number of joints in both hands - num_open_xr_hand_joints=self.num_open_xr_hand_joints, - sim_device=self.sim_device, - hand_joint_names=embodiment.get_action_cfg().upper_body_ik.hand_joint_names, - ), - ], - sim_device=self.sim_device, - xr_cfg=embodiment.get_xr_cfg(), - ), - } - ) diff --git a/isaaclab_arena/teleop_devices/keyboard.py b/isaaclab_arena/teleop_devices/keyboard.py deleted file mode 100644 index 784102a0..00000000 --- a/isaaclab_arena/teleop_devices/keyboard.py +++ /dev/null @@ -1,48 +0,0 @@ -# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: Apache-2.0 - -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from isaaclab.devices.device_base import DevicesCfg -from isaaclab.devices.keyboard import Se3KeyboardCfg - -from isaaclab_arena.assets.register import register_device -from isaaclab_arena.teleop_devices.teleop_device_base import TeleopDeviceBase - - -@register_device -class KeyboardTeleopDevice(TeleopDeviceBase): - """ - Teleop device for keyboard. - """ - - name = "keyboard" - - def __init__(self, sim_device: str | None = None, pos_sensitivity: float = 0.05, rot_sensitivity: float = 0.05): - super().__init__(sim_device=sim_device) - self.pos_sensitivity = pos_sensitivity - self.rot_sensitivity = rot_sensitivity - - def get_teleop_device_cfg(self, embodiment: object | None = None): - return DevicesCfg( - devices={ - "keyboard": Se3KeyboardCfg( - pos_sensitivity=self.pos_sensitivity, - rot_sensitivity=self.rot_sensitivity, - sim_device=self.sim_device, - ), - } - ) diff --git a/isaaclab_arena/teleop_devices/spacemouse.py b/isaaclab_arena/teleop_devices/spacemouse.py deleted file mode 100644 index 76cf4e92..00000000 --- a/isaaclab_arena/teleop_devices/spacemouse.py +++ /dev/null @@ -1,48 +0,0 @@ -# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: Apache-2.0 - -# -# Licensed under the Apache License, Version 2.0 (the "License"); -# you may not use this file except in compliance with the License. -# You may obtain a copy of the License at -# -# http://www.apache.org/licenses/LICENSE-2.0 -# -# Unless required by applicable law or agreed to in writing, software -# distributed under the License is distributed on an "AS IS" BASIS, -# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. -# See the License for the specific language governing permissions and -# limitations under the License. - -from isaaclab.devices.device_base import DevicesCfg -from isaaclab.devices.spacemouse import Se3SpaceMouseCfg - -from isaaclab_arena.assets.register import register_device -from isaaclab_arena.teleop_devices.teleop_device_base import TeleopDeviceBase - - -@register_device -class SpacemouseTeleopDevice(TeleopDeviceBase): - """ - Teleop device for spacemouse. - """ - - name = "spacemouse" - - def __init__(self, sim_device: str | None = None, pos_sensitivity: float = 0.05, rot_sensitivity: float = 0.05): - super().__init__(sim_device=sim_device) - self.pos_sensitivity = pos_sensitivity - self.rot_sensitivity = rot_sensitivity - - def get_teleop_device_cfg(self, embodiment: object | None = None): - return DevicesCfg( - devices={ - "spacemouse": Se3SpaceMouseCfg( - pos_sensitivity=self.pos_sensitivity, - rot_sensitivity=self.rot_sensitivity, - sim_device=self.sim_device, - ), - } - ) diff --git a/isaaclab_arena/teleop_devices/teleop_device_base.py b/isaaclab_arena/teleop_devices/teleop_device_base.py deleted file mode 100644 index 8537f5ea..00000000 --- a/isaaclab_arena/teleop_devices/teleop_device_base.py +++ /dev/null @@ -1,18 +0,0 @@ -# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: Apache-2.0 - -from abc import ABC, abstractmethod - - -class TeleopDeviceBase(ABC): - - name: str | None = None - - def __init__(self, sim_device: str | None = None): - self.sim_device = sim_device - - @abstractmethod - def get_teleop_device_cfg(self, embodiment: object | None = None): - raise NotImplementedError diff --git a/isaaclab_arena/tests/test_device_and_retargeter_registry.py b/isaaclab_arena/tests/test_device_and_retargeter_registry.py new file mode 100644 index 00000000..9467b264 --- /dev/null +++ b/isaaclab_arena/tests/test_device_and_retargeter_registry.py @@ -0,0 +1,84 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +import gymnasium as gym +import torch +import tqdm + +from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser +from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function +from isaaclab_arena.utils.isaaclab_utils.simulation_app import teardown_simulation_app + +NUM_STEPS = 2 +HEADLESS = True +DEVICE_NAMES = ["openxr", "spacemouse", "keyboard"] + + +def _test_all_devices_and_retargeters_in_registry(simulation_app): + # Import the necessary classes. + + from isaaclab_arena.assets.asset_registry import AssetRegistry, DeviceRegistry, RetargeterRegistry + from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder + from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment + from isaaclab_arena.scene.scene import Scene + from isaaclab_arena.tasks.dummy_task import DummyTask + + # Base Environment + asset_registry = AssetRegistry() + device_registry = DeviceRegistry() + retargeter_registry = RetargeterRegistry() + retargeter_keys = retargeter_registry.get_all_keys() + background = asset_registry.get_asset_by_name("packing_table")() + asset = asset_registry.get_asset_by_name("cracker_box")() + + for device_name in DEVICE_NAMES: + # Get all available embodiments for this device + for retargeter_key in retargeter_keys: + if device_name in retargeter_key: + continue + device_name, embodiment_name = retargeter_registry.convert_str_to_tuple(retargeter_key) + embodiment = asset_registry.get_asset_by_name(embodiment_name)() + teleop_device = device_registry.get_device_by_name(device_name)() + isaaclab_arena_environment = IsaacLabArenaEnvironment( + name=f"{device_name}_{retargeter_key}", + embodiment=embodiment, + scene=Scene([background, asset]), + task=DummyTask(), + teleop_device=teleop_device, + ) + + # Remove previous environment if it exists. + if isaaclab_arena_environment.name in gym.registry: + del gym.registry[isaaclab_arena_environment.name] + + # Compile the environment. + args_parser = get_isaaclab_arena_cli_parser() + args_cli = args_parser.parse_args([]) + + builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) + + env = builder.make_registered() + + env.reset() + # Run some zero actions. + for _ in tqdm.tqdm(range(NUM_STEPS)): + with torch.inference_mode(): + actions = torch.zeros(env.action_space.shape, device=env.unwrapped.device) + env.step(actions) + + # Close the environment using safe teardown + # Also creates a new stage for the next test + teardown_simulation_app(suppress_exceptions=True, make_new_stage=True) + + return True + + +def test_all_devices_and_retargeters_in_registry(): + # Basic test that just adds all our pick-up objects to the scene and checks that nothing crashes. + result = run_simulation_app_function( + _test_all_devices_and_retargeters_in_registry, + headless=HEADLESS, + ) + assert result, "Test failed" diff --git a/isaaclab_arena/tests/test_device_registry.py b/isaaclab_arena/tests/test_device_registry.py deleted file mode 100644 index c4a9a3e7..00000000 --- a/isaaclab_arena/tests/test_device_registry.py +++ /dev/null @@ -1,78 +0,0 @@ -# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: Apache-2.0 - -import gymnasium as gym -import torch -import tqdm - -from isaaclab_arena.cli.isaaclab_arena_cli import get_isaaclab_arena_cli_parser -from isaaclab_arena.tests.utils.subprocess import run_simulation_app_function -from isaaclab_arena.utils.isaaclab_utils.simulation_app import teardown_simulation_app - -NUM_STEPS = 2 -HEADLESS = True -DEVICE_NAMES = ["avp_handtracking", "spacemouse", "keyboard"] - - -def _test_all_devices_in_registry(simulation_app): - # Import the necessary classes. - - from isaaclab_arena.assets.asset_registry import AssetRegistry, DeviceRegistry - from isaaclab_arena.embodiments.gr1t2.gr1t2 import GR1T2PinkEmbodiment - from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder - from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment - from isaaclab_arena.scene.scene import Scene - from isaaclab_arena.tasks.dummy_task import DummyTask - - # Base Environment - asset_registry = AssetRegistry() - device_registry = DeviceRegistry() - background = asset_registry.get_asset_by_name("packing_table")() - asset = asset_registry.get_asset_by_name("cracker_box")() - - for device_name in DEVICE_NAMES: - - teleop_device = device_registry.get_device_by_name(device_name)() - isaaclab_arena_environment = IsaacLabArenaEnvironment( - name="kitchen", - embodiment=GR1T2PinkEmbodiment(), - scene=Scene([background, asset]), - task=DummyTask(), - teleop_device=teleop_device, - ) - - # Remove previous environment if it exists. - if isaaclab_arena_environment.name in gym.registry: - del gym.registry[isaaclab_arena_environment.name] - - # Compile the environment. - args_parser = get_isaaclab_arena_cli_parser() - args_cli = args_parser.parse_args([]) - - builder = ArenaEnvBuilder(isaaclab_arena_environment, args_cli) - - env = builder.make_registered() - - env.reset() - # Run some zero actions. - for _ in tqdm.tqdm(range(NUM_STEPS)): - with torch.inference_mode(): - actions = torch.zeros(env.action_space.shape, device=env.unwrapped.device) - env.step(actions) - - # Close the environment using safe teardown - # Also creates a new stage for the next test - teardown_simulation_app(suppress_exceptions=True, make_new_stage=True) - - return True - - -def test_all_devices_in_registry(): - # Basic test that just adds all our pick-up objects to the scene and checks that nothing crashes. - result = run_simulation_app_function( - _test_all_devices_in_registry, - headless=HEADLESS, - ) - assert result, "Test failed" From f6c9d91a4d0ae8d8e69d678f28946005b76ce1af Mon Sep 17 00:00:00 2001 From: Vikram Ramasamy <158473438+viiik-inside@users.noreply.github.com> Date: Thu, 18 Dec 2025 10:44:00 +0100 Subject: [PATCH 25/26] Add warning in docs (#302) ## Summary Add warning to docs --- docs/index.rst | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/docs/index.rst b/docs/index.rst index 2e6b7ae6..5b68a935 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -1,6 +1,10 @@ ``Isaac Lab Arena`` Documentation ================================= +.. warning:: + This is the latest version of IsaacLab Arena. It contains the newest features but may not be fully tested yet. + For the tested version, please refer to the `release/0.1.1 branch `_. + ``Isaac Lab Arena`` is an extends `Isaac Lab `_ to simplify the creation of task/environment libraries. From d7be76bc52ce951c6d15362e986eab3c21ad2acb Mon Sep 17 00:00:00 2001 From: Clemens Volk Date: Thu, 18 Dec 2025 15:32:27 +0100 Subject: [PATCH 26/26] First MVP in 2d using differential optimization --- isaaclab_arena/assets/object.py | 13 +- isaaclab_arena/assets/relations.py | 30 + isaaclab_arena/assets/relations_design.md | 35 + .../examples/compile_env_notebook.py | 6 +- .../examples/spatial_relations_2d_poc.ipynb | 1219 +++++++++++++++++ 5 files changed, 1290 insertions(+), 13 deletions(-) create mode 100644 isaaclab_arena/assets/relations.py create mode 100644 isaaclab_arena/assets/relations_design.md create mode 100644 isaaclab_arena/examples/spatial_relations_2d_poc.ipynb diff --git a/isaaclab_arena/assets/object.py b/isaaclab_arena/assets/object.py index 30322177..a698c7f7 100644 --- a/isaaclab_arena/assets/object.py +++ b/isaaclab_arena/assets/object.py @@ -1,14 +1,3 @@ -# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). -# All rights reserved. -# -# SPDX-License-Identifier: Apache-2.0 - -from isaaclab.assets import ArticulationCfg, AssetBaseCfg, RigidObjectCfg -from isaaclab.sim.spawners.from_files.from_files_cfg import UsdFileCfg - -from isaaclab_arena.assets.object_base import ObjectBase, ObjectType -from isaaclab_arena.assets.object_utils import detect_object_type -from isaaclab_arena.utils.pose import Pose from isaaclab_arena.utils.usd_helpers import has_light, open_stage @@ -38,6 +27,8 @@ def __init__( self.initial_pose = initial_pose self.object_cfg = self._init_object_cfg() + self.relations: list[Relation] = [] + def set_initial_pose(self, pose: Pose) -> None: self.initial_pose = pose self.object_cfg = self._add_initial_pose_to_cfg(self.object_cfg) diff --git a/isaaclab_arena/assets/relations.py b/isaaclab_arena/assets/relations.py new file mode 100644 index 00000000..ca87535b --- /dev/null +++ b/isaaclab_arena/assets/relations.py @@ -0,0 +1,30 @@ +# Copyright (c) 2025, The Isaac Lab Arena Project Developers (https://github.com/isaac-sim/IsaacLab-Arena/blob/main/CONTRIBUTORS.md). +# All rights reserved. +# +# SPDX-License-Identifier: Apache-2.0 + +from isaaclab_arena.assets.asset import Asset + + +class Relation: + """Base class for spatial relationships between objects.""" + + def __init__(self, child: Asset): + self.child = child + + +class On(Relation): + """Represents an 'on top of' spatial relationship.""" + + def __init__(self, child: Asset): + super().__init__(child) + print(f"[On] Created: {self.child.name} will be placed on top of parent") + + +class NextTo(Relation): + """Represents a 'next to' spatial relationship.""" + + def __init__(self, child: Asset, side: str = "right"): + super().__init__(child) + self.side = side + print(f"[NextTo] Created: {self.child.name} will be placed {self.side} of parent") \ No newline at end of file diff --git a/isaaclab_arena/assets/relations_design.md b/isaaclab_arena/assets/relations_design.md new file mode 100644 index 00000000..1fee49ba --- /dev/null +++ b/isaaclab_arena/assets/relations_design.md @@ -0,0 +1,35 @@ +This document should describe the required task to solve: + +The question at hand is to find valid object palcement positions for multiple objects at the same time. I would like to start with a first version in 2d space as a proof +of concept. + + +An asset can hold lists of relations. The relation needs to store the parent asset for later like so + +class Relation: + """Base class for spatial relationships between objects.""" + + def __init__(self, child: Asset): + self.child = child + + +class NextTo(Relation): + """Represents a 'next to' spatial relationship.""" + + def __init__(self, child: Asset, side: str = "right"): + super().__init__(child) + self.side = side + print(f"[NextTo] Created: {self.child.name} will be placed {self.side} of parent") + + +Then the user should be able to call relations via the following api + +from isaaclab_arena.assets.relations import On, NextTo + +packing_table = asset_registry.get_asset_by_name("packing_table")() + +microwave.add_relation(On(packing_table)) +cracker_box.add_relation(On(packing_table), NextTo(microwave)) +apple.add_realation(NextTo(cracker_box)) + + diff --git a/isaaclab_arena/examples/compile_env_notebook.py b/isaaclab_arena/examples/compile_env_notebook.py index 9ebe8611..08844f3b 100644 --- a/isaaclab_arena/examples/compile_env_notebook.py +++ b/isaaclab_arena/examples/compile_env_notebook.py @@ -19,18 +19,20 @@ from isaaclab_arena.environments.arena_env_builder import ArenaEnvBuilder from isaaclab_arena.environments.isaaclab_arena_environment import IsaacLabArenaEnvironment from isaaclab_arena.scene.scene import Scene +from isaaclab_arena.assets.relations import On, NextTo from isaaclab_arena.tasks.dummy_task import DummyTask from isaaclab_arena.utils.pose import Pose asset_registry = AssetRegistry() -background = asset_registry.get_asset_by_name("kitchen")() +background = asset_registry.get_asset_by_name("packing_table")() embodiment = asset_registry.get_asset_by_name("franka")() + cracker_box = asset_registry.get_asset_by_name("cracker_box")() cracker_box.set_initial_pose(Pose(position_xyz=(0.4, 0.0, 0.1), rotation_wxyz=(1.0, 0.0, 0.0, 0.0))) -scene = Scene(assets=[background, cracker_box]) +scene = Scene(assets=[background, cracker_box, microwave]) isaaclab_arena_environment = IsaacLabArenaEnvironment( name="reference_object_test", embodiment=embodiment, diff --git a/isaaclab_arena/examples/spatial_relations_2d_poc.ipynb b/isaaclab_arena/examples/spatial_relations_2d_poc.ipynb new file mode 100644 index 00000000..15f37d10 --- /dev/null +++ b/isaaclab_arena/examples/spatial_relations_2d_poc.ipynb @@ -0,0 +1,1219 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# 2D Differentiable Spatial Relations Solver - Proof of Concept\n", + "\n", + "This notebook demonstrates a differentiable optimization-based solver for spatial relations using PyTorch.\n", + "\n", + "## Overview\n", + "\n", + "- Uses gradient descent to optimize object positions\n", + "- Supports two spatial relations:\n", + " - `On(parent)`: Child must stay within parent's AABB bounds\n", + " - `NextTo(parent, side)`: Child positioned adjacent to parent\n", + "- Soft constraints with repulsive collision potentials\n", + "- Assets can be explicitly marked as `fixed=True` to remain at origin (anchor objects)\n", + "- Visualizes final placements with matplotlib\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Section 1: Setup and Imports\n" + ] + }, + { + "cell_type": "code", + "execution_count": 34, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "PyTorch version: 2.7.0+cu128\n", + "Device: cuda\n" + ] + } + ], + "source": [ + "import torch\n", + "import torch.nn as nn\n", + "import matplotlib.pyplot as plt\n", + "import matplotlib.patches as patches\n", + "from dataclasses import dataclass, field\n", + "import numpy as np\n", + "\n", + "print(f\"PyTorch version: {torch.__version__}\")\n", + "print(f\"Device: {torch.device('cuda' if torch.cuda.is_available() else 'cpu')}\")\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Section 2: Mock Asset Classes\n" + ] + }, + { + "cell_type": "code", + "execution_count": 53, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created: MockAsset2D(test_table, w=2.0, l=1.5)\n", + "Corners at (0,0,0): tensor([[-1.0000, -0.7500],\n", + " [ 1.0000, -0.7500],\n", + " [ 1.0000, 0.7500],\n", + " [-1.0000, 0.7500]])\n" + ] + } + ], + "source": [ + "@dataclass\n", + "class MockAsset2D:\n", + " \"\"\"A simple 2D asset with width and length for testing spatial relations.\"\"\"\n", + " name: str\n", + " width: float # X dimension\n", + " length: float # Y dimension\n", + " fixed: bool = False # If True, asset position won't be optimized\n", + " initial_pos: tuple = (0.0, 0.0, 0.0) # Initial position (x, y, theta) for fixed assets\n", + " relations: list = field(default_factory=list)\n", + " \n", + " def add_relation(self, *relations):\n", + " \"\"\"Add one or more spatial relations to this asset.\"\"\"\n", + " self.relations.extend(relations)\n", + " \n", + " def get_corners(self, pos: torch.Tensor) -> torch.Tensor:\n", + " \"\"\"Get 4 corners given position [x, y, theta].\n", + " \n", + " For 2D POC, we assume theta=0 (axis-aligned rectangles).\n", + " \"\"\"\n", + " x, y = pos[0], pos[1]\n", + " return torch.stack([\n", + " torch.tensor([x - self.width/2, y - self.length/2]),\n", + " torch.tensor([x + self.width/2, y - self.length/2]),\n", + " torch.tensor([x + self.width/2, y + self.length/2]),\n", + " torch.tensor([x - self.width/2, y + self.length/2]),\n", + " ])\n", + " \n", + " def __repr__(self):\n", + " return f\"MockAsset2D({self.name}, w={self.width}, l={self.length})\"\n", + "\n", + "# Test the class\n", + "test_asset = MockAsset2D(\"test_table\", width=2.0, length=1.5)\n", + "print(f\"Created: {test_asset}\")\n", + "print(f\"Corners at (0,0,0): {test_asset.get_corners(torch.tensor([0.0, 0.0, 0.0]))}\")\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Section 3: Relation Classes with Loss Functions\n", + "\n", + "Each relation type defines a `compute_loss` method that returns a differentiable loss term.\n", + "\n", + "**Available Relations:**\n", + "- `On(parent)`: Ensures child stays within parent's 2D bounding box (hard boundary constraint)\n", + "- `NextTo(parent, side)`: Positions child adjacent to parent on specified side\n" + ] + }, + { + "cell_type": "code", + "execution_count": 54, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Created relations: On(table), NextTo(box, side=right)\n", + "Small item relations: [On(table)]\n", + "Box relations: [NextTo(box, side=right)]\n" + ] + } + ], + "source": [ + "class Relation:\n", + " \"\"\"Base class for spatial relationships.\"\"\"\n", + " \n", + " def __init__(self, parent: MockAsset2D):\n", + " self.parent = parent\n", + " \n", + " def compute_loss(self, child_pos, parent_pos, child_asset, parent_asset) -> torch.Tensor:\n", + " \"\"\"Compute differentiable loss term for this relation.\"\"\"\n", + " raise NotImplementedError\n", + "\n", + "\n", + "class On(Relation):\n", + " \"\"\"Child should be placed within the parent's AABB (bounding box).\n", + " \n", + " In 2D: Child must stay within parent's x,y extents.\n", + " In 3D: Would additionally handle z positioning (height).\n", + " \"\"\"\n", + " \n", + " def compute_loss(self, child_pos, parent_pos, child_asset, parent_asset):\n", + " \"\"\"On() relation has no soft constraints - only hard boundary enforcement.\"\"\"\n", + " # Return zero - On() only contributes through compute_boundary_loss()\n", + " return torch.tensor(0.0)\n", + " \n", + " def compute_boundary_loss(self, child_pos, parent_pos, child_asset, parent_asset):\n", + " \"\"\"Hard boundary violation loss - penalizes leaving parent bounds.\"\"\"\n", + " # Extract 2D positions\n", + " child_x, child_y = child_pos[0], child_pos[1]\n", + " parent_x, parent_y = parent_pos[0], parent_pos[1]\n", + " \n", + " # Half-dimensions\n", + " child_hw = child_asset.width / 2\n", + " child_hl = child_asset.length / 2\n", + " parent_hw = parent_asset.width / 2\n", + " parent_hl = parent_asset.length / 2\n", + " \n", + " # Compute how far the child center is from parent center\n", + " dx = torch.abs(child_x - parent_x)\n", + " dy = torch.abs(child_y - parent_y)\n", + " \n", + " # Maximum allowed distance for child center to stay within parent bounds\n", + " max_dx = parent_hw - child_hw\n", + " max_dy = parent_hl - child_hl\n", + " \n", + " # Quadratic penalty for boundary violations (weighted separately in solver)\n", + " violation_x = torch.clamp(dx - max_dx, min=0)\n", + " violation_y = torch.clamp(dy - max_dy, min=0)\n", + " \n", + " return violation_x ** 2 + violation_y ** 2\n", + " \n", + " def __repr__(self):\n", + " return f\"On({self.parent.name})\"\n", + "\n", + "\n", + "apple.add_relation(NextTo(table))\n", + "\n", + "\n", + "class NextTo(Relation):\n", + " \"\"\"Child should be adjacent to parent on specified side.\"\"\"\n", + " \n", + " def __init__(self, parent: MockAsset2D, side: str = \"right\", gap: float = 0.05):\n", + " super().__init__(parent)\n", + " assert side in [\"left\", \"right\", \"front\", \"back\"], f\"Invalid side: {side}\"\n", + " self.side = side\n", + " self.gap = gap\n", + " \n", + " def compute_loss(self, child_pos, parent_pos, child_asset, parent_asset):\n", + " target_pos = self._compute_target_position(\n", + " parent_pos, parent_asset, child_asset\n", + " )\n", + " position_diff = child_pos[:2] - target_pos\n", + " return torch.sum(position_diff ** 2)\n", + " \n", + " def _compute_target_position(self, parent_pos, parent_asset, child_asset):\n", + " \"\"\"Compute the target position for the child asset.\"\"\"\n", + " px, py = parent_pos[0], parent_pos[1]\n", + " pw, pl = parent_asset.width, parent_asset.length\n", + " cw, cl = child_asset.width, child_asset.length\n", + " \n", + " side_offsets = {\n", + " \"right\": torch.tensor([pw/2 + self.gap + cw/2, 0.0]),\n", + " \"left\": torch.tensor([-pw/2 - self.gap - cw/2, 0.0]),\n", + " \"front\": torch.tensor([0.0, pl/2 + self.gap + cl/2]),\n", + " \"back\": torch.tensor([0.0, -pl/2 - self.gap - cl/2]),\n", + " }\n", + " return parent_pos[:2] + side_offsets[self.side]\n", + " \n", + " def __repr__(self):\n", + " return f\"NextTo({self.parent.name}, side={self.side})\"\n", + "\n", + "\n", + "# Test the relation classes\n", + "table = MockAsset2D(\"table\", width=2.0, length=1.5)\n", + "box = MockAsset2D(\"box\", width=0.3, length=0.3)\n", + "small_item = MockAsset2D(\"small_item\", width=0.1, length=0.1)\n", + "\n", + "on_rel = On(table)\n", + "nextto_rel = NextTo(box, side=\"right\")\n", + "\n", + "print(f\"Created relations: {on_rel}, {nextto_rel}\")\n", + "small_item.add_relation(on_rel)\n", + "box.add_relation(nextto_rel)\n", + "print(f\"Small item relations: {small_item.relations}\")\n", + "print(f\"Box relations: {box.relations}\")\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Section 4: Differentiable Solver\n", + "\n", + "The solver uses gradient descent to optimize object positions by minimizing relation losses and collision penalties.\n" + ] + }, + { + "cell_type": "code", + "execution_count": 55, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "RelationSolver2D class defined successfully!\n" + ] + } + ], + "source": [ + "class RelationSolver2D:\n", + " \"\"\"Differentiable solver for 2D spatial relations using gradient descent.\"\"\"\n", + " \n", + " def __init__(self, \n", + " w_relation=1.0, # Weight for relation losses (NextTo, etc.)\n", + " w_boundary=100.0, # Weight for boundary violations (On relation bounds)\n", + " w_collision=10.0, # Weight for collision avoidance\n", + " max_iters=1000,\n", + " lr=0.01,\n", + " convergence_threshold=1e-4,\n", + " verbose=True):\n", + " self.w_relation = w_relation\n", + " self.w_boundary = w_boundary\n", + " self.w_collision = w_collision\n", + " self.max_iters = max_iters\n", + " self.lr = lr\n", + " self.convergence_threshold = convergence_threshold\n", + " self.verbose = verbose\n", + " \n", + " def solve(self, assets: list[MockAsset2D]) -> dict[str, tuple]:\n", + " \"\"\"Solve for optimal positions of all assets.\n", + " \n", + " Args:\n", + " assets: List of MockAsset2D objects with relations\n", + " \n", + " Returns:\n", + " Dictionary mapping asset names to (x, y, theta) tuples\n", + " \"\"\"\n", + " # 1. Initialize positions\n", + " all_positions = self._initialize_positions(assets)\n", + " \n", + " # 2. Identify fixed assets and optimizable assets\n", + " fixed_mask = torch.tensor([asset.fixed for asset in assets])\n", + " optimizable_mask = ~fixed_mask\n", + " \n", + " # Split into fixed and optimizable\n", + " fixed_positions = all_positions[fixed_mask].clone() # These won't change\n", + " optimizable_positions = all_positions[optimizable_mask].clone()\n", + " optimizable_positions.requires_grad = True\n", + " \n", + " if self.verbose:\n", + " n_fixed = fixed_mask.sum().item()\n", + " n_opt = optimizable_mask.sum().item()\n", + " print(f\"Fixed assets: {n_fixed}, Optimizable assets: {n_opt}\")\n", + " \n", + " # 3. Setup optimizer (only for optimizable positions)\n", + " optimizer = torch.optim.Adam([optimizable_positions], lr=self.lr)\n", + " \n", + " # 4. Optimization loop\n", + " loss_history = []\n", + " for iter in range(self.max_iters):\n", + " optimizer.zero_grad()\n", + " \n", + " # Reconstruct full position tensor for loss computation\n", + " all_positions = torch.zeros((len(assets), 3))\n", + " all_positions[fixed_mask] = fixed_positions\n", + " all_positions[optimizable_mask] = optimizable_positions\n", + " \n", + " # Compute total loss\n", + " loss = self._compute_total_loss(all_positions, assets)\n", + " loss_history.append(loss.item())\n", + " \n", + " # Backprop and update (only optimizable positions will update)\n", + " loss.backward()\n", + " optimizer.step()\n", + " \n", + " if self.verbose and iter % 100 == 0:\n", + " print(f\"Iter {iter}: loss = {loss.item():.6f}\")\n", + " \n", + " # Check convergence\n", + " if loss.item() < self.convergence_threshold:\n", + " if self.verbose:\n", + " print(f\"Converged at iteration {iter}\")\n", + " break\n", + " \n", + " # 5. Reconstruct final positions\n", + " final_positions = torch.zeros((len(assets), 3))\n", + " final_positions[fixed_mask] = fixed_positions\n", + " final_positions[optimizable_mask] = optimizable_positions.detach()\n", + " \n", + " # 6. Return positions as dict\n", + " result = self._positions_to_dict(final_positions, assets)\n", + " result['_loss_history'] = loss_history\n", + " return result\n", + " \n", + " def _initialize_positions(self, assets):\n", + " \"\"\"Initialize positions randomly for non-fixed assets.\"\"\"\n", + " n = len(assets)\n", + " positions = torch.zeros(n, 3)\n", + " \n", + " # Initialize based on whether asset is fixed\n", + " for i, asset in enumerate(assets):\n", + " if asset.fixed:\n", + " # Fixed assets use their specified initial position\n", + " positions[i] = torch.tensor(asset.initial_pos, dtype=torch.float32)\n", + " else:\n", + " # Non-fixed assets get random positions\n", + " # Random position within a reasonable range\n", + " positions[i][:2] = torch.randn(2) * 0.3\n", + " positions[i][2] = 0.0 # No rotation\n", + " \n", + " return positions\n", + " \n", + " def _compute_total_loss(self, positions, assets):\n", + " \"\"\"Compute weighted sum of all loss terms.\"\"\"\n", + " rel_loss = self._compute_relation_loss(positions, assets)\n", + " boundary_loss = self._compute_boundary_loss(positions, assets)\n", + " col_loss = self._compute_collision_loss(positions, assets)\n", + " \n", + " total = (self.w_relation * rel_loss + \n", + " self.w_boundary * boundary_loss +\n", + " self.w_collision * col_loss)\n", + " \n", + " return total\n", + " \n", + " def _compute_relation_loss(self, positions, assets):\n", + " \"\"\"Compute loss from spatial relation constraints (NextTo positioning).\"\"\"\n", + " loss = torch.tensor(0.0, requires_grad=True)\n", + " asset_dict = {a.name: (i, a) for i, a in enumerate(assets)}\n", + " \n", + " for i, asset in enumerate(assets):\n", + " for relation in asset.relations:\n", + " parent_idx = asset_dict[relation.parent.name][0]\n", + " rel_loss = relation.compute_loss(\n", + " positions[i], \n", + " positions[parent_idx],\n", + " asset,\n", + " relation.parent\n", + " )\n", + " loss = loss + rel_loss\n", + " \n", + " return loss\n", + " \n", + " def _compute_boundary_loss(self, positions, assets):\n", + " \"\"\"Compute hard boundary violations for On() relations.\"\"\"\n", + " loss = torch.tensor(0.0, requires_grad=True)\n", + " asset_dict = {a.name: (i, a) for i, a in enumerate(assets)}\n", + " \n", + " for i, asset in enumerate(assets):\n", + " for relation in asset.relations:\n", + " if isinstance(relation, On):\n", + " parent_idx = asset_dict[relation.parent.name][0]\n", + " boundary_loss = relation.compute_boundary_loss(\n", + " positions[i], \n", + " positions[parent_idx],\n", + " asset,\n", + " relation.parent\n", + " )\n", + " loss = loss + boundary_loss\n", + " \n", + " return loss\n", + " \n", + " def _compute_collision_loss(self, positions, assets):\n", + " \"\"\"Compute repulsive potential for collision avoidance.\"\"\"\n", + " loss = torch.tensor(0.0, requires_grad=True)\n", + " \n", + " for i in range(len(assets)):\n", + " for j in range(i+1, len(assets)):\n", + " overlap = self._compute_overlap(\n", + " positions[i], assets[i],\n", + " positions[j], assets[j]\n", + " )\n", + " # Soft quadratic penalty when overlapping (much less aggressive than exponential)\n", + " # Only penalize when overlap is negative (objects actually overlapping)\n", + " if overlap < 0:\n", + " # Quadratic penalty proportional to penetration depth\n", + " loss = loss + overlap ** 2\n", + " \n", + " return loss\n", + " \n", + " def _compute_overlap(self, pos1, asset1, pos2, asset2):\n", + " \"\"\"Compute minimum separation distance (negative if overlapping).\"\"\"\n", + " # For axis-aligned boxes\n", + " dx = torch.abs(pos1[0] - pos2[0])\n", + " dy = torch.abs(pos1[1] - pos2[1])\n", + " \n", + " # Half-widths\n", + " hw1, hl1 = asset1.width / 2, asset1.length / 2\n", + " hw2, hl2 = asset2.width / 2, asset2.length / 2\n", + " \n", + " # Overlap distances\n", + " overlap_x = (hw1 + hw2) - dx\n", + " overlap_y = (hl1 + hl2) - dy\n", + " \n", + " # Return minimum overlap (penetration depth)\n", + " # Negative means no overlap\n", + " if overlap_x > 0 and overlap_y > 0:\n", + " return -torch.min(overlap_x, overlap_y)\n", + " else:\n", + " # No overlap, return positive separation\n", + " return torch.max(-overlap_x, -overlap_y)\n", + " \n", + "\n", + " def _positions_to_dict(self, positions, assets):\n", + " \"\"\"Convert position tensor to dictionary.\"\"\"\n", + " result = {}\n", + " for i, asset in enumerate(assets):\n", + " pos = positions[i].detach().numpy()\n", + " result[asset.name] = tuple(pos)\n", + " return result\n", + "\n", + "print(\"RelationSolver2D class defined successfully!\")\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Section 5: Visualization\n" + ] + }, + { + "cell_type": "code", + "execution_count": 56, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Visualization functions defined successfully!\n" + ] + } + ], + "source": [ + "def visualize_scene(positions: dict, assets: dict, title=\"Scene Layout\", figsize=(10, 10)):\n", + " \"\"\"Visualize the 2D scene layout with rectangles representing assets.\n", + " \n", + " Args:\n", + " positions: Dictionary mapping asset names to (x, y, theta) tuples\n", + " assets: Dictionary mapping asset names to MockAsset2D objects\n", + " title: Plot title\n", + " figsize: Figure size\n", + " \"\"\"\n", + " fig, ax = plt.subplots(figsize=figsize)\n", + " \n", + " # Generate colors for each asset\n", + " colors = plt.cm.tab10(np.linspace(0, 1, len(assets)))\n", + " \n", + " # Draw each asset\n", + " for i, (name, pos) in enumerate(positions.items()):\n", + " if name.startswith('_'): # Skip metadata like '_loss_history'\n", + " continue\n", + " \n", + " asset = assets[name]\n", + " x, y, theta = pos\n", + " \n", + " # Draw rectangle (axis-aligned for now)\n", + " rect = patches.Rectangle(\n", + " (x - asset.width/2, y - asset.length/2),\n", + " asset.width, asset.length,\n", + " linewidth=2, \n", + " edgecolor=colors[i], \n", + " facecolor=colors[i], \n", + " alpha=0.3\n", + " )\n", + " ax.add_patch(rect)\n", + " \n", + " # Add label at center\n", + " ax.text(x, y, name, ha='center', va='center', \n", + " fontweight='bold', fontsize=10)\n", + " \n", + " # Add dimensions annotation\n", + " ax.text(x, y - asset.length/2 - 0.1, \n", + " f\"({asset.width:.2f} x {asset.length:.2f})\", \n", + " ha='center', va='top', fontsize=8, alpha=0.7)\n", + " \n", + " # Set aspect ratio and grid\n", + " ax.set_aspect('equal')\n", + " ax.grid(True, alpha=0.3)\n", + " ax.axhline(y=0, color='k', linewidth=0.5, alpha=0.3)\n", + " ax.axvline(x=0, color='k', linewidth=0.5, alpha=0.3)\n", + " ax.set_xlabel('X (meters)')\n", + " ax.set_ylabel('Y (meters)')\n", + " ax.set_title(title)\n", + " \n", + " # Auto-scale with some padding\n", + " ax.autoscale()\n", + " plt.tight_layout()\n", + " plt.show()\n", + "\n", + "\n", + "def plot_loss_history(positions: dict, title=\"Optimization Loss\"):\n", + " \"\"\"Plot the loss history from the solver.\n", + " \n", + " Args:\n", + " positions: Dictionary returned by solver (contains '_loss_history' key)\n", + " title: Plot title\n", + " \"\"\"\n", + " if '_loss_history' not in positions:\n", + " print(\"No loss history found in positions dictionary\")\n", + " return\n", + " \n", + " loss_history = positions['_loss_history']\n", + " \n", + " fig, ax = plt.subplots(figsize=(10, 4))\n", + " ax.plot(loss_history, linewidth=2)\n", + " ax.set_xlabel('Iteration')\n", + " ax.set_ylabel('Total Loss')\n", + " ax.set_title(title)\n", + " ax.grid(True, alpha=0.3)\n", + " ax.set_yscale('log') # Log scale often better for loss curves\n", + " plt.tight_layout()\n", + " plt.show()\n", + "\n", + "\n", + "print(\"Visualization functions defined successfully!\")\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Section 6: Example Scenarios\n", + "\n", + "Now let's test the solver with some example scenarios!\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Example 1: Simple NextTo Chain\n", + "\n", + "Three boxes positioned relative to each other using NextTo relations.\n" + ] + }, + { + "cell_type": "code", + "execution_count": 57, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Fixed assets: 1, Optimizable assets: 2\n", + "Iter 0: loss = 0.473829\n", + "Iter 100: loss = 0.050744\n", + "Iter 200: loss = 0.050299\n", + "Iter 300: loss = 0.050298\n", + "Iter 400: loss = 0.050298\n", + "Iter 500: loss = 0.050298\n", + "Iter 600: loss = 0.050298\n", + "Iter 700: loss = 0.050298\n", + "Iter 800: loss = 0.050298\n", + "Iter 900: loss = 0.050298\n", + "\n", + "Final positions:\n", + " box1: x=0.000, y=0.000, theta=0.000\n", + " box2: x=0.400, y=0.155, theta=0.000\n", + " box3: x=0.075, y=0.310, theta=0.000\n" + ] + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAAA90AAAN+CAYAAAAIRmjGAAAAOnRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjEwLjMsIGh0dHBzOi8vbWF0cGxvdGxpYi5vcmcvZiW1igAAAAlwSFlzAAAPYQAAD2EBqD+naQAAeVpJREFUeJzs3Xd4FOX+9/HPbnoPgRQIgUiRYgEOSARpChrsiCjHRjkcsPywIR7BQhEVVEQUERSkqHhAFD0WBBFBLAhKEaSJVAWS0NL77jx/IPsQk0ACudns8n5dV64rM3vPzHf2u5vNZ2d21mZZliUAAAAAAFDl7O4uAAAAAAAAb0XoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAnNOWL18um82m5cuXu7uUKmOz2TRq1Ci3bLtfv35KTEx0y7bPVaNGjZLNZtOhQ4eqbJ1dunRRly5dqmx9AHAuI3QDAMo1a9Ys2Wy2cn9+/PFHd5dYLU2ZMkW33HKL6tWrJ5vNpn79+lXJer/77jtdffXVio+PV2BgoOrVq6frr79e7733XpWsvzo6HihjY2OVm5tb6vbExERdd911xra/f/9+jRo1SuvXr3fNO/5GTUV+zoTD4dDMmTPVpUsXRUVFKSAgQImJierfv79+/vnnM9wzAMDZ4uvuAgAA1d/TTz+t8847r9T8Ro0auaGa6u/5559XVlaW2rZtqwMHDlTJOufPn6/evXurZcuWevDBB1WjRg3t2rVLK1as0LRp03T77be7xubl5cnX17te4tPS0jRlyhQ98sgjZ3W7+/fv1+jRo5WYmKiWLVtKkpo1a6Z33nmnxLjhw4crNDRUTzzxRJVsNy8vTz179tSiRYvUqVMnPf7444qKitLu3bv1/vvva/bs2dq7d6/q1q1bJdv7uy+//NLIegHgXORdr8gAACOuvvpqtWnTxt1leIxvvvnGdZQ7NDS0StY5atQoNW/eXD/++KP8/f1L3JaWllZiOjAwsEq2WZ20bNlSL774ou677z4FBQW5tZbY2FjdeeedJeaNGzdOtWrVKjX/dD366KNatGiRXn75ZT300EMlbhs5cqRefvnlKtlOef7+GAMAnD5OLwcAnLGRI0fKbrdr6dKlJeYPGjRI/v7++uWXXyRJhYWFGjFihFq3bq2IiAiFhISoY8eOWrZsWYnldu/eLZvNpvHjx2vy5Mlq0KCBgoODddVVV+mPP/6QZVkaM2aM6tatq6CgIN144406cuRIiXUcP+34yy+/VMuWLRUYGKjmzZtrwYIFFdqnVatWqXv37oqIiFBwcLA6d+6s77//vkLL1q9fv0KnFhcVFWnr1q0VOhq+Y8cOXXLJJWWGoZiYmBLTf/9M9/FTtH/77TfdeeedioiIUHR0tJ566ilZlqU//vhDN954o8LDwxUXF6eXXnqpxPqOn049b948Pf7444qLi1NISIhuuOEG/fHHH6es3el0auLEibrgggsUGBio2NhY3X333Tp69Ogplz1uxIgRSk1N1ZQpU6pkexV5zC5fvlyXXHKJJKl///6uU8ZnzZpVoZp37typW265RVFRUQoODtall16qzz///JTL/fnnn3rjjTd05ZVXlgrckuTj46OhQ4eWOsqdnp6ufv36KTIyUhEREerfv3+pU/JnzpypK664QjExMQoICFDz5s3LvE///pnu44+B999/X88++6zq1q2rwMBAde3aVb///nuF7g8AOFcRugEAp5SRkaFDhw6V+Dl8+LDr9ieffFItW7bUgAEDlJWVJUlavHixpk2bphEjRqhFixaSpMzMTE2fPl1dunTR888/r1GjRungwYNKTk4u8ZnZ4+bMmaPXX39d999/vx555BF98803uvXWW/Xkk09q0aJFeuyxxzRo0CB9+umnGjp0aKnlt2/frt69e+vqq6/W2LFj5evrq1tuuUVLliw56f5+/fXX6tSpkzIzMzVy5Eg999xzSk9P1xVXXKHVq1efwT1Z0r59+9SsWTMNHz78lGPr16+vpUuX6s8//zzt7fXu3VtOp1Pjxo1TUlKSnnnmGU2cOFFXXnml4uPj9fzzz6tRo0YaOnSoVqxYUWr5Z599Vp9//rkee+wxPfDAA1qyZIm6deumvLy8k2737rvv1qOPPqrLLrtMr7zyivr37685c+YoOTlZRUVFFaq9Y8eOuuKKK/TCCy9UyfYq8pht1qyZnn76aUnHwvg777yjd955R506dTplvampqWrfvr0WL16s++67T88++6zy8/N1ww036KOPPjrpsl988YWKi4t11113VeSucbn11luVlZWlsWPH6tZbb9WsWbM0evToEmOmTJmi+vXr6/HHH9dLL72khIQE3XfffZo8eXKFtjFu3Dh99NFHGjp0qIYPH64ff/xRd9xxR6XqBIBzjgUAQDlmzpxpSSrzJyAgoMTYjRs3Wv7+/ta///1v6+jRo1Z8fLzVpk0bq6ioyDWmuLjYKigoKLHc0aNHrdjYWOtf//qXa96uXbssSVZ0dLSVnp7umj98+HBLktWiRYsS673tttssf39/Kz8/3zWvfv36liTrww8/dM3LyMiwateubbVq1co1b9myZZYka9myZZZlWZbT6bQaN25sJScnW06n0zUuNzfXOu+886wrr7yyUvdhSEiI1bdv3zJvO76f5d1+orfeesuSZPn7+1uXX3659dRTT1nffvut5XA4So2VZI0cOdI1PXLkSEuSNWjQINe84uJiq27dupbNZrPGjRvnmn/06FErKCioRE3H76P4+HgrMzPTNf/999+3JFmvvPKKa17fvn2t+vXru6a//fZbS5I1Z86cEjUuWrSozPl/d7z2gwcPWt98840lyZowYYLr9vr161vXXnvtaW2vIo/Zn376yZJkzZw586R1XnDBBVbnzp1d0w899JAlyfr2229d87KysqzzzjvPSkxMLLNvxz388MOWJGvdunUn3eZxx++jE59DlmVZN910k1WzZs0S83Jzc0stn5ycbDVo0KDEvM6dO5fYn+OPgWbNmpV4Dr/yyiuWJGvjxo0VqhUAzkUc6QYAnNLkyZO1ZMmSEj9ffPFFiTEXXnihRo8erenTpys5OVmHDh3S7NmzS1zQy8fHx3V6tNPp1JEjR1RcXKw2bdpo7dq1pbZ7yy23KCIiwjWdlJQkSbrzzjtLrDcpKUmFhYXat29fieXr1Kmjm266yTUdHh6uPn36aN26dUpJSSlzX9evX6/t27fr9ttv1+HDh11H9nNyctS1a1etWLFCTqezonfdSSUmJsqyrAqdrvyvf/1LixYtUpcuXfTdd99pzJgx6tixoxo3bqwffvihQtv797//7frdx8dHbdq0kWVZGjBggGt+ZGSkmjRpop07d5Zavk+fPgoLC3NN9+rVS7Vr19bChQvL3eb8+fMVERGhK6+8ssSZEq1bt1ZoaGipjxacTKdOnXT55Zef9Gh3ZbZXkcfs6Vq4cKHatm2rDh06uOaFhoZq0KBB2r17tzZv3lzuspmZmZJU4r6uiHvuuafEdMeOHXX48GHX+iSV+Dz88TNYOnfurJ07dyojI+OU2+jfv3+Jjzh07NhRksp8vAAAjuFCagCAU2rbtm2FLqT26KOPau7cuVq9erWee+45NW/evNSY2bNn66WXXtLWrVtLnFpc1tXR69WrV2L6eABPSEgoc/7fPyPcqFGjUp+tPv/88yUd+9x4XFxcqW1u375dktS3b9+yd1LHwkqNGjXKvd2U5ORkJScnKzc3V2vWrNG8efM0depUXXfdddq6dWupz3b/XVn3Z2BgoGrVqlVq/okfHziucePGJaZtNpsaNWqk3bt3l7vN7du3KyMjo9za/n4RuFMZNWqUOnfurKlTp+rhhx8+4+1V5DF7Ovbs2eN6k+hEzZo1c91+4YUXlrlseHi4JLlOe6+ov/f3+GP06NGjrnV+//33GjlypFauXFnq894ZGRkl3uSq7DYAAGUjdAMAqszOnTtdoXXjxo2lbn/33XfVr18/9ejRQ48++qhiYmLk4+OjsWPHaseOHaXG+/j4lLmd8uZblnUG1R9z/Cj2iy++6PqKqL+rqiuSn67g4GB17NhRHTt2VK1atTR69Gh98cUXJ32jQCr7fjN5X0rH7s+YmBjNmTOnzNujo6Mrtb5OnTqpS5cueuGFF0od2T2d7Z3qMesOTZs2lXSsnvIeg2U5VS937Nihrl27qmnTppowYYISEhLk7++vhQsX6uWXX67QGRymHy8A4I0I3QCAKuF0OtWvXz+Fh4froYce0nPPPadevXqpZ8+erjEffPCBGjRooAULFpQ4Aj1y5EgjNf3++++yLKvEtn777TdJx07tLkvDhg0lHTva2K1bNyN1VaXjZyBU1feBn8zxcHqcZVn6/fffdfHFF5e7TMOGDfXVV1/psssuq7Kv+ho1apS6dOmiN95444y2V5HHbEWuQl+W+vXra9u2baXmb9261XV7ea6++mr5+Pjo3XffrfTF1E7m008/VUFBgT755JMSR6wrc4o/AKDy+Ew3AKBKTJgwQT/88IPefPNNjRkzRu3bt9e9996rQ4cOucYcP0p24lGxVatWaeXKlUZq2r9/f4krRWdmZurtt99Wy5Ytyzy1XJJat26thg0bavz48crOzi51+8GDB6usvsp8Zdjfv9rquOOfp27SpEmV1VWet99+u8Qpzx988IEOHDigq6++utxlbr31VjkcDo0ZM6bUbcXFxUpPT690HZ07d3ZdAT8/P/+0t1eRx2xISIgkVbrOa665RqtXry7x2M7JydGbb76pxMTEk57GnpCQoIEDB+rLL7/UpEmTSt3udDr10ksvVfpK9mU9/zIyMjRz5sxKrQcAUDkc6QYAnNIXX3zhOkJ3ovbt26tBgwbasmWLnnrqKfXr10/XX3+9JGnWrFlq2bKl7rvvPr3//vuSpOuuu04LFizQTTfdpGuvvVa7du3S1KlT1bx58zID7pk6//zzNWDAAP3000+KjY3VjBkzlJqaetKQYbfbNX36dF199dW64IIL1L9/f8XHx2vfvn1atmyZwsPD9emnn550u59++qnru8mLioq0YcMGPfPMM5KkG264wXVk+PhXhvXt2/eUF1O78cYbdd555+n6669Xw4YNlZOTo6+++kqffvqpLrnkEtf9blJUVJQ6dOig/v37KzU1VRMnTlSjRo00cODAcpfp3Lmz7r77bo0dO1br16/XVVddJT8/P23fvl3z58/XK6+8ol69elW6lpEjR+ryyy8/7e1V9DHbsGFDRUZGaurUqQoLC1NISIiSkpLKvAbBiYYNG6b//ve/uvrqq/XAAw8oKipKs2fP1q5du/Thhx/Kbj/5cY+XXnpJO3bs0AMPPKAFCxbouuuuU40aNbR3717Nnz9fW7du1T//+c9K3WdXXXWV/P39df311+vuu+9Wdna2pk2bppiYmLNypgQAnKsI3QCAUxoxYkSZ82fOnKn69eurb9++qlWrliZOnOi6rXHjxho7dqwefPBBvf/++7r11lvVr18/paSk6I033tDixYvVvHlzvfvuu5o/f76WL19e5XU3btxYkyZN0qOPPqpt27bpvPPO07x585ScnHzS5bp06aKVK1dqzJgxeu2115Sdna24uDglJSXp7rvvPuV2P/zwQ82ePds1vW7dOq1bt06SVLdu3ZOejl2e6dOn63//+5/ef/997d+/X5ZlqUGDBnriiSf02GOPVckVt0/l8ccf14YNGzR27FhlZWWpa9euev311xUcHHzS5aZOnarWrVvrjTfe0OOPPy5fX18lJibqzjvv1GWXXXZatXTp0kWdO3fWN998U+ntORyOCj9m/fz8NHv2bA0fPlz33HOPiouLNXPmzFOG7tjYWP3www967LHHNGnSJOXn5+viiy/Wp59+qmuvvfaU+xccHKwvvvhCs2bN0uzZszVmzBjl5uaqTp06uuKKKzRnzhzFx8dX6j5r0qSJPvjgAz355JMaOnSo4uLidO+99yo6Olr/+te/KrUuAEDF2SyufAEA8EKJiYm68MIL9dlnn7m7FI+3fPlyXX755Zo/f/5pHZUGAOBcxme6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAzhM90AAAAAABjCkW4AAAAAAAzhK8NOwel0av/+/QoLC5PNZnN3OQAAAACAasCyLGVlZalOnTqy28s/nk3oPoX9+/crISHB3WUAAAAAAKqhP/74Q3Xr1i33dkL3KYSFhUk6dkeGh4e7uZqyOZ1OHTx4UNHR0Sd9hwXVC33zTE6nU0uXLlXXrl3pmwfh+eaZ6Jtnom+eib55JvrmXpmZmUpISHBlxvIQuk/h+Cnl4eHh1Tp05+fnKzw8nCebB6FvnsnpdCo4OJi+eRieb56Jvnkm+uaZ6Jtnom/Vw6k+hkxnAAAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQX3cXAMD7rEzPVqHTcncZRliWUztyCrTiaJZsNt639BSW5VRxVp58/eibJznet+CAbLWvEe7ucgAAOC2EbgBVrtBp6VBhkbIcDneXUvUsS0eKi7Q7r0Cy2dxdDSrKsuRXWKgi+uZZLEvhxcXy9dI38QAA5wZCNwAjshwOpRYUy8/bAo5lKbfYqSOFDsKbJ7EsBRc7lUvfPEqR0yk/p9PdZQAAcEYI3QCM8bPZdGFYkLvLqFKW5ZQ90E/NwgI5TdmDWJZTzmJ/2embR/k1M9fdJQAAcMb4zwMAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgiMeF7smTJysxMVGBgYFKSkrS6tWrK7Tc3LlzZbPZ1KNHD7MFAgAAAADwF48K3fPmzdOQIUM0cuRIrV27Vi1atFBycrLS0tJOutzu3bs1dOhQdezY8SxVCgAAAACA5OvuAipjwoQJGjhwoPr37y9Jmjp1qj7//HPNmDFDw4YNK3MZh8OhO+64Q6NHj9a3336r9PT0k26joKBABQUFrunMzExJktPplNPprJodqWJOp1OWZVXb+lA2b+6bZTkly5Is69jvXsSyLNeP5F375s3om4c64e+IN/6t9Fbe/PrmzeibZ6Jv7lXR+91jQndhYaHWrFmj4cOHu+bZ7XZ169ZNK1euLHe5p59+WjExMRowYIC+/fbbU25n7NixGj16dKn5Bw8eVH5+/ukVb5jT6VRGRoYsy5Ld7lEnL5zTvLlvxVl58issVHCxU85if3eXU6Usy5KVmyvn0SOy2WzuLgcVZFmWrOwsOSX65kGCcwvkU5ir4iN+SisuOPUCqBa8+fXNm9E3z0Tf3CsrK6tC4zwmdB86dEgOh0OxsbEl5sfGxmrr1q1lLvPdd9/prbfe0vr16yu8neHDh2vIkCGu6czMTCUkJCg6Olrh4eGnVbtpTqdTNptN0dHRPNk8iDf3zdcvS0V5BcotdMgeFujucqqUZVmyBQfLXiOK8OZBLMuSU6JvHibXJ09heXb5RkUpJirC3eWggrz59c2b0TfPRN/cKzCwYv/nekzorqysrCzdddddmjZtmmrVqlXh5QICAhQQEFBqvt1ur9YPZJvNVu1rRGne2jebzS7ZbJLNdux3r3Lsxc3mlfvmzeibRzrh74i3/Z30dt76+ubt6Jtnom/uU9H73GNCd61ateTj46PU1NQS81NTUxUXF1dq/I4dO7R7925df/31rnnHz7n39fXVtm3b1LBhQ7NFAwAAAADOaR7zdoi/v79at26tpUuXuuY5nU4tXbpU7dq1KzW+adOm2rhxo9avX+/6ueGGG3T55Zdr/fr1SkhIOJvlAwAAAADOQR5zpFuShgwZor59+6pNmzZq27atJk6cqJycHNfVzPv06aP4+HiNHTtWgYGBuvDCC0ssHxkZKUml5gMAAAAAYIJHhe7evXvr4MGDGjFihFJSUtSyZUstWrTIdXG1vXv38lkGAAAAAEC14VGhW5IGDx6swYMHl3nb8uXLT7rsrFmzqr4gAAAAAADKwWFhAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQCV1ucfFyk5OlLvvDDW3aUAAABUa77uLgAAgJM5dGC/XhnykHZu+lUZhw/JPzBQMQkJ6tqrt26+b7Dsdt4/BgAA1RehGwBQrWUcOqT1361QTN0E1YiJUeofe7Vr0yZN3zRCTodDvR982N0lAgAAlIvDAwCA01ZcVKypTw5Xr/PP000N6mnSfx5RYUGBJKkgL08znx2jfpe00rV1onVz40SN6nO7dm3eJElyFBfr/quuUHJ0pB7recOxeQ6HHkjuquToSD3a4zo5nU4lNmuuj3f9qbdW/qTXvlqu2Wt+UUBwsCRp0+of3bPjAAAAFcSRbgDAafv4zanyDwxQSHi4Uvbs0Wcz35J/QIDuHvOcRt51m9Z9s1w2m011GzXWof37tfKLhVq/YoVeXfK16jU+X49NeVP3XdFJ679doYXvzFZORoa2rV2j0IgIPfralGOnjv91+vhTt92qowfTlPrHXhXk5kqSLkhq587dBwAAOCWOdAMATlvNuDjNXvOLZv/8i7r07CVJ+nTGdP3wxeda981ySdKgp5/V9B9Wa9oPqxQUEqq8nGzNmzhBklS3YSMNGv2MJGnayKdcF2b7v+fHK6ZuQoltbf9lvbb/sl6ZR45Ikm65/0Hdev+DZ2M3AQAAThuhGwBw2pKuSlZwaJgkqctNPSVJRYWF+mP7dteYK26+RZIUXSdeF1567Mj0b7+sd91+Xb9/6ZKuVyo3K1MFeXnq3KOna5kTzd38m/63Z7+enjNPQSGh+nDyJC169x1TuwYAAFAlCN0AALcqKizUkdQU13TqH3vlcDjKHBsYHKykq5L1jy5d5HQ69fbzz52tMgEAAE4LoRsAcNpWL/lSednZkqQV//tYkuTn76+Exo1dY77+cL4k6eD+ffr1x5WSpPNbtHTdPnvcs9rx60bVqhOviJo1tXXNz/rvy+Ndt/+w8DP9ueN313T6wYP6bf16SVL+X5/tBgAAqK64kBoA4LQdOnBAfdu0UHBYmA7s3i1Jurbfv9T+6mvVqnMXrftmud4c8YS+eGe2Du3fr7ycbAWFhKr3Q0MkSRt/+F4fTp4kSXpowivKyczU2EH/0nsvvai23a7S+S1b6YeFn2t03ztVM662wmtGad+OHSrMz5ckXdn7n27ZbwAAgIoidAMATluPQfeoIC9XS+b9V8GhYepycy8NeGqUJGn0O//VexPG65uPP9S+nTsUFBqqdldfo77DnlC9xucrJytTLw6+R06nU8m336lLunaTJH332Sf69pOP9fy9g/T61yvUqnMX7du5U3/u2K49W7cqMChY5/3jAl1x8y264d+D3Lj3wOn7c/OvKi4ucncZRliWpcy8POWl7pfNZnN3Oagg+uaZzoW++fr6qW7zC91dxhmxWZZlubuI6iwzM1MRERHKyMhQeHi4u8spk9PpVFpammJiYo59vQ48gjf37ZsjWdqVl68jhQ5dGBbk7nKqlGU5teWbZWrW+XLZbN7VN29mWU45jx6RvUYUffMgv2bmKjYvU/FxcepSM8Ld5VSp3RvWKS8jXQV5ee4upcpZlqU8p6Ugu81rQ4A3om+eydv7FhAUpKCISCVe3MrdpZSpolmRI90AAABuUJCXp5yjh2X39a5/xyxJhTYfyXLI+yKA96Jvnsmb++YsLpZUU0ERke4u5Yx53F/5yZMn68UXX1RKSopatGihSZMmqW3btmWOXbBggZ577jn9/vvvKioqUuPGjfXII4/orrvuOstVAwAAlGb39VVMYgN3l1GlLMtSVn6BwgIDvPLIm7eib57Jm/uWtnunu0uoMh51jt28efM0ZMgQjRw5UmvXrlWLFi2UnJystLS0MsdHRUXpiSee0MqVK7Vhwwb1799f/fv31+LFi89y5QAAAACAc5FHHemeMGGCBg4cqP79+0uSpk6dqs8//1wzZszQsGHDSo3v0qVLiekHH3xQs2fP1nfffafk5OQyt1FQUKCCggLXdGZmpqRjn791Op1VtCdVy+l0yrKsalsfyubNfbMsp2RZkmUd+92LWJbl+pG8a9+8GX3zUCf8HfG2v5Wux+Rfv3uTks83eAr65pm8uW/H/z5W5/+XK1qXx4TuwsJCrVmzRsOHD3fNs9vt6tatm1auXHnK5S3L0tdff61t27bp+eefL3fc2LFjNXr06FLzDx48qPy/vqKmunE6ncrIyJBlWV53QS5v5s19K87Kk19hoYKLnXIW+7u7nCplWZas3Fw5jx7xutO4vJllWbKys+SU6JsHCc4tkE9hroqP+CmtuODUC3iQzLw85TktFdp8lJXvXfsmS8orKpZNNnndh0y9GX3zTF7ct0Kbj+S0ZM/LK/fMZnfLysqq0DiPCd2HDh2Sw+FQbGxsifmxsbHaunVructlZGQoPj5eBQUF8vHx0euvv64rr7yy3PHDhw/XkCFDXNOZmZlKSEhQdHR0tb56uc1mU3R0tNeFN2/mzX3z9ctSUV6BcgsdsocFurucKmVZlmzBwX9dBdvLXt28mGVZckr0zcPk+uQpLM8u36goxUR519XL81L3y5mRLlkOhQUGuLucKnXsCL6l0EB/nm8ehL55Jm/uW57lUJDdpvCgIMXExLi7nDIFBlbs/1yPCd2nKywsTOvXr1d2draWLl2qIUOGqEGDBqVOPT8uICBAAQGlX/zsdnu1DkY2m63a14jSvLVvNptdstkkm80Lv57p2JslNq/cN29G3zzSCX9HvO/v5F+PR3nn2Rf///nmffvmzeibZ/LWvh3/+3j8/+XqqKJ1eUzorlWrlnx8fJSamlpifmpqquLi4spdzm63q1GjRpKkli1basuWLRo7dmy5oRsAAAAAgKpSPd8yKIO/v79at26tpUuXuuY5nU4tXbpU7dq1q/B6nE5niQulAQAAAABgiscc6ZakIUOGqG/fvmrTpo3atm2riRMnKicnx3U18z59+ig+Pl5jx46VdOyiaG3atFHDhg1VUFCghQsX6p133tGUKVPcuRsAAAAAgHOER4Xu3r176+DBgxoxYoRSUlLUsmVLLVq0yHVxtb1795Y4rz4nJ0f33Xef/vzzTwUFBalp06Z699131bt3b3ftAgAAAADgHOJRoVuSBg8erMGDB5d52/Lly0tMP/PMM3rmmWfOQlUAAAAAAJTmMZ/pBgAAAADA0xC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhHhe6J0+erMTERAUGBiopKUmrV68ud+y0adPUsWNH1ahRQzVq1FC3bt1OOh4AAAAAgKrkUaF73rx5GjJkiEaOHKm1a9eqRYsWSk5OVlpaWpnjly9frttuu03Lli3TypUrlZCQoKuuukr79u07y5UDAAAAAM5Fvu4uoDImTJiggQMHqn///pKkqVOn6vPPP9eMGTM0bNiwUuPnzJlTYnr69On68MMPtXTpUvXp06fMbRQUFKigoMA1nZmZKUlyOp1yOp1VtStVatXOw8rJSJdfhk02m83d5aCCLMtSUbZ39m1jfr5SiouV5XDKlllw6gU8iWUpNSNP1r4Mycv65tUsS8F5OcrN9aFvHmRvQaEchXnKdmaqU40wd5dTpSzLOvbz1+/exLVvXrZf3o6+eSZv7tvxv4+WZVXbHFbRujwmdBcWFmrNmjUaPny4a57dble3bt20cuXKCq0jNzdXRUVFioqKKnfM2LFjNXr06FLzDx48qPz8/MoXfhbkZKQrOyNTeVkFEv9Leg5L8inOlcML+5bvcMhuORUoqdDmUSfUVIAlR06uCo8cltc1zqtZ8i/OV2Fekeib5whwOuSvQvn4+igtzc/d5VSpzLw85TktFdp8lJXvbW9OSnlFxbLJxtPNk9A3z+TFfSu0+UhOS/a8vHLPbHa3rKysCo3zmNB96NAhORwOxcbGlpgfGxurrVu3Vmgdjz32mOrUqaNu3bqVO2b48OEaMmSIazozM1MJCQmKjo5WeHj46RVvmF+GTXlZ+dqf7y9fH28LOF7MshTkKFKeM8Drjrztk0NH5VSuLOV61qdYTslmWcpz+qigOECWl/XNm9ksS1GOYh0RffMkKZZDAXbJJyhcMTEx7i6nSuWl7pczI12yHAoLDHB3OVXq2BF8S6GB/l53Jpc3o2+eyZv7lmc5FGS3KTwoqNq+BgQGBlZonMeE7jM1btw4zZ07V8uXLz/pnRMQEKCAgNIvfna7XXZ79QwPNptNstnk62PXBfGR7i4HFWRZlhw5kk9IpNf9kXQWFCjAUawsp1MJft51dEqWpYMhAYquFep1b5Z4NctSSJ5TwUH0zZOkHso81i+brdq+Bp8um+3YR4tsf/3ubVz754X75s3om2fy1r4d//toq8avARWty2NCd61ateTj46PU1NQS81NTUxUXF3fSZcePH69x48bpq6++0sUXX2yyTAAAAAAAXKrnWwZl8Pf3V+vWrbV06VLXPKfTqaVLl6pdu3blLvfCCy9ozJgxWrRokdq0aXM2SgUAAAAAQJIHHemWpCFDhqhv375q06aN2rZtq4kTJyonJ8d1NfM+ffooPj5eY8eOlSQ9//zzGjFihN577z0lJiYqJSVFkhQaGqrQ0FC37QcAAAAA4NzgUaG7d+/eOnjwoEaMGKGUlBS1bNlSixYtcl1cbe/evSXOq58yZYoKCwvVq1evEusZOXKkRo0adTZLBwAAAACcgzwqdEvS4MGDNXjw4DJvW758eYnp3bt3my8IAAAAAIByeMxnugEAAAAA8DSEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwxNfdBQDwXg5Z2lNU5O4yqpTNslTgdCqvqEiWzebuclBBNstSLYdDh+ibR3G4uwAAAKoAoRuAEUE2u3eeS2NZkmwKtdslwpvnsCwF2eibp8mRTf60CwDg4QjdAKqcn00Kt9sV7o2p27Iku12xPr6EN09iWQq2+8ifvnmUAtkVKLv86BkAwIMRugFUuab+Ae4uwRjLsmT39VXzgADZCAIew7IsOYr95EPfPIpdeYrx8VF8gPf+TQEAeD8vPAwFAAAAAED1QOgGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAgAfrfH0PNWpzqV55Y5q7SwFQBl93FwAAAADAM/y2Y6emv/Ou1m/cpNRDB2WTTfUT6uqOXjfr1h43uLs8oFriSDcAAACACtm4ebMWfLZQh48eVb34eBUXF2vT1m16/Jnn9Obsd9xdHlAtEboBAAAAL1BcXKxnXpqoNl2vUsvOXTVi3AsqKCyUJOXn5+ulyVN0RY9eanZpB7W+4ird88h/tO33313L3jXoHjW+pJ3uunewJMnhcOjmvv9SozaX6o6775PT6VSduDhNGvecVi/5Qp++944WfzBXYaGhkqRPFi12z44D1RynlwMAAABeYPbc9xXg76+w0FD9sW+/3vtggQL8/fXEkId095BH9f3qn2Sz2dSgfj2lpB3UV9+s0MqfftaCt2eoQf36eubJJ3T7gIFa+dPPmvvRx8rKytYvmzYrPCxML44eIbvdrnaXtCmxzfjatVUnLlbbfs+Wv5+/m/YcqN440g0AAAB4gZjoWlr2yQIt+98CXZ98lSTp3fkfasnyFfp+9U+SpMcfflCLP5inRfPnKiQ4WDm5uZo6821JUv16CRr20P2SpHETJ7kuzDbqsaGqExdX5jZXr12n7Tt3SZJuvYnPdANlIXQDAAAAXuDyDpcpNCREknTtVd0kSUVFRdq5e7drzA3dj4Xx2rExatOyhSRp45Ytrttvv7mnOrdvp+ycHOUXFOjaK7vphu7JZW5v+Xc/aOBDj8jpdKrvP2/VP2/qYWCvAM/H6eUAAAAAJEmFRUVKO3TYNf3ngQNyOBzy8fEpMW7OBx/q6RcnyOFw6KF7Bmnwv/91tksFPAZHugEAAAAvsPy7H5STmytJWvjVUkmSn5+fGiQmusZ8suhLSdKB1DT9vP4XSdJFzZq5bp849U1t+e03xcXGqEZkpH75dZNenzHLdbtlWXr+lUkaOe5F2e12vTRmFIEbOAWOdAMAAABeIPXgQXW5oadCQ0L0x759kqQ7evXUlV066bK2l+j71T/puZdf0dyPPlZKWppycnMVEhyse/r3kSStWf+L3nr3PUnSs08MV3Z2th58/ClNnj5DXS5rr4uaN9Nni5do2jtzJEmhISF6e958vT1vvquGD2e9dZb3Gqj+CN0AAACAF+j7z1uVl1+gjz5fqJCQYN2QnKxHB98nSXpjwoua/NZMffblV9qz9w+FhISoW+dOevjeQWqYmKjMrGyNePY5OZ1O9brhenVu306StOjr5friq6V65KlR+mTObBUWFbq2dzQ9XUfT092xq4BHsVmWZbm7iOosMzNTERERysjIUHh4uLvLKdOK39K078ABpRUG6oL4SHeXgwqyLEuOnHT5hETKZrO5uxxUkGVZ2rx6hZq37UTfPAjPN8+0aV+6YvzzFV+7tjqdH+PucqrU7g3rlJ5yQHlZGYpJbODucqqUZVnKyi9QWGAAzzcPQt88kzf3LW33TgWFRSgyrrYSL27l7nLKVNGsyGe6AQAAAAAw5LROL9+7d6/27Nmj3NxcRUdH64ILLlBAQEBV1wYAAAAAgEercOjevXu3pkyZorlz5+rPP//UiWel+/v7q2PHjho0aJBuvvlm2e0cQAcAAAAAoELp+IEHHlCLFi20a9cuPfPMM9q8ebMyMjJUWFiolJQULVy4UB06dNCIESN08cUX66effjJdNwAAAAAA1V6FjnSHhIRo586dqlmzZqnbYmJidMUVV+iKK67QyJEjtWjRIv3xxx+65JJLqrxYAAAAAAA8SYVC99ixYyu8wu7du592MQAAAAAAeJNKf/g6Ly9Pubm5ruk9e/Zo4sSJWrx4cZUWBgAAAACAp6t06L7xxhv19ttvS5LS09OVlJSkl156ST169NCUKVOqvEAAAAAAADxVpUP32rVr1bFjR0nSBx98oNjYWO3Zs0dvv/22Xn311SovEAAAAAAAT1Xp0J2bm6uwsDBJ0pdffqmePXvKbrfr0ksv1Z49e6q8QAAAAAAAPFWlQ3ejRo308ccf648//tDixYt11VVXSZLS0tIUHh5e5QUCAAAAAOCpKh26R4wYoaFDhyoxMVFJSUlq166dpGNHvVu1alXlBQIAAAAA4Kkq9JVhJ+rVq5c6dOigAwcOqEWLFq75Xbt21U033VSlxQEAAAAA4MkqFbqLiooUFBSk9evXlzqq3bZt2yotDAAAAAAAT1ep08v9/PxUr149ORwOU/UAAAAAAOA1Kv2Z7ieeeEKPP/64jhw5YqIeAAAAAAC8RqU/0/3aa6/p999/V506dVS/fn2FhISUuH3t2rVVVhwAAAAAAJ6s0qG7R48eBsoAAAAAAMD7VDp0jxw50kQdAAAAAAB4nUp/pluS0tPTNX36dA0fPtz12e61a9dq3759VVocAAAAAACerNJHujds2KBu3bopIiJCu3fv1sCBAxUVFaUFCxZo7969evvtt03UCQAAAACAx6n0ke4hQ4aoX79+2r59uwIDA13zr7nmGq1YsaJKiwMAAAAAwJNVOnT/9NNPuvvuu0vNj4+PV0pKSpUUBQAAAACAN6h06A4ICFBmZmap+b/99puio6OrpCgAAAAAALxBpUP3DTfcoKefflpFRUWSJJvNpr179+qxxx7TzTffXOUFAgAAAADgqSodul966SVlZ2crJiZGeXl56ty5sxo1aqSwsDA9++yzJmoEAAAAAMAjVfrq5REREVqyZIm+//57/fLLL8rOztY//vEPdevWzUR9AAAAAAB4rEqH7rffflu9e/fWZZddpssuu8w1v7CwUHPnzlWfPn2qtEAAAAAAADxVpU8v79+/vzIyMkrNz8rKUv/+/aukKAAAAAAAvEGlQ7dlWbLZbKXm//nnn4qIiKiSogAAAAAA8AYVPr28VatWstlsstls6tq1q3x9//+iDodDu3btUvfu3Y0UCQAAAACAJ6pw6O7Ro4ckaf369UpOTlZoaKjrNn9/fyUmJvKVYQAAAAAAnKDCoXvkyJGSpMTERPXu3VuBgYHGigIAAAAAwBtU+jPdffv2VX5+vqZPn67hw4fryJEjkqS1a9dq3759VV4gAAAAAACeqtJfGbZhwwZ169ZNERER2r17twYOHKioqCgtWLBAe/fu1dtvv22iTgAAAAAAPE6lj3Q//PDD6tevn7Zv317iFPNrrrlGK1asqNLiAAAAAADwZJU+0v3zzz/rzTffLDU/Pj5eKSkpVVIUAAAAAADeoNJHugMCApSZmVlq/m+//abo6OgqKQoAAAAAAG9Q6dB9ww036Omnn1ZRUZEkyWazae/evXrsscf4yjAAAAAAAE5Q6dD90ksvKTs7WzExMcrLy1Pnzp3VqFEjhYWF6dlnnzVRIwAAAAAAHqnSn+mOiIjQkiVL9N1332nDhg3Kzs7WP/7xD3Xr1s1EfQAAAAAAeKxKh+7jOnTooA4dOlRlLQAAAAAAeJXTCt0//fSTli1bprS0NDmdzhK3TZgwoUoKAwAAAADA01U6dD/33HN68skn1aRJE8XGxspms7luO/F3AAAAAADOdZUO3a+88opmzJihfv36GSgHAAAAAADvUemrl9vtdl122WUmagEAAAAAwKtUOnQ//PDDmjx5solaAAAAAADwKpU+vXzo0KG69tpr1bBhQzVv3lx+fn4lbl+wYEGVFQcAAAAAgCerdOh+4IEHtGzZMl1++eWqWbMmF08DAAAAAKAclQ7ds2fP1ocffqhrr73WRD0AAAAAAHiNSn+mOyoqSg0bNjRRCwAAAAAAXqXSoXvUqFEaOXKkcnNzTdRzSpMnT1ZiYqICAwOVlJSk1atXlzt206ZNuvnmm5WYmCibzaaJEyeevUIBAAAAAOe8Sp9e/uqrr2rHjh2KjY1VYmJiqQuprV27tsqK+7t58+ZpyJAhmjp1qpKSkjRx4kQlJydr27ZtiomJKTU+NzdXDRo00C233KKHH37YWF0AAAAAAJSl0qG7R48eBsqomAkTJmjgwIHq37+/JGnq1Kn6/PPPNWPGDA0bNqzU+EsuuUSXXHKJJJV5e1kKCgpUUFDgms7MzJQkOZ1OOZ3OM90FIyzLkv76sSzL3eWggqy/+kXPPAt980z0zUOd8NpWXV+DT5frMfnX796E55tnom+eyZv7dvzvY3V+DahoXZUO3SNHjqx0MVWhsLBQa9as0fDhw13z7Ha7unXrppUrV1bZdsaOHavRo0eXmn/w4EHl5+dX2XaqUlF2unyK8xTkKJYjx93VoKIsWXIW5Eg2ySa+BcBTWLLkLMqXIzedvnkQnm+eKciRLZ/iIhVlH1Vamnf9Q5mZl6c8p6VCm4+y8gtOvYAnsaS8ouJjzzWebp6DvnkmL+5boc1Hclqy5+UpLS3N3eWUKSsrq0LjKhS6Lcty+1eDHTp0SA6HQ7GxsSXmx8bGauvWrVW2neHDh2vIkCGu6czMTCUkJCg6Olrh4eFVtp2q5JdhkyMrX3nOQPmERLq7HFTQsTMUJJ/gSLc/v1BxlmXJ7hdI3zwMzzfPlJcuhfnmyy+0hmJiot1dTpXKS90vZ0a6ZDkUFhjg7nKq1LEj+JZCA/15vnkQ+uaZvLlveZZDQXabwoOCyvwocXUQGBhYoXEVCt0XXHCBRowYoZ49e8rf37/ccdu3b9eECRNUv379Cp/OXd0EBAQoIKD0i5/dbpfdXunrzp0VNptN+uvH255s3s72V8/om2ehb56JvnmgE17bqutr8OlyPR7/+t3b8HzzTPTNM3lr347/fazOrwEVratCoXvSpEl67LHHdN999+nKK69UmzZtVKdOHQUGBuro0aPavHmzvvvuO23atEmDBw/Wvffee0bFl6VWrVry8fFRampqifmpqamKi4ur8u0BAAAAAHCmKhS6u3btqp9//lnfffed5s2bpzlz5mjPnj3Ky8tTrVq11KpVK/Xp00d33HGHatSoYaRQf39/tW7dWkuXLnVdzM3pdGrp0qUaPHiwkW0CAAAAAHAmKnUhtQ4dOqhDhw6majmlIUOGqG/fvmrTpo3atm2riRMnKicnx3U18z59+ig+Pl5jx46VdOzia5s3b3b9vm/fPq1fv16hoaFq1KiR2/YDAAAAAHBuqPTVy92pd+/eOnjwoEaMGKGUlBS1bNlSixYtcl1cbe/evSXOq9+/f79atWrlmh4/frzGjx+vzp07a/ny5We7fAAAAADAOcajQrckDR48uNzTyf8epBMTE73yO+sAAAAAAJ6hel4GDgAAAAAAL1Dh0L1//36TdQAAAAAA4HUqHLovuOACvffeeyZrAQAAAADAq1Q4dD/77LO6++67dcstt+jIkSMmawIAAAAAwCtUOHTfd9992rBhgw4fPqzmzZvr008/NVkXAAAAAAAer1JXLz/vvPP09ddf67XXXlPPnj3VrFkz+fqWXMXatWurtEAAAAAAADxVpb8ybM+ePVqwYIFq1KihG2+8sVToBgAAAAAAx1QqMU+bNk2PPPKIunXrpk2bNik6OtpUXQAAAAAAeLwKh+7u3btr9erVeu2119SnTx+TNQEAAAAA4BUqHLodDoc2bNigunXrmqwHAAAAAACvUeHQvWTJEpN1AAAAAADgdbgKGgCcg+ZOm6T2XburXoPGsixLn89/R7/9+otsNpvaXX6VLu1yValligoL9f6MyTqYsl++fn4KDYvQ9bf1U83oWEnSWy8/q/QjhxQYFCxJanVpR7W/ovsZ1blt4zp9seC/spxOxcYnqOddA13rP9HKZV/qp+++ls1mk81mU4du16hlUgdJ0tofv9XC999RRES4bL4BCgoJ0YCHHnetf8uGtepxx4AzqhMAAKA8hG4AOMf8uXuHcnOzVa9BY0nS+lXfK+3APj006kXl5+Xq9bFPqsH5zRVTp/THidp0uFznX9BCNptNPy7/Uh+/O10DHn7CdfvVve5U8xatq6TOwoJ8ffTX+qPj6ujTebO1/IuP1b3n7aXGxtSO18BHnlJQcIgyjh7W5OeeVEKDxq43BBLPb6p/3tlfPiGRstlsruWaXNRKSz9boENpKaoVE1cldQMAAJzI7u4CAABn10/fLVOLS9q7pn9d+6PaXNZFdrtdwSGhurB1kn75eWWp5fz8/dXkwpau0Fr3vEZKP3Ko0tv/ZtH/9O6UCbIsS8VFRXp97FP6ZfX3pcb99usvqp1QX9FxdSRJSZ26acPPP5a5zoZNL1BQcIgkKaJGTYWGRyjz6JEK1XPhP9pqzffLK70fAAAAFUHoBoBzzK7ftqhuYgPXdPqRw4qMquWarlEzWhlHDp9yPT8u+1JNL/pHiXlffjxPk54ZrrnTJ+nIwbQyl+uUfIOcToe+X/qFvvhwjuLrn6cWbS8rNS79aMm6ImvWUlZGuhwOx0nr+n3Lr8rPzVF8/fNc8/bu2K4pLz2rN8c/rV/XrCoxPqFBI+3ctvmU+wsAAHA6OL0cAM4xmelHFBoWcUbr+GbR/3T4YIr6PzjcNa9Xv3sUUaOmLMvSqm+W6N0pL+mBEc+XWtZms6lXv3s1+bknFBQcorsfHXVGtZwoZd9effTuNPUeMFj+AYGSpCYXttQFrS6RT1GeDmfm6O3JLyoiqqYSzmskSQoLj1RGesWOigMAAFQWR7oB4Bzj5++v4uIi13RkVM0Sp4kfPXxQEVE1y13+u68WavP6Nerzf4/K3z/ANT+ixrFlbDabLu1ylY4cPqjcnOwy15F++JAsy1JBQb6KigrLHBNZo2Rd6YcPKSwiUj4+PmWOTzuwT+9OmaCb7hyo+o2auOaHhIa56oypHa/zL2ihPTt+c91eXFwkPz+/cvcXAADgTBC6AeAcExdfTwdTDrimL/hHkn7+frmcTqdyc7L165pVuqh1UpnLfr/0C234aaX63f+Y6zPUkuRwOJSdmeGa3rTuJ4WGhSs4JLTUOvLzcvX+jMnq1fcete1whT6cPVWWZZUa1/iCi3Xgjz06mLJfkrRqxVe6uM2lZdaVdmCf3nl9vG68/V9q1OzCErdlnnAUOzszQzu3bVadhETXvIMp+xUXX6/M9QIAAJwpTi8HgHNM85aX6PctG1zhtGXby7Rv9w69PGqobLKp/RVXu0Lolg1rtXXDWt1057+VcfSwFn34nmrUitGMV56TJPn4+uqe/4yWo7hI77z+koqLi2Sz2RQcGqY77nm4zO1//O5buviS9mrQpLnOO7+Zdv++Td9++Zk6JV9fYlxAYJBuvGOA5rwxUZbTqZja8erZZ5Dr9snPPaG77huq8MgaWjj/XeXn5erLj+fpy4/nSZKu6tFbjZtfrFXffKXNv6yR3XLI5uuv9l27q0GT5q71bN+0QRe0uqTq7mAAAIAT2KyyDi/AJTMzUxEREcrIyFB4eLi7yynTit/StO/AAaUVBuqC+Eh3l4MKsixLjpz0Ul9hhOrNsixtXr1Czdt28ti+FRbk683xT2vQ0BGuzz17u/KebznZWZr5yljd+9jT8vHlfejqZtO+dMX45yu+dm11Oj/G3eVUqd0b1ik95YDysjIUc8KFDb2BZVnKyi9QWGCAx/6dPBfRN8/kzX1L271TQWERioyrrcSLW7m7nDJVNCtyejkAnGP8AwJ19c136Ojhg+4uxe2OHEzV9f/sR+AGAADG8F8GAJyDGja9wN0lVAvHr2AOAABgCke6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhvu4uAADOljuvbKPU/X/qrvseUZ//e9Td5QCAnMXFStu9091lVClLUqHNR3mWQzZ3F4MKo2+eyZv75iwudncJVYbQDQCGvPbs49r484/avWObnA6HatSM1vsrNrq7LADVREBQkKSa7i6jylmWJTktBdltstm8LQZ4L/rmmby9b8f+Tno+jwvdkydP1osvvqiUlBS1aNFCkyZNUtu2bcsdP3/+fD311FPavXu3GjdurOeff17XXHPNWawYwLnqq08/kJ+fn8IjIpV+5LC7ywFQjfj6+ikoIlJBEZHuLqXKWZYle16ewoOCvDIEeCv65pnOhb75+vq5u4Qz5lGhe968eRoyZIimTp2qpKQkTZw4UcnJydq2bZtiYmJKjf/hhx902223aezYsbruuuv03nvvqUePHlq7dq0uvPBCN+wBgOqguLhYU8aN0JJP5svhKFbXa3vqnmFPy98/QAX5eZrzxkR988X/lHZgn4KCQ3RRm0vV7/7HdN75zeQoLtaEMY9r764dapnUQS/O+EAOh0MP3XGdtm5cpxaXtNcLMz6Q3W7Xmx8tU0zteL3w+ANa8r/33b3bAKqRus299/8Qp9OptLQ0xcTEyG7n8kGegr55JvrmGTyqMxMmTNDAgQPVv39/NW/eXFOnTlVwcLBmzJhR5vhXXnlF3bt316OPPqpmzZppzJgx+sc//qHXXnvtLFcOoDr56J1p+urTDxQSFqbc7Cx9Om+2Zrz8nCRpxOC++u+br+jAn3tUu16iiouL9MPXi/TgHddp787t8vH11Z0DBysgKEjrV32nhfPf1Yezp2rrxnUKDY/Qf5571fWiF1M73p27CQAAgGrAY450FxYWas2aNRo+fLhrnt1uV7du3bRy5coyl1m5cqWGDBlSYl5ycrI+/vjjcrdTUFCggoIC13RmZqakY+8iOZ3OM9gDcyzLkv76sSzL3eWggqy/+kXPzr6aMXGa/P5iBYeEaux/7tOyhR/pk//O1EVtLtXalSskSXf/Z5R63jVIB1P26983dFJebo7+O+1VPfrsK4qOra1BQ0dq0phhemP8aDmKiyRJg594TtG140/aU/rtHjzfPNQJr23V9TUYpTmdTnrmgeibZ6Jv7lXR+91jQvehQ4fkcDgUGxtbYn5sbKy2bt1a5jIpKSlljk9JSSl3O2PHjtXo0aNLzV+6dKmCg4NPo3LzdqRlKTMrS1nFvtI+77jYwLnAkiVnYb7s/oGyed31Jqunwr/eUGvUpJl2b1orSWrYsJGWSSoqKtTPK5a4xsbXrq3Nq48F8MSGjbVl43r9+vNKbf5phXb/tlkNmjRXs4taasvG9ZKkVm3bKS66lmuZE6UfSpUkFRcVlnk7zOP55plSMvKU41usw3vClLszzN3loIKcTqeys7MVGhrK6a4ehL55JvrmXrm5uRUa5zGh+2wZPnx4iaPjmZmZSkhIUNeuXRUeHu7Gysr37faD2n/ggNIKA9U8PtLd5aCCLMuSIyddPiGRXnvhi+rGPyBAklQzLl7N23aSJGXk5Lluj004z/X7+a3aqUbNWpKk0Mg3JEkBQcFqfkknyZIat7xUhUX//6ss8vIL1KT1ZfLx8Sm13cj/fShJ8vXzd20XZxfPNw+1L10x/vmqU7u2OjaOdnc1qCCn06mDBw8qOjqaEOBB6Jtnom/udfys6FPxmNBdq1Yt+fj4KDU1tcT81NRUxcXFlblMXFxcpcZLUkBAgAL++sf8RHa7vdo+kG02m/TXD/9MehbbXz2jb2fX6hVL1W/wYwoKCdGKxZ9Kkvz8/FWvQWPXmOULP1LPPsdOL/91zSpJ0vkXtHD16+3XXtSOrb8qOq6OCgvytXXDWv33zVd0132PnHTb9Np9eL55oBNe26rrazDKdrxn9M2z0DfPRN/cp6L3ucd0xt/fX61bt9bSpUtd85xOp5YuXap27dqVuUy7du1KjJekJUuWlDsewLnhUOoB3ZV8ifp0T9LSz44dhb6ud1+1v6K7/tHu2JHoqS+M1IDrO7o+zx0UHKJ/DnxAkrRj22Z9MGuKJOnhUeM1+IljF2Gb88bL2vbretd2Hul3k/p2v1Tff7VQkpSRfkR9u1+qvt0v1ZYNa8/W7gIAAMCNPCZ0S9KQIUM0bdo0zZ49W1u2bNG9996rnJwc9e/fX5LUp0+fEhdae/DBB7Vo0SK99NJL2rp1q0aNGqWff/5ZgwcPdtcuAKgGbrproLpe10vZGRkKDgnVtbf20b+HPCFJevq12bpt0IOKq1tP+/buko+Pr9pf0V2vzPlM9Ro0Vk52lt6d/rqcTqe697xNl3S8Ql2u7qFOydfLUVys54cNVkH+sVPWU/f9of1/7FZuTrYkyelwaP8fu7X/j90qzM8rtz4AAAB4D5vlYZdyfe211/Tiiy8qJSVFLVu21KuvvqqkpCRJUpcuXZSYmKhZs2a5xs+fP19PPvmkdu/ercaNG+uFF17QNddcU+HtZWZmKiIiQhkZGdX2M90rfkvTvr8+030Bn+n2GHzG1DNZlqXNq1eoedtO9M2D8HzzTJv++kx3fO3a6nR+jLvLQQXxvcGeib55JvrmXhXNih7zme7jBg8eXO6R6uXLl5ead8stt+iWW24xXBUAAAAAAKXxdggAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIb7uLqCijhw5ovvvv1+ffvqp7Ha7br75Zr3yyisKDQ0td5k333xT7733ntauXausrCwdPXpUkZGRZ69oAAAA4BTGjRunHj16qGnTprIsS2+++aZ+/vln2Ww23XDDDbruuuvKXO6pp55Senq6bDabgoKCdPfdd6tBgwaSpP379+vll19WZmamQkJC9NBDD6levXpnVOeSJUs0f/58WZaliy++WPfee698fUvHiXfeeUerVq2S3X7s+F6vXr3UqVMnSVJBQYFeffVVbd++XTabTX369NFll10mSZoxY4YaNmyozp07n1GdQHXjMaH7jjvu0IEDB7RkyRIVFRWpf//+GjRokN57771yl8nNzVX37t3VvXt3DR8+/CxWCwAAAJzab7/9pqysLDVt2lSStGzZMu3du1dvvPGGcnJy9OCDD+riiy8uMzAPGzZMISEhkqSVK1fq5Zdf1qRJkyRJkydPVvfu3dW1a1d9//33mjhxoiZMmHDadaampurdd9/VxIkTFRkZqWeeeUaLFy/WtddeW2psz549ddddd0mSDh8+rHvvvVctW7ZUeHi4PvroI/n5+enNN99UamqqHnnkEV188cUKCwvTzTffrP/85z/q2LGjK7AD3sAjHs1btmzRokWLNH36dCUlJalDhw6aNGmS5s6dq/3795e73EMPPaRhw4bp0ksvPYvVAgAAABWzaNEidenSxTX97bffKjk5WXa7XWFhYerYsaO++eabMpc9HrilYwebbDabJCkjI0Pbt293rbd9+/Y6ePCgDhw4UGodkyZN0tSpUyVJ2dnZGjRokH799ddS477//nu1bdtWNWrUkM1m09VXX12huvLz82VZlizLkiStWLFCV199tSQpNjZWF110kVauXClJioiIUO3atbVu3boy1wt4Ko840r1y5UpFRkaqTZs2rnndunWT3W7XqlWrdNNNN1XZtgoKClRQUOCazszMlCQ5nU45nc4q205VsixL+uvn+B80VH/HX4DomWehb56JvnmoE17bqutrMEpzOp30rBI2bNig66+/3nV/paWlqVatWq7p6Ohobdu2rdz78+WXX9bGjRslSSNGjJDT6VRqaqorHB9frlatWkpNTVVsbGyJ5QcOHKhHH31UK1as0Oeff65u3bqpefPmpbaXmppaqq60tLRy6/r000+1cOFCHTp0SPfff7/CwsLkdDqVlpammjVrlqrr+PT555+vdevWqVWrVpW+L89FPN/cq6L3u0eE7pSUFMXExJSY5+vrq6ioKKWkpFTptsaOHavRo0eXmn/w4EHl5+dX6baqSlF2unyK8xTkKJYjx93VoKIsWXIW5Eg2ySabu8tBBVmy5CzKlyM3nb55EJ5vninIkS2f4iIVZR9VWhpvmHgKp9OpjIwMWZbFKcIVsG/fPhUVFSktLU2SlJeXp8OHD7umMzIylJWV5Zr+uzvuuEPSsSPkr7/+uoYOHarDhw8rLy+vxDK5ubk6cuRImesZMGCARowYobp166pjx45ljsnKypKvr6/rtkOHDik/P7/cupKSkpSUlKS9e/dq6tSpqlu3rkJDQ1VQUKCDBw+quLjYtV4/P78S69mzZ0+560VJPN/cKysrq0Lj3Bq6hw0bpueff/6kY7Zs2XKWqjlm+PDhGjJkiGs6MzNTCQkJio6OVnh4+FmtpaL8MmxyZOUrzxkon5BId5eDCjp2hoLkExzpOh0M1Z9lWbL7BdI3D8PzzTPlpUthvvnyC62hmJhod5eDCnI6nbLZbIqOjiYEVEB4eLgiIyNVq1YtSVK9evXkcDhcB5zy8/N13nnnlToA9Xc333yz/vvf/yooKEhNmzZVXl6eatasKR8fH1mWpZycHDVp0qTM9ezZs0cREREqLCxUVFSUAgICSo1p0KBBiQNhe/fuVUJCwinriomJUd26dZWSkqL27durbt26rvnH969p06au6ZCQEEVFRZ1yvTiG55t7BQYGVmicW0P3I488on79+p10TIMGDRQXF1fq3a7i4mIdOXJEcXFxVVpTQEBAmX9o7HZ7tX0g22w26a8f/pn0LLa/ekbfPAt980z0zQOd8NpWXV+DUbbjPaNvp9agQQPt37/fFTI7duyoJUuWqFOnTsrJydH333+vESNGlLovc3JyVFBQoKioKEnSjz/+qPDwcIWHh8tms6lRo0ZasWKF60Jq0dHRio+PL7X9gwcPaurUqXrmmWc0d+5czZgxQ//3f/9XalyHDh302GOPKSMjQ5GRkVq8eLE6d+5cZo//+OMPJSQkSJIOHDignTt3qn79+rLb7erYsaMWL16sZs2aKTU1Vb/++qvuu+8+13r27dunBg0a8NipBJ5v7lPR+9ytoTs6OlrR0ad+57pdu3ZKT0/XmjVr1Lp1a0nS119/LafTqaSkJNNlAgAAAEa0b99ea9euVcuWLSVJl19+uX777TcNGjRINptNPXr0UGJioiRp1apVWrVqlR544AHl5ORo3LhxKiwslM1mU0REhEaMGOF6Y3Hw4MF6+eWX9f777ys4OFgPPvhgqW07HA698MILuvPOO5WQkKDbb79d48eP17fffquOHTuWGBsXF6fbb79d//nPfyRJF110kbp37y7p2Ff7jho1Sq+++qokaebMmUpJSZGvr698fHx0zz33uEJ4z5499corr2jgwIGy2+265557XGeTWpalX375Rb169araOxlwM5vlIVeVufrqq5WamqqpU6e6vjKsTZs2rq8M27dvn7p27aq3335bbdu2lXTss+ApKSn6+eefNXDgQK1YsUJhYWGqV6+e613BU8nMzFRERIQyMjKq7enlK35L074DB5RWGKgL4iPdXQ4qyLIsOXLS5RPC6a6exLIsbV69Qs3bdqJvHoTnm2fatC9dMf75iq9dW53O51RTT3H8YlkxMTEceauA/Px8Pfroo3rxxRcrfKqqCdWhb2vWrNHy5cv1yCOPuGX7nqg69O1cVtGs6DGdmTNnjpo2baquXbvqmmuuUYcOHfTmm2+6bi8qKtK2bduUm5vrmjd16lS1atVKAwcOlCR16tRJrVq10ieffHLW6wcAAAD+LjAwUP/+97+Vmprq7lLcLjc3V/3793d3GUCV84irl0tSVFSU66h2WRITE0t9FcyoUaM0atQow5UBAAAAp69FixbuLqFa+Psp7YC38Jgj3QAAAAAAeBpCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwxGNC95EjR3THHXcoPDxckZGRGjBggLKzs086/v7771eTJk0UFBSkevXq6YEHHlBGRsZZrBoAAAAAcC7zmNB9xx13aNOmTVqyZIk+++wzrVixQoMGDSp3/P79+7V//36NHz9ev/76q2bNmqVFixZpwIABZ7FqAAAAAMC5zNfdBVTEli1btGjRIv30009q06aNJGnSpEm65pprNH78eNWpU6fUMhdeeKE+/PBD13TDhg317LPP6s4771RxcbF8fT1i1wEAAAAAHswjkufKlSsVGRnpCtyS1K1bN9ntdq1atUo33XRThdaTkZGh8PDwkwbugoICFRQUuKYzMzMlSU6nU06n8zT3wCzLsiTLUrHDqU370t1dDirKshTkyFZeuiSbzd3VoKIsSykZedK+dPrmSXi+eaRih1OyLFmWVW1fg1Ga0+mkZx6Ivnkm+uZeFb3fPSJ0p6SkKCYmpsQ8X19fRUVFKSUlpULrOHTokMaMGXPSU9IlaezYsRo9enSp+QcPHlR+fn7Fiz6LirLTFeQsVJ1Am8T/kp7DknyKixTmW0DfPIkl5fgWK8afvnkUnm+eyZKCnIUqyj6qtDTL3dWggpxOpzIyMmRZlux2j/kk4zmPvnkm+uZeWVlZFRrn1tA9bNgwPf/88ycds2XLljPeTmZmpq699lo1b95co0aNOunY4cOHa8iQISWWTUhIUHR0tMLDw8+4FhNCsn0kSTVCa8jGERyPYVmWirKPyo++eRTLsnR4T5jq1I6jbx6E55tnOt63kIiaiomp6e5yUEFOp1M2m03R0dGEAA9C3zwTfXOvwMDACo1za+h+5JFH1K9fv5OOadCggeLi4pSWllZifnFxsY4cOaK4uLiTLp+VlaXu3bsrLCxMH330kfz8/E46PiAgQAEBAaXm2+32avtATmpQU2lpDsXE8GTzJE6nU2lpFn3zME6nU7k7w9SxMX3zJDzfPNP/71tN+uZhbDZbtf7fCWWjb56JvrlPRe9zt4bu6OhoRUdHn3Jcu3btlJ6erjVr1qh169aSpK+//lpOp1NJSUnlLpeZmank5GQFBATok08+qfA7EQAAAAAAVAWPeDukWbNm6t69uwYOHKjVq1fr+++/1+DBg/XPf/7TdeXyffv2qWnTplq9erWkY4H7qquuUk5Ojt566y1lZmYqJSVFKSkpcjgc7twdAAAAAMA5wiMupCZJc+bM0eDBg9W1a1fZ7XbdfPPNevXVV123FxUVadu2bcrNzZUkrV27VqtWrZIkNWrUqMS6du3apcTExLNWOwAAAADg3OQxoTsqKkrvvfdeubcnJiYe++qsv3Tp0qXENAAAAAAAZ5tHnF4OAAAAAIAnInQDAAAAAGAIoRsAAAAAAEMI3QAAAAAAGELoBgAAAADAEEI3AAAAAACGELoBAAAAADCE0A0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0AAAAAABhC6AYAAAAAwBBCNwAAAAAAhhC6AQAAAAAwhNANAAAAAIAhhG4AAAAAAAwhdAMAAAAAYAihGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEN83V1AdWdZliQpMzPTzZWUz+l0KisrS4GBgbLbeR/FU9A3z+R0OpWbm6vMzEz65kF4vnkm+uaZ6Jtnom+eib651/GMeDwzlofQfQpZWVmSpISEBDdXAgAAAACobrKyshQREVHu7TbrVLH8HOd0OrV//36FhYXJZrO5u5wyZWZmKiEhQX/88YfCw8PdXQ4qiL55JvrmmeibZ6Jvnom+eSb65pnom3tZlqWsrCzVqVPnpGcacKT7FOx2u+rWrevuMiokPDycJ5sHom+eib55JvrmmeibZ6Jvnom+eSb65j4nO8J9HCf+AwAAAABgCKEbAAAAAABDCN1eICAgQCNHjlRAQIC7S0El0DfPRN88E33zTPTNM9E3z0TfPBN98wxcSA0AAAAAAEM40g0AAAAAgCGEbgAAAAAADCF0AwAAAABgCKEbAAAAAABDCN0e6siRI7rjjjsUHh6uyMhIDRgwQNnZ2Scdf//996tJkyYKCgpSvXr19MADDygjI+MsVo3K9k2S3nzzTXXp0kXh4eGy2WxKT08/O8WewyZPnqzExEQFBgYqKSlJq1evPun4+fPnq2nTpgoMDNRFF12khQsXnqVKcaLK9G3Tpk26+eablZiYKJvNpokTJ569QlFCZfo2bdo0dezYUTVq1FCNGjXUrVu3Uz4/YUZl+rZgwQK1adNGkZGRCgkJUcuWLfXOO++cxWpxXGVf346bO3eubDabevToYbZAlKkyfZs1a5ZsNluJn8DAwLNYLcpC6PZQd9xxhzZt2qQlS5bos88+04oVKzRo0KByx+/fv1/79+/X+PHj9euvv2rWrFlatGiRBgwYcBarRmX7Jkm5ubnq3r27Hn/88bNU5blt3rx5GjJkiEaOHKm1a9eqRYsWSk5OVlpaWpnjf/jhB912220aMGCA1q1bpx49eqhHjx769ddfz3Ll57bK9i03N1cNGjTQuHHjFBcXd5arxXGV7dvy5ct12223admyZVq5cqUSEhJ01VVXad++fWe58nNbZfsWFRWlJ554QitXrtSGDRvUv39/9e/fX4sXLz7LlZ/bKtu343bv3q2hQ4eqY8eOZ6lSnOh0+hYeHq4DBw64fvbs2XMWK0aZLHiczZs3W5Ksn376yTXviy++sGw2m7Vv374Kr+f999+3/P39raKiIhNl4m/OtG/Lli2zJFlHjx41WCXatm1r/d///Z9r2uFwWHXq1LHGjh1b5vhbb73Vuvbaa0vMS0pKsu6++26jdaKkyvbtRPXr17defvllg9WhPGfSN8uyrOLiYissLMyaPXu2qRJRhjPtm2VZVqtWrawnn3zSRHkox+n0rbi42Grfvr01ffp0q2/fvtaNN954FirFiSrbt5kzZ1oRERFnqTpUFEe6PdDKlSsVGRmpNm3auOZ169ZNdrtdq1atqvB6MjIyFB4eLl9fXxNl4m+qqm8wp7CwUGvWrFG3bt1c8+x2u7p166aVK1eWuczKlStLjJek5OTkcsej6p1O3+B+VdG33NxcFRUVKSoqylSZ+Jsz7ZtlWVq6dKm2bdumTp06mSwVJzjdvj399NOKiYnhzEg3Od2+ZWdnq379+kpISNCNN96oTZs2nY1ycRKEbg+UkpKimJiYEvN8fX0VFRWllJSUCq3j0KFDGjNmzClPbUbVqYq+waxDhw7J4XAoNja2xPzY2Nhye5SSklKp8ah6p9M3uF9V9O2xxx5TnTp1Sr3xBXNOt28ZGRkKDQ2Vv7+/rr32Wk2aNElXXnml6XLxl9Pp23fffae33npL06ZNOxslogyn07cmTZpoxowZ+t///qd3331XTqdT7du3159//nk2SkY5CN3VyLBhw0pd+ODvP1u3bj3j7WRmZuraa69V8+bNNWrUqDMv/Bx3tvoGAPj/xo0bp7lz5+qjjz7iIkEeICwsTOvXr9dPP/2kZ599VkOGDNHy5cvdXRbKkZWVpbvuukvTpk1TrVq13F0OKqFdu3bq06ePWrZsqc6dO2vBggWKjo7WG2+84e7SzmmcV1yNPPLII+rXr99JxzRo0EBxcXGlLp5QXFysI0eOnPKCQFlZWerevbvCwsL00Ucfyc/P70zLPuedjb7h7KhVq5Z8fHyUmppaYn5qamq5PYqLi6vUeFS90+kb3O9M+jZ+/HiNGzdOX331lS6++GKTZeJvTrdvdrtdjRo1kiS1bNlSW7Zs0dixY9WlSxeT5eIvle3bjh07tHv3bl1//fWueU6nU9Kxs/S2bdumhg0bmi0aVfL65ufnp1atWun33383USIqiCPd1Uh0dLSaNm160h9/f3+1a9dO6enpWrNmjWvZr7/+Wk6nU0lJSeWuPzMzU1dddZX8/f31ySefcGSgipjuG84ef39/tW7dWkuXLnXNczqdWrp0qdq1a1fmMu3atSsxXpKWLFlS7nhUvdPpG9zvdPv2wgsvaMyYMVq0aFGJa2Tg7Kiq55vT6VRBQYGJElGGyvatadOm2rhxo9avX+/6ueGGG3T55Zdr/fr1SkhIOJvln7Oq4vnmcDi0ceNG1a5d21SZqAh3X8kNp6d79+5Wq1atrFWrVlnfffed1bhxY+u2225z3f7nn39aTZo0sVatWmVZlmVlZGRYSUlJ1kUXXWT9/vvv1oEDB1w/xcXF7tqNc05l+2ZZlnXgwAFr3bp11rRp0yxJ1ooVK6x169ZZhw8fdscueL25c+daAQEB1qxZs6zNmzdbgwYNsiIjI62UlBTLsizrrrvusoYNG+Ya//3331u+vr7W+PHjrS1btlgjR460/Pz8rI0bN7prF85Jle1bQUGBtW7dOmvdunVW7dq1raFDh1rr1q2ztm/f7q5dOCdVtm/jxo2z/P39rQ8++KDE61hWVpa7duGcVNm+Pffcc9aXX35p7dixw9q8ebM1fvx4y9fX15o2bZq7duGcVNm+/R1XL3ePyvZt9OjR1uLFi60dO3ZYa9assf75z39agYGB1qZNm9y1C7Asi9DtoQ4fPmzddtttVmhoqBUeHm7179+/xD8du3btsiRZy5Ytsyzr/3/dVFk/u3btcs9OnIMq2zfLsqyRI0eW2beZM2ee/R04R0yaNMmqV6+e5e/vb7Vt29b68ccfXbd17tzZ6tu3b4nx77//vnX++edb/v7+1gUXXGB9/vnnZ7liWFbl+nb8ufb3n86dO5/9ws9xlelb/fr1y+zbyJEjz37h57jK9O2JJ56wGjVqZAUGBlo1atSw2rVrZ82dO9cNVaOyr28nInS7T2X69tBDD7nGxsbGWtdcc421du1aN1SNE9ksy7LO3nF1AAAAAADOHXymGwAAAAAAQwjdAAAAAAAYQugGAAAAAMAQQjcAAAAAAIYQugEAAAAAMITQDQAAAACAIYRuAAAAAAAMIXQDAAAAAGAIoRsAAAAAAEMI3QAAeLFt27YpLi5OWVlZ7i6lykydOlXXX3+9u8sAAKBCCN0AAFRjDodD7du3V8+ePUvMz8jIUEJCgp544omTLj98+HDdf//9CgsLM1mmZs2apcjISKPbOO5f//qX1q5dq2+//fasbA8AgDNB6AYAoBrz8fHRrFmztGjRIs2ZM8c1//7771dUVJRGjhxZ7rJ79+7VZ599pn79+p2FSquGw+GQ0+k86Rh/f3/dfvvtevXVV89SVQAAnD5CNwAA1dz555+vcePG6f7779eBAwf0v//9T3PnztXbb78tf3//cpd7//331aJFC8XHx7vmHT8i/dlnn6lJkyYKDg5Wr169lJubq9mzZysxMVE1atTQAw88IIfD4VquoKBAQ4cOVXx8vEJCQpSUlKTly5dLkpYvX67+/fsrIyNDNptNNptNo0aNOuVyJ9bzySefqHnz5goICNDevXu1fPlytW3bViEhIYqMjNRll12mPXv2uJa7/vrr9cknnygvL69q7mQAAAzxdXcBAADg1O6//3599NFHuuuuu7Rx40aNGDFCLVq0OOky3377rdq0aVNqfm5url599VXNnTtXWVlZ6tmzp2666SZFRkZq4cKF2rlzp26++WZddtll6t27tyRp8ODB2rx5s+bOnas6deroo48+Uvfu3bVx40a1b99eEydO1IgRI7Rt2zZJUmho6CmXa9y4saue559/XtOnT1fNmjUVFRWlli1bauDAgfrvf/+rwsJCrV69WjabzbUPbdq0UXFxsVatWqUuXbpUxV0MAIARhG4AADyAzWbTlClT1KxZM1100UUaNmzYKZfZs2dPmaG7qKhIU6ZMUcOGDSVJvXr10jvvvKPU1FSFhoaqefPmuvzyy7Vs2TL17t1be/fu1cyZM7V3717VqVNHkjR06FAtWrRIM2fO1HPPPaeIiAjZbDbFxcW5tlOR5Y7X8/rrr7veRDhy5IgyMjJ03XXXuWps1qxZiX0IDg5WREREiaPfAABUR4RuAAA8xIwZMxQcHKxdu3bpzz//VGJi4knH5+XlKTAwsNT84OBgV5iVpNjYWCUmJrqOTh+fl5aWJknauHGjHA6Hzj///BLrKSgoUM2aNcvdfkWX8/f318UXX+yajoqKUr9+/ZScnKwrr7xS3bp106233qratWuXWE9QUJByc3NPdhcAAOB2hG4AADzADz/8oJdffllffvmlnnnmGQ0YMEBfffVViVOu/65Wrf/Xzr2FRPXuYRx/bLKDEaXssZuo7OCBMhrCKMsoIUIjkCK6KESQmUk0iaRACrroJGZJZpFRGAWVQRFReOpkFlZWFKnZidKiyEwrYzI8rH2x2UOzHcvyv1I338/d+877e9fv9UaeWWvNv9Tc3Nxl3tfX12Ps4+Pjde6/P2j29etXWSwW3bt3TxaLxWPdj0H9f/W0bvjw4V3OkZ+fr9TUVBUVFamgoECbN29WaWmpZs+e7V7T1NQkq9Xa7fUBAOgPCN0AAPRzLpdLCQkJSkpK0sKFCxUUFKTw8HAdPHhQSUlJ3dbZbDbV1NT0+vo2m00dHR1qaGhQVFSU1zVDhgzx+OG1ntb96ro2m03p6emaM2eOTpw44Q7dL168UGtrq2w22+8fCACAv4hfLwcAoJ9LT0+XYRjKyMiQJE2YMEFZWVnauHGjXr161W3d4sWLVVFR0SUM/67g4GCtWrVK8fHxOnv2rF6+fKk7d+5o586dunjxorunr1+/6vLly2psbJTL5epRnTcvX75Uenq6KioqVFdXp5KSEj179szjve7y8nJNnDjR4zF5AAD6I0I3AAD9WFlZmfbv36/8/Hz5+fm5551OpyIjI5WYmCjDMLzWxsTEaPDgwbp06VKv+8jPz1d8fLzS0tIUEhKiuLg4VVZWaty4cZKkyMhIrVmzRitXrpTValVmZmaP6rzx8/NTbW2tli9fruDgYDkcDiUnJ8vpdLrXnDx5Una7vdfnAgDAbD5Gd/+pAQDAgLd//36dP39excXFfd3KP6a6ulrR0dF6+vSpRo0a1dftAADwU7zTDQDA/zGn06lPnz6ppaVFI0eO7Ot2/hHv3r3TsWPHCNwAgAGBO90AAAAAAJiEd7oBAAAAADAJoRsAAAAAAJMQugEAAAAAMAmhGwAAAAAAkxC6AQAAAAAwCaEbAAAAAACTELoBAAAAADAJoRsAAAAAAJMQugEAAAAAMAmhGwAAAAAAkxC6AQAAAAAwCaEbAAAAAACTELoBAAAAADAJoRsAAAAAAJMQugEAAAAAMAmhGwAAAAAAkxC6AQAAAAAwCaEbAAAAAACTELoBAAAAADAJoRsAAAAAAJMQugEAAAAAMAmhGwAAAAAAkxC6AQAAAAAwCaEbAAAAAACTELoBAAAAADAJoRsAAAAAAJMQugEAAAAAMAmhGwAAAAAAkxC6AQAAAAAwCaEbAAAAAACTELoBAAAAADAJoRvAgJGRkaHa2lpJkmEYysvLk91ul8Ph0IULF35Zf+nSJS1dulS3bt1yz33+/FlbtmyRw+FQcnKyqqqqet1nZWWl1qxZI4fDoR07dsjlcv10/efPn7V69Wpt27bNY76goEB2u112u13Hjx/32D83N7fXfQIAAMB8hG4AA8LTp0/V0tKi0NBQSdLVq1dVX1+vvLw87d69W2fPnlV9fX239Q0NDSouLlZISIjH/NGjRxUSEqJDhw5p3bp1ysrKUnt7+x/32draqr1792rz5s06dOiQAgICdOrUqZ/W5ObmatasWR5zVVVVKisr0759+3TgwAHdv39flZWVkqSIiAg9f/5cb9++/eM+AQAA8HcQugEMCEVFRVqwYIF7XF5ersWLF2vQoEEaOXKkoqKiVFZW5rXWMAzl5OTI6XTK19fX47MbN24oJiZGkjRlyhQFBAR4vdt9+vRpbd26VYZhqK2tTevWrdO1a9e6rLt7964mTZqksWPHSpKWLFmi69evd3uu0tJSjRkzRlOnTvWYLy8vV3R0tIYNGyZfX18tWrTIY5958+appKSk230BAADQPxC6AQwIjx49UnBwsHv84cMHBQYGusdjxozRhw8fvNaeO3dOYWFhmjx5ssd8S0uL2tvb5e/v/8t9VqxYoY6ODp07d06HDx/WlClTPL4E6K6vwMBANTU1qaOjo8va9+/fq7CwUPHx8T3a58e+QkND9fDhQ6/nBQAAQP9B6AYwIDQ2Nmr06NG/XVdXV6ebN29q5cqVvbq+j4+P0tLSdP78edXU1Mhut/dqP8MwtHfvXjmdTg0ZMuS36/39/dXY2NirHgAAAGC+wX3dAAD0xNChQ9XW1uYeW61WNTQ0uN/xfv/+vaxWa5e66upqNTQ0yOl0SpKam5uVm5urpqYmxcbGymKxqLm52X23u7t9pP+8F24Yhr59+6bv3797DctWq1UPHjzwqAkICJDFYvFY53K59OrVK2VmZkqSe89NmzZp+/bt7vP9uM+PfbW1tf1RWAcAAMDfxZ1uAANCUFCQ3rx54x7PmzdPxcXF6uzsVEtLi8rLyxUVFdWlLjY2VseOHdORI0d05MgRhYSEKCUlRbGxse59CgsLJUnPnj3Tx48fNW3atC77uFwuZWZmav369YqJidGePXtkGEaXdTNnztSLFy/cvV68eFHz58/vsm7EiBE6ceKEu6/ExETZbDZt377d3deVK1fU2tqqtrY2lZaWeuzz+vVrBQUF/c6fEAAAAH2A0A1gQIiMjNT9+/fd44ULF2rs2LFyOBxav3694uLiNGHCBEnS7du3lZOT06N9ExIS9PjxYzkcDmVnZystLU2DB3d9CCgnJ0cLFizQ9OnTtWzZMvn4+OjMmTNd1g0fPlxr167Vtm3b5HA41NjY6PFoe2pqqpqamn7ZV3h4uObPn6+UlBQlJSVpxowZioiIcH9+7949zZ07t0dnBAAAQN/xMbzdqgGAfqa1tVUbNmzQrl27NGzYsL5up099+fJFmzZtUnZ2ttcvCAAAANB/ELoBDBgPHz7U6NGjNX78+L5upU89efJEnZ2dCgsL6+tWAAAA8AuEbgAAAAAATMI73QAAAAAAmITQDQAAAACASQjdAAAAAACYhNANAAAAAIBJCN0AAAAAAJiE0A0AAAAAgEkI3QAAAAAAmITQDQAAAACASf4NfQ7Q5BD4WjgAAAAASUVORK5CYII=", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Create assets\n", + "box1 = MockAsset2D(\"box1\", width=0.4, length=0.4, fixed=True) # Fixed reference point\n", + "box2 = MockAsset2D(\"box2\", width=0.3, length=0.3)\n", + "box3 = MockAsset2D(\"box3\", width=0.25, length=0.25)\n", + "\n", + "# Define relations - box1 is the root, others position relative to it\n", + "box2.add_relation(NextTo(box1, side=\"right\"))\n", + "box3.add_relation(NextTo(box2, side=\"left\"))\n", + "\n", + "# Solve\n", + "solver = RelationSolver2D()\n", + "assets_list = [box1, box2, box3]\n", + "positions = solver.solve(assets_list)\n", + "\n", + "print(\"\\nFinal positions:\")\n", + "for name, pos in positions.items():\n", + " if not name.startswith('_'):\n", + " print(f\" {name}: x={pos[0]:.3f}, y={pos[1]:.3f}, theta={pos[2]:.3f}\")\n", + "\n", + "# Visualize\n", + "assets_dict = {a.name: a for a in assets_list}\n", + "visualize_scene(positions, assets_dict, title=\"Example 1: Simple NextTo Chain\")\n", + "plot_loss_history(positions)\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "### Example 2: Complex Layout\n", + "\n", + "Multiple objects arranged with nested NextTo relations.\n" + ] + }, + { + "cell_type": "code", + "execution_count": 14, + "metadata": {}, + "outputs": [ + { + "ename": "KeyError", + "evalue": "'microwave'", + "output_type": "error", + "traceback": [ + "\u001b[31m---------------------------------------------------------------------------\u001b[39m", + "\u001b[31mKeyError\u001b[39m Traceback (most recent call last)", + "\u001b[36mCell\u001b[39m\u001b[36m \u001b[39m\u001b[32mIn[14]\u001b[39m\u001b[32m, line 17\u001b[39m\n\u001b[32m 15\u001b[39m full_assets_list = [microwave, cracker_box, apple, banana]\n\u001b[32m 16\u001b[39m solver = RelationSolver2D()\n\u001b[32m---> \u001b[39m\u001b[32m17\u001b[39m positions = \u001b[43msolver\u001b[49m\u001b[43m.\u001b[49m\u001b[43msolve\u001b[49m\u001b[43m(\u001b[49m\u001b[43moptimizing_assets_list\u001b[49m\u001b[43m)\u001b[49m\n\u001b[32m 19\u001b[39m \u001b[38;5;28mprint\u001b[39m(\u001b[33m\"\u001b[39m\u001b[38;5;130;01m\\n\u001b[39;00m\u001b[33mFinal positions:\u001b[39m\u001b[33m\"\u001b[39m)\n\u001b[32m 20\u001b[39m \u001b[38;5;28;01mfor\u001b[39;00m name, pos \u001b[38;5;129;01min\u001b[39;00m positions.items():\n", + "\u001b[36mCell\u001b[39m\u001b[36m \u001b[39m\u001b[32mIn[4]\u001b[39m\u001b[32m, line 30\u001b[39m, in \u001b[36mRelationSolver2D.solve\u001b[39m\u001b[34m(self, assets)\u001b[39m\n\u001b[32m 21\u001b[39m \u001b[38;5;250m\u001b[39m\u001b[33;03m\"\"\"Solve for optimal positions of all assets.\u001b[39;00m\n\u001b[32m 22\u001b[39m \n\u001b[32m 23\u001b[39m \u001b[33;03mArgs:\u001b[39;00m\n\u001b[32m (...)\u001b[39m\u001b[32m 27\u001b[39m \u001b[33;03m Dictionary mapping asset names to (x, y, theta) tuples\u001b[39;00m\n\u001b[32m 28\u001b[39m \u001b[33;03m\"\"\"\u001b[39;00m\n\u001b[32m 29\u001b[39m \u001b[38;5;66;03m# 1. Initialize positions\u001b[39;00m\n\u001b[32m---> \u001b[39m\u001b[32m30\u001b[39m positions = \u001b[38;5;28;43mself\u001b[39;49m\u001b[43m.\u001b[49m\u001b[43m_initialize_positions\u001b[49m\u001b[43m(\u001b[49m\u001b[43massets\u001b[49m\u001b[43m)\u001b[49m\n\u001b[32m 31\u001b[39m positions.requires_grad = \u001b[38;5;28;01mTrue\u001b[39;00m\n\u001b[32m 33\u001b[39m \u001b[38;5;66;03m# 2. Setup optimizer\u001b[39;00m\n", + "\u001b[36mCell\u001b[39m\u001b[36m \u001b[39m\u001b[32mIn[4]\u001b[39m\u001b[32m, line 83\u001b[39m, in \u001b[36mRelationSolver2D._initialize_positions\u001b[39m\u001b[34m(self, assets)\u001b[39m\n\u001b[32m 81\u001b[39m positions[i][:\u001b[32m2\u001b[39m] = positions[parent_idx][:\u001b[32m2\u001b[39m]\n\u001b[32m 82\u001b[39m \u001b[38;5;28;01melif\u001b[39;00m \u001b[38;5;28misinstance\u001b[39m(relation, NextTo):\n\u001b[32m---> \u001b[39m\u001b[32m83\u001b[39m parent_idx = \u001b[43masset_dict\u001b[49m\u001b[43m[\u001b[49m\u001b[43mrelation\u001b[49m\u001b[43m.\u001b[49m\u001b[43mparent\u001b[49m\u001b[43m.\u001b[49m\u001b[43mname\u001b[49m\u001b[43m]\u001b[49m[\u001b[32m0\u001b[39m]\n\u001b[32m 84\u001b[39m parent_pos = positions[parent_idx]\n\u001b[32m 85\u001b[39m target = relation._compute_target_position(\n\u001b[32m 86\u001b[39m parent_pos, relation.parent, asset\n\u001b[32m 87\u001b[39m )\n", + "\u001b[31mKeyError\u001b[39m: 'microwave'" + ] + } + ], + "source": [ + "# Create assets\n", + "microwave = MockAsset2D(\"microwave\", width=0.8, length=0.6)\n", + "cracker_box = MockAsset2D(\"cracker_box\", width=0.2, length=0.3)\n", + "apple = MockAsset2D(\"apple\", width=0.1, length=0.1)\n", + "banana = MockAsset2D(\"banana\", width=0.15, length=0.08)\n", + "\n", + "# Define relations - nested NextTo relations forming a layout\n", + "# microwave is the root object at origin\n", + "cracker_box.add_relation(NextTo(microwave, side=\"right\"))\n", + "apple.add_relation(NextTo(cracker_box, side=\"right\"))\n", + "banana.add_relation(NextTo(microwave, side=\"front\"))\n", + "\n", + "# Solve\n", + "optimizing_assets_list = [cracker_box, apple, banana]\n", + "full_assets_list = [microwave, cracker_box, apple, banana]\n", + "solver = RelationSolver2D()\n", + "positions = solver.solve(optimizing_assets_list)\n", + "\n", + "print(\"\\nFinal positions:\")\n", + "for name, pos in positions.items():\n", + " if not name.startswith('_'):\n", + " print(f\" {name}: x={pos[0]:.3f}, y={pos[1]:.3f}, theta={pos[2]:.3f}\")\n", + "\n", + "# Visualize\n", + "full_assets_dict = {a.name: a for a in full_assets_list}\n", + "visualize_scene(positions, full_assets_dict, title=\"Example 2: Complex Layout with Nested Relations\")\n", + "plot_loss_history(positions)\n" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "#### Iteration Visualization with GIF Export\n", + "\n", + "Let's visualize how positions evolve during optimization with both `On()` and `NextTo()` relations.\n" + ] + }, + { + "cell_type": "code", + "execution_count": 65, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Captured 40 snapshots during optimization\n" + ] + }, + { + "data": { + "image/png": "iVBORw0KGgoAAAANSUhEUgAABv0AAAPeCAYAAAAvUNa6AAAAOnRFWHRTb2Z0d2FyZQBNYXRwbG90bGliIHZlcnNpb24zLjEwLjMsIGh0dHBzOi8vbWF0cGxvdGxpYi5vcmcvZiW1igAAAAlwSFlzAAAPYQAAD2EBqD+naQABAABJREFUeJzs3XdYU2f/BvA7YW+QKUrdVnEPrFtUFHHgnn1ddYt1tXb8+lZr3y5trW0V927VOqvWCVrraB04qHXWgThQAQHZM+f3R5oDkRUkyUnC/bkuLh+Sk5P7QEwO+eb5PjJBEAQQERERERERERERERERkdGSSx2AiIiIiIiIiIiIiIiIiMqHRT8iIiIiIiIiIiIiIiIiI8eiHxEREREREREREREREZGRY9GPiIiIiIiIiIiIiIiIyMix6EdERERERERERERERERk5Fj0IyIiIiIiIiIiIiIiIjJyLPoRERERERERERERERERGTkW/YiIiIiIiIiIiIiIiIiMHIt+REREREREREREREREREaORT8iIh37/fffIZPJ8Pvvv0sdhYiIyOTo6nVWJpPhk08+0eo+TVHPnj0xYcIEqWNUSGV57N+/fx8ymQwbNmzQaabq1atjzJgxOr2Pw4cPw97eHnFxcTq9HyIibeD5RPksXLgQ9erVg0KhkDpKqTZs2ACZTIb79++X+bZjxoxB9erVDSYPka7o6nHZunVrvPfee1rdpzFj0Y+ITJJMJtPoS5M3Sb744gvs2bNH55lVL3wXLlzQ+X0RERFJQfVap/oyNzdHlSpVMGbMGDx+/FjveQ4ePGhwb8R98sknkMlkiI+PlzpKqf744w+EhYXh/fffFy9TFaJkMhkuXrxY6DZjxoyBvb29TnMVde6mzXNDQ7ZlyxZ89913UsfQqR49eqB27dr48ssvpY5CRDr28nmDTCaDh4cHOnfujEOHDkkdzyipXqd37twpdZRSJScnY8GCBXj//fchl6u/hZ2Wlob//e9/aNy4MWxtbeHk5IQOHTpg06ZNEARBosTS0Nd7VlKSyWSYNm1akdeV9l7ae++9B5lMhqFDhxZ5veqDUaovuVyOSpUqISgoCGfOnCm0vepcXfVla2uL1157DX369MH69euRlZX16gdqIAz1MXX9+nV88sknRRYM33//fYSGhuLp06f6D2aAzKUOQESkCz/++KPa95s2bUJ4eHihy+vXr1/qvr744gsMGjQI/fr102ZEIiKiCuvTTz9FjRo1kJmZibNnz2LDhg04ffo0rl69Cmtra73lOHjwIEJDQ4ss/GVkZMDcnH8uleTrr79G165dUbt27SKv/+STT/Drr7/qOVXR527aPDc0FB07dkRGRgYsLS3Fy7Zs2YKrV69i5syZattWq1YNGRkZsLCw0GmmW7duFXpjVhcmTZqEd999F/Pnz4eDg4PO74+IpKU6bxAEAc+ePcOGDRvQs2dP/Prrr+jdu7fU8UhH1q1bh9zcXAwfPlzt8mfPnqFr1664ceMGhg0bhmnTpiEzMxO7du3C6NGjcfDgQWzevBlmZmZ6zTty5EgMGzYMVlZWer3f4t6zkiqPIREEAVu3bkX16tXx66+/IiUlpdjzhuHDh6Nnz57Iy8vDP//8g2XLlqFz586IiIhAo0aNCm2/fPly2NvbIysrC48fP8aRI0fw1ltv4bvvvsP+/fvh4+Oj68PTGV2+D1qex+X169cxf/58+Pv7F5oZ27dvXzg6OmLZsmX49NNPtZTWePGvWCIySf/5z3/Uvj979izCw8MLXU5ERET6FxQUhJYtWwIAxo8fDzc3NyxYsAD79u3DkCFDJE6npM/iozGKjY3FgQMHsGLFiiKvb9q0Kfbv349Lly6hefPmek5XmCmeG8rlco0fpzKZTC+PaX29sThw4EC8/fbb2LFjB9566y293CcRSafgeQMAjBs3Dp6enti6dWuFKvqlpaXBzs5O6hh6s379egQHBxd6/Ro9ejRu3LiBX375BcHBweLl06dPx5w5c/DNN9+gWbNmap0I9MHMzEzvhcaSGFoeKfz+++949OgRfvvtNwQGBmL37t0YPXp0kds2b95c7bywQ4cOCAoKwvLly7Fs2bJC2w8aNAhubm7i93PnzsXmzZsxatQoDB48GGfPntX+ARmgsj4v6epxKZfLMWjQIGzatAnz58+HTCbT+n0YE7b3JKIKKy0tDe+88w58fHxgZWWF119/Hd98841aKwiZTIa0tDRs3LhRnLqvWqckOjoaU6dOxeuvvw4bGxu4urpi8ODBOu+XfvnyZQQFBcHR0RH29vbo2rVroZOJnJwczJ8/H3Xq1IG1tTVcXV3Rvn17hIeHi9s8ffoUY8eORdWqVWFlZYXKlSujb9++7PdORER616FDBwDA3bt31S6/efMmBg0ahEqVKsHa2hotW7bEvn37St3fqVOnMHjwYLz22muwsrKCj48PZs2ahYyMDHGbMWPGIDQ0FIB660eVotbg0eQ1WNVi6I8//sDs2bPh7u4OOzs79O/fX6trkP3222/o0KED7Ozs4OzsjL59++LGjRtq26SkpGDmzJmoXr06rKys4OHhgW7duuHSpUviNrdv38bAgQPh5eUFa2trVK1aFcOGDcOLFy9KvP8DBw4gNzcXAQEBRV7/9ttvw8XFReP2qYcOHRKPx8HBAb169cK1a9fUjlcul2Pu3Llqt9uyZQtkMhmWL18OoORzt9Jocm5YHH9/fzRs2BAXL15E27ZtYWNjgxo1ahRZFI2NjRXfsLa2tkaTJk2wcePGQtv9/PPPaNGiBRwcHODo6IhGjRrh+++/F69/eU0/f39/HDhwANHR0eKxqz4FXdyafpo8jlRtrO7cuYMxY8bA2dkZTk5OGDt2LNLT09W2fXlNv7L8f1AoFPjkk0/g7e0NW1tbdO7cGdevXy9ynUAPDw80btwYe/fuLerXQUQmztnZGTY2NoVm5GvyPF7SGqcvv/aX5fkvKysLs2bNgru7OxwcHBAcHIxHjx4Vug9N30dQPX+eOHECU6dOhYeHB6pWrYrjx49DJpPhl19+KbRv1WtiUS0Jy+revXsYPHgwKlWqBFtbW7Ru3RoHDhwotN2SJUvQoEED2NrawsXFBS1btsSWLVvE6zU5FylKVFQUrly5Uug84+zZszhy5AjGjBmjVvBT+fLLL1GnTh0sWLBAPO9T/c6/+eYbrFq1CrVq1YKVlRX8/PwQERFRYo4LFy5AJpMV+Tp95MgRyGQy7N+/H0Dxa5UtW7YMDRo0gJWVFby9vRESEoKkpKQS7xcAvvnmG7Rt2xaurq6wsbFBixYtCrVlLem8pzx5VOc1169fR+fOnWFra4sqVapg4cKFhXKW9hiQ0ubNm+Hr64vOnTsjICAAmzdv1vi2xf19UpI333wT48ePx7lz59TefyvO48ePMW7cOHh7e8PKygo1atTAlClTkJ2dLW6jyf9F1Tnh9u3b8fnnn6Nq1aqwtrZG165dcefOHbVtSzv3L+kxpXpOvH79OkaMGAEXFxe0b98eAHDlyhWMGTMGNWvWhLW1Nby8vPDWW2/h+fPnavdf1OOyevXq6N27N06fPo1WrVrB2toaNWvWxKZNm9RuN3jwYABA586di2zN361bN0RHRyMyMrLUn72p40w/IqqQBEFAcHAwjh8/jnHjxqFp06Y4cuQI5syZg8ePH2Px4sUAlK2gxo8fj1atWmHixIkAgFq1agEAIiIi8Oeff2LYsGGoWrUq7t+/j+XLl8Pf3x/Xr1+Hra2t1nNfu3YNHTp0gKOjI9577z1YWFhg5cqV8Pf3x4kTJ/DGG28AUL4Qf/nll2L25ORkXLhwAZcuXUK3bt0AKD8hfe3aNbz99tuoXr06YmNjER4ejgcPHmh9AWkiIqKSqP7oc3FxES+7du0a2rVrhypVquCDDz6AnZ0dtm/fjn79+mHXrl3o379/sfvbsWMH0tPTMWXKFLi6uuL8+fNYsmQJHj16hB07dgBQtgeMiYkpssVjUTR9DVZRFb3mzZuH+/fv47vvvsO0adOwbdu2V/gJqTt69CiCgoJQs2ZNfPLJJ8jIyMCSJUvQrl07XLp0SXwdnzx5Mnbu3Ilp06bB19cXz58/x+nTp3Hjxg00b94c2dnZCAwMRFZWFt5++214eXnh8ePH2L9/P5KSkuDk5FRshj///BOurq6oVq1akdc7Ojpi1qxZmDt3bqmz/X788UeMHj0agYGBWLBgAdLT07F8+XK0b98ely9fRvXq1dGlSxdMnToVX375Jfr164fmzZvjyZMnePvttxEQEIDJkyeL+yru3K0kmp4bliQxMRE9e/bEkCFDMHz4cGzfvh1TpkyBpaWlOBstIyMD/v7+uHPnDqZNm4YaNWpgx44dGDNmDJKSkjBjxgwAQHh4OIYPH46uXbtiwYIFAIAbN27gjz/+ELd52UcffYQXL17g0aNHYt6S1k/U9HGkMmTIENSoUQNffvklLl26hDVr1sDDw0PMVxJN/j98+OGHWLhwIfr06YPAwED89ddfCAwMRGZmZpH7bNGihUGuN0NE2vfixQvEx8dDEATExsZiyZIlSE1NVZuVo43n8eJo8vw3fvx4/PTTTxgxYgTatm2L3377Db169Sq0r7K+jzB16lS4u7tj7ty5SEtLg7+/P3x8fLB58+ZC50KbN29GrVq10KZNm1c+VkDZPrNt27ZIT0/H9OnT4erqio0bNyI4OBg7d+4U73f16tWYPn06Bg0ahBkzZiAzMxNXrlzBuXPnMGLECACln4sU588//wSAQtuo2oaPGjWqyNuZm5tjxIgRmD9/Pv744w+1ouGWLVuQkpKCSZMmQSaTYeHChRgwYADu3btXbPvrli1bombNmti+fXuhGWLbtm2Di4sLAgMDiz2OTz75BPPnz0dAQACmTJmCW7duYfny5YiIiMAff/xRYtvt77//HsHBwXjzzTeRnZ2Nn3/+GYMHD8b+/fvFx1ZZz3vKkicxMRE9evTAgAEDMGTIEOzcuRPvv/8+GjVqhKCgIACaPQa0JTMzs8g1r1NTU4vcPisrC7t27cI777wDQNm+c+zYsXj69Cm8vLxKvb+i/j7RxMiRI7Fq1SqEhYWJ778VJSYmBq1atUJSUhImTpyIevXq4fHjx9i5cyfS09NhaWmp8f9Fla+++gpyuRzvvvsuXrx4gYULF+LNN9/EuXPnAECjc39NHlODBw9GnTp18MUXX4gfqggPD8e9e/cwduxYeHl54dq1a1i1ahWuXbuGs2fPljrz7s6dOxg0aBDGjRuH0aNHY926dRgzZgxatGiBBg0aoGPHjpg+fTp++OEH/N///Z/Ykr9ga/4WLVoAUK473qxZM01+XaZLICKqAEJCQoSCT3l79uwRAAifffaZ2naDBg0SZDKZcOfOHfEyOzs7YfTo0YX2mZ6eXuiyM2fOCACETZs2iZcdP35cACAcP368xIzr168XAAgRERHFbtOvXz/B0tJSuHv3rnhZTEyM4ODgIHTs2FG8rEmTJkKvXr2K3U9iYqIAQPj6669LzERERKRNqte6o0ePCnFxccLDhw+FnTt3Cu7u7oKVlZXw8OFDcduuXbsKjRo1EjIzM8XLFAqF0LZtW6FOnTriZUW9zhb1Gv3ll18KMplMiI6OFi97+fygIADCvHnzxO81fQ1WHWNAQICgUCjEy2fNmiWYmZkJSUlJJf6M5s2bJwAQ4uLiit2madOmgoeHh/D8+XPxsr/++kuQy+XCqFGjxMucnJyEkJCQYvdz+fJlAYCwY8eOEjMVpX379kKLFi0KXa76fezYsUNISkoSXFxchODgYPH60aNHC3Z2duL3KSkpgrOzszBhwgS1/Tx9+lRwcnJSuzwtLU2oXbu20KBBAyEzM1Po1auX4OjoqPY7FYTiz90KKs+5YVE6deokABAWLVokXpaVlSX+rrKzswVBEITvvvtOACD89NNP4nbZ2dlCmzZtBHt7eyE5OVkQBEGYMWOG4OjoKOTm5hZ7n0U99nv16iVUq1at0LZRUVECAGH9+vXiZZo+jlSPybfeekttn/379xdcXV3VLqtWrZraz17T/w9Pnz4VzM3NhX79+qnt75NPPhEAFPn7/OKLLwQAwrNnzwpdR0SmQfUc8vKXlZWVsGHDBrVtNX0eL+r5UOXl135Nn/8iIyMFAMLUqVPVthsxYkShfWr6PoLq2Nu3b1/oteDDDz8UrKys1M4pYmNjBXNzc7X7KkrB1+nizJw5UwAgnDp1SrwsJSVFqFGjhlC9enUhLy9PEARB6Nu3r9CgQYMS76+0c5Hi/Pe//xUACCkpKWqX9+vXTwAgJCYmFnvb3bt3CwCEH374QRCE/N+5q6urkJCQIG63d+9eAYDw66+/lpjlww8/FCwsLNRum5WVJTg7O6s9NlS/s6ioKEEQlL8TS0tLoXv37uLPTBAEYenSpQIAYd26deJlo0ePLvT6/fJjJTs7W2jYsKHQpUsXtcuLO+8pTx7VeU3Bx2RWVpbg5eUlDBw4ULxMk8eANhT1PPDy18vvpe3cuVMAINy+fVsQBEFITk4WrK2thcWLF6ttp3p8zJ8/X4iLixOePn0qnDp1SvDz8yvy/0pp5+qq99v69+9f4jGNGjVKkMvlRb4HqDpn0vT/our/df369YWsrCxx2++//14AIPz999+CIGh+7l/cY0p17MOHDy90XVHPbVu3bhUACCdPnhQve/lxKQjK88eXt4uNjRWsrKyEd955R7xsx44dpb6/amlpKUyZMqXE46sI2N6TiCqkgwcPwszMDNOnT1e7/J133oEgCDh06FCp+7CxsRHHOTk5eP78OWrXrg1nZ+dSW1W8iry8PISFhaFfv36oWbOmeHnlypUxYsQInD59GsnJyQCU7U6uXbuG27dvF5vd0tISv//+OxITE7WelYiIqCQBAQFwd3eHj48PBg0aBDs7O+zbtw9Vq1YFACQkJOC3337DkCFDkJKSgvj4eMTHx+P58+cIDAzE7du38fjx42L3X/A1Oi0tDfHx8Wjbti0EQcDly5fLnLcsr8EqEydOVPtEa4cOHZCXl4fo6Ogy339BT548QWRkJMaMGYNKlSqJlzdu3BjdunXDwYMHxcucnZ1x7tw5xMTEFLkv1Uy+I0eOFGpTVprnz5+X+slnJycnzJw5E/v27Sv25x4eHo6kpCQMHz5c/D3Hx8fDzMwMb7zxBo4fPy5ua2triw0bNuDGjRvo2LEjDhw4gMWLF+O1114rU/aiaOPc0NzcHJMmTRK/t7S0xKRJkxAbG4uLFy+K9+Pl5YXhw4eL21lYWGD69OlITU3FiRMnACh/d2lpaRq1hnoVZXkcqahmU6p06NABz58/L/TYL0pp/x+OHTuG3NxcTJ06Ve12b7/9drH7VD3+ivrUPxGZltDQUISHhyM8PBw//fQTOnfujPHjx2P37t3iNtp4Hi9Oac9/qufMl+975syZhfZV1vcRJkyYUGj9q1GjRiErK0ut1eO2bduQm5urlbVqDx48iFatWolt+wDlzPGJEyfi/v37uH79OgDla9WjR49KbJFZ2rlIcZ4/fw5zc/NCM9ZTUlIAAA4ODsXeVnXdy69PQ4cOVTt3UbVvvHfvXolZhg4dipycHLXHW1hYGJKSkjB06NBib3f06FFkZ2dj5syZkMvz34KfMGECHB0di2yXWlDBx0piYiJevHiBDh06vPL7TWXNY29vr/Z4srS0RKtWrdR+Xpo8BrSlb9++4vNAwa85c+YUuf3mzZvRsmVL1K5dGwDE9vHFtficN28e3N3d4eXlhQ4dOuDGjRtYtGgRBg0aVKacqses6rFaFIVCgT179qBPnz5q65WqqM6ZNP2/qDJ27FhYWlqK37/8GC/PuX9BLz8nAuqPV9WszNatWwOARo9ZX19fMS8AuLu74/XXXy/1/+fLXFxceG4IrulHRBVUdHQ0vL29C50oqqaFa/KGXEZGBubOnSuuF+Dm5gZ3d3ckJSWVug7Oq4iLi0N6ejpef/31QtfVr18fCoUCDx8+BAB8+umnSEpKQt26ddGoUSPMmTMHV65cEbe3srLCggULcOjQIXh6eqJjx45YuHAhnj59qvXcREREL1O9ebdz50707NkT8fHxsLKyEq+/c+cOBEHAxx9/DHd3d7WvefPmAVCui1acBw8eiMUMe3t7uLu7o1OnTgDwSq/RZXkNVnm5EKV6k6m8H7ZRnaMUlyU+Ph5paWkAgIULF+Lq1avw8fFBq1at8Mknn6j94VyjRg3Mnj0ba9asgZubGwIDAxEaGqrxz0jQYK27GTNmwNnZudi1/VQfUOrSpUuh33VYWFih33O7du0wZcoUnD9/HoGBgWLbzPLSxrmht7c37Ozs1C6rW7cugPwWUdHR0ahTp47am21F3c/UqVNRt25dBAUFoWrVqnjrrbdw+PDhsh9YMcryOFIpz2O6tNuq8qjemFOpVKlSscVl1eOvtHZRRGT8WrVqhYCAAAQEBODNN9/EgQMH4Ovri2nTpolrX2njebw4mjyHyeXyQi3winqOLev7CDVq1Ch0Wb169eDn56dWvNi8eTNat25d6Hn0VURHRxf7+qC6HgDef/992Nvbo1WrVqhTpw5CQkLwxx9/qN2mtHORslL9fksqqBRXGHzV17EmTZqgXr16ai2pt23bBjc3N3Tp0qXY2xX3WmtpaYmaNWuW+pjcv38/WrduDWtra1SqVAnu7u5Yvnz5K7/fVNY8VatWLfQa6+Liovbz0uQxUJSnT5+qfRVcd7s4VatWFZ8HCn75+voW2jYpKQkHDx5Ep06dcOfOHfGrXbt2uHDhAv75559Ct5k4cSLCw8Px66+/imuB5+XllZrrZap2oyUVpuPi4pCcnIyGDRuWuC9N/y+qlPYYL++5v0pRz0sJCQmYMWMGPD09YWNjA3d3d3E7TfZf1If4Xn68aUIQBJ4bgkU/IqJX9vbbb+Pzzz/HkCFDsH37doSFhSE8PByurq5QKBSSZuvYsSPu3r2LdevWoWHDhlizZg2aN2+ONWvWiNvMnDkT//zzD7788ktYW1vj448/Rv369V9pBgQREVFZqN68GzhwIPbt24eGDRtixIgR4h/JqtfRd999t8hP9IaHhxf7plZeXh66deuGAwcO4P3338eePXsQHh6ODRs2qO1b117+VL6KJoUybRkyZAju3buHJUuWwNvbG19//TUaNGigNtth0aJFuHLlCv7v//4PGRkZmD59Oho0aIBHjx6VuG9XV1eN/ggvbbaf6vfx448/Fvl73rt3r9r2WVlZ+P333wEAd+/eLdenlA2Zh4cHIiMjsW/fPnGNqqCgoELrCelTeR7Tuvj/oHr8ubm5vfI+iMg4yeVydO7cGU+ePCm2u01xinszuKQ397X5HFbW9xEKzp4paNSoUThx4gQePXqEu3fv4uzZs1qZ5VcW9evXx61bt/Dzzz+jffv22LVrF9q3by9+QAvQ7FykKK6ursjNzS1U3FMVOwp+qPllquteLgaV5/c4dOhQHD9+HPHx8cjKysK+ffswcOBAmJubl3rbV3Hq1CkEBwfD2toay5Ytw8GDBxEeHo4RI0bo7VxSk5+XJo+BolSuXFntSxtrXhe0Y8cOZGVlYdGiRahTp474NXv2bAAocrZfnTp1EBAQgN69e+Pbb7/FrFmz8MEHH+DChQtluu+rV68CKPxBJn3Q5Hf2quf+BRX1vDRkyBCsXr0akydPxu7duxEWFiZ+YE2Tv7+09TyblJTEc0Ow6EdEFVS1atUQExNT6ATy5s2b4vUqxf1RsHPnTowePVqc7t+tWze0b98eSUlJOsns7u4OW1tb3Lp1q9B1N2/ehFwuh4+Pj3hZpUqVMHbsWGzduhUPHz5E48aNC33KvlatWnjnnXcQFhaGq1evIjs7G4sWLdJJfiIioqKYmZnhyy+/RExMDJYuXQoAYgtNCwuLIj/RGxAQUOynZ//++2/8888/WLRoEd5//3307dsXAQEB8Pb2LrStpp8CLetrsC6pzlGKy+Lm5qY226xy5cqYOnUq9uzZg6ioKLi6uuLzzz9Xu12jRo3w3//+FydPnsSpU6fw+PFjrFixosQc9erVQ1RUlEaZZ86cCWdnZ8yfP7/QdapZER4eHkX+nv39/dW2nzdvHm7cuIFvvvkGUVFR+OCDDwrt81U+3VuWc8PixMTEFJodp/okefXq1cX93L59u9CbH0Xdj6WlJfr06YNly5bh7t27mDRpEjZt2oQ7d+4Um0HTYy/r40jXVHlePrbnz58XW1yOiooSZ8gQUcWTm5sLIH9WjabP46qZLy//3V6emYDVqlWDQqHA3bt31S4v6jlWW+8jDBs2DGZmZti6dSs2b94MCwuLEltNlkW1atWKfX1QXa9iZ2eHoUOHYv369Xjw4AF69eqFzz//HJmZmeI2mpyLvKxevXoAUOhco3fv3gCATZs2FXm7vLw8bNmyBS4uLmjXrp0GR6uZoUOHIjc3F7t27cKhQ4eQnJyMYcOGlXib4l5rs7OzERUVVeK5xa5du2BtbY0jR47grbfeQlBQEAICAorctryv/ZrkKYkmj4GXvfwhr8DAwFe67+Js3rwZDRs2xI4dOwp9BQQEYMuWLaXu46OPPoKDgwP++9//lum+f/zxRwAo8Zjc3d3h6OgoFgiLU5b/i2VR2rl/Wc+lExMTcezYMXzwwQeYP38++vfvj27duqkti6ANpeV6/PgxsrOzxQ8HVGQs+hFRhdSzZ0/k5eWJby6qLF68GDKZDEFBQeJldnZ2RZ6Am5mZFfrEyZIlS15p+r8mzMzM0L17d+zdu1dsEQUAz549w5YtW9C+fXs4OjoCUL5BUpC9vT1q166NrKwsAEB6enqhE7BatWrBwcFB3IaIiEhf/P390apVK3z33XfIzMyEh4cH/P39sXLlSjx58qTQ9nFxccXuS/Up0YKv0YIg4Pvvvy+0raqoUdobbWV5Dda1ypUro2nTpti4caNa7qtXryIsLAw9e/YEoHzT6+VWOh4eHvD29hZf65OTk8U3TVUaNWoEuVxe6vlAmzZtkJiYqFGLLtVsv7179yIyMlLtusDAQDg6OuKLL75ATk5OodsW/F2fO3cO33zzDWbOnIl33nkHc+bMwdKlS8V18FSKO3crSVnODYuTm5uLlStXit9nZ2dj5cqVcHd3R4sWLcT7efr0qdon2nNzc7FkyRLY29uLbWhfPpeTy+Vo3LgxAJT4u7Gzs9OohZKmjyN96dq1K8zNzbF8+XK1y1/+fRR08eJFtGnTRtfRiMgA5eTkICwsDJaWluKbu5o+jzs6OsLNzQ0nT55U227ZsmWvnEe17x9++EHt8u+++67Qttp6H8HNzQ1BQUH46aefsHnzZvTo0UNrs1t69uyJ8+fP48yZM+JlaWlpWLVqFapXry7OoHv5tcrS0hK+vr4QBAE5OTkanYsUR/X8/vIsq7Zt2yIgIADr16/H/v37C93uo48+wj///IP33nuv2FmSr6J+/fpo1KgRtm3bhm3btqFy5cro2LFjibcJCAiApaUlfvjhB7Xf+dq1a/HixQv06tWr2NuamZlBJpOpPS7u37+PPXv2FNpW0/Oe8uQpTmmPgZKyFPyqXLlyme+7OA8fPsTJkycxZMgQDBo0qNDX2LFjcefOHZw7d67E/Tg7O2PSpEk4cuRIofPX4mzZsgVr1qxBmzZt0LVr12K3k8vl6NevH3799dciZxKqfj+a/l/UlKbn/mU9ly7q7y+g6OfA8ijtbzfVGtpt27bV6v0aI93MQSYiMnB9+vRB586d8dFHH+H+/fto0qQJwsLCsHfvXsycOVOtF3+LFi1w9OhRfPvtt/D29kaNGjXwxhtvoHfv3vjxxx/h5OQEX19fnDlzBkePHoWrq2u5sq1bt67INVtmzJiBzz77DOHh4Wjfvj2mTp0Kc3NzrFy5EllZWVi4cKG4ra+vL/z9/dGiRQtUqlQJFy5cwM6dOzFt2jQAyk+dd+3aFUOGDIGvry/Mzc3xyy+/4NmzZ6V+Wo2IiEgX5syZg8GDB2PDhg2YPHkyQkND0b59ezRq1AgTJkxAzZo18ezZM5w5cwaPHj3CX3/9VeR+6tWrh1q1auHdd9/F48eP4ejoiF27dhU5W0hViJk+fToCAwNhZmZW7Ougpq/B2vLtt9/C1tZW7TK5XI7/+7//w9dff42goCC0adMG48aNQ0ZGBpYsWQInJydxVn9KSgqqVq2KQYMGoUmTJrC3t8fRo0cREREhzur/7bffMG3aNAwePBh169ZFbm4ufvzxR5iZmWHgwIEl5uvVqxfMzc1x9OhRTJw4sdTjmTFjBhYvXoy//vpLbQaZo6Mjli9fjpEjR6J58+YYNmwY3N3d8eDBAxw4cADt2rXD0qVLkZmZidGjR6NOnTri7ID58+fj119/xdixY/H333+L+y3u3K0kZTk3LI63tzcWLFiA+/fvo27duti2bRsiIyOxatUqWFhYAFCuF7Ny5UqMGTMGFy9eRPXq1bFz50788ccf+O6778QZrOPHj0dCQgK6dOmCqlWrIjo6GkuWLEHTpk1L/PRyixYtsG3bNsyePRt+fn6wt7dHnz59itxWk8eRvnh6emLGjBlYtGgRgoOD0aNHD/z11184dOgQ3NzcCn2yOzY2FleuXEFISIhecxKRNA4dOiTObImNjcWWLVtw+/ZtfPDBB+KHbsryPD5+/Hh89dVXGD9+PFq2bImTJ08WucaXppo2bYrhw4dj2bJlePHiBdq2bYtjx44VOTNbm+8jjBo1CoMGDQIA/O9//yvTbXft2iX+TAsaPXo0PvjgA2zduhVBQUGYPn06KlWqhI0bNyIqKgq7du0S16Xt3r07vLy80K5dO3h6euLGjRtYunQpevXqBQcHByQlJZV6LlKcmjVromHDhjh69Gih9Xs3bdqErl27om/fvhgxYgQ6dOiArKws7N69G7///juGDh2KOXPmlOnnoYmhQ4di7ty5sLa2xrhx4wqtz/syd3d3fPjhh5g/fz569OiB4OBg3Lp1C8uWLYOfn1+J7Vh79eqFb7/9Fj169MCIESMQGxuL0NBQ1K5du1BrU03Pe8qTpzilPQaksGXLFgiCgODg4CKv79mzJ8zNzbF58+ZSzw9nzJiB7777Dl999RV+/vlntet27twJe3t7ZGdn4/Hjxzhy5Aj++OMPNGnSBDt27Cg15xdffIGwsDB06tQJEydORP369fHkyRPs2LEDp0+fhrOzs8b/FzWl6bl/Wc+lHR0d0bFjRyxcuBA5OTmoUqUKwsLCNO4KoqmmTZvCzMwMCxYswIsXL2BlZYUuXbrAw8MDgHIG6WuvvYZmzZpp9X6NkkBEVAGEhIQILz/lpaSkCLNmzRK8vb0FCwsLoU6dOsLXX38tKBQKte1u3rwpdOzYUbCxsREACKNHjxYEQRASExOFsWPHCm5uboK9vb0QGBgo3Lx5U6hWrZq4jSAIwvHjxwUAwvHjx0vMuH79egFAsV8PHz4UBEEQLl26JAQGBgr29vaCra2t0LlzZ+HPP/9U29dnn30mtGrVSnB2dhZsbGyEevXqCZ9//rmQnZ0tCIIgxMfHCyEhIUK9evUEOzs7wcnJSXjjjTeE7du3v8JPl4iISDOq17qIiIhC1+Xl5Qm1atUSatWqJeTm5gqCIAh3794VRo0aJXh5eQkWFhZClSpVhN69ews7d+4Ub1fU6+z169eFgIAAwd7eXnBzcxMmTJgg/PXXXwIAYf369eJ2ubm5wttvvy24u7sLMplM7VwBgDBv3jy1jJq8Bhd3jJqeD8ybN6/YcwEzMzNxu6NHjwrt2rUTbGxsBEdHR6FPnz7C9evXxeuzsrKEOXPmCE2aNBEcHBwEOzs7oUmTJsKyZcvEbe7duye89dZbQq1atQRra2uhUqVKQufOnYWjR4+WmFElODhY6Nq1a5HHuWPHjmKPzc7OrtB1x48fFwIDAwUnJyfB2tpaqFWrljBmzBjhwoULgiAIwqxZswQzMzPh3Llzare7cOGCYG5uLkyZMkW8rLhzt4LKc25YlE6dOgkNGjQQLly4ILRp00awtrYWqlWrJixdurTQts+ePRPPIS0tLYVGjRqpPS4FQRB27twpdO/eXfDw8BAsLS2F1157TZg0aZLw5MkTtZ/Zy4+p1NRUYcSIEYKzs7MAQKhWrZogCIIQFRVV6PEvCKU/jgQh//cWFxendrnqsR4VFSVe9vJ5cFn+P+Tm5goff/yx4OXlJdjY2AhdunQRbty4Ibi6ugqTJ09Wu/3y5csFW1tbITk5udDPl4hMR1F/I1tbWwtNmzYVli9fXuj5WdPn8fT0dGHcuHGCk5OT4ODgIAwZMkSIjY0t9Npflue/jIwMYfr06YKrq6tgZ2cn9OnTR3j48GGhfWr6PkJJ50wqWVlZgouLi+Dk5CRkZGRo9DNVPf8W93Xq1ClBEJTnYIMGDRKcnZ0Fa2troVWrVsL+/fvV9rVy5UqhY8eOgqurq2BlZSXUqlVLmDNnjvDixQsxX2nnIiX59ttvBXt7eyE9Pb3QdSkpKcInn3wiNGjQQLCxsREcHByEdu3aCRs2bCj0+1a9Bn799deF9lPU+V5xbt++Lf6cTp8+Xej6oh4XgiAIS5cuFerVqydYWFgInp6ewpQpU4TExES1bUaPHi2+ZqusXbtWqFOnjmBlZSXUq1dPWL9+vfiYLKi4857y5FGd17zs5ZylPQa0BYAQEhJS5HUv/19p1KiR8Nprr5W4P39/f8HDw0PIyckp8fEhCIIwZswYwczMTLhz544gCIXP1a2trYWqVasKvXv3FtatWydkZmZqfFzR0dHCqFGjBHd3d8HKykqoWbOmEBISImRlZYnbaPJ/sbjz75fP/zQ99y/uMVXcc6IgCMKjR4+E/v37C87OzoKTk5MwePBgISYmptD/seLOH3v16lVon506dRI6deqkdtnq1auFmjVrCmZmZmrnknl5eULlypWF//73v0X9qCscmSDocSV5IiIiIiIiMgmnTp2Cv78/bt68iTp16kgdR1L+/v6Ij48vdW0WKpukpCS4uLjgs88+w0cffSRe3qxZM/j7+2Px4sUSpiMiklZubi68vb3Rp08frF27Vuo4WvfixQvUrFkTCxcuxLhx46SOQ0QGbM+ePRgxYgTu3r2r1Xaxxopr+hEREREREVGZdejQAd27d9dJe1OqeDIyMgpdploLxt/fX7zs8OHDuH37Nj788EM9JSMiMkx79uxBXFwcRo0aJXUUnXBycsJ7772Hr7/+GgqFQuo4RGTAFixYgGnTprHg9y/O9CMiIiIiIiIqB870K78NGzZgw4YN6NmzJ+zt7XH69Gls3boV3bt3x5EjR6SOR0RkMM6dO4crV67gf//7H9zc3HDp0iWpIxERkQExlzoAEREREREREVVsjRs3hrm5ORYuXIjk5GR4enpixowZ+Oyzz6SORkRkUJYvX46ffvoJTZs2xYYNG6SOQ0REBoYz/YiIiIiIiIiIiIiIiIiMHNf0IyIiIiIiIiIiIiIiIjJyLPoRERERERERERERERERGTmu6SchhUKBmJgYODg4QCaTSR2HiIiIdEgQBKSkpMDb2xtyOT93pQmeKxEREVUcPFd6NTxfIiIiqhg0PVdi0U9CMTEx8PHxkToGERER6dHDhw9RtWpVqWMYBZ4rERERVTw8Vyobni8RERFVLKWdK7HoJyEHBwcAyl+So6OjVvetUCgQFxcHd3d3k/6EHI/TtPA4TQuP0/RUlGPV1XEmJyfDx8dHfP2n0vFcSTsqyrHyOE0Lj9O08DhNC8+VDAvPl8qPx2laeJymhcdpWnic5aPpuRKLfhJStV1wdHTUyYlZZmYmHB0dTf4/EI/TdPA4TQuP0/RUlGPV9XGy7ZLmeK6kHRXlWHmcpoXHaVp4nKaF50qGhedL5cfjNC08TtPC4zQtPE7tKO1cyXR/skREREREREREREREREQVBIt+REREREREREREREREREaORT8iIiIiIiIiIiIiIiIiI8eiHxEREREREREREREREZGRY9GPiIiIiIiIiIiIiIiIyMix6EdERERERERERERERERk5Fj0IyIiIiIiIiIiIiIiIjJyLPoRERERERERERERERERGTkW/YiIiIiIiIiIiIiIiIiMHIt+REREREREREREREREREaORT8iIiIiIiIiIiIiIiIiI8eiHxEREREREREREREREZGRY9GPiIiIiIiIiIiIiIiIyMix6EdERERERERERERERERk5Fj0M1G3b9/GvHnzcP/+famjEBERERmchARg8WI7HD0qdRIiIiIiIiLdi0+Px29Rv+HBiwdSRyEiHTKXOgBp308//YSRI0cCAJydnbFgwQKJExEREREZjmvXgFatZEhPd8DZswK6d5c6ERERERERke58dfor/Pe3/yJPyINcJsekFpPwXY/vYGlmKXU0ItIyzvQzQQEBAbCwsAAArFu3DpmZmRInIiIiItJcaGgofH194efnp5P9168PvPaacnzypAznz+vkboiIiIiIiCQXej4UHx77EHlCHgBAISiw/MJyTD0wFYIgSJyOiLSNRT8T5OXlhQEDBgAA4uPjsWPHDokTEREREWkuJCQE169fR0REhE72L5cDs2bl/3H79dc6uRsiIiIiIiJJxabFYk74HPH7Zl7NYC5XNv9be3ktfrryk1TRiEhHWPQzUVOnThXHoaGhEiYhIiIiMjz/+Q/g7q78pOvu3cDduxIHIiIiIiIi0rJFfy5CRm4GAGByi8m4NOkSNvbbKF7/4bEPkZ6TLlU8ItIBFv1MVLt27eDr6wsAOHfuHC5evChxIiIiIiLDYW0NjBun/ONWoQC+/VbiQERERERERFqUmp2K0AjlZBArMyt83OljAMCIRiPQp24fAMDjlMdYcm6JZBmJSPtY9DNRMpkMY8aMEb/nbD8iIiIidaNHp8POTtnmc/16ID5e4kBERERERERacuj2IaTlpAEARjYeCW8Hb/G6BQELIJcpSwM/nP8BOXk5kmQkIu1j0c+EDRw4EE5OTgCArVu34vnz5xInIiIiIjIczs4Cxo1TjjMyAH5GioiIiIiITMXum7vF8bCGw9Suq+9eH8GvBwMAYlJisPvGbhCRaWDRz4TZ2tpi9OjRAIDMzExs2LBB2kBEREREBmbmTAFmZsrx0qVAOpezICIiIiIiI5eZm4n9/+wHAFSyqYSO1ToW2ubtVm+L42UXluktGxHpFot+Jm7KlCniePny5VAoFBKmISIiIjIs1aoBQ4Yox/HxwMaNJW9PRERERERk6E4/OI3U7FQAQJ+6fWBhZlFom87VO6OeWz0AwMnok4hOitZrRiLSDRb9TFzdunXRrVs3AMDdu3dx5MgRiRMRERERGZY5c/LHixYBeXnSZSEiIiIiIiqv0w9Oi+PutboXuY1MJsN/Gv1H/H7r1a06z0VEuseiXwUQEhIijkO5WA0RERGRmmbNgK5dleO7d4E9eySNQ0REREREVC5/PPxDHLf1aVvsdiMajRDHm//erNNMRKQfLPpVAL1798Zrr70GADh48CCioqIkTkRERERkWArO9vv6a0AQpMtCRERERET0qvIUeTj76CwAwNvBG9WcqhW7bQ2XGmhTtQ0A4GrsVdxNuKuXjESkOyz6VQBmZmaYNGkSAEAQBPz4448SJyIiIiIyLN27A40bK8fnzgGnT5e8PRERERERkSH6O/ZvcT2/dj7tIJPJSty+7+t9xfH+f/brNBsR6R6LfhIIDQ2Fr68v/Pz89Hafo0aNEp/gN23aBIEfXyciIiISyWTAu+/mf79okXRZiIiIiIiIXpVqlh9QcmtPld51e4vj/bdZ9CMydiz6SSAkJATXr19HRESE3u6zatWq6NKlCwDg7t27OHv2bCm3ICIiIqpYhg0DqlRRjvftA+7ckTYPERERmb7q1aujcePGaNq0KTp37ix1HCIyAX8/+1scN6/cvNTtfd19Ud25OgDgxP0TSM5K1lU0ItIDFv0qkJEjR4pjtvgkIiIiUmdhAUybphwLAvDDD9LmISIioorhzz//RGRkJI4fPy51FCIyAVfjrorjhh4NS91eJpOhT90+AIAcRQ7C7obpLBsR6R6LfhXIgAEDYGNjAwD4+eefkZWVJXEiIiIiIsMycSJga6scr1sHJCVJGoeIiIiIiEhjgiCIM/28HbxRyaaSRrdTa/HJdf2IjBqLfhWIg4MDBgwYAABITEzEwYMHJU5EREREZFgqVQJGj1aO09KANWukzUNERETSOXnyJPr06QNvb2/IZDLs2bOn0DahoaGoXr06rK2t8cYbb+D8+fNlug+ZTIZOnTrBz88Pmzdv1lJyIqqonqQ+QWJmIgCgkUcjjW/XqVon2FnYAQAO3j6IPEWeTvIRke6x6FfBFGzxuX37dgmTEBERERmmGTPyx0uWALm50mUhIiIi6aSlpaFJkyYIDQ0t8vpt27Zh9uzZmDdvHi5duoQmTZogMDAQsbGx4jZNmzZFw4YNC33FxMQAAE6fPo2LFy9i3759+OKLL3DlyhW9HBsRmaarsWVr7aliZW6F7rW6AwDi0uMQEROh9WxEpB/mUgcg/erSpQucnJzw4sULhIWFIS8vD2ZmZlLHIiIiIjIYr78O9OwJHDwIPHgA7N4NDBkidSoiIiLSt6CgIAQFBRV7/bfffosJEyZg7NixAIAVK1bgwIEDWLduHT744AMAQGRkZIn3UaVKFQBA5cqV0bNnT1y6dAmNGzcudvusrCy15VqSk5MBAAqFAgqFQqPj0pRCoYAgCFrfr6HhcZqWin6cqtaeAODr7lumn0NQ7SD8cvMXAED43XC08m6lnbDlUNF/n6aGx1n+/WqCRb8KxsLCAt26dcPOnTuRkJCA8+fPo02bNlLHIiIiIjIos2Ypi34AsHgxi35ERESkLjs7GxcvXsSHH34oXiaXyxEQEIAzZ85otI+0tDQoFAo4ODggNTUVv/32G4aUctLx5ZdfYv78+YUuj4uLQ2ZmZtkOohQKhQIvXryAIAiQy023WRiP07RU9OO89PCSOPY281abeVyapo5NxfHhfw5jwusTtJK1PCr679PU8DjLJyUlRaPtWPSrgIKCgrBz504AwKFDh1j0IyIiInpJ165Ao0bA338DZ88CERGAn5/UqYiIiMhQxMfHIy8vD56enmqXe3p64ubNmxrt49mzZ+jfvz8AIC8vDxMmTIBfKSccH374IWbPni1+n5ycDB8fH7i7u8PR0bGMR1EyhUIBmUwGd3d3k39zlsdpOir6cT7NfCqOW9VuBWdrZ4336eHhgRrONRCVFIULzy7AwcUBNhY22oxdZhX992lqeJzlY21trdF2LPpVQD169BDHhw4dwqeffiphGiIiIiLDI5MB06cDE/79cOuyZcD69dJmIiIiItNSs2ZN/PXXX2W6jZWVFaysrApdLpfLdfIGqkwm09m+DQmP07Ro+ziz87Lx05Wf4Gbrhj51+0Amk2llv+VV1HHeTbwLAHCxdkEl20pl3mfXGl2x5vIaZOdl48zjMwioGaC1vK+Kj1vTwuN8dZruy7R/slQkb29vNGnSBABw4cKFMk3zJiIiIqooRowAnJyU459/Bp4/lzYPERERGQ43NzeYmZnh2bNnapc/e/YMXl5eEqUiIm3LycvB4B2DMW7fOPT9uS96bO6B9Jx0qWMVKTsvGw+THwIAarrUfKV9dKnRRRz/FvWbVnIRkX6x6FdBFVyI+siRIxImISIiIjJMtrbA2LHKcWYmZ/oRERFRPktLS7Ro0QLHjh0TL1MoFDh27BiXUSEyIf87+T/su7VP/D7sbhgWnF4gYaLiPXjxAApBAQCoVanWK+2jYNHvWNSxErYkIkPFol8FVbDod+jQIQmTEBERERmuKVPyx8uXAwqFdFmIiIhIv1JTUxEZGYnIyEgAQFRUFCIjI/HgwQMAwOzZs7F69Wps3LgRN27cwJQpU5CWloaxqk8NEZFRy1PkYc2lNYUuD40INcjZfncT7orjms6vNtPP094TDT0aAgAuxFzAi8wXWslGRPrDol8F1aZNG3GB5yNHjiAvL0/iRERERESGp25doFs35fjePSAsTNo8REREpD8XLlxAs2bN0KxZMwDKIl+zZs0wd+5cAMDQoUPxzTffYO7cuWjatCkiIyNx+PBheHp66jxbaGgofH194efnp/P7IqqoTj84jSepTwAAwa8H481GbwIAnmc8x6a/NkkZrUj3Eu+J41dt7wkAXaorZ/spBAVORJ8ody4i0i8W/SooCwsLdPv3HayEhARERERInIiIiIjIME2dmj9etky6HERERKRf/v7+EASh0NeGDRvEbaZNm4bo6GhkZWXh3LlzeOONN/SSLSQkBNevX+f7OUQ6tP3adnE8tMFQzG4zW/z+l5u/SBGpRNoq+nWt2VUcH7vHFp9ExoZFvwqMLT6JiIiISte7N+Djoxzv3w/cvy9pHCIiIiIi0oNDd5Tvl1qZWaFP3T5o5tUMVR2rAgBORp9ERk6GlPEKuZeUX/R71TX9AKBTtU6Qy5Rlg+P3j5c7FxHpF4t+FViPHj3EMYt+REREZCgMrV2VuTkwaZJyLAjAypXS5iEiIiIiIt1KzEhEVFIUAKCld0s4WDlAJpMhsFYgACAzNxOnHpySMmIhD14o1xuVy+RicfJVOFk7oXnl5gCAv2P/RlxanFbyEZF+sOhXgVWpUgWNGzcGoOxTHxfHJ3AiIiKSniG2qxo3DrCwUI7XrAGysqTNQ0REREREunP56WVx3MyrmTjuXqu7OA67a1gLfj9OfgwA8LL3grncvFz76ly9szg+GX2yXPsiIv1i0a+CU7X4FAQBR44ckTgNERERkWHy8gIGDlSO4+OBHTukzUNERERERLpz6cklcaya9QYAXWvkr3d3IvqEXjOVJCcvB09TnwIAqjhUKff+/Kv7i2O2+CQyLiz6VXBc14+IiIhIMyEh+eNly6TLQUREREREulVc0c/V1hV1XesCAK48u4LsvGy9ZyvK09SnECAAAKo4lr/o1+G1DjCTmQFg0Y/I2LDoV8G1bdsWjo6OAIAjR44gLy9P4kREREREhqldO6BhQ+X4zBng2jVp8xAREVHFZWhrIBOZGlXRz9LMEr7uvmrXtajcAgCQnZeNa7GG8UfB45TH4lgbM/0crBzQ0rslAOB63HU8S31W7n0SkX6w6FfBWVhYICAgAADw/PlzXLhwQeJERERERIZJJgMmTsz/fvVq6bIQERFRxWaIayATmYqs3Cz88/wfAEBDj4awMLNQu15VDAOAi08u6jVbcVTr+QHaKfoB6uv6/X7/d63sk4h0j0U/UmvxyXX9iIiIiIr3n/8A1tbK8aZNQGamtHmIiIiIiEi7ol9Ei60y61SqU+h61Uw/ALgYYyBFvwIz/ao6VtXKPjvXyC/6scUnkfFg0Y8QGBgojg8fPixhEiIiIiLD5uICDB6sHCcmArt2SZuHiIiIiIi0KyoxShzXcK5R6PpmlZuJY0OZ6fco+ZE41saafgDQzqcdLOTKWY4s+hEZDxb9CD4+PvD1VfamPnfuHBITEyVORERERGS4JkzIH7PFJxERERGRaYlKKlD0cylc9HO0chRnAF6NvQqFoNBbtuJoe00/ALCztEOrKq0AAP88/wcxKTFa2S8R6RaLfgQA6NGjBwBAoVDg6NGjEqchIiIiMlzt2wP16inHJ04At25Jm4eIiIiIiLSntJl+AFDfvT4AICM3Aw9ePNBLrpKoremnpZl+gPq6fsejONuPyBiw6EcA2OKTiIiISFMymfpsvzVrpMtCRERERETaVdpMPwCo71ZfHN+Mv6nzTKVRzfRztHKEvaW91vbLdf2IjA+LfgQA6NixI2xsbAAAR44cgSAIEiciIiIiMlyjRgGWlsrxhg1AVpakcYiIiIiISEtURT8ZZHjN6bUit6nnVk8c34i7oZdcJXmW+gwAUNm+slb326ZqG1iaKf/wYdGPyDiw6EcAAGtra/j7+wMAHj9+jGvXrkkbiIiIiMiAubkBAwYox/HxwN690uYhIiKiiiU0NBS+vr7w8/OTOgqRybmfdB+Ask2mquD1MkOa6ZeRk4GU7BQAgIedh1b3bWNhg9ZVWwMA7iXeM4hWpkRUMhb9SMQWn0RERESaK9jic/Vq6XIQERFRxRMSEoLr168jIiJC6ihEJiU1OxXx6fEAil/PD3hppl+8tDP94tLjxLG7nbvW9891/YiMC4t+JOrRo4c4PnLkiIRJiIiIiAyfvz9Qu7ZyfPQocPeupHGIiIiIiKicopOixXF15+rFbudk7SS20pR6pl9cWn7Rz8NWuzP9gJeKfmzxSWTwWPQjUd26dVGtWjUAwMmTJ5GWliZxIiIiIiLDJZcD48fnf792rXRZiIiIiIio/J6mPhXH3g7eJW6rmu0Xlx6HhIwEneYqSWxarDjWdntPAGhdtTWsza0BAL/f/13r+yci7WLRj0QymUyc7ZednY0TJ05InIiIiIjIsI0ZA5ibK8fr1wM5OZLGISIiIiKicniW9kwce9p5lrhtLZda4jgqMUpnmUqj6/aeVuZWaOvTFgAQ/SIa9xLvaf0+iEh7WPQjNVzXj4iIiEhznp5A377K8dOnwP790uYhIiIiIqJX9yy1QNHPvuSiX02XmuJYykKYrmf6AUCX6l3E8ZE7XBaKyJCx6EdqunTpAvN/P67Ooh8RERFR6SZOzB+vXi1dDiIiIiIiKp+yzPQzlKJfwTX93G21P9MPAILqBInjA7cP6OQ+NCUIgqT3T2TozKUOQIbFyckJbdu2xcmTJ3H79m3cu3cPNWvWLP2GRERERBVUQABQrRoQHQ0cPgw8fAj4+EidioiIiIiIykqt6FeGmX5RSdK194xN1/1Mv2ZezVDZvjKepD7BsahjSM9Jh62FrU7uq6CcvBwcvn8YJ86eQERMBO4n3Ud6TjpcbV3h7eCNBu4NEFAzAN1rdUdVx6o6z0NkDDjTjwop2OLzyBFO1yYiIiIqiVwOjBunHAuCcm0/IiIiIiIyPmrtPUuZ6VfDpYY4NpiZfjpY0w8AZDIZetXpBQDIzM3E8ajjOrkflVxFLlZdXIVaS2ph7JGx2PDXBlyLu4a0nDQIEBCfHo8rz65g69WtGLdvHHwW+6Dzxs748a8fkZGTodNsRIaORT8qpEePHuKYRT8iIiKi0o0Zoyz+AcDatUBenqRxiIiIyMSFhobC19cXfn5+UkchMimqmX5mMjO42rqWuK2rjSscLB0AGMaafjLI4GpTcuby6FW3lzjWZYvPW/G30G5dO0zaPwmPUx6Ll1vILfC66+toUbkFXnN6DRZyC7Xb/X7/d4zaMwpVF1fFB0c/wIMXD3SWkciQsb0nFdK0aVO4u7sjLi4Ox44dQ3Z2NiwtLaWORURERGSwfHyAHj2AgweBBw+Ao0eBAs0TiIiIiLQqJCQEISEhSE5OhpOTk9RxiEyGaqafu5075LKS58vIZDLUdKmJv579hegX0chT5MFMbqaPmGri0pUz/dxs3XR6/wE1A2BpZonsvGwcuH0AgiBAJpNp9T5+vfUr3tz9JlKyU8TLur3WDdPbTkdArQBYm1uLl+fk5SAiJgJhd8Ow9epW/PP8HwBAQkYCFvyxAF//+TX61euH6a2mo2O1jlrPqomcvBw8z3iO5+nPEZ8ej7ScNGTlZiE7Lxu5ilxYmFnA0swS5jJzpKekwzPTEw5WDrCzsIO9pT3sLO1gZ2EHCzOL0u+M6F8s+lEhcrkcgYGB+Omnn5Camoo///wT/v7+UsciIiIiMmgTJiiLfgCwZg2LfkRERERExkQhKMRZc172XhrdpoZLDfz17C/kKnLxKPkRqjlX02XEIqky66q1p4q9pT06VeuE8HvhePDiAa7GXkUjz0Za2//mK5sxes9o5AnKtil1Xetide/VqGtdFx4eHpDL1YuwFmYWaOvTFm192mJep3k48+gMVlxYgW3XtiE7LxsKQYHdN3Zj943daOzZGG+3ehsjGo3QyVqEGTkZuBl/E9firuFa7DVci7uGq7FXcT/pPgQI5d6/hdxCLAAWLAYW/NfeovDlZnIzCIIAhaAQvwSof6/6ylPkKf8V8or9vqjrBKHk4ytYbBUEAZmZmbC2toZMJoMMxRdiSyrSGvrtBEHAyNoj4eGhmzU2S8OinwRCQ0MRGhqKPAPu+6Qq+gHKFp8s+hERERGVrFcvwNMTePYM2LsXiI0FJDrHJyIiIiKiMkrMSESOIgdA6ev5qdRwzl/XLyopSu9Fv/ScdKTnpAMA3G11W/QDgF51eiH8XjgAYP8/+7VW9FtzaQ0m/jpRLJANbTAUa4PXwsbcBrGxsaXeXiaTiQXAr7t9jVUXV2H5heV4kvoEAHDl2RVM+HUC3j/6PoY3HI5+9fqhU7VOZZ5Bl5mbiVvxt9SKe9firuFe4j0oBEXZD1xDOYocJGUmISkzSWf3QdoVWEW6TwGz6CcBY2jB0L17d3F8+PBhfPnllxKmISIiIjJ8FhbKtf0WLABycoAffwTeeUfqVEREREREpAnVen4A4GmvWdHvNafXxPHDFw+1nqk0CRkJ4ri0NQi1oc/rfTDzyEwAwI7rO/Bhhw/Lvc/t17Zjwq8TxO+ntpyKJT2XQC6TQ6EoeyHN094TH3f6GO+3fx+7b+zGD+d+wJlHZwAof16hEaEIjQiFjbkNWni3QMvKLVHduTqqOlaFvaU9LMwskJWbhaTMJDxNfYp7ifdwN/Eu7iTcwd3EuxoX9+ws7FDfvT4q21eGq60r3Gzc4GDlACszK2VLT7k5chW5yM7LRlZuFhJTEiG3lCM9Jx1pOWlIy0lDanYq0rKV44L/pmanijMiiV7Goh8VycPDAy1atMDFixcRGRmJp0+fwstLs2ntRERERBXVuHHKoh8ArF4NzJ4NSLB0BBERERERlZFqPT9A85l+Po4+4vhR8iOtZypNwaKfi7WLzu+vpktNtPRuiQsxF3D56WXcir+F191ef+X9RTyOwOg9o8Xv32nzDr7u9rVW1t+zNLPEsIbDMKzhMFyIuYAl55dg29VtyMrLAgBk5Gbg9IPTOP3gdLnux9bCFvXd6qOBRwM0cP/3y6MBXnN6rdR1IVUUCgViY2OLbGNaFEEQkJ2XXagYWPDf1OxUcd1FuUwOuUwOGfLHcplcvM5MZqb8V26m8feqcUnH+HLrT4VCgYSEBFSqVAkyefG/45JahpbULtVQbqcQFKikqFTs7XSNRT8qVmBgIC5evAgACAsLw6hRoyRORERERGTY6tQB/P2B338Hbt0C/vgDaN9e6lRERERERFSauPQ4cexhp1mffh+n/KLfw2T9z/RLzEwUx5Vs9FNkGN5wOC7EXAAAbL26FZ/4f/JK+3mU/Ah9f+6LzNxMAMDoJqO1VvB7WUvvltjYbyOWBi3F4TuHse+fffjjwR+ISorSeB+2FrZ43fX1QsW96s7VNS7uaYtMJoOVuRWszK309nvXBoVCgVhoXtw0VqoirlRY9KNi9ejRA1988QUAZYtPFv2IiIiISjd+vLLoBwBr1rDoR0RERERkDBIz8gtoms6aKzjTT5Ki3ytkLq+hDYbi3bB3IUDAxr82Ym6nuWUueqVlpyF4a7C45l6H1zpgZe+VOin4FeRg5YDBDQZjcIPBAIDYtFhci72Gh8kPEZMSg8zcTGTnZcPKzArO1s5wtXVFDecaqFWpFjztPHWej0gbWPSjYrVu3RoODg5ISUlBWFgY8vLyYGZmJnUsIiIiIoM2YADg7AwkJQHbtwPffw8Y6DLORERERET0r6TMJHHsYqNZAc3T3hMWcgvkKHKkWdMvs0B7Tw0zl1cVxyoIrB2Iw3cO437SfYTdDUOP2j00vr1CUOA/v/wHl59eBgDUcK6B3UN3w8rcSleRi+Vh5wGPGprN6iQyFqY7h5LKzcLCAgEBAQCA58+f49KlSxInIiIiIjJ8NjbAf/6jHGdkAFu2SJuHiIiIiIhKV7BVpqaz5uQyOao4VgEgzUy/pIwkcayvmX4AMLnFZHG8/MLyMt32o2MfYc/NPQAARytH7B+xH262btqMR1ShsehHJQoMDBTHR44ckTAJERERkfGYMCF/vGaNdDmIiIiIiEgzBWf6OVs7a3w7VYvPhIwEpOekazlVyaRY0w8AetXthSoOymLnvlv7cDX2qka32/TXJnz1x1cAlAXTbYO2wdfdV2c5iSoiFv2oRAWLfocPH5YwCREREZHxaNwY8PNTji9dUn4RERERaUtoaCh8fX3hpzrhIKJyU5vpV4ZWmT5OBdb103OLz1fNXF7mcnPMbjNb/P6zk5+Vepuj945i/L7x4vffBX5XpragRKQZFv2oRNWrV0e9evUAAGfPnkVSUpK0gYiIiIiMxPj8v2exdq10OYiIiMj0hISE4Pr164iIiJA6CpHJKO9MP0D/LT4TMgqs6afH9p4AMLnlZHjYKdfD23ZtG04/OF3sthdjLqL/tv7IUeQAAKa0nIJprabpJSdRRcOiH5VKNdsvLy8Px44dkzgNERERkXEYNgywtVWON28G0vXb6YeIiIiIiMogMUM5a04GGRytHDW+nVrRr4LM9AMAWwtb/LfDf8XvJ/w6AWnZaYW2+/vZ3wjaHITU7FQAQN/X++KHoB8gk8n0lpWoImHRj0rVo0f+NGu2+CQiIiLSjKOjsvAHAC9eADt3SpuHiIiIiIiKp5rp52TtBLlM87fNvR28xfGT1CfajlWipIwkAMpCpZOVk17vGwCm+k1FqyqtAAA3429i8I7BaoW/3Td2o/369ohLjwMAdHitA7YO3ApzubnesxJVFCz6Uak6duwIKysrAMCRI0cgCILEiYiIiIiMQ8EWn2vWSJeDiIiIiIhKppo1V9Y2mQWLfjEpMVrNVJqETGV7TydrJ5jJzfR63wBgJjfDhr4bxILjoTuH4LvMFxP2TUCbtW0wcPtAJGclAwD8vP2wb/g+2FjY6D0nUUXCoh+VytbWFp06dQIAPHz4EDdu3JA4EREREZFxaN0a8PVVjk+dAm7elDYPEREREREVJgiCONOvLOv5AUBlh8riWN8z/VQtSfW9nl9B9d3rY++wvbC1UK5t8ODFA6y5vAZnH50VtxlYfyCOjz5e5p8tEZUdi36kEdW6fgBbfBIRERFpSiZTn+23dq10WYiIiIiIqGhpOWnIVeQCKPvaeF72XuL4SYr+in4FC5WVbCrp7X6L0ql6J1yedBldanRRu7yBewNsGbAFOwbvgJ2lnUTpiCoWFv1IIwXX9Tty5IiESYiIiIiMy8iRgKWlcrxxI5CdLW0eIiIiIiJSp5oxB5R9pp+lmSXcbN0A6Le9Z2pOKvKEPABlL1TqQl3Xujg26hievfsMZ8adwb3p9/D3lL8xvNFwyGQyqeMRVRgs+pFG6tevDx8fHwDAiRMnkJ6eLnEiIiIiIuPg5gb0768cx8UBv/4qbR4iIiIiIlKnmjEHvFqrzMr2yhafT1KfQBAEbcUqUVJWkjiWsr3nyzzsPNC6amvUcKnBYh+RBFj0I43IZDKxxWdWVhZOnjwpcSIiIiIyBvv378frr7+OOnXqYM2aNVLHkUzBFp+rV0uXg4iIiIiICkvMfPWZfkD+un7ZedlIyEjQVqwSGWrRj4ikxaIfaaxgi0+u60dERESlyc3NxezZs/Hbb7/h8uXL+Prrr/H8+XOpY0miSxegRg3lOCwMiI6WNg8REREREeUr70w/bwdvcfwkVT/r+qVkp4hjJ2snvdwnERk+Fv1IY127doWZmRkArutHREREpTt//jwaNGiAKlWqwN7eHkFBQQgLC5M6liTkcmDcOOVYEID166XNQ0RERERE+Qqu6fcq6+Op2nsCwJMUCYp+Viz6EZESi36kMWdnZ7Ru3RoAcPPmTdy/f1/aQERERKRTJ0+eRJ8+feDt7Q2ZTIY9e/YU2iY0NBTVq1eHtbU13njjDZw/f168LiYmBlWqVBG/r1KlCh4/fqyP6AZpzBhl8Q8A1q0D8vIkjUNERERERP8qONPvldp7Fij6xaTEaCFR6VJzUsWxo5WjXu6TiAwfi35UJqp1/QDO9iMiIjJ1aWlpaNKkCUJDQ4u8ftu2bZg9ezbmzZuHS5cuoUmTJggMDERsbKyekxqHKlWAnj2V44cPlW0+iYiIiF5FaGgofH194efnJ3UUIpPwIuuFOH6VWXNStPdMzWbRj4gKM5c6ABmXHj16YO7cuQCURb9JkyZJnIiIiIh0JSgoCEFBQcVe/+2332LChAkYO3YsAGDFihU4cOAA1q1bhw8++ADe3t5qM/seP36MVq1aFbu/rKwsZGVlid8nJycDABQKBRQKRXkPR41CoYAgCFrfb2nGjQP271d+7m71agGBgYLO71OqY9U3Hqdp4XGaFh6nadHVcZr6z03bQkJCEBISguTkZDg5sa0fUXkVLKA5WDmU+faVHSRo75mT396TRT8iUmHRj8qkRYsWcHNzQ3x8PI4ePYqcnBxYWFhIHYuIiIj0LDs7GxcvXsSHH34oXiaXyxEQEIAzZ84AAFq1aoWrV6/i8ePHcHJywqFDh/Dxxx8Xu88vv/wS8+fPL3R5XFwcMjMztZpfoVDgxYsXEAQBcrn+ml+0bAl4errj2TMz/PorcO1aPNzddfsmp1THqm88TtPC4zQtPE7ToqvjTElJKX0jIiIdKVj0s7e0L/PtPe08xXFsun46nxRc0+9VCpVEZJpY9KMykcvl6NatG7Zu3YqUlBScPXsWHTp0kDoWERER6Vl8fDzy8vLg6empdrmnpydu3rwJADA3N8eiRYvQuXNnKBQKvPfee3B1dS12nx9++CFmz54tfp+cnAwfHx+4u7vD0VG7n1xVKBSQyWRwd3fX+xuzY8fK8NVXQG6uDIcOueHdd3V7f1Ieqz7xOE0Lj9O08DhNi66O09raWmv7IiIqq4JFPzsLuzLf3sPOQxw/S32mlUylYXtPIioKi35UZj169MDWrVsBAIcPH2bRj4iIiIoVHByM4OBgjba1srKClZVVocvlcrlO3jyVyWQ623dJxo8HvvpKOV67Vo45cwCZTLf3KdWx6huP07TwOE0Lj9O06OI4Tf1nRkSGLS0nTRy/ykw/e0t72JjbICM3A8/S9FT0y2HRj4gK4xkVlVn37t3F8eHDhyVMQkRERFJxc3ODmZkZnj1T/4P22bNn8PLykiiVcahVC+jSRTn+5x/g1Clp8xARERERVXTlbe8pk8ngaa/sgqKvmX4F23uy6EdEKiz6UZl5eXmhadOmAIBLly4hNlY/faqJiIjIcFhaWqJFixY4duyYeJlCocCxY8fQpk0bCZMZh/Hj88dr1kiXg4iIiIiIXmrvaVn29p5A/rp+zzOeI1eRq5VcJeFMPyIqCot+9EoCAwPFcVhYmIRJiIiISFdSU1MRGRmJyMhIAEBUVBQiIyPx4MEDAMDs2bOxevVqbNy4ETdu3MCUKVOQlpaGsWPHSpjaOPTvD7i4KMc7dgCJidLmISIiIiKqyNKyle09rcysYC5/tRWxCq7rF5cWp5VcJVHN9JNB9krrEBKRaWLRj15Jjx49xPGRI0ckTEJERES6cuHCBTRr1gzNmjUDoCzyNWvWDHPnzgUADB06FN988w3mzp2Lpk2bIjIyEocPH4anp6eUsY2CtTUwcqRynJkJbNkibR4iIiIioopMNdPvVVp7qqhm+gHQy7p+KTnKop+DlQNkul4knIiMBot+9Eratm0Le3vli+CRI0egUCgkTkRERETa5u/vD0EQCn1t2LBB3GbatGmIjo5GVlYWzp07hzfeeKPc9xsaGgpfX1/4+fmVe1+GrGCLz9WrAUGQLgsRERERUUWmlaKffYGinx7W9VNlZmtPIiqIRT96JZaWlujSpQsAIC4uDpcvX5Y4EREREZmKkJAQXL9+HREREVJH0alGjQBVjfSvv4BLl6TNQ0RERERUUaXlKNt7vup6foD+Z/qp1vRj0Y+ICmLRj14ZW3wSERERlc/Ls/2IiIiIiEi/FIJCXNOvPDP9Cq7pF5sWW+5cJclT5ImFShb9iKggFv3olQUGBorjw4cPS5iEiIiIyDgNHQrY/fth4i1bgLQ0afMQEREREVU0GTkZEKDstW8s7T1VrT0BFv2ISB2LfvTKatasiTp16gAAzpw5gxcvXkiciIiIiMi4ODgAw4crxykpwI4d0uYhIiIiIqpoVDPmAMDOwjjaeyZnJYtjFv2IqCAW/ahcVLP9cnNzcezYMYnTEBERERmfgi0+16yRLgcRERERUUVUcNactmb66bq9Z8Gin4Olg07vi4iMC4t+VC49e/YUxwcOHJAwCREREZFxatUKaNhQOf7jD+D6dWnzEBERERFVJNoq+jlbO0MuU77d/jzjeblzlSQlO0Ucc6YfERXEoh+VS+fOnWFrawtAWfRTKBQSJyIiIiIyLjKZ+my/tWuly0JEREREVNGkZee39yxP0U8uk6OSTSUAQHx6fLlzlYTtPYmoOCz6UblYW1sjICAAAPDs2TNcvHhR4kRERERk7EJDQ+Hr6ws/Pz+po+jNyJGAlZVyvGkTkJUlbR4iIiIiooqi4Ey/8qzpBwButm4AWPQjIumw6Efl1rt3b3G8f/9+CZMQERGRKQgJCcH169cREREhdRS9qVQJGDBAOY6PB/btkzYPERERGbaK+CEpIl3RVntPIL/ol5qdiqxc3X2SLzmba/oRUdFY9KNyK7iuH4t+RERERK+mYIvP1auly0FERESGryJ+SIpIV9JytNPeE8gv+gG6XdcvPTtdHJc3MxGZFhb9qNyqVKmC5s2bAwAuXbqEx48fS5yIiIiIyPj4+wM1ayrH4eHAvXuSxiEiIiIiqhDU2ntalq+9p6uNqzjWZYvPgoXK8mYmItPCoh9pRcEWnwcPHpQwCREREZFxksvVZ/utWiVdFiIiIiKiikIX7T0B3Rb9tLkOIRGZFhb9SCu4rh8RERFR+b31FmBhoRyvWwdk6W4ZECIiIiIiApCWraP2num6a++pzZakRGRaWPQjrWjRogU8PT0BAEePHkVGRobEiYiIiIiMj6cnMGCAchwXB+zeLW0eIiIiIiJTp81Zc3pr75nN9p5EVDQW/Ugr5HI5evXqBQBIT0/H77//Lm0gIiIiIiM1ZUr+ePly6XIQEREREVUExtjeU21NP7b3JKICWPQjrSnY4vPXX3+VMAkRERGR8erYEfD1VY5PnQKuXpU2DxERERGRKVMroJVz1pwka/pxph8RFcCiH2lNQEAALC0tASjX9RMEQeJEREREZIxCQ0Ph6+sLPz8/qaNIQiYDJk/O/37lSumyEBERERGZuozc/GWKbC1sy7UvtTX9MnS3pl96Tro45pp+RFQQi36kNQ4ODvD39wcAPHz4EH///be0gYiIiMgohYSE4Pr164iIiJA6imRGjgRs/32/YdMmIDW15O2JiIiIiOjVZOZmimNrc+ty7cvVVv9r+pW3UElEpoVFP9Kqgi0+9+/fL2ESIiIiIuPl7AwMH64cJycDW7dKGoeIiIiIyGRps+jnbO0MuUz5lrs+1vSzMbcR74+ICGDRj7SsV69e4phFPyIiIqJXN2VK/nj5coCd04mIiIiItE+bRT+5TA5XG+VsP12291St6cfWnkT0Mhb9SKtq1qwJX19fAMDZs2fx7NkziRMRERERGacWLQDVsoaXLwMVuNspEREREZHOZOVmAVAW7Mzl5uXen2pdP33M9LOztNPZfRCRcWLRj7QuODgYACAIAmf7EREREZXD5Mn54+XLpctBRERERGSqVDP9yjvLT0W1rl9qdqraLEJtUq3pZ2fBoh8RqWPRj7SuX79+4njPnj2S5SAiIiIydsOGKdf3A4CffwYSEiSNQ0RERERkcrRd9FPN9AOA5+nab/GpEBT5M/1Y9COil7DoR1rn5+eHypUrAwDCw8ORmpoqcSIiIiIi42RrC4werRxnZgIbN0qbh4iIiIjI1Gi96GdToOing3X9MnIyxDHX9COil7HoR1onl8vFFp9ZWVkICwuTOBERERGR8SrY4nPFCkAQpMtCRERERGRqdDnTTxfr+qlm+QGArYWt1vdPRMaNRT/SCbb4JCIiItKOevUAf3/l+J9/gOPHJY1DRERERGRSdLWmH6Cjol92ftHPzpLtPYlIHYt+EggNDYWvry/8/PykjqIznTt3hoODAwBg//79yM3NlTgRERERkfGaMiV/vHy5dDmIiIiIiEyNsa3pl5qdv5QS1/Qjopex6CeBkJAQXL9+HREREVJH0RkrKysEBQUBABITE3Hq1CmJExEREZGxqAgfkCqrfv0AT0/leM8e4MkTKdMQEREREZmGPEUechQ5AIyzvSfX9COil7HoRzpTsMXn3r17pQtCRERERqUifECqrCwtgfHjlePcXGDtWmnzEBERERGZgqy8LHFsZWallX262uixvSdn+hHRS1j0I50JCgqCubk5AOW6foIgSJyIiIiIyHhNmADIZMrxqlVAXp60eYiIiIiIjF1Wbn7RTyftPTO0396z4Ew/rulHRC9j0Y90xtnZGZ07dwYAREdH48qVKxInIiIiIjJe1aoBvXopxw8fAgcOSJuHiIiIiMjYqdbzA4ynvWfBNf3Y3pOIXsaiH+lUwRafe/bskSwHERERkSmYMiV/vHy5dDmIiIiIiEyBLop+TtZOMJOZAdB9e09bC1ut75+IjBuLfqRTwcHB4phFPyIiIqLyCQwEqldXjo8cAe7dkzQOERERSSQ0NBS+vr7w8/OTOgqRUdNF0U8uk6OSTSUAOir65XBNPyIqHot+pFNVq1ZFy5YtAQCRkZGIjo6WOBERERGR8TIzAyZOVI4FAVi5Uto8REREJI2QkBBcv34dERERUkchMmq6KPoB+S0+dbKmXzbX9COi4rHoRzpXsMXn3r17pQtCREREZALGjQMsLJTjdeuArCxp8xARERERGStdF/1Ss1ORlavdE/aCa/pxph8RvYxFP9K5vn37iuPdu3dLmISIiIjI+Hl4AAMHKsfx8cCuXdLmISIiIiIyVroq+rnYuIjjxMxEre0XANJz0sUxZ/oR0ctY9COda9CgAerUqQMAOHXqFGJjYyVORERERGTcpkzJHy9fLl0OIiIiIiJjVrDoZ2VmpbX9ulgXKPpl6K7oZ2tuq9V9E5HxY9GPdE4mk2Hgvx9HVygU2LNnj7SBiIiIiIxchw6Ar69yfPo08Pff0uYhIiIiIjJGOpvpV6Dol5CRoLX9AkB6boGinwWLfkSkjkU/0otBgwaJ413sQUVERERULjIZMHly/vcrV0qXhYiIiIjIWBl7e08W/YjoZSz6kV40b94c1atXBwD89ttvSEjQ7idciIiIyHSEhobC19cXfn5+UkcxaKNGAbb//o2/aROQmiptHiIiIiIiY5OVlyWOtVn0q2RTSRzrtL0ni35E9BIW/UgvZDIZBgwYAADIzc3Fvn37JE5EREREhiokJATXr19HRESE1FEMmpMTMGKEcpySAmzZIm0eIiIiIiJjo4/2npzpR0T6xKIf6Y1qXT+ALT6JiIiItGHKlPzx8uWAIEiXhYiIiIjI2OilvaeOZvpZyC1gYWah1X0TkfFj0Y/0pnXr1vD29gYAhIWFITk5WeJERERERMateXOgVSvlODISOHdO0jhEREREREbFmGf62ZjbaHW/RGQaWPQjvZHL5WKLz+zsbOzfv1/iRERERETGb/Lk/PHy5dLlICIiIiIyNgWLflbmVlrbb8GZfgkZCVrbL8CiHxGVjEU/0iu2+CQiIiLSrqFDAWdn5XjbNiBBu+8pEBERERGZLM70IyJTw6If6VWHDh3g7u4OADh06BDS0tIkTkRERERk3GxtgTFjlOOsLGDDBinTEBEREREZD2Ne049FPyIqCot+pFdmZmbo378/ACAjIwOHDx+WOBERERGR8SvY4nPFCkChkC4LEREREZGx0FXRz9LMEnYWdgC0O9NPEAQW/YioRCz6kd6xxScRERGRdr3+OtCli3J8+zbw22/S5iEiIiIiMga6KvoB+bP9tDnTr2BeFv2IqCgs+pHede7cGS4uyhe9X3/9FZmZmaXcgoiIiIhKU3C23/Ll0uUgIiIiIjIWWXlZ4ljrRb9/1/XT5kw/1Sw/gEU/Iioai36kdxYWFggODgYApKamIiwsTOJERERERMavXz/Ay0s53rsXePxY0jhERERERAZPHzP9MnMzkZGToZV9suhHRKVh0Y8kMXjwYHG8bds2CZMQERERmQYLC2D8eOU4Lw9Yu1baPEREREREhk6nRb9/Z/oB2pvtx6IfEZWGRT+SRLdu3cQWn/v27UNGhnY+7UJERERUkU2cCMj/PcNftQrIzZU2DxERERGRIStY9LMys9LqvlUz/QDtrevHoh8RlYZFP5KEpaUl+vfvD0DZ4vPgwYMSJyIiIiIyfj4+QO/eyvHjx8D+/dLmISIiIiIyZGpFP3MtF/0404+IJMCiH0lm6NCh4pgtPomIiIi0Y/Lk/PHy5dLlICIiIiIydKqin4XcAnKZdt8qr2RTSRxzph8R6QuLfiSZLl26wM3NDQCwf/9+pKamSpyIiIiIDEFoaCh8fX3h5+cndRSjFBgI1KihHIeFAXfuSJuHiIhIaklJSVJHICIDlZOXAwCwNLPU+r51MdMvLSdNHLPoR0RFYdGPJGNubo6BAwcCADIyMrCf/aeIiIgIQEhICK5fv46IiAipoxgluRyYNCn/+9WrZdKFISIi0rMFCxaodRMaMmQIXF1dUaVKFfz1118SJiMiQ5SrUC6CbS431/q+uaYfEUmBRT+S1LBhw8QxW3wSERERacdbbwGW/35Yef16IDOz5O2JiIhMxYoVK+Dj4wMACA8PR3h4OA4dOoSgoCDMmTNH4nREZGhyFMqZfhZmFlrfd8GZfgkZCVrZJ4t+RFQaFv1IUh06dICXlxcA4NChQ0hOTpY4EREREZHxc3cHBg1Sjp8/l2H/fmtpAxEREenJ06dPxaLf/v37MWTIEHTv3h3vvfceuwgQUSGq9p4Wch0U/Wy0396TRT8iKg2LfiQpMzMzDB48GACQlZWFvXv3SpyIiIiIyDRMnpw/3rTJVrogREREeuTi4oKHDx8CAA4fPoyAgAAAgCAIyMvLkzIaERkgnbb31MGafiz6EVFpWPQjyQ0dOlQcs8UnERERkXa0bw80aKAcR0RY4soVafMQERHpw4ABAzBixAh069YNz58/R1BQEADg8uXLqF27tsTpiMjQ6LS9J9f0IyIJsOhHkmvTpg2qVq0KAAgLC0NionZeBImIiEzRw4cP8ejRI/H78+fPY+bMmVi1apWEqcgQyWTAlCn5369YIZMuDBERkZ4sXrwY06ZNg6+vL8LDw2Fvbw8AePLkCaZOnSpxOiIyNDpt78mZfkQkARb9SHJyuRxDhgwBAOTk5OCXX36ROBEREZHhGjFiBI4fPw5AuWZNt27dcP78eXz00Uf49NNPJU5HhmbkSMDOTgAAbN4MpKRIHIiIiEjHLCws8O677+L7779Hs2bNxMtnzZqF8ePHS5iMiAyRLtt7WphZwN5S+cEDzvQjIn1h0Y8MAlt8EhERaebq1ato1aoVAGD79u1o2LAh/vzzT2zevBkbNmyQNhwZHEdHYMQI5Tg1VYbNm6XNQ0REpGsbN27EgQMHxO/fe+89ODs7o23btoiOjpYwGREZIl229wTyZ/slZCRoZX8s+hFRaVj0I4Pg5+eHGjVqAACOHTuGuLg4iRMREREZppycHFhZWQEAjh49iuDgYABAvXr18OTJEymjkYGaNEkQx8uXA4JQwsZERERG7osvvoCNjfKN8DNnziA0NBQLFy6Em5sbZs2aJXE6IjI0umzvCeSv65eYmQhBCyfiLPoRUWlY9CODIJPJxBafeXl52L17t8SJiIiIDFODBg2wYsUKnDp1CuHh4ejRowcAICYmBq6urhKnI0PUrBnQvHk2AODKFeDMGYkDERER6dDDhw9Ru3ZtAMCePXswcOBATJw4EV9++SVOnTolcToiMiQKQQEBykKcLtp7Avkz/bLzspGRm1Hu/aXlpIlja3Prcu+PiEwPi35kMNjik4iIqHQLFizAypUr4e/vj+HDh6NJkyYAgH379oltP4leNnp0/ieCV6+WMAgREZGO2dvb4/nz5wCAsLAwdOvWDQBgbW2NjIzyv+FORKZDNcsP0GF7z39n+gHaWdcvJSt/kW4HS4dy74+ITA+LfmQwmjZtijp16gAAfv/9d8TExEiciIiIyPD4+/sjPj4e8fHxWLdunXj5xIkTsWLFCgmTkSHr3TsTTk7KTzFv2wa8eCFxICIiIh3p1q0bxo8fj/Hjx+Off/5Bz549AQDXrl1D9erVpQ1HRAZFtZ4foMP2ntYFin6ZWij6ZSuLfhZyC1iZWZV7f0Rkelj0I4Mhk8kwfPhwAIAgCJztR0REVISMjAxkZWXBxUX5x2N0dDS+++473Lp1Cx4eHhKnI0Nlawu8+aZynJEBbN4sbR4iIiJdCQ0NRZs2bRAXF4ddu3aJ7c8vXrwovudgSKKiotC5c2f4+vqiUaNGSEtLK/1GRKQVuYpccazr9p6Admb6JWclAwAcrRzLvS8iMk0s+pFBeVP1bhSAzXw3ioiIqJC+ffti06ZNAICkpCS88cYbWLRoEfr164fly5dLnI4M2fjxgjheuRIQhBI2JiIiMlLOzs5YunQp9u7dK659DADz58/HRx99JGGyoo0ZMwaffvoprl+/jhMnTsDKijN3iPRFH+09K9lUEscJGQnl3p+qvaeDFVt7ElHRWPQjg1K3bl20bNkSgPJTeDdv3pQ4ERERkWG5dOkSOnToAADYuXMnPD09ER0djU2bNuGHH36QOB0ZsiZNgDfeUI6vXAEiIqTNQ0REpCtJSUlYtGiR2OZz8eLFeGGAva2vXbsGCwsL8dyuUqVKMDfXzWwjIipML+09bXTT3pPr+RFRcVj0I4MzYsQIcczZfkREROrS09Ph4KD8Ay8sLAwDBgyAXC5H69atER0dLXE6MnQTJuSPV6+WLgcREZGuXLhwAbVq1cLixYuRkJCAhIQEfPvtt6hVqxYuXbpUpn2dPHkSffr0gbe3N2QyGfbs2VNom9DQUFSvXh3W1tZ44403cP78eY33f/v2bdjb26NPnz5o3rw5vvjiizLlI6Ly0Ud7T2drZ3H8IrN8Hz7IyctBZm4mALb3JKLisehHBmfYsGGQy5UPzS1btkBg7ykiIiJR7dq1sWfPHjx8+BBHjhxB9+7dAQCxsbFwdOQfflSyoUOBf2vG2LoVSE6WNg8REZG2zZo1C8HBwbh//z52796N3bt3IyoqCr1798bMmTPLtK+0tDQ0adIEoaGhRV6/bds2zJ49G/PmzcOlS5fQpEkTBAYGIjY2VtymadOmaNiwYaGvmJgY5Obm4tSpU1i2bBnOnDmD8PBwhIeHl+fwiagM9NHes2DRLykzqVz7Us3yAwB7S/ty7YuITJfR9Qx4+PAhZDIZqlatCgA4f/48tmzZAl9fX0ycOFHidKQNlStXRpcuXXD06FHcu3cPZ8+eRZs2baSORUREZBDmzp2LESNGYNasWejSpYv4GhkWFoZmzZpJnI4Mnb098OabwIoVQFqasvA3aZLUqYiIiLTnwoULWL16tVqbTHNzc7z33nviciKaCgoKQlBQULHXf/vtt5gwYQLGjh0LAFixYgUOHDiAdevW4YMPPgAAREZGFnv7KlWqoGXLlvDx8QEA9OzZE5GRkejWrVuxt8nKykJWVpb4ffK/n+BRKBRQKBQaH5smFAoFBEHQ+n4NDY/TtJTlOLNzs8WxucxcJz8bJysncZyQkVCu+3iRkT9T0MHSgb9PE8LjNC26Ok5N92d0Rb8RI0Zg4sSJGDlyJJ4+fYpu3bqhQYMG2Lx5M54+fYq5c+dKHZG04M0338TRo0cBKFt8suhHRESkNGjQILRv3x5PnjxBkyZNxMu7du2K/v37S5iMjMXEicqiHwCsWsWiHxERmRZHR0c8ePAA9erVU7v84cOHYot0bcjOzsbFixfx4YcfipfJ5XIEBATgzJkzGu3Dz88PsbGxSExMhJOTE06ePIlJpbwwf/nll5g/f36hy+Pi4pCZmVm2gyiFQqHAixcvIAiC2JHJFPE4TUtZjvNZwjNxnJudqzZLV1vy0vLE8dOkp+W6j/vP74tjC4UFkpKS+Ps0ETxO06Kr40xJSSl9Ixhh0e/q1ato1aoVAGD79u1o2LAh/vjjD4SFhWHy5Mks+pmIAQMGYMqUKcjMzMS2bduwePFiWFjoZpo9ERGRsfHy8oKXlxcePXoEAKhatap4fmQKQkNDERoairy8vNI3pjJr1gxo2RK4cAG4dAm4eBFo0ULqVERERNoxdOhQjBs3Dt988w3atm0LAPjjjz8wZ84cDB8+XGv3Ex8fj7y8PHh6eqpd7unpiZs3b2q0D3Nzc3zxxRfo2LEjBEFA9+7d0bt37xJv8+GHH2L27Nni98nJyfDx8YG7u7vWW70rFArIZDK4u7ub/JuzPE7TUZbjfJz3WBw72DnAw8ND63nybPL/pslEZrnu407WHXHs7uQOZ2dn/j5NBI/TtOjqOK2trTXazuiKfjk5ObCysgIAHD16FMHBwQCAevXq4cmTJ1JGIy1ydHREnz59sGPHDsTHxyM8PBw9e/aUOhYREZHkFAoFPvvsMyxatAipqakAAAcHB7zzzjv46KOPTOLEOSQkBCEhIUhOToaTk1PpN6AymzBBWfQDgNWrWfQjIiLT8c0330Amk2HUqFHIzc0FAFhYWGDKlCn46quvJE5XWGktRF9mZWUlvi9WkFwu18l5oEwm09m+DQmP07RoepwK5LfKszSz1MnPpZJtJXH8IutFue4jLSdNHDtaOfL3aWJ4nKZFF8ep6b6M7ifboEEDrFixAqdOnUJ4eDh69OgBAIiJiYGrq6vE6Uib3nzzTXG8efNmCZMQEREZjo8++ghLly7FV199hcuXL+Py5cv44osvsGTJEnz88cdSxyMjMXw4YGenHG/eDPxbPyYiIjJ6lpaW+P7775GYmIjIyEhERkYiISEBX3/9NZ4/f661+3Fzc4OZmRmePXumdvmzZ8/g5eWltfshIt3JUeSIY3O5bubG2FjYwMpMWahPzEws176Ss5LFsaOVdmf2EpHpMLqi34IFC7By5Ur4+/tj+PDh4lo2+/btM6m2VqT8tJuLiwsAYM+ePeJsBiIioops48aNWLNmDaZMmYLGjRujcePGmDp1KlavXo0NGzZIHY+MhIMDMGKEcpyaCvz8s7R5iIiItM3W1haNGjVCo0aNYGtri2vXrsHHx0dr+7e0tESLFi1w7Ngx8TKFQoFjx46hTZs2WrsfItKdnLz8op+FXHfLCjlbOwMAkjKTyrWflOz89bzsLe3LtS8iMl1GV/Tz9/dHfHw84uPjsW7dOvHyiRMnYsWKFRImI22ztLTE4MGDAQDp6enYu3evxImIiIikl5CQgHr16hW6vF69ekhISJAgERmriRPzx6tXS5eDiIjIUKWmpoqzBQEgKioKkZGRePDgAQBg9uzZWL16NTZu3IgbN25gypQpSEtLw9ixYyVMTUSaylXkimMLMyMo+mXlF/0cLB3KtS8iMl1GV/TLyMhAVlaWOAMsOjoa3333HW7duqWTxVZJWmzxSUREpK5JkyZYunRpocuXLl0qdkAg0kSLFkDTpsrx+fPAv+9nEhER0b8uXLiAZs2aoVmzZgCURb5mzZph7ty5AIChQ4fim2++wdy5c9G0aVNERkbi8OHD8PT01Hm20NBQ+Pr6ws/PT+f3RWSq9NHeE8gv+iVnJSNPkffK+2F7TyLShO6ezXSkb9++GDBgACZPnoykpCS88cYbsLCwQHx8PL799ltMmTJF6oikRe3bt4ePjw8ePnyIsLAwxMbGsrhLREQV2sKFC9GrVy8cPXpUbB115swZPHz4EAcPHpQ4HRkTmUw522/qVOX3q1cDoaHSZiIiIjIk/v7+EAShxG2mTZuGadOm6SlRvpCQEISEhCA5ORlOTk56v38iU6Cv9p4uNi7iODkrWe37sijY3tPBijP9iKhoRjfT79KlS+jQoQMAYOfOnfD09ER0dDQ2bdqEH374QeJ0pG1yuRwj/l1wJi8vD9u3b5c4ERERkbQ6deqEf/75B/3790dSUhKSkpIwYMAA3Lp1SzxHItLUiBGAra1y/NNPQFqatHmIiIhe1ZUrV0r8unXrltQRicjA6Lu9JwAkZia+8n7Y3pOINGF0M/3S09Ph4KB8UgsLC8OAAQMgl8vRunVrREdHS5yOdOHNN9/EggULAChbfErxCToiIiJD4u3tjc8//1ztskePHmHixIlYtWqVRKnIGDk5AcOGAevWAcnJwI4dwJgxUqciIiIqu6ZNm0ImkxU5M091uUwmkyAZERkqvbX3tHIWx+VZ1y85+6X2nrklbExEFZbRzfSrXbs29uzZg4cPH+LIkSPo3r07ACA2NhaOjuxlbIoaNWqERo0aAQDOnj2L27dvS5yIiIjI8Dx//hxr166VOgYZoQkT8sesGRMRkbGKiorCvXv3EBUVVehLdfm9e/ekjklEBkRf7T0LzvQrT9GPM/2ISBNGV/SbO3cu3n33XVSvXh2tWrUS17IJCwsTF1Ym0zNq1ChxvGnTJgmTEBEREZmWN94A/v18Fc6cAf7+W9o8REREr6JatWoafRERqRRs76nTmX7aKvoVWNPP0YqTX4ioaEZX9Bs0aBAePHiACxcu4MiRI+LlXbt2xeLFiyVMRrr05ptvQi5XPlx//PFHKBQKiRMRERERmQaZDJg4Mf97ThglIiIiooqgYHtPXa7p52LjIo4TM159Tb/kLGV7TzOZGazNrcudi4hMk9EV/QDAy8sLzZo1Q0xMDB49egQAaNWqFerVqydxMtKVypUri61co6OjcerUKYkTEREREZmON98ErKyU4x9/BLKypM1DREREJQsNDYWvry/8/PykjkJktIytvaeq6Odg5cA1SomoWLqbt6wjCoUCn332GRYtWoTU1FQAgIODA9555x189NFH4mwwMj2jRo3C4cOHAShbfHbq1EniRERERPozYMCAEq9PSkrSTxAySS4uwMCBwJYtQEICsGcPMHSo1KmIiIioOCEhIQgJCUFycjKcnJykjkNklIypvacgCIhJiQEAeNl7aSEVEZkqo6uQffTRR1i6dCm++uorXL58GZcvX8YXX3yBJUuW4OOPP5Y6HulQ37594eCgXKR2x44dSE9PlzgRERGR/jg5OZX4Va1aNbU1cInKavz4/DFbfBIRERGRqdNXe09tFP2SMpOQnqN8L9TH0UcLqYjIVBndTL+NGzdizZo1CA4OFi9r3LgxqlSpgqlTp+Lzzz+XMB3pkq2tLYYMGYK1a9ciJSUFe/bswbBhw6SORUREpBfr16+XOgKZuE6dgJo1gXv3gPBw4P59oHp1qVMRERGVzbx58/DWW2+hWrVqUkchIgOnr/aeLtb5a/olZSW90j4eJj8Ux1Udq5Y3EhGZMKOb6ZeQkFDk2n316tVDQkKCBIlInwrOYNi0aZOESYiIiIhMi1wOjBuX/z3rzEREZIz27t2LWrVqoWvXrtiyZQuyuFAtERVDivaeiRmJr7SPR8mPxDGLfkRUEqMr+jVp0gRLly4tdPnSpUvRpEkTCRKRPrVv3x7V//3IeXh4OGJiYqQNRERERGRCxoxRFv8AYN06IC9P0jhERERlFhkZiYiICDRo0AAzZsyAl5cXpkyZgoiICKmjEZGB0Vd7Tyfr/HU3X7W9Z8GiH9t7ElFJjK7ot3DhQqxbtw6+vr4YN24cxo0bB19fX2zYsAFff/211PFIx+RyOUaOHAkAUCgU2LJli8SJiIiIiEyHtzfQs6dy/OiRss0nERGRsWnWrBl++OEHxMTEYO3atXj06BHatWuHxo0b4/vvv8eLFy+kjkhEBkBf7T0tzSxha2EL4NWLfg9fsL0nEWnG6Ip+nTp1wj///IP+/fsjKSkJSUlJGDBgAG7duoUOHTpIHY/04OUWn4IgSJiGiIiIyLSMH58/XrNGuhxERETlJQgCcnJykJ2dDUEQ4OLigqVLl8LHxwfbtm2TOh4RSUxf7T2B/HX9XnmmXwrbexKRZoyu6AcA3t7e+Pzzz7Fr1y7s2rULn332GRQKBSZOnCh1NNKD2rVro23btgCAa9eu4erVqxInIiIiIjIdPXsCnp7K8d69QGystHmIiIjK6uLFi5g2bRoqV66MWbNmoVmzZrhx4wZOnDiB27dv4/PPP8f06dOljlkuoaGh8PX1hZ+fn9RRiIyWvtp7Avnr+iVmln9NPx8ntvckouLp9iMMevT8+XOsXbsWq1atkjoK6cGoUaPw559/AgC2b9+Orl27SpyIiIhIf27fvo3jx48jNjYWCoVC7bq5c+dKlIpMhYWFcm2/BQuA3Fzgxx+Bd96ROhUREZFmGjVqhJs3b6J79+5Yu3Yt+vTpAzMzM7Vthg8fjhkzZkiUUDtCQkIQEhKC5ORkODk5lX4DIipEX+09gfyiX3pOOrLzsmFpZlmm26vae9pZ2MHJyomdz4ioWEY5049oyJAhsLKyAgD88ssvyMnJKeUWREREpmH16tWoX78+5s6di507d+KXX34Rv/bs2SN1PDIRb72VP16zBuB7CkREZCyGDBmC+/fv48CBA+jXr1+hgh8AuLm5FfrgFBFVPPps76kq+gHAi8yyrSsqCII408/HyQcymUyb0YjIxLDoR0bJxcUFwcHBAJSzPI8cOSJxIiIiIv347LPP8Pnnn+Pp06eIjIzE5cuXxa9Lly5JHY9MRN26QMeOyvHNm8CZM9LmISIi0kROTg42bNiA5ORkqaMQkRHQZ3tPFxsXcVzWdf2Ss5KRlpMGAKjiUEWbsYjIBLHoR0Zr1KhR4njjxo0SJiEiItKfxMREDB48WOoYVAGMG5c/XrNGuhxERESasrCwQGZmptQxiMhIqBX9dN3e08pZHJd1Xb8nqU/EcWWHytqKREQmymjW9BswYECJ1yclJeknCBmMwMBAeHh4IDY2Fr/++ivi4+Ph5uYmdSwiIiKdGjx4MMLCwjB58mSpo5CJGzQIePttIDkZ2LYN+O47wNFR6lREREQlCwkJwYIFC7BmzRqYmxvN215EJAGp2nuWdabfk5QCRT97Fv2IqGRGc/ZT2qLETk5OajO/yPRZWFhg5MiRWLRoEXJycrB582ajX4ibiIioNLVr18bHH3+Ms2fPolGjRrCwUP9E6vTp0yVKRqbG1hYYMQJYsQJIT1cW/iZMkDoVERFRySIiInDs2DGEhYWhUaNGsLOzU7t+9+7dEiUjIkOTk6e/9p7lKfrFpMSIY28Hby0lIiJTZTRFv/Xr10sdgQzQmDFjsGjRIgDAunXrMH36dC5mS0REJm3VqlWwt7fHiRMncOLECbXrZDIZi36kVePHK4t+ALB2LYt+RERk+JydnTFw4ECpYxCREdBne8/yrOmn1t6TM/2IqBRGU/QjKoqvry9atGiBixcv4sqVK7h8+TKaN28udSwiIiKdiYqKkjqCzoWGhiI0NBR5eXlSR6nwmjcHmjQB/voLOHcOuHoVaNhQ6lRERETF44fGiUhTRtnek2v6EVEp5FIHICqvoUOHiuN169ZJmISIiEi/BEGAIAhSx9C6kJAQXL9+HREREVJHqfBkMuVsP5W1a6XLQkRERPlCQ0Ph6+sLPz8/qaMQGS2p2nsmZiSW6bac6UdEZcGiHxm9vn37wsbGBgCwefNmZGZmSpyIiIhItzZt2oRGjRrBxsYGNjY2aNy4MX788UepY5GJevNNwMpKOd60CcjKkjYPERFRaXbu3IkhQ4agdevWaN68udqXqeCHpIjKT5/tPcs10y+VM/2ISHMs+pHRc3R0FPv1JyUlYc+ePdIGIiIi0qFvv/0WU6ZMQc+ePbF9+3Zs374dPXr0wOTJk7F48WKp45EJcnEBVEsjJSQAe/dKm4eIiKgkP/zwA8aOHQtPT09cvnwZrVq1gqurK+7du4egoCCp4xGRAdFne08X6wJr+mUllem2qvae9pb2sLe012YsIjJBLPqRSRg7dqw4Zv9+IiIyZUuWLMHy5cuxYMECBAcHIzg4GAsXLsSyZcvwww8/SB2PTFTBFp9r1kiXg4iIqDTLli3DqlWrsGTJElhaWuK9995DeHg4pk+fjhcvXkgdj4gMiFTtPcs60y8mJQYA4O3grcVERGSqdPsRBi3Zt2+fxtsGBwfrMAkZqo4dO6JmzZq4d+8ewsPD8eDBA7z22mtSxyIiItK6J0+eoG3btoUub9u2LZ48eVLELYjKr1MnoGZN4N494OhR4P59oHp1qVMREREV9uDBA/FcycbGBikpKQCAkSNHonXr1li6dKmU8YjIgKhm+sllcshlup0b42jlKI7LsqZfWnYaUrKVz2Ncz4+INGEURb9+/fpptJ1MJkNeXp5uw5BBksvlGDt2LD7++GMIgoCNGzfi448/ljoWERGR1tWuXRvbt2/H//3f/6ldvm3bNtSpU0eiVGTq5HJg3Djgo48AQQDWrwfmz5c6FRERUWFeXl5ISEhAtWrV8Nprr+Hs2bNo0qQJoqKiIAiC1PGIyICo1vTTdWtPADCTm8HRyhHJWcllmunH9fyIqKyMor2nQqHQ6IsFv4pt9OjRkMlkAJQtPhUKhcSJiIiItG/+/PmYO3cuevTogf/973/43//+hx49emD+/Pn49NNPpY5HJmz0aGXxD1AW/XjqTUREhqhLly5ix6ixY8di1qxZ6NatG4YOHYr+/ftLnI6IDImqvaeFXLetPVVULT7LVPRLKVD040w/ItKAURT9iDTh4+ODbt26AQCioqJw4sQJiRMRERFp38CBA3Hu3Dm4ublhz5492LNnD9zc3HD+/Hm+kUU6VaUK0LOncvzwIRAeLm0eIiKioqxatQofffQRACAkJATr1q1D/fr18emnn2L58uUSpyMiQ6Jq76nr9fxUXKxdAJSx6JfKoh8RlY1RtPd8WVpaGk6cOIEHDx4gOztb7brp06dLlIoMwVtvvYWwsDAAytl+nTt3ljgRERGR9rVo0QI//fST1DGoAho3Dti/Xzleuxbo0UPaPERERC+Ty+WQy/M/4z5s2DAMGzZMwkREZKj02d4TyJ/pl5WXhczcTFibW5d6G7WZfmzvSUQaMLqi3+XLl9GzZ0+kp6cjLS0NlSpVQnx8PGxtbeHh4cGiXwXXt29fuLi4IDExETt37sSSJUvg5OQkdSwiIqJySU5OhqOjozguiWo7Il3o1Qvw9ASePQP27QMSEoBKlaRORUREFd2VK1c03rZx48Y6TEJExkSq9p4AkJiRqFERLyYlRhx7O3jrIhYRmRijK/rNmjULffr0wYoVK+Dk5ISzZ8/CwsIC//nPfzBjxgyp45HErK2t8eabb2Lp0qXIyMjAzz//jEmTJkkdi4iIqFxcXFzw5MkTeHh4wNnZWVzDtiBBECCTybjGMemUhQUwYgSweDGQnQ1s3w5Mnix1KiIiquiaNm0KmUwmng+VhOdKRKSi7/aeBYt+SZlJGhX92N6TiMrK6Ip+kZGRWLlyJeRyOczMzJCVlYWaNWti4cKFGD16NAYMGCB1RJLYW2+9haVLlwIAVq9ezaIfEREZvd9++w2V/p1Odfz4cYnTUEU3erSy6AcAmzax6EdERNKLiooSx5cvX8a7776LOXPmoE2bNgCAM2fOYNGiRVi4cKFUEbUuNDQUoaGhLGISlYO+23uq1vQDNF/XT63ox/aeRKQBoyv6WVhYiL3ZPTw88ODBA9SvXx9OTk54+PChxOnIEDRr1gwtW7bEhQsXcPHiRVy8eBEtWrSQOhYREdEr69SpkziuUaMGfHx8Cn2KXRAEnguRXjRpAjRuDFy5Apw5A9y+DdSpI3UqIiKqyKpVqyaOBw8ejB9++AE9e/YUL2vcuDF8fHzw8ccfo1+/fhIk1L6QkBCEhIQgOTmZy5oQvSIp23tqXPT7d00/a3NrOFnx/zoRlU5e+iaGpVmzZoiIiACgfANs7ty52Lx5M2bOnImGDRtKnI4MxcSJE8XxqlWrJExCRESkXTVq1EBcXFyhyxMSElCjRg0JElFFNGpU/njTJulyEBERvezvv/8u8pyoRo0auH79/9m77/AoqraP479NIAESEloCRJAuEKr0IkVAioigSBOlKc2gIuoj6KOCClgRhChiAcRCFXhUpEjvAlINIh1EEjqkAIHsef/YN0uWJBAgyWQ334/XXs7Mzs7cZ2eZPZl75z4RFkQEIKuysrzn2Utn0/SaxDv9ivoXvWn5YgCQ3DDpN2rUKBUt6riVeeTIkcqfP78GDhyokydP6vPPP8/0eB555BHlz59fjz32WKbvG6nr2rWr/P39JUnff/+9oqOjLY4IAID0kdpYNTExMcqVK5cFESE7evxx6f+Lb2jaNMlutzYeAAASVaxYUaNHj1Z8fLxzWXx8vEaPHq2KFStaGBmArCYx6edt886U/d3qnX6Xr17WmYtnJFHaE0DauV15z1q1ajmng4ODtXDhQgujkZ5//nn16dNHU6dOtTQOuMqbN68ef/xxTZo0STExMZo+fbr69u1rdVgAANy2IUOGSJJsNptef/115cmTx/lcQkKCNm7cqOrVq1sUHbKbokWlli2lhQulw4el1aulJFVoAQCwzMSJE9WuXTsVK1ZMVatWlSTt2LFDNptNP/30k8XRAchK7MbxyzUvW+bcF5M/962N6Zd0PL+QvCEZERIAD+R2d/o1a9ZM586dS7b8woULatasWabH07RpU+XNmzfT94ubo8QnAMCTbN26VVu3bpUxRjt37nTOb926VX/99ZeqVaumKVOmWB0mshFKfAIAsqI6derowIEDeuedd1S1alVVrVpVI0eO1IEDB1SnTh2rwwOQhWR20u9W7/RLHM9PcpT3BIC0cLs7/VasWOFSoiHRpUuXtHr16lva1qpVq/TBBx9oy5YtOn78uObOnZtsQOfw8HB98MEHioyMVLVq1TR+/Hg6iW6iZs2aqlGjhv744w9t3rxZf/zxh2rUqGF1WAAA3Jbly5dLknr37q1x48YpICDA4oiQ3XXoIAUESBcuSLNmSePHS0luQAUAwDJ+fn4uPwQGgJQYGUlZOOkXQ9IPwK1zm6Tfjh07nNMRERGKjIx0zickJGjhwoW66667bmmbsbGxqlatmvr06aNHH3002fMzZszQkCFDNHHiRNWtW1djx45Vq1attGfPHgUHB99+Y5Bp+vfvr/79+0ty3O03ceJEiyMCAODOTJ482eoQAElS7txSp07SV19J0dHS//4nde1qdVQAAEh79+7V8uXLdeLECdmvG3j2jTfesCgqAFmNlXf6nb109qbru9zpx5h+ANLIbZJ+1atXl81mk81mS7GMZ+7cuTV+/Phb2mabNm3Upk2bVJ8fM2aM+vbtq969e0ty1IX/5Zdf9PXXX2vo0KG31gBYolu3bhoyZIhiY2P13Xff6cMPP5S/v7/VYQEAcEc2b96smTNn6siRI8kqIPz4448WRYXsqHt3R9JPkmbMIOkHALDeF198oYEDB6pQoUIqUqSIbDab8zmbzUbSD4AkyRjjnE56nshI+XPd/ph+3OkHIK3cJul38OBBGWNUunRp/f777woKCnI+5+Pjo+DgYHl7e6fb/uLj47VlyxYNGzbMuczLy0stWrTQ+vXrb2ubly9f1uXLl53zFy5ckCTZ7fZkvzy7U3a7XcaYdN9uVnOzdvr5+albt2768ssvFRMTo++//15PP/10Jkd55zienoV2epbs0k4p+7Q1o9qZXtubPn26evTooVatWmnx4sVq2bKl/v77b0VFRemRRx5Jl30AadW4sVS0qHT8uLRggXTunJQvn9VRAQCys3feeUcjR47UK6+8YnUoALKwxNKeUubd6efv4y8vm5fsxn7rY/pxpx+ANHKbpF+JEiUkpd8Fs5s5deqUEhISVLhwYZflhQsX1l9//eWcb9GihbZv367Y2FgVK1ZMs2bNUv369VPc5ujRozVixIhky0+ePKlLly6la/x2u13nz5+XMUZeXpnzxWWFtLSzY8eO+vLLLyVJn376qR5++OHMDDFdcDw9C+30LNmlnVL2aWtGtTM6OjpdtjNq1Ch9/PHHCgsLU968eTVu3DiVKlVK/fv3V9Gi/CGIzOXtLXXuLI0bJ8XHS/PmSb16WR0VACA7O3v2rDp16mR1GACyuMTSnlLmJf1sNpvy58qv0xdP68zFMzdd/9+Yf53TIXlDMjI0AB7EbZJ+Se3fv19jx47V7t27JUmhoaF6/vnnVaZMmUyP5bfffkvzusOGDdOQIUOc8xcuXFDx4sUVFBSkgICAdI3LbrfLZrMpKCjI4y/M3qydDzzwgO69915t3bpV27dv1z///KMaNWpkcqR3huPpWWinZ8ku7ZSyT1szqp25cuVKl+3s379fbdu2leSodhAbGyubzaYXXnhBzZo1S/EHRkBG6trVkfSTpOnTSfoBAKzVqVMnLV68WAMGDLA6FABZWNKkn02ZU95TkgrkLpDmpF/inX45vXKqYO6CGR0aAA/hdkm/RYsW6eGHH1b16tXVsGFDSdLatWtVqVIl/fTTT3rggQfSZT+FChWSt7e3oqKiXJZHRUWpSJEit7VNX19f+fr6Jlvu5eWVIRdPbTZbhm07K0lLO/v166eBAwdKkr766ivVqlUrs8JLNxxPz0I7PUt2aaeUfdqaEe1Mr23lz5/fedfgXXfdpV27dqlKlSo6d+6c4uLi0mUfwK2oW1cqUUI6fFj67Tfp5EkpSSV+AAAyVdmyZfX6669rw4YNqlKlinLmzOny/HPPPWdRZACykqRj+mXWnX6SI+knOcb0S7AnyNsr9eGqEsf0K+JfJNPGHQTg/tzuit3QoUP1wgsvaOPGjRozZozGjBmjjRs3avDgwelar93Hx0c1a9bU0qVLncvsdruWLl2aavlOZF2PP/64/Pz8JEnfffedYmJiLI4IAIDb07hxYy1ZskSS45fszz//vPr27atu3bqpefPmFkeH7Mhmc9ztJ0kJCdLs2dbGAwDI3iZNmiR/f3+tXLlSEyZM0Mcff+x8jB071urw0k14eLhCQ0NVu3Ztq0MB3JIV5T2la0k/STcc1++q/apOxp6UxHh+AG6N2yX9du/eraeeeirZ8j59+igiIuKWthUTE6Nt27Zp27ZtkqSDBw9q27ZtOnLkiCRpyJAh+uKLLzR16lTt3r1bAwcOVGxsrHr37n3H7UDmCggIULdu3SQ5xlT6/vvvLY4IAIDbM2HCBHX9/wzLa6+9piFDhigqKkodO3bUV199ZXF0yK7+v5slyVHiEwAAqxw8eDDVx4EDB6wOL92EhYUpIiJCmzZtsjoUwC25lPfMxLvokib9blTiMyomSkaOuxGL+pP0A5B2blfeMygoSNu2bVO5cuVclm/btk3BwcG3tK3Nmzfr/vvvd84njrfXs2dPTZkyRV26dNHJkyf1xhtvKDIyUtWrV9fChQtVuHDhO28IMt2AAQP05ZdfSnJcMO3bty+3xgMA3E6BAtf+SPTy8tLQoUMtjAZwqFpVqlBB+usvafVq6Z9/pGLFrI4KAAAASJlVd/olHZvvRkm/xNKeEkk/ALfGbZJ+b731ll566SX17dtX/fr104EDB9SgQQNJjjH93nvvPWfSLq2aNm3qUr85JYMGDdKgQYNuO25kHTVr1lS9evW0YcMG7dy5U2vWrFGjRo2sDgsAgJu6cOFCmtcNCAjIwEiAlCWW+Bw+XDJGmjlTusWuOQAA6aJPnz43fP7rr7/OpEgAZGWJd9FJ1pX3PH3xdKrr/Rv9r3M6JG9IhsYEwLO4TdJvxIgRGjBggF5//XXlzZtXH330kYYNGyZJCgkJ0fDhwxmMGTcVFhamDRs2SHLc7UfSDwDgDvLly3fTu9ONMbLZbEpISMikqABXiUk/SZoxg6QfAMAaZ8+edZm/cuWKdu3apXPnzqlZs2YWRQUgq8kKY/rd8E6/6CR3+jGmH4Bb4DZJv8Q78mw2m1544QW98MILio6OliTlzZvXytDgRjp16qQhQ4bo5MmT+vHHH/Xvv/8qJIRfywAAsrbly5dbHQJwU+XLO8p87tgh/f67dPSoVLy41VEBALKbuXPnJltmt9s1cOBAlSlTxoKIAGRFLmP6KeuN6Ud5TwC3y22SflLyQVVJ9uFW+fr6qm/fvho1apSuXr2qSZMmaXjiT9IBAMiimjRpYnUIQJp07OhI+knSjz9Kzz9vbTwAAEiOcZCHDBmipk2b6j//+Y/V4QDIApIO+cSdfgA8Sead0dLBPffcowIFCtzwAdzMgAED5OXl+OhPmjRJV65csTgiAABuzerVq/XEE0+oQYMGOnbsmCRp2rRpWrNmjcWRIbvr2PHa9Jw51sUBAMD19u/fr6tXr1odBoAswqryngXzFHROc6cfgIzgVnf6jRgxQoGBgVaHATdXvHhxdejQQT/++KOOHz+uuXPnqnPnzlaHBQBAmsyZM0dPPvmkunfvrj/++EOXL1+WJJ0/f16jRo3SggULLI4Q2VloqFShgvTXX9KaNVJkpFSkiNVRAQCykyHXDSprjNHx48f1yy+/qGfPnhZFBSCrcSnveZPx09NT0jv9Tl88nep6iUk/L5uXgv2CMzwuAJ7DrZJ+Xbt2VXAwJzncubCwMP3444+SpAkTJpD0AwC4jXfeeUcTJ05Ujx49NH36dOfyhg0b6p133rEwMkCy2Rx3+40cKRkjzZsnDRhgdVQAgOxk69atLvNeXl4KCgrSRx99pD59+lgUFYCsxihrl/f8N/pfSVJhv8Ly9vLO8LgAeA63Sfpl5i8u4Pnuv/9+VaxYUbt379bq1au1Y8cOVa1a1eqwAAC4qT179qhx48bJlgcGBurcuXOZHxBwncSkn+Qo8UnSDwCQmZYvX251CADcgFXlPQN9A2WTTUYm1aRfgj1BUTFRkhjPD8Ctc5sx/ZIOruruwsPDFRoaqtq1a1sdSrZls9kUFhbmnA8PD7cwGgAA0q5IkSLat29fsuVr1qxR6dKlLYgIcFW9ulSqlGN6+XLpdOpViwAAyDAnT57UmjVrtGbNGp08edLqcABkMVYl/by9vJUvVz5Jqd/pdyrulBJMgiTG8wNw69wm6We32z2mtGdYWJgiIiK0adMmq0PJ1nr06KG8efNKkr799ludPXvW4ogAALi5vn376vnnn9fGjRtls9n077//6rvvvtNLL72kgQMHWh0e4CzxKUkJCdL//mdtPACA7CU2NlZ9+vRR0aJF1bhxYzVu3FghISF66qmnFBcXZ3V4ALIIlzH9lLkV5hJLfJ6OS/nXcYnj+Ukk/QDcOrdJ+gHpLW/evM5BvOPi4vT1119bHBEAADc3dOhQPf7442revLliYmLUuHFjPf300+rfv7+effZZq8MDJF1L+kmOEp8AAGSWIUOGaOXKlfrpp5907tw5nTt3TvPnz9fKlSv14osvWh0egCwiaVW5zLzTT5IK5ikoSTp36ZwS7AnJnj8enSTpR3lPALeIpB+ytUGDBjmnw8PDlZCQ/IsWAICsxGaz6bXXXtOZM2e0a9cubdiwQSdPntTbb7+tixcvWh0eIEmqU0e66y7H9JIl0vnz1sYDAMg+5syZo6+++kpt2rRRQECAAgIC9OCDD+qLL77Q7NmzrQ4PQBZhVXlPSQr2c1SzMzI6fTH53X7c6QfgTpD0Q7ZWvnx5tW7dWpJ08OBB/fLLLxZHBABA2vj4+Cg0NFR16tRRzpw5NWbMGJVKHEgNsJiXl/Too47p+Hhp0SJr4wEAZB9xcXEqXLhwsuXBwcGU9wTg5FLe05a55T2D8gQ5p0/Enkj2/L/R/zqnQ/KGZEpMADwHST9ke0lLoX3yyScWRgIAQOouX76sYcOGqVatWmrQoIHmzZsnSZo8ebJKlSqljz/+WC+88IK1QabgkUceUf78+fXYY49ZHQoy2cMPX5v+6Sfr4gAAZC/169fXm2++qUuXLjmXXbx4USNGjFD9+vUtjAxAVmJkXXnPxDv9pJSTfpT3BHAnclgdAGC11q1bq2zZstq3b5+WLl2qP//8U5UqVbI6LAAAXLzxxhv6/PPP1aJFC61bt06dOnVS7969tWHDBo0ZM0adOnWSt7e31WEm8/zzz6tPnz6aOnWq1aEgkzVuLOXNK0VHSwsWSAkJUhb8iAIAPMy4cePUqlUrFStWTNWqVZMkbd++Xbly5dIiD7r1PDw8nGFKgDuQFcp7Sqkk/SjvCeAOcKcfsj0vLy+Xu/0mTJhgYTQAAKRs1qxZ+uabbzR79mwtXrxYCQkJunr1qrZv366uXbtmyYSfJDVt2lR58+a1OgxYwMdHatXKMX3mjLRhg7XxAACyh8qVK2vv3r0aPXq0qlevrurVq+vdd9/V3r17PeoHvmFhYYqIiNCmTZusDgVwSy7lPZW55T1vlvT758I/khzJyCL+RTItLgCegaQfIKlXr17y9/eXJH3zzTc6e/asxREBAODqn3/+Uc2aNSU5Lmb5+vrqhRdeuKPxJ1atWqV27dopJCRENpvNWTI0qfDwcJUsWVK5cuVS3bp19fvvv9/2/pD9PPTQtWlKfAIAMkuePHnUt29fffTRR/roo4/09NNPK3fu3FaHBSALycp3+iUm/Yr4F1FO75yZFhcAz0DSD5AUEBCgXr16SXIM+v31119bGxAAANdJSEiQj4+Pcz5HjhzOH6zcrtjYWFWrVk3h4eEpPj9jxgwNGTJEb775pv744w9Vq1ZNrVq10okT1/4wrV69uipXrpzs8e+//6a4TWQvbdpIiXnpn3+2NhYAQPZw+vRp5/TRo0f1xhtv6OWXX9aqVassjApAVmNM1hzT70rCFUXGREqSigUUy9S4AHgGxvQD/t+gQYOcpT3Dw8M1ePDgLFsqDQCQ/Rhj1KtXL/n6+kqSLl26pAEDBsjPz89lvR9//DHN22zTpo3atGmT6vNjxoxR37591bt3b0nSxIkT9csvv+jrr7/W0KFDJUnbtm27xZak7vLly7p8+bJz/sKFC5Iku90uu92e2stui91ulzEm3bebFVnZ1kKFpHr1bFq/3qY//5T277erVKmM2Vd2Oaa007PQTs9CO+98u3di586dateunY4ePapy5cpp+vTpat26tWJjY+Xl5aWPP/5Ys2fPVocOHdInYABuLave6Xc85riMHAlJkn4AbgdJP+D/lS9fXq1atdKiRYt08OBB/fLLL3r44YetDgsAAElSz549XeafeOKJDN1ffHy8tmzZomHDhjmXeXl5qUWLFlq/fn2G7HP06NEaMWJEsuUnT57UpUuX0nVfdrtd58+flzFGXl6eXfzC6rY2aeKn9esd4zpOnx6jp56Ky5D9WN3OzEI7PQvt9Cy0885ER0ff0ev/85//qEqVKvruu+80bdo0PfTQQ2rbtq2++OILSdKzzz6rd999l6QfAEnWjulXKE8h5/T1Sb/E0p6SVCwvST8At46kH5DEc889p0WLFkmSPvnkE5J+AIAsY/LkyZm6v1OnTikhIUGFCxd2WV64cGH99ddfad5OixYttH37dsXGxqpYsWKaNWuW6tevn+K6w4YN05AhQ5zzFy5cUPHixRUUFKSAgIDba0gq7Ha7bDabgoKCPPrCrGR9W7t0kd591zG9dm1eDRt2Z2VpU2N1OzML7fQstNOz0M47kytXrjt6/aZNm7Rs2TJVrVpV1apV06RJk/TMM884Y3z22WdVr1699AgVgAdIvJtOyvw7/Xy8fZQ/V36dvXT2xkk/7vQDcBtI+gFJtG7dWmXLltW+ffu0dOlSRUREKDQ01OqwAABwW7/99lua1/X19XWWL03Ky8srQy6e2my2DNt2VmNlW6tVk4oWlY4fl1autOnKFZtSOMzpIrscU9rpWWinZ6Gdt+9Ot3XmzBkVKVJEkuTv7y8/Pz/lz5/f+Xz+/Pnv+G5CAJ7DyvKekqPEJ0k/ABnBs3uhwC3y8vLSoEGDnPPjx4+3MBoAAKxTqFAheXt7KyoqymV5VFSU84IakBY2m9SypWM6Lk5as8baeAAAnstms91wHgASuZT3tOBckTiuX3R8tC5euehcTtIPwJ0i6Qdcp1evXvL3d5Sd+uabb3T27FmLIwIAIPP5+PioZs2aWrp0qXOZ3W7X0qVLUy3PCaSmVatr0/9fSR0AgHTXq1cvPfroo3r00Ud16dIlDRgwwDnfp08fq8MDkIUYY115T+la0k9yHdePpB+AO0XSD7hOYGCgevbsKUmKi4vL9DGUAADILDExMdq2bZu2bdsmSTp48KC2bdumI0eOSJKGDBmiL774QlOnTtXu3bs1cOBAxcbGqnfv3hZGDXfUooXjjj9JWrzY2lgAAJ6pZ8+eCg4OVmBgoAIDA/XEE08oJCTEOR8cHKwePXpYHSaALMLq8p5F/Ys6p5Mm+pJOh+QNydSYAHgGxvSzQHh4uMLDw5WQkGB1KEjFoEGDFB4eLkmaMGGCnn/+eXl7e1scFQAA6Wvz5s26//77nfNDhgyR5LhoNmXKFHXp0kUnT57UG2+8ocjISFWvXl0LFy5U4cKFrQoZbiooSKpRQ9qyRdq+XYqMlKgSCwBIT/xgF8CtsDrpVyJfCef04fOH1VANJUkHzx2UJBXxLyLfHBk0EDYAj8adfhYICwtTRESENm3aZHUoSEWFChXU6v/rUB08eFC//PKLxREBAJD+mjZtKmNMsseUKVOc6wwaNEiHDx/W5cuXtXHjRtWtWzfD4woPD1doaKhq166d4ftC5kla4pO7/QAAAGAllzH9lPlj+pUITJL0O3dYkhQTH6PImEhJUrkC5TI9JgCegaQfkIpnn33WOf3JJ59YGAkAANkLP5DyTCT9AAAAkFUYWTum3/V3+knS/jP7ncvKFCiT6TEB8Awk/YBUtGnTRmXKOL5gly5dqoiICIsjAgAAcF/16kn+/o7pxYslu/3G6wMAAAAZxfLynoHJk377zuxzLiubv2ymxwTAM5D0A1Lh5eXlcrff+PHjLYwGAADAvfn4SM2aOaZPnpS2bbM0HAAAAGRjLuU9bZlf3jPYL1i5cuSSdK28p0vSrwBJPwC3h6QfcAO9evWSn5+fJOmbb77RuXPnrA0IAADAjSUt8blokXVxAAAAIHszxtrynjabzXm33+Hzh2WMIekHIF2Q9ANuIDAwUL169ZIkxcXFadq0adYGBAAA4MYY1w8AAABZgdXlPaVr4/rFXYnT6Yunte/staQfY/oBuF0k/YCbGDhwoHN64sSJLr8EAgAAQNqVKeN4SNLatVJMjLXxAAAAIHtyKe+pzC/vKV03rt+5w847/QrmLqh8ufJZEhMA90fSD7iJSpUqqWHDhpKkiIgIrV271uKIAAAA3NcDDzj+f+WKI/EHAAAAZDYja8t7SlLJfCWd02uPrtU/F/6RJN1T8B5L4gHgGUj6AWnQv39/5/Tnn39uYSQAAHi+8PBwhYaGqnbt2laHggxw//3Xppctsy4OAAAAZF9Zobxn7ZBrf++MXjPaOd2weEMrwgHgIUj6AWnw2GOPKX/+/JKkWbNm6fTp0xZHBACA5woLC1NERIQ2bdpkdSjIAE2bXpsm6QcAAAArZIWkX/3i9eVt85YkRcZEOpc3LtHYkngAeAaSfkAa5M6dWz179pQkXb58Wd98843FEQEAALin4GCpShXH9B9/SOfOWRoOAAAAsiGXMf1s1ozp5+/jr5ohNV2W2WTTfXffZ0k8ADwDST8gjfr16+ec/vzzz2WMucHaAAAASE1iiU+7XVq1ytpYAAAAkP0kva5n1Z1+ktSkRBOX+aqFqyp/7vwWRQPAE5D0A9KoYsWKatzYcXv9nj17tIorVAAAALelWbNr05T4BAAAQGbLCuU9JallmZYu8+3uaWdRJAA8BUk/4Bb079/fOf35559bGAkAAID7atJE8vr/v0SWL7c2FgAA3FF4eLhCQ0NVu3Ztq0MB3JJLeU9ZU95TkpqXaq4xLceoT/U++qLdF/pv4/9aFgsAz0DSD7gFHTt2VMGCBSVJc+bM0alTpyyOCAAAwP3kyyfVqOGY3rFDOnnS0nAAAHA7YWFhioiI0KZNm6wOBXBLRlmjvKfNZtML9V/QV+2/0tM1npZvDl/LYgHgGUj6AbfA19dXvXr1kiTFx8drypQplsYDAADgrhLH9ZOkFSssCwMAAADZUFYp7wkA6Y0zGnCL+vXr55z+8ssvXQb+BQAAQNokHdePEp8AAADITC7lPW3WlfcEgPRG0g+4Rffcc48aNWokSdqzZ4927txpcUQAAADu5777pBw5HNPLllkbCwAAALIX7vQD4Kk4o1mAwZbdX5cuXZzTM2fOtDASAAA8D32l7MHfX6pTxzG9Z4907Ji18QAAACD7SFq5i6QfAE/CGc0CDLbs/jp27Oi89X/mzJmU+AQAIB3RV8o+KPEJAAAAK3CnHwBPxRkNuA1FihRRkyZNJEl79+7Vjh07LI4IAADA/SRN+q1YYVkYAAAAyGZcxvQTY/oB8Bwk/YDb1LlzZ+c0JT4BAABuXb16Us6cjunVq62NBQAAANmHEeU9AXgmzmjAbXr00Ufl5eX4J0SJTwAAgFuXO/e1cf3+/luKjLQ2HgAAAGQPlPcE4Kk4owG3qXDhwmratKkkad++fdq2bZul8QAAALijxo2vTXO3HwAAADKDS3lPG+U9AXgOkn7AHaDEJwAAwJ1JmvRbtcq6OAAAAJB9JK3YxZ1+ADwJZzTgDjzyyCOU+AQAALgDDRpI/9+dIukHAACATEF5TwCeijMacAeCg4N1//33S5IOHDigP/74w+KIAAAA3EtAgHTvvY7pnTulM2esjQcAAACej6QfAE/FGQ24Q5T4BAAAuDONGjn+b4y0dq21sQAAAMDzuYzpJ8b0A+A5SPoBd+iRRx6Rt7e3JEp8AgCQHsLDwxUaGqratWtbHQoyCeP6AQAAIDMZMaYfAM/EGQ24Q0FBQWrWrJkk6dChQ9q8ebPFEQEA4N7CwsIUERGhTZs2WR0KMsl9912bJukHAACAjEZ5TwCeijMakA4o8QkAAHD7goKk0FDH9JYtUkyMtfEAAADAs7mU97RR3hOA5yDpB6QDSnwCAADcmcQSnwkJ0vr11sYCAAAAz5b02h13+gHwJJzRgHRQsGBBtWjRQpJ05MgR/f777xZHBAAA4F4Y1w8AAACZhfKeADwVZzQgnVDiEwAA4PY1anRtmqQfAAAAMpJLeU9R3hOA5yDpB6STDh06KEeOHJKkWbNmyW633+QVAAAASFSsmFS6tGN640bp8mVr4wEAAIDn4k4/AJ6KMxqQTgoUKKAHHnhAknT06FFt3LjR4ogAAADcS+LdfpcvS1u2WBsLAAAAPJcRY/oB8Eyc0YB0RIlPAACA29ew4bXpNWusiwMAAACejTv9AHgqzmhAOmrfvr1y5swpiRKfAAAAtypp0m/tWuviAAAAgGdzGdPPxph+ADwHST8gHeXPn18tW7aUJB07dkzr16+3OCIAAAD3UaGClD+/Y3rdOsmYG68PAAAA3A5jKO8JwDNxRrNAeHi4QkNDVbt2batDQQagxCcAAMDt8fK6drffqVPS339bGw8AAAA8E+U9AXgqzmgWCAsLU0REhDZt2mR1KMgADz/8sHx8fCQ5SnwmJCRYHBEAAID7YFw/AAAAZDSX8p6ivCcAz0HSD0hn+fLlU6tWrSRJx48f1xquVgEAcEuoipC9Ma4fAAAAMpoR5T0BeCbOaEAG6Nq1q3N6+vTpFkYCAID7oSpC9larlpQzp2OapB8AAAAyAuU9AXgqzmhABnj44YeVO3duSY4Sn1euXLE4IgAAAPeQO7dUs6Zj+u+/pZMnrY0HAAAAnoekHwBPxRkNyAD+/v5q166dJOn06dNaunSpxREBAAC4j/vuuza9bp11cQAAAMAzuYzpZ2NMPwCeg6QfkEGSlvj84YcfLIwEAADAvSQd14/hkQEAAJDejGFMPwCeiTMakEHatGmjgIAASdLcuXN16dIliyMCAABwDw0aXJtmXD8AAACkN8p7AvBUnNGADJIrVy498sgjkqTo6GgtWLDA4ogAAADcQ3CwVK6cY3rLFonfTgEAACA9uZT3FOU9AXgOkn5ABurWrZtzevr06RZGAgAA4F4Sx/WLj5c2b7Y2FgAAMsqePXtUvXp15yN37tyaN2+e1WEBHs+I8p4APBNnNCADNWvWTIUKFZIk/fTTT4qOjrY4IgAAAPeQdFw/SnwCADxV+fLltW3bNm3btk1r1qyRn5+fHnjgAavDAjwe5T0BeCrOaEAGypkzpzp16iRJunTpkv73v/9ZHBEAAIB7SJr0W7PGujjgHoxx3BV69qx07Ji0d6+0Z4/j//v2SQcOSIcOSUeOSMePS6dOSRcuOErHJiRYHT0AOPzvf/9T8+bN5efnZ3UogMdzKe9po7wnAM+Rw+oAAE/XtWtXffbZZ5IcJT67d+9ucUQAAABZX/nyUsGC0unT0rp1kt0uefGTxWwrLk7avduRxNu7V9q/X/r3XykyUoqKcnxO7iR55+Ul5cwp+fg4HonTd7osZ85rn9uk1xOTTsfG+snPL/l6Ka1/o2W3un5qjEmf5UmfM0aKifGTv79j/2l5za3sJ6u4vp2eyhipd2+ro8g8q1at0gcffKAtW7bo+PHjmjt3rjp06OCyTnh4uD744ANFRkaqWrVqGj9+vOrUqXPL+5o5c6Z69OiRTpEDuBFjKO8JwDOR9AMy2H333ae77rpLx44d06JFi3TmzBkVKFDA6rAAAACyNJtNatBA+ukn6cwZx11bFStaHRUyQ0KCtHWr9OuvebRnj01bt0p//eVI/GYUu126fNnxyFxekvJm9k4tQDs9i5d69bI6hswTGxuratWqqU+fPnr00UeTPT9jxgwNGTJEEydOVN26dTV27Fi1atVKe/bsUXBwsCSpevXqunr1arLXLl68WCEhIZKkCxcuaN26dZo+fXrGNgiAJMp7AvBcJP2ADObl5aUuXbpozJgxunLliubMmaO+fftaHRYAAECWd999jqSf5BjXj6SfZ7p61ZHkW7lSWrHCUc71/HkvSQE3fa2Pj1SkiFSokOTn53jkySPlzi3lyOFI5tntjjuT7HZHQvHqVUcp0Ph46coV1//fbFlGJh4BZE1t2rRRmzZtUn1+zJgx6tu3r3r//+2PEydO1C+//KKvv/5aQ4cOlSRt27btpvuZP3++WrZsqVy5ct1wvcuXL+tykl8oXLhwQZJkt9tlT+eTlN1ulzEm3beb1dBOz5LWdiaYJCUCjNzufeF4ehba6Vkyqp1p3R5JPyATdOvWTWPGjJEkfffddyT9AAAA0uD6cf2eftq6WJC+jh+XFi6UFiyQliyRzp9Pfd2cOaXKlaXq1R1lX8uVk8qWle6+WwoMzNwyigkJyZOCN0sYSq6lKZOWvLTb7Tp37pwCA/PJy8vL5bmU1k9t2e2sf6P3LbXnbnV54nN2u13nz59XYGCgvP6/jml67j+rSKmdnshut2f5Y5FZ4uPjtWXLFg0bNsy5zMvLSy1atND69etvaVszZ85Uv379brre6NGjNWLEiGTLT548qUuXLt3SPm8m8TNtjPH4zzTt9BxpbWdsXKxz+uzZszrhfSIzwks3HE/PQjs9S0a1Mzo6Ok3rkfQDMkHNmjVVvnx57dmzRytXrtThw4dVokQJq8MCAADI0mrWdNzJFR/vGNcP7stulzZulH7+Wfr1V8edfakJCpIaNzaqUSNaDzzgr6pVveTrm3mx3oi3t+Nxkxtx0sxul06ciFdwsGePWelo52Xa6SEc7bQ6iqzh1KlTSkhIUOHChV2WFy5cWH/99Veat3P+/Hn9/vvvmjNnzk3XHTZsmIYMGeKcv3DhgooXL66goCAFBNz8Dulb4Ujw2hQUFOTxF2dpp+dIazuT3lVbqEAhZzled8Hx9Cy007NkVDtvVg0gEUk/IBPYbDY9+eST+u9//ytJ+vbbb/Xaa69ZHBUAAFlTeHi4wsPDlZCQcPOV4dFy5ZJq1XIk/PbudVxkdrPrMdlaQoK0erU0Z440d6507FjK6xUoILVoITVtKjVp4ijjaozRiRNxCg729+jkCQBIUmBgoKKiotK0rq+vr3xT+CWEl5dXhlxAtdlsGbbtrIR2epa0tNPo2i3xObxzuOV7wvH0LLTTs2REO9O6Lc9+Z4Es5IknnnBOf/PNNzJJ6+0AAACnsLAwRUREaNOmTVaHgiygQYNr09ztl/XZ7dKyZVL//lJIiHT//dKECckTfjVrSv/9r+OYnjghzZghDRwohYZm/RKOAJCoUKFC8vb2Tpawi4qKUpEiRSyKCkBa2M21sbFsdD4AeBCSfkAmKVGihJo2bSpJ+vvvv7mQCQAAkAZJx/Vbu9a6OHBjf/4pDR0qlSghNW8uTZrkWv7Px0d66CHp668d4/lt3iy9/bZUv76jXCYAuCMfHx/VrFlTS5cudS6z2+1aunSp6tevb2FkAG4m6Y/xvWxcIgfgOSjvCWSiHj16aMWKFZIcd/vVqVPH2oAAAACyOO70y7pOnpS+/VaaNi3lMfpy55YefFDq2FFq21ZK56GmACBTxMTEaN++fc75gwcPatu2bSpQoIDuvvtuDRkyRD179lStWrVUp04djR07VrGxserdu7eFUQO4Gbuu3elH0g+AJyHpB2Sijh07KiwsTBcvXtQPP/ygMWPGyMfHx+qwAAAAsqzgYKlcOceYfps3S5cuOcb6gzWMcYzTN3GiY6y++HjX53PkkFq3lp580pHo8/OzJk4ASC+bN2/W/fff75wfMmSIJKlnz56aMmWKunTpopMnT+qNN95QZGSkqlevroULF6pw4cIZGhdjIAN3Jml5T5J+ADwJZzQgEwUEBKhDhw6SpDNnzujXX3+1NiAAAAA3kHi3X3y8tGWLtbFkVzEx0vjxUqVKUpMm0g8/uCb8ateWPvlE+vdf6aefpM6dSfgB8AxNmzaVMSbZY8qUKc51Bg0apMOHD+vy5cvauHGj6tatm+FxMQYycGdcxvQTY/oB8Bwk/YBM1qNHD+f0N998Y2EkAAAA7oFx/axz/Lj06qtS8eLSc89Ju3dfe65gQenllx3Lfv9devZZKSjIulgBAADSijH9AHgqynsCmaxFixYqUqSIIiMj9dNPP+n06dMqWLCg1WEBAABkWST9Mt+ePdIHHzjG67u+hGejRtKAAY6x+nx9rYkPAADgTlDeE4Cn4owGZLIcOXLoiSeekCRduXJF06ZNszgiAACArK1CBSl/fsf0unWOceWQMQ4ckHr2lEJDpa++upbwy5lT6tVL2rFDWrVKevxxEn4AAMB9uZT3tFHeE4DnIOlngfDwcIWGhqp27dpWhwKLPPXUU87pL774wqWkAAAAAFx5eV0b1+/UKWnvXmvj8USRkY6798qXl775RrL//3WwwEDplVekgwelyZOlKlWsjRMAACA9GFHeE4Bn4oxmAQZbRoUKFXTfffdJkiIiIrRhwwaLIwIAAMjaEpN+EiU+01N8vPThh9I990iffy5dvepYnj+/NGqUdOSI9O670l13WRsnAABAeqK8JwBPxRkNsEjfvn2d01988YWFkQAAAGR9jOuX/hYulCpXll5+WYqOdizz95feeMNR5nPYMCkgwNoYAQApo4oUcGdcynuK8p4APAdJP8Aijz32mAIDAyVJM2bM0IULFyyOCAAAIOuqXVvKkcMxvW6dtbG4uzNnHOP2tWlzrVSqzSb17Svt3y+NGCHly2dpiACAm6CKFHBnkg61w51+ADwJZzTAInny5FH37t0lSXFxcfrhhx8sjggAACDrypNHqlHDMb17tyNxhVs3d64UGuoYty9Ro0bSli3SpElScLB1sQEAAGQWynsC8FSc0QALUeITAAAg7ZKO68fdfrcmNlbq00d69FEpKsqxLDBQ+uoraeVK6d57rY0PAAAgM5H0A+CpOKMBFqpevbpq1aolSdqyZYu2bt1qcUQAAABZF+P63Z7t26VataTJk68ta9dOiohwJAJtDGMDAACyGZcx/egMAfAgJP0Aiz399NPO6YkTJ1oYCQAAQNZG0u/Wff65VLeu9Ndfjnk/P2nqVGn+fCkkxNrYAAAArGLEmH4APBNnNMBi3bp1k7+/vyRp2rRpOnv2rMURAQAAZE1Fi0qlSjmmN22S4uOtjScri4+XBgxwPC5fdiy7917pjz+kHj24uw8AAGRvlPcE4Kk4owEWCwgIUO/evSVJFy9e1FdffWVxRAAAAFlX4rh+ly5JVEZP2YkTUosWjrv8Ej37rLR+vXTPPdbFBQAAkFW4lPcUv4YC4DlI+gFZwKBBg5zT4eHhSkhIsDAaAACsFR4ertDQUNWuXdvqUJAFUeLzxnbtkmrXllavdsz7+krffCN98oljGgDgGegvAXfGGMp7AvBMnNGALOCee+5RmzZtJEmHDh3Szz//bHFEAABYJywsTBEREdq0aZPVoSALIumXupUrpfvuk44cccyHhEirVklPPmltXACA9Ed/CbgzlPcE4Kk4owFZxHPPPeec/uSTTyyMBAAAIOuqVEkKCHBMr1snJfmRdrY2a5bUsqV0/rxjvlYtx7iHdepYGxcAAEBW5FLek8GOAXgQkn5AFtGyZUuVK1dOkrRs2TLt2rXL4ogAAACyHm9vqX59x3RkpHTwoLXxZAUTJkhdukjx8Y75Nm2k5csdd/oBAAAgOe70A+CpOKMBWYSXl5eeffZZ5/z48eMtjAYAACDratDg2nR2L/H5/vvSs89eu+OxTx9p/nzJ39/auAAAALIyI8b0A+CZOKMBWUjPnj2VN29eSdK0adN08uRJiyMCAADIehjXz+Gdd6RXXrk2/+qr0pdfSjlzWhcTAACAO+BOPwCeijMakIUEBASoT58+kqSLFy9qwoQJFkcEAACQ9dSt6yjzKWXPpJ8x0ptv2vT669eWjRzpeDAkDQAAwM25jOknOlAAPAdJPyCLGTJkiHLkyCHJUeIzJibG4ogAAACyFn9/qVo1x/Sff0rnzlkaTqYbM8ZP77xz7eLUhx867vIDAABA2hhDeU8AnokzGpDF3H333Xr88cclSWfPntUXX3xhcUQAAABZT+K4fsZIGzZYG0tmGjdO+vDDvM75Tz6RXnzRwoAAAADckMudfpRKAOBBSPoBWdB//vMf5/RHH32k+Ph4C6MBAADIerLjuH5ffy0NGXLtT7iPP5aefdbCgAAAlgkPD1doaKhq165tdSiAW0pM+lHaE4CnIekHZEGVKlXSww8/LEk6duyYvvnmG4sjAgAAyFqyW9Jv9mypb99r82++adfgwZaFAwCwWFhYmCIiIrRp0yarQwHckpGjvCelPQF4Gs5qQBY1bNgw5/To0aO52w8AACCJ4sUdD0nauFG6csXaeDLS6tVS9+6S/f+rUPXrF6vXX7c2JgAAAHeWeKcfST8AnoazGpBF1atXT61atZIkHTp0SDNnzrQ4IgAAgKwlcVy/uDhpxw5rY8kof/8tdeggJf7+q1cvo+HDo8XQMwAAALePpB8AT8VZDcjCRowY4ZweO3Ysd/sBAAAkkbTE57p11sWRUU6elB58UDpzxjHfqpU0caIh4QcAAHCHnGP60bEC4GFI+gFZWN26dfXggw9Kcozt9/XXX1scEQAAQNbhOq6fZ12wuXhRat9e2r/fMV+1qjRzppQzp7VxAQAAeAJjGNMPgGfirAZkccOHD3dOv/POO4qNjbUuGAAAgCykalXJ398xvXq19P/XbtyeMVL//tL69Y75kBDpl1+kgABr4wIAAPAUlPcE4Kk4qwFZXO3atdWhQwdJ0vHjxzVmzBhrAwIAAMgicuSQ7rvPMR0ZadP+/d7WBpROPvlEmjbNMe3nJ/38s1SsmLUxAQAAeBJneU95VrUIACDpB7iBUaNGydvbcRHr/fffV1RUlMURAQAAZA1Nm16bXrfOx7I40svy5dKLL16bnzxZuvde6+IBAADwREaU9wTgmTirAW6gfPnyeuKJJyRJMTExGjFihMURAQAAZA1Jk37r17t30u/wYalzZykhwTE/dKjUqZO1MQEAAHgiynsC8FSc1QA38eKLL8rPz0+SNGnSJO3cudPiiAAAAKxXo8a1cf3WrfNx23H9Ll+WOnaUTp1yzLduLb3zjrUxAQAAeCpneU8b5T0BeBaSfoCbCAoK0iuvvCJJSkhI0KBBg2Tc9aoWAABAOsmZU2rUyDF94oS3/v7b2nhu13/+I23Z4pguU0b6/nvJ2zOGKAQAZIDw8HCFhoaqdu3aVocCuKXEa2rc6QfA03BWswAdM9yuF198UWXKlJEkrVq1Sj/88IPFEQEAAFgvaYnPFSusiuL2zZ0rffKJY9rXV5o9W8qf39qYAABZW1hYmCIiIrRp0yarQwHcEuU9AXgqzmoWoGOG25UrVy6NGzfOOf/SSy/pwoULFkYEAABgvaRJv5Ur3atE06FDUp8+1+Y//liqXt2qaAAAALIHkn4APBVnNcDNtG3bVu3atZMkHT9+XMOGDbM4IgAAAGs5xvVzlGhauVJuM65ffLzUtat07pxj/rHHpAEDLA0JAAAgW3CO6Sf3+sEYANwMST/ADY0bN0558uSRJH366adauXKlxREBAABYJ0cO6b77HNORkTa3GddvxAhp40bHdOnS0pdfSjauOwEAAGQ4I8b0A+CZOKsBbqhUqVIaNWqUc/7pp59WXFychREBAABYq2nTa7f3ucO4fuvWSe++65jOkUOaMUMKDLQ2JgAAgOyC8p4APBVnNcBNDRo0SA0aNJAk7du3T6+++qrFEQEAAFgn6bh+WT3pFxMj9egh2R3XmjR8uFSrlqUhAQAAZCvO8p6UWQDgYUj6AW7K29tbX331lXx9fSU5Sn4uXLjQ4qgAAACsce+9kr+/4+LNihVZe1y/l16S9u93TNerJ73yirXxAAAAZDfGUN4TgGfirAa4sQoVKui9995zzvfs2VNRUVEWRgQAwJ0LDw9XaGioateubXUocCM5ckh168ZLkiIjpT17LA4oFQsWSJ9/7pjOk0eaNs0ROwAAADIP5T0BeCrOaoCbe+6559SmTRtJ0okTJ9SzZ08lJCRYHBUAALcvLCxMERER2rRpk9WhwM00bBjvnF6yxMJAUnHqlPTUU9fmP/pIKlvWungAAACyK5J+ADwVZzXAzdlsNk2ZMkWFCxeWJC1atEjDhw+3NigAAAALNGlyLemXFaueP/OM4y5ESWrTRurf39p4AAAAsivnmH5iTD8AnoWkH+ABgoOD9f3338vLy/FP+p133tHcuXMtjgoAACBzVax4VUWLOsZnWbFCunTJ2niSmjNHmjXLMV2ggPTVV5KNa0wAAACWMGJMPwCeibMa4CGaNWum999/3znfo0cP7dy508KIAAAAMpfNJrVs6ZiOi5PWrLE2nkRnz0phYdfmw8OlokWtiwcAACC7o7wnAE/FWQ3wIEOGDFHXrl0lSTExMWrTpo3++ecfi6MCAADIPK1aGef0okUWBpLEiy9KUVGO6XbtpC5drI0HAOD+wsPDFRoaqtq1a1sdCuCWnOU9Kb0AwMOQ9AM8iM1m05dffuns9B87dkxt2rTR+fPnLY4MAAAgc7Roca1sZlYY12/JEmnyZMd0QID06aeU9QQA3LmwsDBFRERo06ZNVocCuCVjKO8JwDNxVgM8jJ+fn37++WeVLl1akrRr1y61bdtWMTExFkcGAACQ8QoWlBJveti1Szp2zLpYYmOlfv2uzb//vlSsmHXxAAAAwIHyngA8FWc1wAMFBwdr4cKFKlSokCRp7dq1atu2rWJjYy2ODAAAIOO1bn1tevFi6+L473+lQ4cc002aSH37WhcLAAAArnGW9xQlGAB4FpJ+gIcqV66clixZovz580uSVq1apbZt2+rChQsWRwYAAJCxkib9fvrJmhg2bJDGjXNM58olffGF5MVfXwAAAFmCEeU9AXgmzmqAB6tevboWL16sgIAASdLKlSvVpEkTRUZGWhwZAABAxqlTRwoOdkwvXCjFxWXu/i9flp56Svr/oWI0YoRUrlzmxgAAAIDUUd4TgKfirAZ4uFq1amnJkiUqWLCgJGnbtm1q2LCh9u/fb3FkAAAAGcPbW+rQwTF98aK0aFHm7n/0aCkiwjFdo4Y0ZEjm7h8AAAA3RtIPgKfirAZkA3Xq1NGaNWtUvHhxSdKBAwfUoEEDrVu3zuLIAAAAMsajj16b/vHHzNvvrl3SqFGOaW9v6auvpBw5Mm//AAAAuDnnmH42xvQD4FlI+gHZRIUKFbRu3TpVqlRJknTixAk1bdpU4eHhMom1pwAAADzE/fdLgYGO6Z9+kuLjM36fCQnS009LV6445l95RapePeP3CwAAgLRLeh2MO/0AeBrOakA2UqxYMa1evVpNmzaVJF25ckWDBg1Sz549FZfZg90AAABkIB8f6aGHHNPnz0vLl2f8PseNkzZudEyXLy+9/nrG7xMAAAC3xoikHwDPxVkNyGby58+vJUuWaEiSwWWmTZum2rVra8uWLRZGBgAAkL4ys8Tnvn3Sf//rmLbZHGU9c+XK2H0CAADg1iWW9pQkmyjvCcCzkPQDsqEcOXLoo48+0vTp0+Xn5ydJioiIUL169TRixAhdSaxJBQAA4MZatZJy53ZMz517rexmerPbpb59pYsXHfODBkkNG2bMvgAAAHBnKO8JwJNxVgOysS5dumjjxo269957JUlXr17V8OHDVa9ePW1MrE0FAADgpvz8pLZtHdMnT0qLF2fMfr74QlqxwjFdsqQ0alTG7AcAAAB3LumdfiT9AHgazmpANlepUiVt2LBBb7zxhry9vSVJf/zxh+rVq6fevXsrMjLS4ggBAABuX48e16anTUv/7R89Kr388rX5SZMkf//03w8AAADSh0t5TxvlPQF4FpJ+AOTj46MRI0Zow4YNqly5snP5lClTdM8992jUqFGKjo62MEIAAIDb07q1VKiQY3rePOns2fTbtjHSgAFSYjepTx/pgQfSb/sAAABIf0aU9wTguTirAXCqVauWtm7dqk8++UT58uWTJEVHR+u1115T6dKl9f777ys2NtbaIAEAAG5BzpxS9+6O6cuXpalT02/b334rLVjgmC5aVProo/TbNgAAADIG5T0BeDLOagBc5MiRQ88++6z+/vtv9e3bV15ejtPEqVOn9Morr6hkyZJ6/fXX9e+//1ocKQAAQNr0739teuJExx16d+rwYWnQoGvzn30m/f9vpgAAAJCFkfQD4Mk4qwFIUVBQkCZNmqSIiAg9/vjjzhrnp06d0jvvvKMSJUqoe/fuWr16tUx6XDkDAADIIBUrSk2aOKb37JGWLLmz7SUkSE8+KV244Jh/4gmpffs72yYAALciPDxcoaGhql27ttWhAG7HZUw/MaYfAM9C0g/ADZUvX17fffed/vzzTz3++OPKkSOHJOnq1av6/vvv1bhxY5UrV05vv/22Dh06ZG2wAAAAqUh6V957793Ztt5/X1q92jFdooQ0YcKdbQ8AgFsVFhamiIgIbdq0yepQALeT9Mfr3OkHwNNwVgOQJhUrVtR3332nQ4cO6dVXX1XBggWdz+3fv19vvPGGSpUqpRo1auitt97Szp07uQMQAABkGY88IpUr55hetkzasOH2trN8ufT6645pLy9p2jQpMDB9YgQAAEDGo7wnAE/GWQ3ALbnrrrs0cuRIHT16VN9++61atGjhLP0pSVu3btWbb76pqlWrqmzZsgoLC9OcOXN06tQpC6MGAADZnbe39PLL1+aHDr31sf2OHpW6dHGU95SkV1+VGjVKvxgBAACQ8VzKe9oo7wnAs5D0A3BbcufOre7du2vJkiU6fPiwRo0apVq1armsc+DAAX366ad67LHHFBQUpGrVqun555/X999/r3379nEnIAAAyFS9el2722/lSumnn9L+2rg4qWNH6eRJx3yrVtLw4ekdIQAAADKaEeU9AXiuHFYHAMD9FS9eXMOGDdOwYcN09OhRzZ8/X/PmzdOKFSuUkPhTeEk7duzQjh07nPP58+dXrVq1dO+996pSpUqqUKGCS9lQAACA9JQzpzRqlNSpk2P+mWekJk1uXp7z8mXp0UelxGGTSpWSvv/ecfcgAAAA3AvlPQF4MpJ+ANJV8eLFNWjQIA0aNEjR0dFavXq1li9fruXLl+uPP/5wubvv7NmzWrJkiZYsWeKyjRIlSig0NFRly5ZVqVKlVLJkSZUsWVKlSpVSvnz5MrlFAADAk3TsKLVsKS1eLB07JvXvL/3wg5RaZacrVxwlPRctcsznzSv9+KNUoEDmxQwAAID0Q9IPgCcj6Qcgw+TNm1cPPvigHnzwQUmOJN/GjRv1+++/a9OmTfr999914sSJZK87fPiwDh8+nOI2AwICVLRoURUuXFhFihRR4cKFXR758+dXYGCg8uXLp8DAQPn7+8vLiw4cAABwsNmkL76QKleWoqOlGTOkEiWkd99Nnvg7c0bq2lVK/H1SnjzSggVS9eqZHjYAAADSicuYfmJMPwCehaQfgEyTP39+tW7dWq1bt5YkGWP0zz//aNeuXYqIiNCff/6pHTt2aO/evbpw4UKK27hw4YIuXLigPXv2pGmfXl5eCggISJYI9PPzU548eZz/T2k6d+7cypkzp3x8fJz/Tzqd0nM5cuSQl5eX88GA0AAAZD133y19+63UoYNkjPT++9KBA47/lyolXbzouPvvtdekyEjHa3x9pfnzpfvuszR0AAAA3KGkVai40w+ApyHpB8AyNptNxYsXV/HixdWmTRvZ7XadOHFCQUFBioqK0sGDB3Xw4EEdOnTI+Th8+LAiIyMVExOTpn3Y7XadO3dO586dS/XuwYxks9lckoDe3t7OZKC3t7dzPnGZpyUJ7XZ7trjTMmk7Pe0YXi87HNN7771XX375pdVhAMhgDz8sTZggDRrkSPzNnu14BAdLZ886ynomKlTIUdKzUSPr4gUAAED6oLwnAE9G0g9AlmOz2RQSEqKQkBA1bNgwxXXi4uIUFRWlyMhIRUVFKSoqSidOnNC5c+d0/vx5nT9/3jmd9P/x8fGZ2hZjjBISEpSQkJCp+wVw+4oXL251CAAyyTPPSEWKSH37Okp5StL1lcfbtZM++0y6667Mjw8AAADpz+janX6e/sNdANkPST8AbilPnjwqVaqUSpUqdUuvu3TpkmJjYxUbG6u4uDjn/5NOJ/7/4sWLunLliuLj45P9P7VlCQkJstvtstvtLtPXz8fHx8tms7k8b7fbb94AN5OQkCBvb+90327SUhxZQUa1M72k5/uVHe70CwoKsjoEAJno0Uelpk2lTz91jNf377+Sv79Uv7701FNSvXpWRwgAAAAAQNqQ9LNAeHi4wsPDufMHsECuXLmUK1cuFSxY0LIYEsuYBgcHe3TyhHZ6nuzS1sR2Asg+ChSQ/vtfxwMAAAAAAHfluVfssrCwsDBFRERo06ZNVocCAAAAAAAAAAAAD0DSDwAAAAAAAAAAAHBzJP0AAAAAAAAAAAAAN0fSDwAAAAAAAAAAAHBzJP0AAAAAAAAAAAAAN0fSDwAAAAAAAAAAAHBzJP0AAACQIY4ePaqmTZsqNDRUVatW1axZs6wOCQAAAAAAwGPlsDoAAAAAeKYcOXJo7Nixql69uiIjI1WzZk09+OCD8vPzszo0AAAAAAAAj0PSDwAAABmiaNGiKlq0qCSpSJEiKlSokM6cOUPSDwAAAAAAIANQ3hMAACCbWrVqldq1a6eQkBDZbDbNmzcv2Trh4eEqWbKkcuXKpbp16+r333+/rX1t2bJFCQkJKl68+B1GDQAAAAAAgJSQ9AMAAMimYmNjVa1aNYWHh6f4/IwZMzRkyBC9+eab+uOPP1StWjW1atVKJ06ccK5TvXp1Va5cOdnj33//da5z5swZ9ejRQ5MmTcrwNgEAAAAAAGRXlPcEAADIptq0aaM2bdqk+vyYMWPUt29f9e7dW5I0ceJE/fLLL/r66681dOhQSdK2bdtuuI/Lly+rQ4cOGjp0qBo0aHDTdS9fvuycv3DhgiTJbrfLbrenpUlpZrfbZYxJ9+1mRdmlrbTTs9BOz0I7PUtGtdPT37f0Fh4ervDwcCUkJFgdCgAAyEJI+gEAACCZ+Ph4bdmyRcOGDXMu8/LyUosWLbR+/fo0bcMYo169eqlZs2Z68sknb7r+6NGjNWLEiGTLT548qUuXLqU9+DSw2+06f/68jDHy8vLs4hfZpa2007PQTs9COz1LRrUzOjo63baVHYSFhSksLEwXLlxQYGCg1eEAAIAsgqQfAAAAkjl16pQSEhJUuHBhl+WFCxfWX3/9laZtrF27VjNmzFDVqlWd4wVOmzZNVapUSXH9YcOGaciQIc75CxcuqHjx4goKClJAQMDtNSQVdrtdNptNQUFBHn1hVso+baWdnoV2ehba6Vkyqp25cuVKt20BAABkVyT9AAAAkCHuu+++WyrV5evrK19f32TLvby8MuTiqc1my7BtZzXZpa2007PQTs9COz1LRrTT098zAACAzEDSz0LGGEnXxqtJT3a7XdHR0cqVK5dHd5xpp2ehnZ6Fdnqe7NLWjGpn4vd94vd/VleoUCF5e3srKirKZXlUVJSKFCmSKTHQV0of2aWttNOz0E7PQjs9C32lrIX+0p2jnZ4lLe2MvhAt/f/oAVfirmTIv5+MxvH0LLTTs1jdVyLpZ6HEevXFixe3OBIAAJBZoqOj3WLcFR8fH9WsWVNLly5Vhw4dJDk6rkuXLtWgQYMyJQb6SgAAZD/u0lfKKugvAXdmzv//BwDu4mZ9JZJ+FgoJCdHRo0eVN29e2Wy2dN124hg4R48eTfcxcLIS2ulZaKdnoZ2eJ7u0NaPaaYxRdHS0QkJC0m2bdyomJkb79u1zzh88eFDbtm1TgQIFdPfdd2vIkCHq2bOnatWqpTp16mjs2LGKjY1V7969MyU++krpI7u0lXZ6FtrpWWinZ8lOfSV3QH/pztFOz0I7PQvt9Cy0886kta9E0s9CXl5eKlasWIbuIyAgwKP/ASWinZ6FdnoW2ul5sktbM6KdWe1X65s3b9b999/vnB8yZIgkqWfPnpoyZYq6dOmikydP6o033lBkZKSqV6+uhQsXqnDhwpkSH32l9JVd2ko7PQvt9Cy007Nkh76SO6C/lH5op2ehnZ6FdnoW2nn70tJXIukHAACQTTVt2vSmteAHDRqUaeU8AQAAAAAAcPs8d7REAAAAAAAAAAAAIJsg6eehfH199eabb8rX19fqUDIU7fQstNOz0E7Pk13aml3amd1lp+OcXdpKOz0L7fQstNOzZJd2Ivsca9rpWWinZ6GdnoV2Zg6buVlNJwAAAAAAAAAAAABZGnf6AQAAAAAAAAAAAG6OpB8AAAAAAAAAAADg5kj6AQAAAAAAAAAAAG6OpB8AAAAAAAAAAADg5kj6eajw8HCVLFlSuXLlUt26dfX7779bHdIdGT58uGw2m8ujQoUKzucvXbqksLAwFSxYUP7+/urYsaOioqIsjDhtVq1apXbt2ikkJEQ2m03z5s1zed4YozfeeENFixZV7ty51aJFC+3du9dlnTNnzqh79+4KCAhQvnz59NRTTykmJiYTW3FzN2tnr169kh3f1q1bu6yT1ds5evRo1a5dW3nz5lVwcLA6dOigPXv2uKyTls/pkSNH1LZtW+XJk0fBwcF6+eWXdfXq1cxsyg2lpZ1NmzZNdjwHDBjgsk5Wb+dnn32mqlWrKiAgQAEBAapfv75+/fVX5/OecCylm7fTE45lSt59913ZbDYNHjzYucxTjinSjr4SfaWsJDv0lST6S0l5wncs/SUHTziW16OvBIm+En2lrNWHoK90jSecj+krOXjCsZSyZ19JyuL9JQOPM336dOPj42O+/vpr8+eff5q+ffuafPnymaioKKtDu21vvvmmqVSpkjl+/LjzcfLkSefzAwYMMMWLFzdLly41mzdvNvXq1TMNGjSwMOK0WbBggXnttdfMjz/+aCSZuXPnujz/7rvvmsDAQDNv3jyzfft28/DDD5tSpUqZixcvOtdp3bq1qVatmtmwYYNZvXq1KVu2rOnWrVsmt+TGbtbOnj17mtatW7sc3zNnzrisk9Xb2apVKzN58mSza9cus23bNvPggw+au+++28TExDjXudnn9OrVq6Zy5cqmRYsWZuvWrWbBggWmUKFCZtiwYVY0KUVpaWeTJk1M3759XY7n+fPnnc+7Qzv/97//mV9++cX8/fffZs+ePebVV181OXPmNLt27TLGeMaxNObm7fSEY3m933//3ZQsWdJUrVrVPP/8887lnnJMkTb0legrZaU+hDHZo69kDP0l+kvudyyNyX79JfpKMIa+En2lrNeHoK9EX8kdv1/pK3lmX8mYrN9fIunngerUqWPCwsKc8wkJCSYkJMSMHj3awqjuzJtvvmmqVauW4nPnzp0zOXPmNLNmzXIu2717t5Fk1q9fn0kR3rnrOy12u90UKVLEfPDBB85l586dM76+vuaHH34wxhgTERFhJJlNmzY51/n111+NzWYzx44dy7TYb0VqnbP27dun+hp3bOeJEyeMJLNy5UpjTNo+pwsWLDBeXl4mMjLSuc5nn31mAgICzOXLlzO3AWl0fTuNcXyZJ/3Cu547ttMYY/Lnz2++/PJLjz2WiRLbaYznHcvo6GhTrlw5s2TJEpe2efoxRXL0legrZeU+RHbpKxlDf8mTvmMT0V9Kzp3aSV8Jiegr0VfKyn0I+kqedz6mr+TgCccykaf2lYxxj/4S5T09THx8vLZs2aIWLVo4l3l5ealFixZav369hZHdub179yokJESlS5dW9+7ddeTIEUnSli1bdOXKFZc2V6hQQXfffbdbt/ngwYOKjIx0aVdgYKDq1q3rbNf69euVL18+1apVy7lOixYt5OXlpY0bN2Z6zHdixYoVCg4OVvny5TVw4ECdPn3a+Zw7tvP8+fOSpAIFCkhK2+d0/fr1qlKligoXLuxcp1WrVrpw4YL+/PPPTIw+7a5vZ6LvvvtOhQoVUuXKlTVs2DDFxcU5n3O3diYkJGj69OmKjY1V/fr1PfZYXt/ORJ50LMPCwtS2bVuXYyd57r9PpIy+kgN9pazbh0iNp/WVJPpLnvQdS3/JM44lfSVI9JUS0VfK2n2IlNBXct/zMX0lB084lp7eV5Lco7+UI922hCzh1KlTSkhIcPngSFLhwoX1119/WRTVnatbt66mTJmi8uXL6/jx4xoxYoQaNWqkXbt2KTIyUj4+PsqXL5/LawoXLqzIyEhrAk4HibGndCwTn4uMjFRwcLDL8zly5FCBAgXcqu2tW7fWo48+qlKlSmn//v169dVX1aZNG61fv17e3t5u10673a7BgwerYcOGqly5siSl6XMaGRmZ4vFOfC6rSamdkvT444+rRIkSCgkJ0Y4dO/TKK69oz549+vHHHyW5Tzt37typ+vXr69KlS/L399fcuXMVGhqqbdu2edSxTK2dkuccS0maPn26/vjjD23atCnZc5747xOpo690DX0l92m7p/WVJPpLnvIdS3/Jc44lfSUkoq90DX0l92k7fSX3PR/TV8rnsr67Hsvs0FeS3Ke/RNIPbqFNmzbO6apVq6pu3boqUaKEZs6cqdy5c1sYGdJD165dndNVqlRR1apVVaZMGa1YsULNmze3MLLbExYWpl27dmnNmjVWh5KhUmtnv379nNNVqlRR0aJF1bx5c+3fv19lypTJ7DBvW/ny5bVt2zadP39es2fPVs+ePbVy5Uqrw0p3qbUzNDTUY47l0aNH9fzzz2vJkiXKlSuX1eEAGYK+kmfztL6SRH/JU75j6S95Rn+JvhKyA/pKno2+kvuir+QZPL2vJLlXf4nynh6mUKFC8vb2VlRUlMvyqKgoFSlSxKKo0l++fPl0zz33aN++fSpSpIji4+N17tw5l3Xcvc2Jsd/oWBYpUkQnTpxwef7q1as6c+aMW7e9dOnSKlSokPbt2yfJvdo5aNAg/fzzz1q+fLmKFSvmXJ6Wz2mRIkVSPN6Jz2UlqbUzJXXr1pUkl+PpDu308fFR2bJlVbNmTY0ePVrVqlXTuHHjPO5YptbOlLjrsdyyZYtOnDihGjVqKEeOHMqRI4dWrlypTz75RDly5FDhwoU96pjixugrXePubaav5J59JYn+Ukrc9TuW/lJy7ngs6SshKfpK17h7m+kr0VdK+nzic1kJfSXPOZae3leS3Ku/RNLPw/j4+KhmzZpaunSpc5ndbtfSpUtd6ui6u5iYGO3fv19FixZVzZo1lTNnTpc279mzR0eOHHHrNpcqVUpFihRxadeFCxe0ceNGZ7vq16+vc+fOacuWLc51li1bJrvd7jyBuqN//vlHp0+fVtGiRSW5RzuNMRo0aJDmzp2rZcuWqVSpUi7Pp+VzWr9+fe3cudOlI7pkyRIFBAQ4b4m32s3amZJt27ZJksvxzOrtTIndbtfly5c95limJrGdKXHXY9m8eXPt3LlT27Ztcz5q1aql7t27O6c9+ZjCFX0lB/pKWacPcTvcsa8k0V+6EXf9jr0e/SX3PJb0lZAUfSUH+kpZqw9xq+grZe3zMX0l+kqS+x1Lt+ovGXic6dOnG19fXzNlyhQTERFh+vXrZ/Lly2ciIyOtDu22vfjii2bFihXm4MGDZu3ataZFixamUKFC5sSJE8YYYwYMGGDuvvtus2zZMrN582ZTv359U79+fYujvrno6GizdetWs3XrViPJjBkzxmzdutUcPnzYGGPMu+++a/Lly2fmz59vduzYYdq3b29KlSplLl686NxG69atzb333ms2btxo1qxZY8qVK2e6detmVZNSdKN2RkdHm5deesmsX7/eHDx40Pz222+mRo0aply5cubSpUvObWT1dg4cONAEBgaaFStWmOPHjzsfcXFxznVu9jm9evWqqVy5smnZsqXZtm2bWbhwoQkKCjLDhg2zokkpulk79+3bZ9566y2zefNmc/DgQTN//nxTunRp07hxY+c23KGdQ4cONStXrjQHDx40O3bsMEOHDjU2m80sXrzYGOMZx9KYG7fTU45lapo0aWKef/5557ynHFOkDX0l+kpZqQ9hTPboKxlDf4n+kvsdS2Oyb3+JvlL2Rl+JvlJW60PQV6Kv5I7fr/SVPLuvZEzW7S+R9PNQ48ePN3fffbfx8fExderUMRs2bLA6pDvSpUsXU7RoUePj42Puuusu06VLF7Nv3z7n8xcvXjTPPPOMyZ8/v8mTJ4955JFHzPHjxy2MOG2WL19uJCV79OzZ0xhjjN1uN6+//ropXLiw8fX1Nc2bNzd79uxx2cbp06dNt27djL+/vwkICDC9e/c20dHRFrQmdTdqZ1xcnGnZsqUJCgoyOXPmNCVKlDB9+/ZN9sdEVm9nSu2TZCZPnuxcJy2f00OHDpk2bdqY3Llzm0KFCpkXX3zRXLlyJZNbk7qbtfPIkSOmcePGpkCBAsbX19eULVvWvPzyy+b8+fMu28nq7ezTp48pUaKE8fHxMUFBQaZ58+bOTpkxnnEsjblxOz3lWKbm+o6ZpxxTpB19JfpKWUl26CsZQ3+J/pL7HUtjsm9/ib4S6CvRV8pK6CtNdq7jCedj+koOnnAsjcm+fSVjsm5/yWaMMbd/nyAAAAAAAAAAAAAAqzGmHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBQBZVsmRJjR071uowAAAAsiT6SgAAAKmjrwRkTyT9AEBSr1691KFDB0lS06ZNNXjw4Ezb95QpU5QvX75kyzdt2qR+/fplWhwAAACpoa8EAACQOvpKALKKHFYHAACeKj4+Xj4+Prf9+qCgoHSMBgAAIGuhrwQAAJA6+koAbgd3+gFAEr169dLKlSs1btw42Ww22Ww2HTp0SJK0a9cutWnTRv7+/ipcuLCefPJJnTp1yvnapk2batCgQRo8eLAKFSqkVq1aSZLGjBmjKlWqyM/PT8WLF9czzzyjmJgYSdKKFSvUu3dvnT9/3rm/4cOHS0pehuHIkSNq3769/P39FRAQoM6dOysqKsr5/PDhw1W9enVNmzZNJUuWVGBgoLp27aro6OiMfdMAAEC2QV8JAAAgdfSVAFiNpB8AJDFu3DjVr19fffv21fHjx3X8+HEVL15c586dU7NmzXTvvfdq8+bNWrhwoaKiotS5c2eX10+dOlU+Pj5au3atJk6cKEny8vLSJ598oj///FNTp07VsmXL9J///EeS1KBBA40dO1YBAQHO/b300kvJ4rLb7Wrfvr3OnDmjlStXasmSJTpw4IC6dOnist7+/fs1b948/fzzz/r555+1cuVKvfvuuxn0bgEAgOyGvhIAAEDq6CsBsBrlPQEgicDAQPn4+ChPnjwqUqSIc/mECRN07733atSoUc5lX3/9tYoXL66///5b99xzjySpXLlyev/99122mbSOe8mSJfXOO+9owIAB+vTTT+Xj46PAwEDZbDaX/V1v6dKl2rlzpw4ePKjixYtLkr755htVqlRJmzZtUu3atSU5OnFTpkxR3rx5JUlPPvmkli5dqpEjR97ZGwMAACD6SgAAADdCXwmA1bjTDwDSYPv27Vq+fLn8/f2djwoVKkhy/AoqUc2aNZO99rffflPz5s111113KW/evHryySd1+vRpxcXFpXn/u3fvVvHixZ0dM0kKDQ1Vvnz5tHv3bueykiVLOjtmklS0aFGdOHHiltoKAABwq+grAQAApI6+EoDMwp1+AJAGMTExateund57771kzxUtWtQ57efn5/LcoUOH9NBDD2ngwIEaOXKkChQooDVr1uipp55SfHy88uTJk65x5syZ02XeZrPJbren6z4AAACuR18JAAAgdfSVAGQWkn4AcB0fHx8lJCS4LKtRo4bmzJmjkiVLKkeOtJ86t2zZIrvdro8++kheXo6bq2fOnHnT/V2vYsWKOnr0qI4ePer8VVZERITOnTun0NDQNMcDAABwp+grAQAApI6+EgArUd4TAK5TsmRJbdy4UYcOHdKpU6dkt9sVFhamM2fOqFu3btq0aZP279+vRYsWqXfv3jfsWJUtW1ZXrlzR+PHjdeDAAU2bNs05EHPS/cXExGjp0qU6depUiuUZWrRooSpVqqh79+76448/9Pvvv6tHjx5q0qSJatWqle7vAQAAQGroKwEAAKSOvhIAK5H0A4DrvPTSS/L29lZoaKiCgoJ05MgRhYSEaO3atUpISFDLli1VpUoVDR48WPny5XP+0iol1apV05gxY/Tee++pcuXK+u677zR69GiXdRo0aKABAwaoS5cuCgoKSjZgs+QopzB//nzlz59fjRs3VosWLVS6dGnNmDEj3dsPAABwI/SVAAAAUkdfCYCVbMYYY3UQAAAAAAAAAAAAAG4fd/oBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kHwAAAAAAAAAAAODmSPoBAAAAAAAAAAAAbo6kH5CFNW3aVE2bNnXOHzp0SDabTVOmTHEuGz58uGw22y1tN6XtIDm73a7KlStr5MiRVodyU7169VLJkiVv6TUrVqyQzWbTihUrMiSm7KhkyZLq1avXLb8upX+TQ4cOVd26ddMvOABAurqd796kr/X390/fgG7RlClTZLPZdOjQIUvjAAAA2VNmXZu63b/TcWtsNpsGDRp0W6/l+hSQvkj6Aelo//796t+/v0qXLq1cuXIpICBADRs21Lhx43Tx4kWrw8sSssJFrrT64YcfdPTo0dvutCDzfP/99xo7dmym7GvdunUaPny4zp07l6H7GTx4sLZv367//e9/GbofAPAkM2fOlM1m09y5c5M9V61aNdlsNi1fvjzZc3fffbcaNGiQGSHekri4OA0fPtzSCyCJPzA7deqUZTHcihUrVujRRx9VkSJF5OPjo+DgYLVr104//vij1aF5hFGjRmnevHlWhwEAcAOJPzBK6TF06FCrw0vmTpJWmSUxUZr0ERAQoOrVq2vChAlKSEiwOkQAWUAOqwMAPMUvv/yiTp06ydfXVz169FDlypUVHx+vNWvW6OWXX9aff/6pSZMmpft+//vf/95yZ6lEiRK6ePGicubMme7xeJIPPvhAXbt2VWBgoNWhZIjGjRvr4sWL8vHxsTqUO/b9999r165dGjx4cIbva926dRoxYoR69eqlfPnyuTy3Z88eeXmlz+9pihQpovbt2+vDDz/Uww8/nC7bBABPd99990mS1qxZo0ceecS5/MKFC9q1a5dy5MihtWvX6v7773c+d/ToUR09elRdu3a9pX198cUXstvt6RN4KuLi4jRixAhJcqn+gJS9+eabeuutt1SuXDn1799fJUqU0OnTp7VgwQJ17NhR3333nR5//HGrw3Rro0aN0mOPPaYOHTpYHQoAwE289dZbKlWqlMuyypUrc23qDnTr1k0PPvigJOn8+fNasGCBnn32WR0+fFgffPCBxdEBsBpJPyAdHDx4UF27dlWJEiW0bNkyFS1a1PlcWFiY9u3bp19++SVD9p0jRw7lyHFr/5RtNpty5cqVIfF4iq1bt2r79u366KOPbrpubGys/Pz8MiGq9OXl5cXnIJ35+vqm6/Y6d+6sTp066cCBAypdunS6bhsAPFFISIhKlSqlNWvWuCxfv369jDHq1KlTsucS5xMThmnFBaqsZfbs2Xrrrbf02GOP6fvvv3c5Pi+//LIWLVqkK1euWBghAADZU5s2bVSrVq0Un+OaxO2pUaOGnnjiCef8M888o7p16+r777+/YdLPGKNLly4pd+7cmREmAItQ3hNIB++//75iYmL01VdfuST8EpUtW1bPP/+8c/7q1at6++23VaZMGfn6+qpkyZJ69dVXdfny5Vved0pj+i1ZskT33Xef8uXLJ39/f5UvX16vvvqq8/nU6qYvW7ZMjRo1kp+fn/Lly6f27dtr9+7dKe5v3759zjudAgMD1bt3b8XFxd1y/KmZNWuWatasqdy5c6tQoUJ64okndOzYMZd1IiMj1bt3bxUrVky+vr4qWrSo2rdv7zI2zebNm9WqVSsVKlRIuXPnVqlSpdSnT5+b7n/evHny8fFR48aNXZYntj8iIkKPP/648ufP73KR8Ntvv3XGXaBAAXXt2lVHjx512UbTpk1VuXJlbdmyRQ0aNHDGNXHiRJf1UhtrJ621zqdPn66aNWsqb968CggIUJUqVTRu3LhUtzNo0CD5+/uneBy7deumIkWKuJSK+PXXX52fl7x586pt27b6888/bxhT0natWrVK/fv3V8GCBRUQEKAePXro7Nmzydb/9NNPValSJfn6+iokJERhYWEupTWbNm2qX375RYcPH3aWt0g6xtLly5f15ptvqmzZsvL19VXx4sX1n//8J9m/t8RSHvPmzVPlypXl6+urSpUqaeHChc51hg8frpdfflmSVKpUKef+Eo/R9WMFnDlzRi+99JKqVKkif39/BQQEqE2bNtq+fftN3ydJatGihSRp/vz5aVofAOBI3m3dutWltPratWtVqVIltWnTRhs2bHC5Q2/t2rWy2Wxq2LChc1lavs9TGtPv9OnTevLJJxUQEKB8+fKpZ8+e2r59e6rj1Rw7dkwdOnSQv7+/goKC9NJLLzm/aw8dOqSgoCBJ0ogRI5zfOcOHD3e+/q+//tJjjz2mAgUKKFeuXKpVq1aKZaH//PNPNWvWTLlz51axYsX0zjvvpPtdimnpR0ZHR2vw4MEqWbKkfH19FRwcrAceeEB//PGHc529e/eqY8eOKlKkiHLlyqVixYqpa9euOn/+/A33//rrr6tAgQL6+uuvU0zItmrVSg899JBz/sSJE3rqqadUuHBh5cqVS9WqVdPUqVNdXpPYZ/7www8VHh6u0qVLK0+ePGrZsqWOHj0qY4zefvttFStWTLlz51b79u115swZl22ULFlSDz30kBYvXqzq1asrV65cCg0NTbHc6IEDB9SpUycVKFBAefLkUb169ZL9cDCx/zZz5kyNHDlSxYoVU65cudS8eXPt27cv2TY3btyo1q1bKzAwUHny5FGTJk20du1al3XS2r+32WyKjY3V1KlTnZ/HxH5PWo4tAABJpXRtKnFImBv1kRJ9+OGHatCggQoWLKjcuXOrZs2amj17dobGHBsbqxdffFHFixeXr6+vypcvrw8//FDGGJf1bnZdTpLGjx+vSpUqKU+ePMqfP79q1aql77///rbistlsKly4cLKbAhL7IYsWLVKtWrWUO3duff7555Kkc+fOafDgwc62lC1bVu+9916yPuKdvM/vvPOOvLy8NH78eOeyf/75Rx06dJCfn5+Cg4P1wgsvpHo99GbXBv/3v//JZrNpx44dzmVz5syRzWbTo48+6rKtihUrqkuXLi7v2c2uAQHuijv9gHTw008/qXTp0mkeC+bpp5/W1KlT9dhjj+nFF1/Uxo0bNXr0aO3evTvFMWhuxZ9//qmHHnpIVatW1VtvvSVfX1/t27cv2R/31/vtt9/Upk0blS5dWsOHD9fFixc1fvx4NWzYUH/88Ueyi1qdO3dWqVKlNHr0aP3xxx/68ssvFRwcrPfee++O4pccSaHevXurdu3aGj16tKKiojRu3DitXbtWW7dudZZU7Nixo/788089++yzKlmypE6cOKElS5boyJEjzvmWLVsqKChIQ4cOVb58+XTo0KE0jemybt06Va5cOdVf8Xfq1EnlypXTqFGjnJ27kSNH6vXXX1fnzp319NNP6+TJkxo/frwaN27sErcknT17Vg8++KA6d+6sbt26aebMmRo4cKB8fHzSlJS8mSVLlqhbt25q3ry585js3r1ba9eudUlAJ9WlSxeFh4c7S9UmiouL008//aRevXrJ29tbkjRt2jT17NlTrVq10nvvvae4uDh99tlnzgut139eUjJo0CDly5dPw4cP1549e/TZZ5/p8OHDzotZkuMi1IgRI9SiRQsNHDjQud6mTZu0du1a5cyZU6+99prOnz+vf/75Rx9//LEkOceNtNvtevjhh7VmzRr169dPFStW1M6dO/Xxxx/r77//TjYmzZo1a/Tjjz/qmWeeUd68efXJJ5+oY8eOOnLkiAoWLKhHH31Uf//9t3744Qd9/PHHKlSokCQ5L8pe78CBA5o3b546deqkUqVKKSoqSp9//rmaNGmiiIgIhYSE3PA9CgwMVJkyZbR27Vq98MILN31PAQCOpN+0adO0ceNGZ0nMtWvXqkGDBmrQoIHOnz+vXbt2qWrVqs7nKlSooIIFC0q6te/zpOx2u9q1a6fff/9dAwcOVIUKFTR//nz17NkzxfUTEhLUqlUr1a1bVx9++KF+++03ffTRRypTpowGDhyooKAgffbZZxo4cKAeeeQR54WLxLj//PNPNWzYUHfddZeGDh0qPz8/zZw5Ux06dNCcOXOc5U0jIyN1//336+rVq871Jk2alK6/8E5rP3LAgAGaPXu2Bg0apNDQUJ0+fVpr1qzR7t27VaNGDcXHx6tVq1a6fPmynn32WRUpUkTHjh3Tzz//rHPnzqVacn3v3r3666+/1KdPH+XNm/em8V68eFFNmzbVvn37NGjQIJUqVUqzZs1Sr169dO7cuWR9pe+++07x8fF69tlndebMGb3//vvq3LmzmjVrphUrVuiVV17Rvn37NH78eL300kv6+uuvk8XXpUsXDRgwQD179tTkyZPVqVMnLVy4UA888IAkKSoqSg0aNFBcXJyee+45FSxYUFOnTtXDDz+s2bNnu5SrlaR3331XXl5eeumll3T+/Hm9//776t69uzZu3OhcZ9myZWrTpo1q1qypN998U15eXpo8ebKaNWum1atXq06dOi7bvFn/ftq0aXr66adVp04d9evXT5JUpkyZNB1bAED2df78+WRjAyf+LZ2Sm/WREo0bN04PP/ywunfvrvj4eE2fPl2dOnXSzz//rLZt26Z7O4wxevjhh7V8+XI99dRTql69uhYtWqSXX35Zx44dc16PSMt1uS+++ELPPfecHnvsMT3//PO6dOmSduzYoY0bN6apFHlcXJzzPb1w4YJ+/fVXLVy4UMOGDUu27p49e9StWzf1799fffv2Vfny5RUXF6cmTZro2LFj6t+/v+6++26tW7dOw4YN0/HjxzV27Fjn62/3ff7vf/+rUaNG6fPPP1ffvn0lOfpgzZs315EjR/Tcc88pJCRE06ZN07Jly5K9Pi3XBu+77z7nj8oT+8irV6+Wl5eXS3WPkydP6q+//ko2ZuPNrgEBbssAuCPnz583kkz79u3TtP62bduMJPP000+7LH/ppZeMJLNs2TLnsiZNmpgmTZo45w8ePGgkmcmTJzuXvfnmmybpP+WPP/7YSDInT55MNYaUtlO9enUTHBxsTp8+7Vy2fft24+XlZXr06JFsf3369HHZ5iOPPGIKFix40/b37NnT+Pn5pfp8fHy8CQ4ONpUrVzYXL150Lv/555+NJPPGG28YY4w5e/askWQ++OCDVLc1d+5cI8ls2rTppnFdr1ixYqZjx47Jlie2v1u3bi7LDx06ZLy9vc3IkSNdlu/cudPkyJHDZXmTJk2MJPPRRx85l12+fNl5DOLj440xxkyePNlIMgcPHnTZ5vLly40ks3z5cueynj17mhIlSjjnn3/+eRMQEGCuXr2aahuv347dbjd33XVXsnbPnDnTSDKrVq0yxhgTHR1t8uXLZ/r27euyXmRkpAkMDEy2/HqJ7apZs6azrcYY8/777xtJZv78+cYYY06cOGF8fHxMy5YtTUJCgnO9CRMmGEnm66+/di5r27atS/sTTZs2zXh5eZnVq1e7LJ84caKRZNauXetcJsn4+PiYffv2OZdt377dSDLjx493Lvvggw9SPC7GGFOiRAnTs2dP5/ylS5dcYjfG8e/P19fXvPXWWy7Lrv83mahly5amYsWKyZYDAFL2559/Gknm7bffNsYYc+XKFePn52emTp1qjDGmcOHCJjw83BhjzIULF4y3t7fzu+tWvs+v/+6dM2eOkWTGjh3rXJaQkGCaNWuW7Bzfs2dPI8nlu8AYY+69915Ts2ZN5/zJkyeNJPPmm28ma2fz5s1NlSpVzKVLl5zL7Ha7adCggSlXrpxz2eDBg40ks3HjRueyEydOmMDAwFS/z5JK7PvcqG+Z1n5kYGCgCQsLS3U7W7duNZLMrFmzbhjT9ebPn28kmY8//jhN648dO9ZIMt9++61zWXx8vKlfv77x9/c3Fy5cMMZc+34OCgoy586dc647bNgwI8lUq1bNXLlyxbm8W7duxsfHx+WYlChRwkgyc+bMcS47f/68KVq0qLn33nudyxKPU9I+S3R0tClVqpQpWbKksz+R2H+rWLGiuXz5snPdcePGGUlm586dxhjHZ6FcuXKmVatWxm63O9eLi4szpUqVMg888IBz2a307/38/Fz6OoludmwBANlP4t/+KT2MSfnv4LT2kYxxfKclFR8fbypXrmyaNWvmsvz6v9NTI+mG32Xz5s0zksw777zjsvyxxx4zNpvNeS0hLdfl2rdvbypVqnTTmK6X+J6l9Bg4cKDLd74x1/ohCxcudFn+9ttvGz8/P/P333+7LB86dKjx9vY2R44ccS5L6/uc9P178cUXjZeXl5kyZYrLOol9sJkzZzqXxcbGmrJly7pcn0rrtUFjjKlUqZLp3Lmzc75GjRqmU6dORpLZvXu3McaYH3/80Ugy27dvd4k3LdeAAHdEeU/gDl24cEGS0vSrYklasGCBJGnIkCEuy1988UVJuuOx/xJ/fT5//vw0l206fvy4tm3bpl69eqlAgQLO5VWrVtUDDzzgjDmpAQMGuMw3atRIp0+fdr4ft2vz5s06ceKEnnnmGZfa7m3btlWFChWc70/u3Lnl4+OjFStWpFgSUrr2Xvz888+3PIbL6dOnlT9//lSfv779P/74o+x2uzp37qxTp045H0WKFFG5cuW0fPlyl/Vz5Mih/v37O+d9fHzUv39/nThxQlu2bLmlWFOSL18+xcbGasmSJWl+jc1mU6dOnbRgwQLFxMQ4l8+YMUN33XWXs4zpkiVLdO7cOXXr1s2lrd7e3qpbt26ytqamX79+LndSDhw4UDly5HB+3n777TfFx8dr8ODB8vK69nXVt29fBQQEpOnfyqxZs1SxYkVVqFDBJdZmzZpJUrJYW7Ro4fzFuuT4NxAQEKADBw6kqU3X8/X1dcaekJCg06dPO0t7pLXcVf78+ZP9KhIAkLqKFSuqYMGCzl/3bt++XbGxsc6KDA0aNHD+0nr9+vVKSEhwfsfd6vd5UgsXLlTOnDmdv2SWHOPnhoWFpfqalPpTafnOOXPmjJYtW6bOnTsrOjraGefp06fVqlUr7d2711n6aMGCBapXr57LXV1BQUHq3r37TfeTFrfSj8yXL582btyof//9N8VtJd7Jt2jRolsqG387/fEiRYqoW7duzmU5c+bUc889p5iYGK1cudJl/U6dOrncZVi3bl1J0hNPPOFSRqtu3bqKj49PVpI+JCTE5U69xLLmW7duVWRkpDOmOnXquJSN9/f3V79+/XTo0CFFRES4bLN3797y8fFxzjdq1EiSnJ+fbdu2ae/evXr88cd1+vRp52ckNjZWzZs316pVq5L9rXAn/fubHVsAQPYVHh6uJUuWuDxuJi19pKRVC86ePavz58+rUaNGGVZaesGCBfL29tZzzz3nsvzFF1+UMUa//vqrpLRdl8uXL5/++ecfbdq06bZi6devn/O9nDNnjsLCwvT5558nu9YoOYYmadWqlcuyWbNmqVGjRs7rDYmPFi1aKCEhQatWrXKueyvvszFGgwYN0rhx4/Ttt98mq3ixYMECFS1aVI899phzWZ48eZwVBBKl9dqg5PhsrF69WpKj3Pj27dvVr18/FSpUyLl89erVypcvnypXruyyn/S+BgRkFST9gDsUEBAgyfHFkhaHDx+Wl5eXypYt67K8SJEiypcvnw4fPnxH8XTp0kUNGzbU008/rcKFC6tr166aOXPmDROAifssX758sucqVqzovECQ1N133+0yn5ggSy0Bl1Y3iqVChQrO5319ffXee+/p119/VeHChdW4cWO9//77zgsnktSkSRN17NhRI0aMUKFChdS+fXtNnjw5zWMnmutqsidVqlQpl/m9e/fKGKNy5copKCjI5bF7926dOHHCZf2QkBD5+fm5LLvnnnskKdkYfrfjmWee0T333KM2bdqoWLFi6tOnT5rqknfp0kUXL150jgcUExOjBQsWqFOnTs6Sm3v37pUkNWvWLFlbFy9enKytqSlXrpzLvL+/v4oWLepsf2qfBR8fH5UuXTpN/1b27t2rP//8M1mcie/19bFe/7mWHJ/t2/1c2+12ffzxxypXrpx8fX1VqFAhBQUFaceOHTcdmyiRMSbZuJ0AgNTZbDY1aNDAOXbf2rVrFRwc7Ox7JU36Jf4/MdFyq9/nSR0+fFhFixZVnjx5XJZf3+dLlCtXrmTlodP6nbNv3z4ZY/T6668ni/PNN9+UdO077vDhw8m+c6WU+1q341b6ke+//7527dql4sWLq06dOho+fLjLRZVSpUppyJAh+vLLL1WoUCG1atVK4eHhN/3OvJ3+eLly5Vx+VJQYb9I2Jbq+f5CYACxevHiKy68/hmXLlk32XX59v+/w4cOpvodpien6vnhif61nz57JPiNffvmlLl++nOx9vZP+/c2OLQAg+6pTp45atGjh8riRtPaRfv75Z9WrV0+5cuVSgQIFnKXR0/q39q06fPiwQkJCkv3I6Prv6rRcl3vllVfk7++vOnXqqFy5cgoLC7vpsDxJlStXzvlePvroo5owYYKeeeYZjR07Vjt37nRZ9/rrV5Kjn7Bw4cJkfYTEY5O0z3sr7/M333yj8PBwjR8/3uXHVYkOHz6cYr/o+j5QWq8NSo6k3/Hjx7Vv3z6tW7dONptN9evXd0kGrl69Wg0bNkzW90vva0BAVsGYfsAdCggIUEhIiHbt2nVLr8uoi/i5c+fWqlWrtHz5cv3yyy9auHChZsyYoWbNmmnx4sXOMdnuVGrbuVGiLL0NHjxY7dq107x587Ro0SK9/vrrGj16tJYtW6Z7771XNptNs2fP1oYNG/TTTz9p0aJF6tOnjz766CNt2LDBOe5bSgoWLHjDL/nrx8Gx2+2y2Wz69ddfU3xvbrSv1KT2Gbl+8OqUBAcHa9u2bVq0aJF+/fVX/frrr5o8ebJ69OihqVOnpvq6evXqqWTJkpo5c6Yef/xx/fTTT7p48aLLYMeJHdVp06apSJEiybZx/cDRVrLb7apSpYrGjBmT4vPXX6xL78/1qFGj9Prrr6tPnz56++23VaBAAXl5eWnw4MFpvhP37NmzNxzvAACQ3H333aeffvpJO3fudI7nl6hBgwbOsVfWrFmjkJAQlS5dWlLGfJ+n5k76ZInfIS+99FKyX24nSi3ZaKXOnTurUaNGmjt3rhYvXqwPPvhA7733nn788Ue1adNGkvTRRx+pV69emj9/vhYvXqznnntOo0eP1oYNG1SsWLEUt1uhQgVJSnaRK72kdqys7A/fbN+Jn5EPPvhA1atXT3Hd6z/Pd9KetBxbAADSIi19pNWrV+vhhx9W48aN9emnn6po0aLKmTOnJk+erO+//z4TokxdWq7LVaxYUXv27NHPP/+shQsXas6cOfr000/1xhtvaMSIEbe13+bNm2vChAlatWqVqlSp4hLP9ex2ux544AH95z//SXFbiT9OutX3uWHDhtq2bZsmTJigzp07u1SByCiJP95btWqVDhw4oBo1asjPz0+NGjXSJ598opiYGG3dulUjR45M9tqscG0TyAhZ58os4MYeeughTZo0SevXr1f9+vVvuG6JEiVkt9u1d+9e56+BJCkqKkrnzp1TiRIl7jgeLy8vNW/eXM2bN9eYMWM0atQovfbaa1q+fHmKv6hK3OeePXuSPffXX3+pUKFCye5KyyhJY0kswZhoz549yd6fMmXK6MUXX9SLL76ovXv3qnr16vroo4/07bffOtepV6+e6tWrp5EjR+r7779X9+7dNX36dD399NOpxlGhQgUdPHgwzXGXKVNGxhiVKlXK2Tm6kX///VexsbEu7+vff/8tSSpZsqSka7+uPnfunMtr03o3qI+Pj9q1a6d27drJbrfrmWee0eeff67XX3/9hhcCO3furHHjxunChQuaMWOGSpYsqXr16rm0VXIkFm/2C70b2bt3r+6//37nfExMjI4fP64HH3xQkutnIfFirCTFx8fr4MGDLvtOLUFapkwZbd++Xc2bN0+3RPutbGf27Nm6//779dxjkF4AAP08SURBVNVXX7ksP3fuXJoTeQcPHlS1atVuKUYAyO4S//hfs2aN1q5dq8GDBzufq1mzpnx9fbVixQpt3LjR+b0j3fr3eVIlSpTQ8uXLFRcX53K33759+267Hal95yR+L+bMmfOm38UlSpRw3vWVVEr9vttxq/3IokWL6plnntEzzzyjEydOqEaNGho5cqRLYqhKlSqqUqWK/vvf/2rdunVq2LChJk6cqHfeeSfFGO655x6VL19e8+fP17hx426anC1RooR27Nghu93u8ovvv/76y6VN6SXxzsykx/P6fl+JEiVSfQ9vJ6bE/lpAQMAd9deud6N+UFqOLQAA6WHOnDnKlSuXFi1aJF9fX+fyyZMnZ9g+S5Qood9++03R0dEud/ul9F2dlutyfn5+6tKli7p06aL4+Hg9+uijGjlypIYNG+ZS0jKtrl69Kkkuw7WkpkyZMoqJiblpH+FW3+eyZcvq/fffV9OmTdW6dWstXbrU5b0qUaKEdu3alaxfdH0f6FauDd599926++67tXr1ah04cMBZ8rxx48YaMmSIZs2apYSEBDVu3PiGbQU8CeU9gXTwn//8R35+fnr66acVFRWV7Pn9+/dr3LhxkuS8sDR27FiXdRLvRGrbtu0dxXLmzJlkyxJ/3ZtaWcuiRYuqevXqmjp1qkuCadeuXVq8eLHLxbCMVqtWLQUHB2vixIku8f7666/avXu38/2Ji4vTpUuXXF5bpkwZ5c2b1/m6s2fPJvt1zs3ei0T169fXrl270lwK9NFHH5W3t7dGjBiRbJ/GGJ0+fdpl2dWrV/X555875+Pj4/X5558rKChINWvWdLZHkkst9YSEBE2aNOmm8Vy/Py8vL1WtWlXSzdvepUsXXb58WVOnTtXChQvVuXNnl+dbtWqlgIAAjRo1KsWxEk+ePHnT+CRp0qRJLq//7LPPdPXqVeeFoRYtWsjHx0effPKJy3v61Vdf6fz58y7/Vvz8/FIsLdG5c2cdO3ZMX3zxRbLnLl68mKxsbVokXri8PhmbEm9v72Sfh1mzZiUb6yc158+f1/79+13uUAEA3FytWrWUK1cufffddzp27JjLedTX11c1atRQeHi4YmNjXcZQu9Xv86RatWqlK1euuHzn2O12hYeH33Y7EpOH13/nBAcHq2nTpvr88891/PjxZK9L+l384IMPasOGDfr9999dnv/uu+9uO66k0tqPTEhISPZdHRwcrJCQEGff5MKFC84LVomqVKkiLy+vm/ZfRowYodOnT+vpp59Otg1JWrx4sX7++WdJjvckMjJSM2bMcD5/9epVjR8/Xv7+/mrSpEna34A0+PfffzV37lzn/IULF/TNN9+oevXqzqoJDz74oH7//XetX7/euV5sbKwmTZqkkiVLKjQ09Jb2WbNmTZUpU0Yffvhhihf/0tpfu56fn1+yz2Naji0AAOnJ29tbNpvNpRLSoUOHNG/evAzb54MPPqiEhARNmDDBZfnHH38sm83mvJaRluty1/cpfXx8FBoaKmNMitdZ0uKnn36SpDT9aLhz585av369Fi1alOy5c+fOOftSt/M+V61aVQsWLNDu3bvVrl07Xbx40fncgw8+qH///VezZ892LouLi0t2nSut1wYTNWrUSMuWLdPvv//uTPpVr15defPm1bvvvqvcuXM7r7UB2QF3+gHpoEyZMvr+++/VpUsXVaxYUT169FDlypUVHx+vdevWadasWerVq5ckx5dvz549NWnSJJ07d05NmjTR77//rqlTp6pDhw4udz7djrfeekurVq1S27ZtVaJECZ04cUKffvqpihUr5nJR63offPCB2rRpo/r16+upp57SxYsXNX78eAUGBmr48OF3FNP1rly5kuIvtQsUKKBnnnlG7733nnr37q0mTZqoW7duioqK0rhx41SyZEm98MILkhy/jm7evLk6d+6s0NBQ5ciRQ3PnzlVUVJS6du0qSZo6dao+/fRTPfLIIypTpoyio6P1xRdfKCAg4KaJzPbt2+vtt9/WypUr1bJly5u2qUyZMnrnnXc0bNgwHTp0SB06dFDevHl18OBBzZ07V/369dNLL73kXD8kJETvvfeeDh06pHvuuUczZszQtm3bNGnSJOXMmVOSVKlSJdWrV0/Dhg3TmTNnVKBAAU2fPj3FC1nXe/rpp3XmzBk1a9ZMxYoV0+HDhzV+/HhVr17d5Q7TlNSoUUNly5bVa6+9psuXL7uU9pQcvxj/7LPP9OSTT6pGjRrq2rWrgoKCdOTIEf3yyy9q2LBhsk5wSuLj453HcM+ePfr0009133336eGHH5YkBQUFadiwYRoxYoRat26thx9+2Lle7dq19cQTTzi3VbNmTc2YMUNDhgxR7dq15e/vr3bt2unJJ5/UzJkzNWDAAC1fvlwNGzZUQkKC/vrrL82cOVOLFi1SrVq1bhprUokdxddee01du3ZVzpw51a5duxTvhn3ooYf01ltvqXfv3mrQoIF27typ7777zuXOxRv57bffZIxR+/btbylGAMjufHx8VLt2ba1evVq+vr7J/shv0KCBPvroI0ly6R/d6vd5Uh06dFCdOnX04osvat++fapQoYL+97//OS/83M4d57lz51ZoaKhmzJihe+65RwUKFFDlypVVuXJlhYeH67777lOVKlXUt29flS5dWlFRUVq/fr3++ecfbd++XZLjx2nTpk1T69at9fzzz8vPz0+TJk1y3u2WVmPGjEk2XqGXl5deffXVNPUjo6OjVaxYMT322GOqVq2a/P399dtvv2nTpk3OY7Fs2TINGjRInTp10j333KOrV69q2rRp8vb2VseOHW8YX5cuXbRz506NHDlSW7duVbdu3VSiRAmdPn1aCxcu1NKlS51lqPr166fPP/9cvXr10pYtW1SyZEnNnj1ba9eu1dixY5ON1XOn7rnnHj311FPatGmTChcurK+//lpRUVEuv5IfOnSofvjhB7Vp00bPPfecChQooKlTp+rgwYOaM2dOsjFobsbLy0tffvml2rRpo0qVKql379666667dOzYMS1fvlwBAQHOi4O3ombNmvrtt980ZswYhYSEqFSpUipfvvxNjy0AAOmpbdu2GjNmjFq3bq3HH39cJ06cUHh4uMqWLXtL/Zvrbd68OcXrVU2bNlW7du10//3367XXXtOhQ4dUrVo1LV68WPPnz9fgwYOdP9xOy3W5li1bqkiRImrYsKEKFy6s3bt3a8KECWrbtm2a+iF//PGHs8JVdHS0li5dqjlz5qhBgwZpuob18ssv63//+58eeugh9erVSzVr1lRsbKx27typ2bNn69ChQypUqNBtv8/16tXT/Pnz9eCDD+qxxx7TvHnzlDNnTvXt21cTJkxQjx49tGXLFhUtWlTTpk1L1sfMmTNnmq4NJmrUqJG+++472Ww253vs7e2tBg0aaNGiRWratKl8fHxu+r4AHsMASDd///236du3rylZsqTx8fExefPmNQ0bNjTjx483ly5dcq535coVM2LECFOqVCmTM2dOU7x4cTNs2DCXdYwxpkmTJqZJkybO+YMHDxpJZvLkyc5lb775pkn6T3np0qWmffv2JiQkxPj4+JiQkBDTrVs38/fff99wO8YY89tvv5mGDRua3Llzm4CAANOuXTsTERHhsk7i/k6ePOmyfPLkyUaSOXjw4A3fo549expJKT7KlCnjXG/GjBnm3nvvNb6+vqZAgQKme/fu5p9//nE+f+rUKRMWFmYqVKhg/Pz8TGBgoKlbt66ZOXOmc50//vjDdOvWzdx9993G19fXBAcHm4ceeshs3rz5hjEmqlq1qnnqqafS1P5Ec+bMMffdd5/x8/Mzfn5+pkKFCiYsLMzs2bPHuU6TJk1MpUqVzObNm039+vVNrly5TIkSJcyECROSbW///v2mRYsWxtfX1xQuXNi8+uqrZsmSJUaSWb58ucv7WqJECef87NmzTcuWLU1wcLDx8fExd999t+nfv785fvy4c53ly5cn206i1157zUgyZcuWTfX9Wb58uWnVqpUJDAw0uXLlMmXKlDG9evW66fub+FlZuXKl6devn8mfP7/x9/c33bt3N6dPn062/oQJE0yFChX+j717j++x/v84/vjsbA5zNoc5HydGTlEYJlEOpajkHKVJLPpSUTpQybE+UXIuP0RHopjzIecVzSGFCXMaxtiwz/X742qfWRttbLt2eN5vt+u26/D+XNfr/WHbtc/rer/ehru7u1GiRAljwIABxvnz55O0uXz5svH0008bBQsWNIAk78W1a9eM999/36hZs6bh6elpFCpUyKhXr54xevRo4+LFi852gBEcHJzs+uXKlTN69uyZZN/bb79tlC5d2nBxcUny//7fbWNjY42XX37ZKFmypJEnTx7j/vvvN7Zs2ZKq723DMIyuXbsaDzzwwG3fTxERSdmIESMMwGjSpEmyY19//bUBGPnz5zdu3LiR7Hhqfp//+3evYRjGmTNnjKefftrInz+/4ePjY/Tq1cvYtGmTARgLFixI8tq8efMmu+6/7+sMwzA2b95s1KtXz/Dw8DAA44033nAe+/PPP40ePXoYvr6+hru7u1G6dGnjkUceMRYvXpzkHL/99pvRvHlzw8vLyyhdurTx9ttvGzNmzEjVvVtCTCktrq6uznb/dR8ZFxdnDBs2zAgICDDy589v5M2b1wgICDA++eQTZ5u//vrL6NOnj1GpUiXDy8vLKFy4sNGiRQtj1apVt43xZgn3wsWLFzfc3NyMYsWKGe3btze+++67JO1OnTpl9O7d2yhatKjh4eFh1KpVK9nv4YTfz+PGjUuyP+Ee6quvvkqyP+EeZ/v27c595cqVMx5++GHjp59+MmrXrm14enoa1atXT/ZawzD/PR9//HGjYMGChpeXl9GwYUNj6dKlqbr2re4ldu/ebTz22GNGkSJFDE9PT6NcuXJGly5djNDQUGebtNzf79+/32jWrJmRJ08eAzB69uyZqn9bERHJfVL6vXizlH53peUeacaMGUaVKlWcv1tnzZqVYruU/qZPya3udwDj7bffNgzDMC5dumQMGTLEKFWqlOHu7m5UqVLFGDdunOFwOJznSc3ncp9++qnRrFkz5+/nSpUqGcOGDUvyGcXt3rObFzc3N6NixYrGsGHDjEuXLiXr+8MPP5ziuS5dumSMGDHCqFy5suHh4WEULVrUaNKkifHhhx8a165dS/P7nNJnKt99953h5uZmdO3a1YiPjzcMwzCOHj1qdOjQwfD29jaKFi1qvPTSS8aKFStS/Hzqvz4bTPD7778bgFGjRo0k+9955x0DMEaOHJnsNWn5DEgku7EZhmamFBFJybx58wgODiYiIoKCBQum23kDAwM5e/Yse/fuTbdzZiezZ8+md+/ebN++Pc2j7HKTyMhIKlSowIIFCzTST0QkG/v222959NFH2bhxI/fff7/V4UgmK1++PPfcc4+ztKiIiIiIiEhG0px+IiK30K1bN8qWLXtXc/GI3KlJkyZRq1YtJfxERLKRm+csAXOus48++ogCBQpw7733WhSViIiIiIiI5Baa009E5BZcXFxy7Wg8sd57771ndQgiIpJGL774IlevXqVx48bExcXx9ddfs3nzZsaMGUOePHmsDk9ERERERERyOCX9RERERERE0kHLli0ZP348S5cuJTY2lsqVK/PRRx8xcOBAq0MTERERERGRXEBz+omIiIiIiIiIiIiIiIhkc5rTT0RERERERERERERERCSbU9JPREREREREREREREREJJtT0k9EREREREREREREREQkm3OzOoDczOFwcOLECfLnz4/NZrM6HBEREclAhmFw6dIlSpUqhYuLnrtKDd0riYiI5B66V7ozul8SERHJHVJ7r6Skn4VOnDiBn5+f1WGIiIhIJjp27BhlypSxOoxsQfdKIiIiuY/uldJG90siIiK5y3/dKynpZ6H8+fMD5j9SgQIF0vXcDoeDM2fOUKxYsRz9hJz6mbOonzmL+pnz5Ja+ZlQ/o6Oj8fPzc/7+l/+me6X0kVv6qn7mLOpnzqJ+5iy6V8paMvJ+SURERLKO1N4rKelnoYSyCwUKFMiQD7JiY2MpUKBAjv9jQ/3MOdTPnEX9zHlyS18zup8qu5R6uldKH7mlr+pnzqJ+5izqZ86ie6WsJSPvl0RERCTr+a97pZx7FyoiIiIi2ZLdbsff358GDRpYHYqIiIiIiIiISLahpF86Wbp0KdWqVaNKlSp8/vnnVocjIiIikm0FBwcTHh7O9u3brQ5FRERERERERCTbUHnPdHDjxg1CQkJYs2YNPj4+1KtXj0cffZQiRYpYHZqIiIiIiIiIiIiIiIjkAkr6pYNt27ZRs2ZNSpcuDUDbtm35+eefeeqppyyOTERERERERLKS+Ph4rl+/Dphzo12/fp3Y2NgcPwec+plz3Gk/3d3dcXV1zcDIRERERCRLJ/2mTp3K1KlTOXLkCAA1a9Zk1KhRtG3bNt2usX79esaNG8fOnTs5efIk33zzDZ06dUrWzm63M27cOCIjIwkICOCjjz6iYcOGAJw4ccKZ8AMoXbo0x48fT7cYRURERHITu92O3W4nPj7e6lBERNKNYRhERkZy4cKFJPscDgeXLl3CZrNZF1wGUz9zlrvpZ8GCBfH19c3R74+IiIiIlbJ00q9MmTK89957VKlSBcMwmDNnDh07dmT37t3UrFkzWftNmzbRsGFD3N3dk+wPDw+nSJEilChRItlrYmJiCAgIoE+fPjz22GMpxrFw4UJCQkKYNm0ajRo1YtKkSbRp04YDBw5QvHjx9OmsiIiIiADmnH7BwcFER0fj4+NjdTgiIukiIeFXvHhxvL29sdlsGIbBjRs3cHNzy9FJEPUzZ7mTfhqGwZUrVzh9+jQAJUuWzMgQRURERHKtLJ30a9++fZLtd999l6lTp/LLL78kS/o5HA6Cg4OpUqUKCxYscJaMOHDgAC1btiQkJIRXXnkl2TXatm37nyMHJ0yYQL9+/ejduzcA06ZNY9myZcycOZPhw4dTqlSpJCP7jh8/7hwFKCIiIiIiIrlbfHy8M+F389zvShLlLOrn7eXJkweA06dPU7x4cZX6FBEREckA2abIfHx8PAsWLCAmJobGjRsnO+7i4sKPP/7I7t276dGjBw6Hgz///JOWLVvSqVOnFBN+qXHt2jV27txJUFBQkmsFBQWxZcsWABo2bMjevXs5fvw4ly9fZvny5bRp0+bOOioiIiIiIiI5SsIcft7e3hZHImKthO+BhO8JEREREUlfWXqkH8CePXto3LgxsbGx5MuXj2+++QZ/f/8U25YqVYrVq1fTtGlTnn76abZs2UJQUBBTp0694+ufPXuW+Pj4ZKVBS5Qowf79+wFwc3Nj/PjxtGjRAofDwSuvvJLk6c1/0zw1IiIiIiIiuU9OHv0lkhr6HhARERHJWFk+6VetWjXCwsK4ePEiixcvpmfPnqxbt+6Wib+yZcsyb948mjdvTsWKFZkxY0am3FR26NCBDh06pKqt5qkRERERuTU9ICUiIiJye7pfEhERkZRk+fKeHh4eVK5cmXr16jF27FgCAgKYPHnyLdufOnWK/v370759e65cucKQIUPu6vpFixbF1dWVU6dOJbuOr6/vXZ1bRERERJILDg4mPDyc7du3Wx2KiIjcpbVr1+Li4sKFCxfu+jw2m+2uz5Ma586do3jx4hw5ciTDr2WladOm0b59e6vDkDuk+yURERFJSZZP+v2bw+EgLi4uxWNnz56lVatW1KhRg6+//prQ0FAWLlzI0KFD7/h6Hh4e1KtXj9DQ0CQxhIaGpji3oIiIiIiIiEhO0KtXL2w2GzabDXd3dypUqMArr7xCbGxshl43MDCQwYMHJ9nXpEkTTp48mSnVct599106duxI+fLlM/xaAIMGDaJevXp4enpSp06dFNv89ttvNG3aFC8vL/z8/Pjggw/+87wRERE8/PDDeHt7U7x4cYYNG8aNGzecx/v06cOuXbvYsGFDenVFRERERCyWpct7jhgxgrZt21K2bFkuXbrE/PnzWbt2LT/99FOytg6Hg7Zt21KuXDkWLlyIm5sb/v7+rFy5kpYtW1K6dOkUR/1dvnyZQ4cOObcPHz5MWFgYhQsXpmzZsgCEhITQs2dP6tevT8OGDZk0aRIxMTH07t074zovIiIiIiIiYrGHHnqIWbNmcf36dXbu3EnPnj2x2Wy8//77mRqHh4dHplTbuXLlCjNmzEjxc4eM1KdPH7Zu3cpvv/2W7Fh0dDQPPvggQUFBTJs2jT179tCnTx8KFixI//79UzxffHw8Dz/8ML6+vmzevJmTJ0/So0cP3N3dGTNmDGC+p08//TRTpkyhadOmGdo/EREREckcWXqk3+nTp+nRowfVqlWjVatWbN++nZ9++onWrVsna+vi4sKYMWNYsmQJHh4ezv0BAQGsWrWKJ554IsVr7Nixg7p161K3bl3ATPDVrVuXUaNGOdt07dqVDz/8kFGjRlGnTh3CwsJYsWIFJUqUSOcei4iIiEhmcDjg0CFXq8MQEcnyPD098fX1xc/Pj06dOhEUFMTKlSudxx0OB2PHjqVChQrkyZOHgIAAFi9efMvznTt3jqeeeorSpUvj7e1NrVq1+L//+z/n8V69erFu3TomT57sHGV45MiRFMt7LlmyhJo1a+Lp6Un58uUZP358kmuVL1+eMWPG0KdPH/Lnz0/ZsmX57LPPbtvfH3/8EU9PT+677z7nvvr16/Phhx86tzt16oS7uzuXL18G4O+//8ZmsyV5oDgtpkyZQnBwMBUrVkzx+Jdffsm1a9eYOXMmNWvW5Mknn2TQoEFMmDDhluf8+eefCQ8P54svvqBOnTq0bduWt99+G7vdzrVr15zt2rdvz/fff8/Vq1fvKHYRERERyVqydNJvxowZHDlyhLi4OE6fPs2qVatSTPglaN26NV5eXsn2161blzJlyqT4msDAQAzDSLbMnj07SbuBAwdy9OhR4uLi2Lp1K40aNbqrvlkiPh4++ggeegjatIG//rI6IhERERFLjBsHrVoV5ZNPwDCsjkZEcqsGDaBCBTf8/KBMmcxZ6te/83j37t3L5s2bkzxoO3bsWObOncu0adP4/fffGTJkCM888wzr1q1L8RyxsbHUq1ePZcuWsXfvXvr370/37t3Ztm0bAJMnT6Zx48b069ePkydPcvLkSfz8/JKdZ+fOnXTp0oUnn3ySPXv28OabbzJy5Mhkf8uPHz+e+vXrs3v3bl544QUGDBjAgQMHbtnHDRs2UK9evST7mjdvztq1awEwDIMNGzZQsGBBNm7cCMC6desoXbo0lStXBuD5558nX758t13SYsuWLTRr1izJ+96mTRsOHDjA+fPnb/maWrVqJXlYuU2bNkRHR/P7778799WvX58bN26wdevWNMUkIiIiIllTli7vKeno6lV48kn4/vvEfQMHwo8/WheTiIiISArsdjt2u534+PgMOf+OHTBypI34eBsvvmhj9WqYMQMKFcqQy4mI3FJkJBw/brM6jNtaunQp+fLl48aNG8TFxeHi4sLHH38MQFxcHGPGjGHVqlXOOe8rVqzIxo0b+fTTT2nevHmy85UuXZqhQ4c6t1988UV++uknFi1aRMOGDfHx8cHDwwNvb+/blvOcMGECrVq1YuTIkQBUrVqV8PBwxo0bR69evZzt2rVrxwsvvADA//73PyZOnMiaNWuoVq1aiuc9evQopUqVSrIvMDCQGTNmEB8fz969e/Hw8KBr166sXbuWhx56iLVr1ybp61tvvcWwYcNu97amSWRkJBUqVEiyLyGZFxkZSaEUfoFFRkYmq05082sSeHt74+Pjw9GjR9MtXhERERGxjpJ+ucXAgUkTfgDLl8P+/VC9ujUxiYiIiKQgODiY4OBgoqOj8fHxSffz16pl3hpNnmxuf/MN7NoF//d/8M9n1iIimcLMaSUMN86c5F9ap8Vr0aIFU6dOJSYmhokTJ+Lm5kbnzp0BOHToEFeuXElWkefatWvOKTT+LT4+njFjxrBo0SKOHz/OtWvXiIuLw9vbO01x7du3j44dOybZd//99zNp0iTi4+NxdTVLONeuXdt53Gaz4evry+nTp2953qtXryarINS0aVMuXbrE7t272bx5M82bNycwMJD33nsPMEf63ZzkK168eLaaDiRPnjxcuXLF6jBERESyr/btrY5AspIffrD08kr65QZffQUzZ5rrefNCw4awZo25PWUKfPKJdbGJiIiIZDJPT5gwweDeey8wZEhBoqJsHD0KTZvCu+/CsGHgkqWL4ItITrF9O9y4cQM3NzdsWXTAX968eZ1lK2fOnElAQAAzZsygb9++zjntli1bRunSpZO8ztPTM8XzjRs3jsmTJzNp0iRq1apF3rx5GTx4cJJ55tKTu7t7km2bzYbD4bhl+6JFiyYrmVmwYEECAgJYu3YtW7ZsoXXr1jRr1oyuXbty8OBB/vjjjyQj/Z5//nm+/PLL28aV8N6lhq+vL6dOnUqyL2H7VqMhfX19nSVT/+s1UVFRFCtWLNXxiIiIiEjWpY8zcoOPPkpcnzrVfJw9YQ6BOXMgKsqauEREREQs9OCDcezaZfDAA+Z2fDwMHw7t2sFtBoGIiORaLi4uvPrqq7z++utcvXoVf39/PD09iYiIoHLlykmWlObhA9i0aRMdO3bkmWeeISAggIoVK3Lw4MEkbTw8PP6zxHONGjXYtGlTsnNXrVrVOcrvTtStW5fw8PBk+5s3b86aNWtYv349gYGBFC5cmBo1avDuu+9SsmRJqlat6mz71ltvERYWdtslLRo3bsz69eu5fv26c9/KlSupVq1aiqU9E16zZ8+eJKMaV65cSYECBfD393fu+/PPP4mNjb3lyEwRERERyV6U9Mvpzp6FhD+EqleH7t3Bxwd69zb3XbkC06dbF5+IiIiIhfz8zAIIr7+Oc5TNTz9BQEBiYQQREUn0xBNP4Orqit1uJ3/+/AwdOpQhQ4YwZ84c/vzzT3bt2sVHH33EnDlzUnx9lSpVWLlyJZs3b2bfvn0899xzyUaxlS9fnq1bt3LkyBHOnj2b4si8l19+mdDQUN5++20OHjzInDlz+Pjjj5PMF3gn2rRpw++//55stF9gYCA//fQTbm5uVP9niozAwEC+/PLLZHMXFi9ePFkS9N/LzQ4dOkRYWBiRkZFcvXrVmRhMGP349NNP4+HhQd++ffn9999ZuHAhkydPJiQkxHmOb775xhkXwIMPPoi/vz/du3fn119/5aeffuL1118nODg4ySjMDRs2ULFiRSpVqnRX75uIiIiIZA1K+uV0P/4ICX8gdeiQuH/QoMRPtj7+GG56YlBEREQkN3Fzg7ffhpUrE+e6ioyEoCD48EMwjNu/XkQkN3Fzc2PgwIF88MEHxMTE8PbbbzNy5EjGjh1LjRo1eOihh1i2bBkVKlRI8fWvv/469957L23atCEwMBBfX186deqUpM3QoUNxdXXF39+fYsWKERERkew89957L4sWLWLBggXcc889jBo1irfeeotevXrdVf9q1arlPPfNmjZtisPhSJLgCwwMJD4+nsDAwLu65rPPPkvdunX59NNPOXjwIHXr1qVu3bqcOHECAB8fH37++WcOHz5MvXr1ePnllxk1ahT9+/d3nuPixYscOHDAue3q6srSpUtxdXWlcePGPPPMM/To0YO33norybX/7//+j379+t1V/CIiIiKSddgMQx9jWCU6OhofHx8uXrxIgQIF0vXcDoeD06dPU+KFF7B98425c+NGuP/+xEYdO8L335vrCxZA167pGkNmSOhn8eLFccnBk++onzmL+pmz5JZ+Qu7pa0b1MyN/7+dUmXGv9O9/51OnoEcP+PnnxLaPP25Oj5w/f7qGkGn0vZuzqJ/ZU2xsLIcPH6ZChQp4eXk59xuGcdOcfll0Ur90kN36uWzZMoYNG8bevXvT9P8vu/Xz999/p2XLlhw8eBAfH59Uv+5u+nmr7wXQvdKd0vsmIpIFtG9vdQSSlfzwQ4acNrW/87P/X09ya7GxiZ9YFSsG992X9PjgwYnrEydmWlgiIiIiWVWJEmahhJEjE/ctXgyNGsH+/dbFJSIimefhhx+mf//+HD9+3OpQMtTJkyeZO3dumhJ+IiIiIpK1KemXg3ls2oQtJsbceOQR+Pdk5oGBULu2ub51K2zfnqnxiYiIiGRFrq7w1ltmQYSEz0H37YOGDTPsgT0REcliBg8ejJ+fn9VhZKigoCDatGljdRgiIiIiko6U9MvBvG6uS3XzfH4JbDZ48cXE7alTMz4oERERkWyifXvYsQPuucfcvnTJrI4+bpzm+RMRERERERGRrEdJv5zKMPBMSPp5ekLr1im3e+qpxEfY/+//4Pz5zIlPRERE5Bbsdjv+/v40aNDA6lCoXBl++QW6dDG3DQNeeQX69IG4OGtjExERERERERG5mZJ+OdWuXbhGRprrQUGQN2/K7fLmhV69zPXYWJg9OzOiExEREbml4OBgwsPD2Z5FSo/nzQsLFsCbbybumz3bvMU6c8aqqEREREREREREklLSL4ey3TzhTEqlPW/2/POJ61OngsORMUGJiIiIZFM2G7zxBixcCF5e5r6NG815/vbutTY2ERERyX2yUmUEERERyTqU9Mupbk76PfLI7dtWrw4tW5rrf/wBq1dnXFwiIiIi2ViXLrB+PZQsaW4fOQJNmsDy5ZaGJSIiIrlMVquMICIiIlmDkn45UUQEtrAwAIwGDaBUqf9+zQsvJK5/8knGxCUiIiKSAzRoANu3w733mtuXLpnPWNnt1sYlIiIiIiIiIrmbkn450Z49GN7eABjt26fuNR06JD6y/v338PffGRSciIiISBYWG2veBx0/DoZxy2alS8OGDdC5s7ntcMDAgfDSSxAfn0mxiojkckeOHMFmsxH2z0OvVhg5ciT9+/e37PpZRXh4OGXKlCEmJsbqUERERERyNSX9cqKHH8Y4fZrz8+ZBt26pe427OyT8oRIfD9OnZ1x8IiIiIlnF6dPmnMatWoGvL+TJA35+UKaM+UBUly7mEL69e5PNe+ztDYsWwf/+l7hvyhTo2NEc/Scikt316tULm83mXIoUKcJDDz3Eb7/9ZnVoWUJkZCSTJ0/mtddey5TrrV+/nvbt21OqVClsNhvffvttsjaGYTBq1ChKlixJnjx5CAoK4o8//kjSJioqim7dulGgQAEKFixI3759uXz58m2vHRsbS3BwMEWKFCF//vx06dKFU6dOOY/7+/tz3333MWHChHTpq4iIiIjcGSX9cqo8eYgLCoLy5VP/mn79wNXVXJ8+Ha5fz5DQRERERCwVEwOzZlHoySexlSljljlfvRpu+vASMLe/+socwlerFhQvDo89Zmb2fvsNHA5cXOC99+Dzz8HNzXzZsmXQtCkcO5b5XRMRSW8PPfQQJ0+e5OTJk4SGhuLm5sYj/zVvfDZy7dq1O37t559/TpMmTShXrlw6RnRrMTExBAQEYL9NPekPPviAKVOmMG3aNLZu3UrevHlp06YNsbGxzjbdunXj999/Z+XKlSxdupT169f/52jFIUOG8MMPP/DVV1+xdu1aTp48SeeE4e7/6N27N1OnTuXGjRt311ERERERuWNK+kmi0qXNR9MBTp6E776zNh4RERGRjHDpErb+/fFctw7bzbU4fX2hcWMzsffQQ1CgQNLXnTsH33xj1vAMCIASJeCJJ2DqVPrev5+fVhgULGg2/fVXaNQIdu7MtF6JiGQIT09PfH198fX1pU6dOgwfPpxjx45x5swZZ5s9e/bQsmVL8uTJQ5EiRejfv3+SkWMtWrTg5ZdfTnLeTp060atXL+d2+fLlGTNmDH369CF//vyULVuWzz77LMlrtm3bRt26dfHy8qJ+/frs3r07yfH4+Hj69u1LhQoVyJMnD9WqVWPy5MlJ2vTq1YtOnTrx7rvvUqpUKapVq8Zbb73FPffck6zvderUYeTIkbd8bxYsWED7m6bUWLp0KcWKFSP+n98tYWFh2Gw2hg8f7mzz7LPP8swzz9zynLfTtm1b3nnnHR599NEUjxuGwaRJk3j99dfp2LEjtWvXZu7cuZw4ccI5KnDfvn2sWLGCzz//nEaNGvHAAw/w0UcfsWDBAk6cOJHieS9evMiMGTOYMGECLVu2pF69ekyfPp3Nmzfzyy+/ONu1bt2aqKgo1q1bd0f9ExEREZG7p6SfJPXCC4nrn3xiXRwiIiIiGcXXF1q0AMAoXx6GD4ewMDhxAjZvhiVLYPlyiIqCHTtg/Hhz/uNChZKe5+xZWLzYvH+qUYOW3Utz5IFuDC/6ORX5k5MnDZo2hRSqr4mIZEuXL1/miy++oHLlyhQpUgQwR5+1adOGQoUKsX37dr766itWrVrFwIED03z+8ePHO5N5L7zwAgMGDODAgQPOaz/yyCP4+/uzc+dO3nzzTYYOHZrk9Q6HgzJlyvDVV18RHh7OqFGjePXVV1m0aFGSdqGhoRw4cMA50q1Pnz7s27eP7du3O9vs3r2b3377jd69e6cYa1RUFOHh4dSvX9+5r2nTply6dMmZjFy3bh1FixZl7dq1zjbr1q0jMDAQgIiICPLly3fbZcyYMal+/w4fPkxkZCRBQUHOfT4+PjRq1IgtW7YAsGXLFgoWLJgk7qCgIFxcXNi6dWuK5925cyfXr19Pct7q1atTtmxZ53kBPDw8qFOnDhs2bEh1zCIiIiKSvtysDkCymJYtoVo1OHAA1qyBffugRg2roxIREZFs7NFHH2Xt2rW0atWKxYsXWx0OAMbo0UQNGUKhhx7CllDe/N9cXaFePXMJCTHn9NuzB9auNe+T1q6FixcT2588ic/S+YxlPmOBo5RlzdUWfPNoS0691oL+b/ths2VC50Qk22gwvQGRlyMz9Zq++XzZ0X9HqtsvXbqUfPnyAWaCr2TJkixduhQXF/MZ4vnz5xMbG8vcuXPJmzcvAB9//DHt27fn/fffp0SJEqm+Vrt27XjhnwdR//e//zFx4kTWrFlDtWrVmD9/Pg6HgxkzZuDl5UXNmjX5+++/GTBggPP17u7ujB492rldoUIFtmzZwqJFi+jSpYtzf968efn888/x8PBw7mvTpg2zZs2iQYMGAMyaNYvmzZtTsWLFFGONiIjAMAxKlSrl3Ofj40NAQABr166lQYMGrF27liFDhjB69GguX77MxYsXOXToEM2bNwegVKlShIWF3fY9KVy4cCrfPXOOQSDZe16iRAnnscjISIoXL57kuJubG4ULF3a2Sem8Hh4eFEwYzp7CeROUKlWKo0ePpjpmEREREUlfSvpJUjYbPP88DBlibk+bBv8qhyIiIiKSFi+99BJ9+vRhzpw5VoeSqHFjrp8+TZqycC4uZlnPgACzxGd8vDlCcPVqMwm4YQPcVM6uHBH0Yg69mAPvwumPKlH0iZa4tGphjjT09U3/folIthJ5OZLjl45bHcZttWjRgqlTpwJw/vx5PvnkE9q2bcu2bdsoV64c+/btIyAgwJnwA7j//vtxOBwcOHAgTUm/2rVrO9dtNhu+vr6cPn0aMMtS1q5dGy8vL2ebxo0bJzuH3W5n5syZREREcPXqVa5du0adOnWStKlVq1aShB9Av3796NOnDxMmTMDFxYX58+czceLEW8Z69epVgCTxADRr1ox169YxdOhQNmzYwNixY1m0aBEbN24kKiqKUqVKUaVKFcBMtlWuXDkV70z2kSdPHq5cuWJ1GCIiIiK5lpJ+klzPnvDqq3D1KsyeDWPGwE1/wImIiIikRWBgYJLSZjnGzSMBhw2D69fNcqBr1sCaNRgbN2KLjXU2Lx79J8z4E2ZMN3fUqGEm/1q2hObNoWhRizoiIlbxzZf5yf+0XjNv3rxJElOff/45Pj4+TJ8+nXfeeSdV53BxccEwjCT7rl+/nqydu7t7km2bzYbD4Uh1rAsWLGDo0KGMHz+exo0bkz9/fsaNG5esbGXeFP6+bd++PZ6ennzzzTd4eHhw/fp1Hn/88Vteq+g/P7PPnz9PsWLFnPubNWvG7Nmz+fXXX3F3d6d69erO34Pnz593jvIDc7Sgv7//bfv06quv8uqrr6aq/77/PExy6tQpSpYs6dx/6tQpZ+Lz5kRqghs3bhAVFeV8fUrnvXbtGhcuXEgy2u/UqVPJXhMVFUWlSpVSFa+IiIiIpD8l/SS5QoXgqadg5kyIjob/+z949lmroxIRERELrF+/nnHjxrFz505OnjzJN998Q6dOnZK0sdvtjBs3jsjISAICAvjoo49o2LChNQFbyd0dGjc2l1dfxRYXB1u38tuk1Vz4dg2NjF/w5Fpi+337zCVhHuXatc0EYIsW0KwZ/KuMmojkPNv7befGjRu4ublhyyb1f202Gy4uLs6RbjVq1GD27NnExMQ4k2mbNm3CxcWFatWqAVCsWDFOnjzpPEd8fDx79+6lxT/zq6ZGjRo1mDdvHrGxsc7Rdb/88kuSNps2baJJkybOEqEAf/75Z6rO7+bmRs+ePZk1axYeHh48+eST5MmT55btK1WqRIECBQgPD6dq1arO/Q888ACXLl1i4sSJzgRfYGAg7733HufPn+fll192tk3v8p4VKlTA19eX0NBQZ5IvOjqarVu3OsugNm7cmAsXLrBz507q1asHwOrVq3E4HDRq1CjF89arVw93d3dCQ0Pp3LkzAAcOHCAiIiLZaMu9e/feNlkqIiIiIhnLxeoAJIu6aV4Epk6Ffz2VKSIiIrlDTEwMAQEB2O32FI8vXLiQkJAQ3njjDXbt2kVAQABt2rRJNoogV/L0hGbNqP31m7huWEeVIucJYiXv8irb3Rpj/Hsuwd9+g0mToGNHKFIEGjSAV16BFSuSlA0VEclMcXFxREZGEhkZyb59+3jxxRe5fPky7du3B6Bbt254eXnRs2dP9u7dy5o1a3jxxRfp3r27s7RnixYtWL58OcuWLWP//v0MGDCACxcupCmOp59+GpvNRr9+/QgPD+fHH3/kww8/TNKmSpUq7Nixg59++omDBw8ycuRItm/fnuprPPvss6xevZoVK1bQp0+f27Z1cXEhKCiIjRs3JtlfqFAhateuzZdffklgYCBgjv7btWsXBw8eTDLSL6G85+2Wm5N+ly9fJiwszJkoPHz4MGFhYURERABmQnbw4MG88847fP/99+zZs4cePXpQqlQp5wM7NWrU4KGHHqJfv35s27aNTZs2MXDgQJ588knn/ITHjx+nevXqbNu2DTDnKuzbty8hISGsWbOGnTt30q9fPxo3bsx9993njO/IkSMcP36coKCgVL/nIiIiIpK+NNJPUla/vrns2AG7dsH27ZAbn9gXERHJ5dq2bUvbtm1veXzChAn069eP3r17AzBt2jSWLVvGzJkzGT58eJquFRcXR1xcnHM7OjoaAIfDkabybqnhcDgwDCPdz3srjRtD6BYvOnRoxev7g3j9BhTxiOarkA0EOtbA2rWwaxe2hAetHA7zPmzHDhg3DsPNzUwCtmiBERgITZrAbUag3Cyz+2oV9TNnyWn9TOhPwnKzhO1/788qVqxY4SwVmT9/fqpXr86iRYto3rw5hmGQJ08eVqxYweDBg2nQoAHe3t489thjTJgwwdmnPn36sHv3bnr27ImbmxuDBw92jvK7ud+3en8MwyBv3rx8//33DBgwgLp16+Lv7897773H448/7mzTv39/du/eTdeuXbHZbDz55JMMGDCAFStW3PJ9v1nlypVp0qQJUVFRNGzY8D//Tfr27Uv//v15//33cXFxcZ63WbNmhIWFOd+jQoUK4e/vz6lTp6hateod/1tv376dli1bOrdDQkIAnCMUAYYNG8bly5fp378/Fy5c4IEHHmD58uV4eno6r/vFF1/w4osv0qpVK1xcXHjssceYMmWK8/i1a9c4cOAAMTExzn0TJkzAZrPRuXNn4uLiaN26NVOnTk3Sl/nz5/Pggw9StmzZW/Yx4d8qpd/tOeX7XURERMRKNiOr/mWRC0RHR+Pj48PFixcpUKBAup7b4XBw+vRpihcv7vzjI81mzoS+fc313r3N7SwmXfqZDaifOYv6mbPkln5C7ulrRvUzI3/vZxabzZakvOe1a9fw9vZm8eLFSUp+9uzZkwsXLvDdd985961du5aPP/6YxYsX3/L8b775JqNHj062/+DBg+TPnz/d+gHmv/PFixfx8fHJ1P/PFy7Y6NevIBs3ejr3DRt2iSFDYnC5eAGPX37BY9MmPDZvxj08/JbnMTw8uF6vHnH338+1++/n+r33godHim2t6mtmUz9zlpzWz+vXr3Px4kXKlSvnLE0JZgIkPj4eV1fXbFPe805kl34ahoG/vz/PPfccgwcPTlX7+++/n0GDBvHkk09mm37erZT6ee3aNfz9/Zk7dy5NmjS55WtjY2M5evQoPj4+yeZwvHTpElWrVs3W90pWyAn3mCIi2d4/FRBEAPjhhww5bWp/52ukn9zak0/Cyy/DhQuwYAGMH2/O9yciIiICnD17lvj4eGf5tgQlSpRg//79zu2goCB+/fVXYmJiKFOmDF999VWyOYAARowY4Ry1AOYNrZ+fH8WKFcuQB6RsNhvFihXL1IRC8eKwahW88ILBzJnmB6XjxuXnxIl8TJ9eHM+qVaFHDzPGM2dg3Tpsa8yRgLab3lPbtWt4bNmCx5Yt8OGHGHnyQJMmGC1bQmCgWbHBzc3SvmY29TNnyWn9jI2N5dKlS7i5ueHmlvzP8H8nP3KqrNzPM2fOsGDBAiIjI+nbt2+K/04p+eyzz9izZ0+S9lm5n+np5n4eOXKEESNG0KxZs9u+xs3NDRcXF4oUKZIkAQ4k2xYRERGRtFPST27N2xt69oTJk+HqVZgzB1LxtKOIiIjIzVatWpWqdp6ennh6emK327Hb7cTHxwPmvEkZ8aG/zWbLsHPfjqcnfP45VK9uTtkH8OWXNo4etfHNN1C06D8NS5SALl3MBeDkSVizJnH588/Evly9CqGh2EJDzR358kGzZtCiBQQGYitZ0pK+Zjar/k0zm/qZ/bi4uGCz2ZxLAsMwnNs5fWRYVu9niRIlKFq0KJ999lmSefT+S926dalbty6QPfqZHlLqZ5UqVahSpcp/vjbheyCl7+2c8L0uIiIiYjXdUcntPf984vq0aaBqsCIiIvKPokWL4urqyqlTp5LsP3XqFL6+vnd83uDgYMLDw9m+ffvdhphl2WwwbBgsWZI4Nd/GjXDffXDgwC1eVLIkPP00TJ8Ohw7B0aMwe7Y5MtDPL2nby5fhxx9h2DBcGjSgeM2a2B59FKZMgT17zDkDRUTEyTAMzpw5w9NPP211KCIiIiIid0xJP7m96tXNElFgfgK1Zo2l4YiIiEjW4eHhQb169QhNGF2GWZIvNDQ0xfKdktxjj8G6dZCQI/3zTzPxl6pbrrJlzaoMc+aYCcBDh+Czz+CppxJP+A+Xixexff89vPQS1K6dOIpw6lTzHk8PdomIiIiIiIhke0r6yX8bMCBxfepU6+IQERGRTHf58mXCwsIICwsD4PDhw4SFhREREQFASEgI06dPZ86cOezbt48BAwYQExND79697/iadrsdf39/GjRokB5dyPIaNICtW6FWLXP7wgV48EGYNSsNJ7HZoFIl6NcP5s+HEycgPBzsdozOnXH8e17ms2fhq6/ghRfMh7xKl4Zu3WDGDPjrLyUBRURERERERLIhzekn/61TJ/Np8FOn4NtvzflkSpa0OioRERHJBDt27KBFixbO7ZCQEAB69uzJ7Nmz6dq1K2fOnGHUqFFERkZSp04dVqxYQYkSJe74msHBwQQHBxMdHY2Pj89d9yE7KFsWNm2Crl1h+XK4cQP69IGDB+HddyHN0xzZbFCjBtSogfH885yOjKT46dO4rF1rDiNctw4uXkxsf/KkmSycPz8xoJYtnXMCUrZsOvVURERERERERDKKRvrJf/PwgGefNddv3IDPP7c2HhEREck0gYGBGIaRbJk9e7azzcCBAzl69ChxcXFs3bqVRo0aWRdwNpY/P3z/Pbz4YuK+994zE4FXr97lyV1czLKegwfDd9/BuXOwfTt88AG0bQt58yZtHxFhzhfYsyeUKwcVKkCvXubwwz//1EhAERERERERkSxIST9Jnf79Ex8x/+wzM/knIiIikgFyW3nPm7m5wZQp5pJw67V4sTnYLjIyHS/k6gr168OwYfDjj3D+PGzeDO+8A61agZdX0vZHjphzB/bpA5Urg5+fWQ70s880J6CIiIiIiIhIFqGkn6RO2bLw8MPm+t9/w7Jl1sYjIiIiOVZwcDDh4eFs377d6lAs8+KL8MMPkC+fub1tGzRqBHv2ZNAF3d2hcWN47TVYtcqcWHDtWnjjDbPE57+TgMePm6VAn3vOnBOwZEl48kmYOdM8JiIiIiIiIiKZTkk/Sb0BAxLXp061Lg4RERGRXKBdO3OePz8/czsiApo0MUuAZjhPT2jeHN58E1avNpOAGzaYIwFbtwZv76TtT52ChQuhb18oUwZq1YKhQ83XOByZELCIiIiIiIiIKOknqdemjTmfC8BPP5nzuYiIiIiks9xc3vPfateGrVvNSpwAly9Dp07mXH+ZWlHT0xMeeMAcCfjzz2YScMsWM5C2bc0JCW+2dy+MHw/NmkGlSvD667BvXyYGLCJZyZtvvkn9hB9kQK9evejUqZNzOzAwkMGDB6fqXGlpe7dGjhxJ//79M+VaGeW+++5jyZIlVoch/2Hp0qVUq1aNKlWq8Pnnn1sdjoiIiGRjSvpJ6rm4mCWcEnz6qXWxiIiISI6l8p5JlSwJ69ZBly7mtmHAiBHwzDNw9apFQbm7w333wf/+Z84JGBVlDkscNcqsQ2qzJbY9cgTefRf8/c3s5aRJ6TxBoYhkpMjISF588UUqVqyIp6cnfn5+tG/fntDQ0HS7xtdff83bb7+d7m3vRmRkJJMnT+a1117L8GuBmRi12WxJlurVq//n67766iuqV6+Ol5cXtWrV4scff0xy/PXXX2f48OE4NOo6y7px4wYhISGsXr2a3bt3M27cOM6dO2d1WCIiIpJNKeknadOnD3h4mOszZ0JcnLXxiIiIiOQC3t6wYAHc/Dn3/PlmBc4TJ6yLy8nNzaw9Ono0/PILnDkDc+ealSJcbvqTY+dOGDIESpeGhx6CL74why+KSJZ05MgR6tWrx+rVqxk3bhx79uxhxYoVtGjRguDg4HS7TuHChcn/7xHD6dD2bnz++ec0adKEcuXKZfi1EtSsWZOTJ086l40bN962/ebNm3nqqafo27cvu3fvplOnTnTq1Im9e/c627Rt25ZLly6xfPnyjA5f7tC2bduoWbMmpUuXJl++fLRt25aff/7Z6rBEREQkm1LST9KmWDF4/HFz/dw5WLzY2nhEREREcgmbzayS+fXXkDevuW/7dmjQwPyapRQpAt27w4oVcPw4TJwI9eolHnc4zHLx3btDiRLmsMUVK+DGDetiFpFkXnjhBWw2G9u2baNz585UrVqVmjVrEhISwi+//OJsFxERQceOHcmXLx8FChSgS5cunDp1KtXX+XfJzk8++YQqVarg5eVFiRIleDzhb9AU2p4/f54ePXpQqFAhvL29adu2LX/88Yfz+OzZsylYsCA//fQTNWrUIF++fDz00EOcPHnytjEtWLCA9u3bO7eXLl1KwYIFiY+PByAsLAybzcbw4cOdbZ599ll69uyZ6n7/m5ubG76+vs6laNGit20/efJkHnroIYYNG0aNGjV4++23uffee/n444+dbVxdXWnXrh0LFiy447jk9tavX0/79u0pVaoUNpuNb7/9Nlkbu91O+fLl8fLyolGjRmzbts157MSJE5QuXdq5Xbp0aY4fP54ZoYuIiEgOpKSfpN3zzyeuT51qXRwiIiIiudCjj5qVNBMGn5w4YU6dN3++tXHdkq8vDB4MO3ZAeLg5L+DNI2euXIEvvzTnBixdOrFtpk5aKGKRBg1wq1AB/PygTJnMWW6aW+92oqKiWLFiBcHBweRNeNLgJgULFgTA4XDQsWNHoqKiWLduHStXruSvv/6ia9eud/SW7Nixg0GDBvHWW29x4MABVqxYQbNmzW7ZvlevXuzYsYPvv/+eLVu2YBgG7dq14/r16842V65c4cMPP2TevHmsX7+eiIgIhg4detu+h4eHJ5mHsGnTply6dIndu3cDsG7dOooWLcratWudbdavX0/z5s0BMxGaL1++2y5jxoxJct0//viDUqVKUbFiRbp160ZERMRt36stW7YQFBSUZF+bNm3YsmVLkn0NGzZkw4YNtz2X3LmYmBgCAgKw2+0pHl+4cCEhISG88cYb7Nq1i4CAANq0acPp06czOVIRERHJDdysDkCyoQcegJo14fffzU+c9uyBWrWsjkpERERyCLvdjt1ud46mkOQCAmDbNujcGTZuhNhY6NYN9u6Fd95JWlEzS6lRwwzwrbdg82azvOeiRXD+vHn89GmYPNlcKlc2M5yPPmrOE5hlOyVyFyIjsWXRET2HDh3CMIz/nFcuNDSUPXv2cPjwYfz8/ACYO3cuNWvWZPv27TRo0CBN142IiCBv3rw88sgj5M+fn3LlylG3bt0U2/7xxx98//33bNq0iSZNmgDw5Zdf4ufnx7fffssTTzwBwPXr15k2bRqVKlUCYODAgbz11lu3jcEwDEqVKuXc5+PjQ506dVi7di3169dn7dq1DBkyhNGjR3P58mUuXrzIoUOHaNq0KQClSpUiLCzstn0tXLiwc71Ro0bMnj2batWqcfLkSUaPHk3Tpk3Zu3fvLcuZRkZGUqJEiST7SpQoQeS/5k0tVaoUx44dw+Fw4KKfpemubdu2tG3b9pbHJ0yYQL9+/ejduzcA06ZNY9myZcycOZPhw4dTqlSpJCP7jh8/TsOGDW95vri4OOJummolOjoaMBPwmrtRRMQiN89pLpJBv49T+3teST9JO5sNBgyAgQPN7alT4ZNPrI1JREREcozg4GCCg4OJjo7Gx8fH6nCyrOLFITQUXngBZsww940daz6X9cUXkAlTXt05FxfzQbIHHjATfMuXm0H/8ANcu2a2OXQIxo0zF19f6NjRTAAGBoKnp6Xhi6QbX18SxrRm2kdFvr6pamakcrTtvn378PPzcyb8APz9/SlYsCD79u1Lc9KvdevWlCtXjooVK/LQQw/x0EMP8eijj+Lt7Z3itd3c3GjUqJFzX5EiRahWrRr79u1z7vP29nYm/ABKlix521FWV69eBcDLyyvJ/ubNm7N27VpefvllNmzYwNixY1m0aBEbN24kKiqKUqVKUaVKFcAs1Vm5cuVU9/vmpFHt2rVp1KgR5cqVY9GiRfTt2zfV50lJnjx5cDgcxMXFkSdPnrs6l6TNtWvX2LlzJyNGjHDuc3FxISgoyDkis2HDhuzdu5fjx4/j4+PD8uXLGTly5C3POXbsWEaPHp1s/5kzZ4iNjU3/ToiIyH+76T5IhAwazX/p0qVUtVPST+5M9+7wv/9BTAzMmwfvv5/FP1kSERERyXk8PGD6dKhdG4YMMR8o/P57aNLE/FqhgtURpoKnJ3TqZC7nz8OSJWat0nXrEp+QjIyETz81F29vaNEC2rSBhx4yRwTqyVrJrrZv58aNG7i5uWW5/8dVqlTBZrOxf//+TL1u/vz52bVrF2vXruXnn39m1KhRvPnmm2zfvt1ZUjSt3N3dk2zbbLbbJjUT5tI7f/48xYoVc+4PDAxk5syZ/Prrr7i7u1O9enUCAwNZu3Yt58+fd5b2BHO0oL+//23jevXVV3n11VdTPFawYEGqVq3KoUOHbvl6X1/fZHMnnjp1Ct9/JXajoqLImzevEn4WOHv2LPHx8SmOyEz43nJzc2P8+PG0aNECh8PBK6+8QpEiRW55zhEjRhASEuLcjo6Oxs/Pj2LFilGgQIGM6YiIiNzesWNWRyBZSfHiGXLafz+QditK+smdKVDArCH12Wdw+bI5D8vNc/2JiIiISKaw2WDQIKheHbp2hQsXzDKfDRqY+bN/Ks1lD4UKwbPPmsvZs7B0KXzzDfz8s1nDFMw5AJctMxcwM5tt2kCzZrjUqJFhf2CJ5DaFCxemTZs22O12Bg0alGxevwsXLlCwYEFq1KjBsWPHOHbsmHO0X3h4OBcuXPjPpNetuLm5ERQURFBQEG+88QYFCxZk9erVPPbYY0na1ahRgxs3brB161Znec9z585x4MCBO742QKVKlShQoADh4eFUrVrVuT9hXr+JEyc6E3yBgYG89957nD9/PkkiJq3lPf/t8uXL/Pnnn3Tv3v2WbRo3bkxoaCiDBw927lu5ciWNGzdO0m7v3r23LJEqWUOHDh3o0KFDqtp6enrimcKIdxcXF5VvFRGxiuYjl5tl0O/j1P6e192A3LkBAxLXp07VDzcRERERCz34IGzdCtWqmdvnzkFQkPmMVrZUtCj06gXffQdnzsDixdCjR/LShIcPw7RpuDz9NMXr1sVWpQr07g0zZ8LBg7pHFbkLCfOrNmzYkCVLlvDHH3+wb98+pkyZ4kwsBQUFUatWLbp168auXbvYtm0bPXr0oHnz5tSvXz/N11y6dClTpkwhLCyMo0ePMnfuXBwOB9USfrjdpEqVKnTs2JF+/fqxceNGfv31V5555hlKly5Nx44d77jfCeUXN27cmGR/oUKFqF27Nl9++SWBgYEANGvWjF27dnHw4MEkI/0Synvebrk56Td06FDWrVvHkSNH2Lx5M48++iiurq489dRTzjY9evRIUibypZdeYsWKFYwfP579+/fz5ptvsmPHDgYmTMXxjw0bNvDggw/e8fshd65o0aK4urqmakSmiIiISHpQ0k/uXJ06cN995vpvv8E/9ehFRERE7obdbsff3z/N80AJVK0Kv/xiDnwDuHEDBgxw4bXX8nP9urWx3ZV8+aBzZ5gzB06cgLAws7x8y5ZmjdOb2P76C2bPhr59zQxo4cJm9nP4cHPo49GjSgSKpFLFihXZtWsXLVq04OWXX+aee+6hdevWhIaGMnXqVMAslfndd99RqFAhmjVrRlBQEBUrVmThwoV3dM2CBQvy9ddf07JlS2rUqMG0adP4v//7P2rWrJli+1mzZlGvXj0eeeQRGjdujGEY/Pjjj8lKeqbVs88+y4IFC3AklBn+R/PmzYmPj3cm/QoXLoy/vz++vr4pJiZT6++//+app56iWrVqdOnShSJFivDLL78kKS8aERHByZMnndtNmjRh/vz5fPbZZwQEBLB48WK+/fZb7rnnHmeb48ePs3nzZnr37n3Hscmd8/DwoF69eoSGhjr3ORwOQkNDk43IFBEREUkPNiO1s3NLuouOjsbHx4eLFy+me911h8PB6dOnKV68eMaWd5g7F3r2NNefecac3y8TZVo/LaZ+5izqZ86SW/oJuaevGdXPjPy9n1PliHsli9y4YU6/PGFC4r5WrQwWLbJxm2py2VNMDGzciLF+PddXr8Z9925scXG3f03hwnDPPVCzZtKvt5lDKavI6f93E+S0fsbGxnL48GEqVKiQZC4OwzCcc/rZsticfukpO/bTMAwaNWrEkCFDkoy2+6/XZLV+/u9//+P8+fN8lo7Dvu+mn7f6XoDse690+fJl59yLdevWZcKECbRo0YLChQtTtmxZFi5cSM+ePfn0009p2LAhkyZNYtGiRezfvz/ZXH9pYbfbnaNxDx48mO3eNxGRHKV9e6sjkKzkhx8y5LSpvVfSnH5yd7p0gSFDICoKFi2CiRPNUkwiIiIiYhk3Nxg/3sxjPfecwfXrNkJDbTRqBN9/DzVqWB1hOsqbF9q0wWjdmqgXX6R4gQLYdu2C9evNeqfbt8NNI2MA8951/XpzuZmvr/nmVK4MVaqYXytXhkqVwNs78/okIpaz2Wx89tln7Nmzx+pQ7krx4sWTzDUo6W/Hjh20aNHCuZ3wfvfs2ZPZs2fTtWtXzpw5w6hRo4iMjKROnTqsWLHirhJ+AMHBwQQHBzs/ABQREREBJf3kbnl5mXOmjB8P167BrFkwbJjVUYmIiIgI5m1a5coGjz3m4OxZVw4dgkaNYMECaNfO6ugyiJcXPPCAuSQ4cQJ27DCX7dvN0vQnTiR/bWSkuaxZk/xY6dKJCcCyZZMuZcpAnjwZ1ycRsUSdOnWoU6eO1WHclZdfftnqEHK8wMBA/quI1sCBA5PNtSgiIiKSEZT0k7v33HNm0g/g00/h5ZchB5TgEREREckJ7r8fli8/x7PPFuPXX21cugSPPAIffGDetmWRCnQZq1Qp6NDBXBKcPw+//24ue/cmfj1zJuVzHD9uLuvWpXy8WLHEJKCfH5QsCSVKmKMHE5ZixcxhmCIiIiIiIiIZQH9xyt2rUgVat4aVK+HPP82vbdpYHZWIiIiI/KNMGQcbNhj07m1jyRIwDLM4w++/m89seXhYHaEFChVKPiIQzGTgn3/CH3/AoUOJXw8dunVCEMxjZ87Azp23bmOzmYm/m5OBxYqZcwwWKWIu/1739s4lmVkRERERERG5W0r6Sfp4/nkz2QcwbZqSfiIiInLH7HY7drud+Ph4q0PJUfLmNadgfustGD3a3Dd7Nhw9CkuWmDkwwXwj6tc3l3+7cMF8wyIiEpdjxxLXjx8Hh+PW5zYMOH3aXFI7T5inZ2ICsHBhbAUK4OPhga14cfDxgQIFbr/kz2+WHlUljizhv0oAiuR0+h5IP7pfEhERkZQo6Sfpo0MHs2zSiRPw/ffw99/m3CYiIiIiaRQcHExwcDDR0dH4+PhYHU6O4uICb74J/v7QowfExZnT1zVpAsuWQcWKVkeYxRUsaC4BASkfv3HDvB8+dgxOnUqcI/Dm9YTl2rXUXTMuzjznP3MQ2oA7mj3Q09McNZiw5Mlz+20vL/M1Hh4pL2k55uaWdHF1zXVJSHd3dwCuXLlCHs3/KLnYlStXgMTvCblzul8SERGRlCjpJ+nDzQ369TMfG3c4YPr0xEfIRURERCRL6dLFnHauY0ezIuX+/XDffeazW/fdZ3V02ZibW+K8frdjGOaowchIOHcucYmKSvlrwvrVq3ceW1ycuZw/f+fnSE82W9Ik4L+SgjY3N4rabNg8PW/ZJsXEYUqlUP+9L63lUm83Mum/Ri39c9wVKBgUxOnmzaFQIbxdXLDZbBiGgWEY3LDZyMlFXA1QP3MQA7hRpgxu7u7YUvn9ZBgGV65c4fTp0xQsWBBXV9eMDVJEREQkl1LST9JPv37wzjsQH28m/V5/HfT0noiIiEiW1Lgx/PILPPywmfQ7cwZatIC5c+GJJ6yOLoez2cwyommtqRobi+PCBc4dPkwRd3dcLl+G6OjbL5cumcnCK1fM5eb12NiM6V9qGAZcv24uKbCR8/5Y9V2/Hnr35nSHDuYISM3VKNlYvMOByz/J67QoWLAgvr6+GRSViIiIiOS0v6PESqVLm2U+v/kGTp40HxXv3NnqqERERETkFipWhM2bzVu2NWvMHFCXLjB2LPzvf8pJZDleXlC8OPEAxYvffYlMhyMxCXhzMjBh+/p1swxpXJz59VbL7Y7HxZllT+Pjza83L//ed9O2ceMGxvXr2BwObDcfv0WSMDuwGQYlZ86k+IIFXC9aVN9gkq2dWb+eIkWL4pKGn0Pu7u4a4SciIiKSwZT0k/Q1YICZ9AOYOlVJPxEREZEsrlAhWLECnnsOZs82940YAYcOmbdzKtyQg7m4QN685pLFGA4Hp0+fpnjx4tj+nVRwOMwk4L9La6ZUajO1bf4rAXe742l8res/C4DD4eD0mTMUL1781smTu4ktNcczgeOmf8+0JImym9zUT/ezZ/Hy8srR/RQRERHJjpT0k/TVqhVUrmx+ShQaCgcPQtWqVkclIiIiIrfh4QEzZ0KVKvDaa+a+GTPgyBFYvBgKFrQyOpF/cXEx/9PmBA6H2RcPj7sfuZmV2WzmPIy3mosxp8hN/cwCyeTczm63Y7fbiY+PtzoUERERyUJy8F2oWMLFBZ5/PnF72jTrYhERERGRVLPZ4NVX4f/+Dzw9zX2hoXD//WbyT0RERLKO4OBgwsPD2b59u9WhiIiISBaipJ+kv169Ej8pmj3bnA9ERERERLKFJ580k31Fipjb4eHQqBFs3WptXCIiIiIiIiJye0r6SforUgS6djXXz5+HRYusjUdERERE0uT+++GXXxKrtJ8+DYGB8O23VkYlIiIiIiIiIrejpJ9kjJtLfE6dal0cIiIiku3Y7Xb8/f1p0KCB1aHkapUrw5Yt0KyZuR0bC507g91ubVwiIiIiIiIikjIl/SRj3HcfBASY61u3wu7d1sYjIiIi2YbmqMk6CheGn3+Gbt3MbYcDBg6E4cPNdRERERERERHJOpT0k4xhs8GAAYnb06ZZF4uIiIiI3DFPT5g710z0JXj/fejeHeLirItLRERERERERJJS0k8yztNPQ7585vqXX0J0tLXxiIiIiMgdcXGBsWPN0p4u//wFMX8+tG0LFy9aG5uIiEhupHLoIiIikhIl/STj5M9vPgIOEBMD8+ZZG4+IiIiI3JUXXoCvv4Y8ecztNWvMOf9OnbI2LhERkdxG5dBFREQkJUr6ScZ6/vnE9WnTwDCsi0VERERE7lrHjrB6NRQtam7/9hsEBsLx45aGJSIiIiIiIpLrKeknGat2bWjSxFzfuxc2bbI2HhERERG5a/fdZ97W+fmZ2/v3myP+jh61Ni4RERERERGR3ExJP8l4AwYkrk+dal0cIiIiIpJuqlaF9euhYkVz+6+/zMTfoUPWxiUiIiIiIiKSWynpJxnv8cehSBFzffFiOHPG2nhEREREJF2UL28m/qpWNbcjIszE3/79loYlIiIiIiIikisp6ScZz8sLevc2169dg1mzrI1HREREMs3SpUupVq0aVapU4fPPP7c6HMkApUvDunVQs6a5ffIktGypEX8iIiIiIiIimU1JP8kczz2XuP7pp+BwWBeLiIiIZIobN24QEhLC6tWr2b17N+PGjePcuXNWhyUZwNcX1q6FunXN7ZMnoVUrzfEnIiIiIiIikpmU9JPMUbkytG5trv/1F6xcaW08IiIikuG2bdtGzZo1KV26NPny5aNt27b8/PPPVoclGaRoUfMW7557zO2ICHPE3/Hj1sYlIiKSE9ntdvz9/WnQoIHVoYiIiEgWoqRfOlHpqlQYMCBxfepU6+IQERGRVFm/fj3t27enVKlS2Gw2vv3222Rt7HY75cuXx8vLi0aNGrFt2zbnsRMnTlC6dGnndunSpTmuDFCOVqQIrFqVOMffX3+ZI/40wFNERCR9BQcHEx4ezvbt260ORURERLIQJf3SgUpXpVL79lCqlLn+ww/w99/WxiMiIiK3FRMTQ0BAAHa7PcXjCxcuJCQkhDfeeINdu3YREBBAmzZtOH36dCZHKllJiRIQGgoVKpjbBw5Ax44QG2ttXCIiIiIiIiI5nZJ+6UClq1LJzQ369TPXHQ6YPt3aeEREROS22rZtyzvvvMOjjz6a4vEJEybQr18/evfujb+/P9OmTcPb25uZM2cCUKpUqSQj+44fP06phAeAJEcrU8ZM/Pn6mtubNkHPnprWWURERERERCQjuVkdwO2MHTuWr7/+mv3795MnTx6aNGnC+++/T7Vq1dLtGuvXr2fcuHHs3LmTkydP8s0339CpU6dk7ex2O+PGjSMyMpKAgAA++ugjGjZsCKh0VZr06wfvvAPx8WbS7/XXwd3d6qhEREQkja5du8bOnTsZMWKEc5+LiwtBQUFs2bIFgIYNG7J3716OHz+Oj48Py5cvZ+TIkbc8Z1xcHHFxcc7t6OhoABwOB450zhY5HA4Mw0j382ZFVvW1XDn4/nsIDLRx5YqNRYugXDmD994zMuR6ueXfVP3MWdTPnEX9vPvzioiIiMjdydJJv3Xr1hEcHEyDBg24ceMGr776Kg8++CDh4eHkzZs3WftNmzbRsGFD3P+VRAoPD6dIkSKUKFEi2WsSylb16dOHxx57LMU4EkpXTZs2jUaNGjFp0iTatGnDgQMHKF68ePp0NrcoXRo6dIBvvoGTJ80yn7d430VERCTrOnv2LPHx8cnur0qUKMH+/fsBcHNzY/z48bRo0QKHw8Err7xCkSJFbnnOsWPHMnr06GT7z5w5Q2w614Z0OBxcvHgRwzBwccnZxS+s7KufH0yb5kmvXgVxOGyMG2ejWLFoune/mu7Xyi3/pupnzqJ+5izq5925dOlSup1LREREJLfK0km/FStWJNmePXs2xYsXZ+fOnTRr1izJMYfDQXBwMFWqVGHBggW4uroCcODAAVq2bElISAivvPJKsmu0bduWtm3b3jaOm0tXAUybNo1ly5Yxc+ZMhg8fnmLpqoRRgJKC5583k34AU6cq6SciIpKDdejQgQ4dOqSq7YgRIwgJCXFuR0dH4+fnR7FixShQoEC6xuVwOLDZbBQrVixHfzAL1ve1WzeIjjYYONAGwGuvFeC++/Jz//3pex2r+5lZ1M+cRf3MWdTPu+Pl5ZVu5xIRERHJrbJ00u/fLl68CEDhwoWTHXNxceHHH3+kWbNm9OjRg3nz5nH48GFatmxJp06dUkz4pUZGlK6y2+3Y7Xbi4+PvKKZsLygIKlWCP/+EVavgjz+gShWroxIREZE0KFq0KK6urpw6dSrJ/lOnTuGbMJFbGnl6euLp6ZnsXsnFxSVDPjy12WwZdu6sxuq+BgfDoUMwaRJcv27jiSds7NxpFoFIT1b3M7OonzmL+pmzqJ93Lqe/ZyIiIiKZIdsk/RwOB4MHD+b+++/nnnvuSbFNqVKlWL16NU2bNuXpp59my5YtBAUFMXXq1Du+bkaUrgoODiY4OJjo6Gh8fHzuOLZsy8XFHO03bJi5/emn8OGH1sYkIiIiaeLh4UG9evUIDQ11zofscDgIDQ1l4MCBd3XuXH+vlEONGwe//QarV8OpU9C5M6xbB56eVkcmIiIit9K+vdURSFbyww9WRyAiIv8l2zxGFRwczN69e1mwYMFt25UtW5Z58+axcOFC3NzcmDFjBjabLcPj69ChAwcPHuTQoUP0798/w6+X7fXqlfgJz6xZcDX953URERGRu3P58mXCwsIICwsD4PDhw4SFhREREQFASEgI06dPZ86cOezbt48BAwYQExPjLIkucjM3N1iwAMqWNbe3boW7zA+LiIiIiIiIyE2yRdJv4MCBLF26lDVr1lCmTJnbtj116hT9+/enffv2XLlyhSFDhtzVtTOidJUARYvCE0+Y61FRsHixtfGIiIhIMjt27KBu3brUrVsXMJN8devWZdSoUQB07dqVDz/8kFGjRlGnTh3CwsJYsWJFsgoJaWW32/H396dBgwZ33QfJWooVM6d2Tpi26fPPYfZsS0MSERHJlnS/JCIiIinJ0kk/wzAYOHAg33zzDatXr6ZChQq3bX/27FlatWpFjRo1+PrrrwkNDWXhwoUMHTr0jmO4uXRVgoTSVY0bN77j8wowYEDi+l2UYBUREZGMERgYiGEYyZbZN2VpBg4cyNGjR4mLi2Pr1q00atTorq8bHBxMeHg427dvv+tzSdZz770wfXridnAwhIdbF4+IiEh2pPslERERSUmWTvoFBwfzxRdfMH/+fPLnz09kZCSRkZFcTaEUpMPhoG3btpQrV85Z2tPf35+VK1cya9YsJk6cmOI1/qtsFah0VYZp3Bhq1TLXt2yBX3+1Nh4RERERyRTPPAPPPmuuX7kCXbqYX0VERERERETkzmXppN/UqVO5ePEigYGBlCxZ0rksXLgwWVsXFxfGjBnDkiVL8PDwcO4PCAhg1apVPJFQSvJf/qtsFWRc6apcz2bTaD8RERFJRuWqcocpUxKf//r9d3jxRWvjEREREREREcnu3KwO4HYMw0hT+9atW6e4PyGhl5KEslX/ZeDAgQwcODBN8UgqdOsGr7wCly/Dl1/CuHGQP7/VUYmIiIiFgoODCQ4OJjo6Gh8fH6vDkQySJw8sWgT160NMDMycCS1amKMARURERERERCTtsvRIP8kFChQwE3+QmPgTERERkVyhevWkxR5eeAGOHLEsHBEREREREZFsTUk/sd5zzyWuT5sGaRzhKSIiIjmLynvmLt27Q48e5vqlS+Z2fLy1MYmIiIiIiIhkR0r6ifXq1oVGjcz1X3+FrVutjUdEREQsFRwcTHh4ONu3b7c6FMkkH30E5cub6xs3wgcfWBqOiIiIiIiISLakpJ9kDc8/n7g+bZp1cYiIiIhIpitQAObNA5d//joZNQp27rQ2JhEREREREZHsRkk/yRq6doWCBc31hQshKsrScEREREQkcz3wAIwYYa7fuGFO+3zlirUxiYiIiIiIiGQnSvpJ1pAnD/TqZa7HxsKcOZaGIyIiIiKZ7403oH59c/3AARg61Np4RERERERERLITJf0k63juucT1adPAMKyLRURERCxjt9vx9/enQYMGVocimczdHb74wnweDGDqVPjxR2tjEhEREREREckulPSTrKN6dQgMNNcPHoS1a62MRkRERCwSHBxMeHg427dvtzoUsUC1ajBhQuJ2375w9qx18YiIiIiIiIhkF25WByCSxPPPJyb7pk2DFi0sDUdEREREMt9zz8H338Py5RAZCQMGwKJFYLNZHZlkNIcDLlyAU6fgwAF3btyA6Gi4dCnx681LbCxcv27OA3n9etJ1wwAXF3Ox2ZKvp7TvTtb/q93t/t8aho3Y2AJ4edks/f+d0ddOj35mh+//rPLvmdEMw8bbb1sdhdjtdux2O/Hx8VaHIiIiIlmIkn6StTz6KBQvDqdPw9dfm3/tlyhhdVQiIiIikolsNpgxA+65B6KiYPFimD8funWzOjK5U7GxcPw4/P23+TVhOX3aXM6cMb+ePWsm7cyiNEUsjjoz2ABvq4PIBOpnzqKkX1YQHBxMcHAw0dHR+Pj4WB2OiIiIZBFK+knW4uFh1nAaO9b8a3/GDHj1VaujEhEREZFMVrKkWfihSxdzOzgYmjUDPz9r45Lk4uPNBN7hw+Zy9GjSBN/ff5vJ28zg6mrODenmZiaPDcMcPehwpLwuIiIiIiKSkyjpJ1lPv37w3nvmX+KffQb/+5/517uIiIjkCipXJQmeeMIc3ffll3DxIvTuDT//bJZNlMx1+TIcOAB//gl//ZWY4EtI8l2/fnfn9/AwC34UK2Z+LVrUIF++K5Qrl4ciRVzInx/nUqBA4nqePGaC7+ZEX1oYRmIC8L8ShLdbv92x23E4HJw7d44iRYrgkg7/sQ3jrk+RIddyOBxERUVRuHDhO+pnZvbrbtxtP7MLh8ORo8uXioiIiGRnSvpJ1lOhAjz0kDmJy9Gj8NNP0K6d1VGJiIhIJlG5KrnZxx+bUz4fPw6hoWC3w4svWh1VznXuHPz+O+zbl3Q5duzOzufuDqVLm0uZMsnXS5Qwk3z58ydN2DkcBqdPX6J48TwZmuRNmHPPqvyMwwGnT8dTvHjOTmab/byhfuYQZj+tjkJEREREUqKkn2RNAwaYST8w6zop6SciIiKSKxUsCLNnQ+vW5vYrr5jr1atbGVXOcPIk7NqVdImISNs58uc3n9lLWCpWhHLlzDKspUtD0aI5O/khIiIiIiKSlSjpJ1lTu3bmJwXHjsGyZeanD2XLWh2ViIiIiFggKMgc3ffRRxAbC927w+bN5igySR2HA8LDYcOGxOXvv1P32oIFoUYNM9FataqZ2EtI8hUpkvaSmiIiIiIiIpIxlPSTrMnV1Zzbb9Qo8xOK6dPh7betjkpERERELPLee+Z8fgcOwI4dMGYMvPGG1VFlXYYBf/xhFs8IDYVNmyAq6vavyZ8f6taF2rXB399M8tWoYZbgVGJPREREREQk61PST7Kuvn1h9GiIj4fPPzcTgHqcW0RERCRX8vaGefOgcWPz9vDtt83iEA0aWB1Z1hETA6tXw4oVZrLv8OFbt/X2hvvug/r14d57zaVSJZXiFBERERERyc6U9JOsq1Qp6NgRvv4aIiPh+++hc2eroxIREZEMZrfbsdvtxMfHWx2KZDENGsDrryc+F9a9O+zeDXnyWB2Zdc6fh+++g8WLYeVKuHYt5XZFisADD0DTpuZSt66epxMREREREclp9BynZG0DBiSuT5tmXRwiIiKSaYKDgwkPD2f79u1WhyJZ0GuvmaPTwCz1OXy4tfFY4dw5GzNmQNu2ULw49O5tToN9c8LP3R1atIAPPoBff4XTp+Hbb+Hll6FhQyX8REREREREciKN9JOsrWVLqFwZDh2CVavMiUmqVLE6KhERERGxiLu7Weazbl2IjYUpU6B9e/O2MSeLi4OlS2H2bBvLlxcnPj75JHulS5vvRdu2ZsIvf34LAhURERERERHLaKSfZG0uLvDcc4nbn35qXSwiIiIikiVUrw7vv5+43bs3XLhgWTgZaudOGDjQrHz/+OOwdKktScKvbFkICYHNmyEiAqZOhQ4dlPATERERERHJjZT0k6yvVy/w8DDXZ80yH+kWERERkVxt4EBo1cpc//tvGDQo+ci37OrqVZgzxyzDWb8+2O0QFZV4vGTJeIYONdi2DY4cgfHjoXFj83k5ERERERERyb30Z6FkfUWLwhNPmOtRUbB4sbXxiIiIiIjlXFzM58F8fMztL7+0sXSpp7VB3aUjR2DYMChTxnzu7eZpLfPkgW7dYMUKB9u3n+H99w0aNABbzsl1ioiIiIiIyF1S0k+yhwEDEtenTrUuDhERERHJMvz84OOPE7dfecWHkyeti+dOhYWZCb3KleHDD5OO6qtTx6xwHxkJX3wBrVuDq6tVkYqIiIiIiEhWpqSfZA9NmsA995jrmzfDb79ZG4+IiIiIZAnduplz3QGcP+/Cs8/acDisjSk1DANCQ6FNG6hbF+bPh/h485iHBzzzDGzZArt2Qf/+UKCAtfGKiIiIiIhI1qekn2QPNhs8/3zi9qefWheLiIiIiGQZNhtMmwa+vgYAK1bYeO89i4O6DcOA776DBg0gKAh+/jnxWNGi8NZb5hyF8+bBffepfKeIiIiIiIiknpJ+kn088wx4e5vr8+bB5cvWxiMiIiIiWUKRIjBrloHNZib+Xn8dVqywOKh/MQz48Ucz2depE+zcmXisQgWw2+HoURg5EooVsyxMERHJJux2O/7+/jRo0MDqUERERCQLUdJPsg8fH7N+E8ClS/B//2dtPCIiIpIh9CGW3IkHH4Rhw8yHwgwDnn4aDh2yOKh/Ylm50qxW//DDSZN9devCggVw8CC88ELi820iIiL/JTg4mPDwcLZv3251KCIiIpKFKOkn2ctzzyWuT51qfooiIiIiOYo+xJI79dJLMbRvb94fnj8PbdvCmTPWxbN2LTRvbiYkf/klcX+dOvD992YCsGtXcHOzKkIRERERERHJSZT0k+ylXj2zJhLA7t2gDwNFRERE5B8uLjBnjkHNmub2oUPQvj1cuZK5cfzyizlfX4sWsGFD4v577oElS8xkX/v2mq9PRERERERE0peSfpL9PP+8c9X26acWBiIiIiIiWY2Pjzl3XqlS5vbWrfDoo5mT+Pv1VzOZ17gxhIYm7q9e3Szj+euv8NhjZnJSREREREREJL3pz03Jfrp2NT/NAVi4ENuFC5aGIyIiIiJZS9myZuIvf35z++efzfn0Ll/OmOsdOGDeotapA0uXJu6vWBHmzoW9e83jSvaJiGS+6Ohovv32W/bt22d1KCIiIiIZTn92SvaTNy/07AmA7epV8nz1lcUBiYiIiEhWExAAy5cnJv7WroVWreDvv9PvGn/8Ab17g78/LFqUuL90afj0U9i/H7p3B1fX9LumiIjcXpcuXfj4448BuHr1KvXr16dLly7Url2bJUuWWBydiIiISMZS0k+yp+eec656z50LhmFhMCIiIiKSFd1/P6xaBQULmtvbtkHduua+u7FjBzzxBFSrBrNng8Nh7i9WDCZONOcS7N8f3N3v7joiIpJ269evp2nTpgB88803GIbBhQsXmDJlCu+8847F0YmIiIhkLCX9JHvy94dmzQBwO3QI1q+3OCARERERyYoaNjRH+ZUrZ26fPQutW0OPHnDsWOrPc/UqfPEFNG8ODRrA4sWJz50VLAjvvgt//QWDB4OXVzp3QkREUu3ixYsULlwYgBUrVtC5c2e8vb15+OGH+eOPPyyOTkRERCRjKekn2dfzzztXbZ9+amEgIiIiIpKVBQTArl3Qtm3ivnnzoGpV6NcPQkPh0qWkr4mPh4MHzXZdu4Kvr1mq8+ZnzUqUgDFj4PBhePVVyJcvc/ojIiK35ufnx5YtW4iJiWHFihU8+OCDAJw/fx4vPZUhIiIiOZySfpJ9PfYYRrFi5vrXX8Pp09bGIyIiIsk8+uijFCpUiMcff9zqUCSXK1wYli6FKVOgUCFzX2wsfP45BAVBgQJmYq96dShf3tyuVs0cEbhoEURHJ56rWjWYNg2OHIERIxLLh4qIiPUGDx5Mt27dKFOmDKVKlSIwMBAwy37WqlXL2uBEREREMpiSfpJ9eXpC794A2K5fh5kzLQ5IRERE/u2ll15i7ty5VochAoCLC7z4Ivz5J7z8MuTPn/T4qVNw4AAcPQpXriQ9Vrgw9OoFGzbAvn3mFNMaMCIikvW88MILbNmyhZkzZ7Jx40ZcXMyPvipWrKg5/URERCTHc7M6AJG7YfTrh+2DD8yNTz+FV14xP80RERGRLCEwMJC1a9daHYZIEoUKwYcfwptvwrJlsGqVmez74w8z2ZcnD/j4wD33mKVBAwOhSRNw019PIiLZQv369alfvz4A8fHx7NmzhyZNmlAoYai3iIiISA6l7IhkbxUrEvdPqQ6OHIGff7YyGhERkWxl/fr1tG/fnlKlSmGz2fj222+TtbHb7ZQvXx4vLy8aNWrEtm3bMj9QkQySL585X9/06eZcfSdPwsWLEBlpJgGXLIFRo6BZMyX8RESyi8GDBzNjxgzATPg1b96ce++9Fz8/Pz2IJCIiIjmekn6S7V3p0SNxY9o06wIRERHJZmJiYggICMBut6d4fOHChYSEhPDGG2+wa9cuAgICaNOmDadvmke3Tp063HPPPcmWEydOZFY3RERERJwWL15MQEAAAD/88AOHDx9m//79DBkyhNdee83i6EREREQylp5XlWwvrnVrjNKlsR0/Dj/8ABERULas1WGJiIhkeW3btqVt27a3PD5hwgT69etH73/m0J02bRrLli1j5syZDB8+HICwsLDMCFVEREQkVc6ePYuvry8AP/74I0888QRVq1alT58+TJ482eLoRERERDKWkn6S/bm5mXP7vfkmOBzm3H7vvmt1VCIiItnatWvX2LlzJyNGjHDuc3FxISgoiC1btmTINePi4oiLi3NuR0dHA+BwOHA4HOl6LYfDgWEY6X7erCi39FX9zFnUz5xF/cxZMqqf6XW+EiVKEB4eTsmSJVmxYgVTp04F4MqVK7i6uqbLNURERESyKiX9JGd49ll45x24ccOclGXUKPD0tDoqERGRbOvs2bPEx8dTokSJJPtLlCjB/v37U32eoKAgfv31V2JiYihTpgxfffUVjRs3TrHt2LFjGT16dLL9Z86cITY2Nm0d+A8Oh4OLFy9iGAYuLjm74n1u6av6mbOonzmL+pmzZFQ/L126lC7n6d27N126dKFkyZLYbDaCgoIA2Lp1K9WrV0+Xa4iIiIhkVUr6Sc5QsiR07gwLF8KZM/DVV/DMM1ZHJSIikuutWrUq1W1HjBhBSEiIczs6Oho/Pz+KFStGgQIF0jUuh8OBzWajWLFiOfqDWcg9fVU/cxb1M2dRP3OWjOqnl5dXupznzTff5J577uHYsWM88cQTeP7zQLCrq6uzPLmIiIhITqWkn+QcwcFm0g/AblfST0RE5C4ULVoUV1dXTp06lWT/qVOnnPPkpDdPT088PT2x2+3Y7Xbi4+MBs6xoRnx4arPZMuzcWU1u6av6mbOonzmL+pmzZEQ/0/Ncjz/+eLJ9PXv2TLfzi4iIiGRVOfsuVHKXBx6AWrXM9V9+gV27rI1HREQkG/Pw8KBevXqEhoY69zkcDkJDQ29ZnjO9BAcHEx4ezvbt2zP0OiIiIpIzrVu3jvbt21O5cmUqV65Mhw4d2LBhg9VhiYiIiGQ4Jf0k57DZzNF+Cex262IRERHJBi5fvkxYWBhhYWEAHD58mLCwMCIiIgAICQlh+vTpzJkzh3379jFgwABiYmLo3bu3hVGLiIiI3NoXX3xBUFAQ3t7eDBo0iEGDBpEnTx5atWrF/PnzrQ5PREREJEOpvKfkLN26wSuvQHQ0zJ8P48ZB4cJWRyUiIpIl7dixgxYtWji3E+bT69mzJ7Nnz6Zr166cOXOGUaNGERkZSZ06dVixYgUlSpTI0Lj+Xd5TREREJLXeffddPvjgA4YMGeLcN2jQICZMmMDbb7/N008/bWF0IiIiIhlLI/0kZ8mXDxJGH8TGwqxZ1sYjIiKShQUGBmIYRrJl9uzZzjYDBw7k6NGjxMXFsXXrVho1apThcam8p4iIiNypv/76i/bt2yfb36FDBw4fPmxBRCIiIiKZR0k/yXleeCFx/ZNPwOGwLhYREZF0tmLFCjZu3Ojcttvt1KlTh6effprz589bGJmIiIiI9fz8/JLMSZxg1apV+Pn5WRDRf3v00UcpVKgQjz/+uNWhiIiISDanpJ/kPFWrQuvW5vpff8GKFdbGIyIiko6GDRtGdHQ0AHv27OHll1+mXbt2HD582FmeM7uz2+34+/vToEEDq0MRERGRbObll19m0KBBDBgwgHnz5jFv3jyef/55Bg8ezNChQ60OL0UvvfQSc+fOtToMERERyQE0p5/kTMHBsHKluW63Q7t21sYjIiKSTg4fPoy/vz8AS5Ys4ZFHHmHMmDHs2rWLdjnk911wcDDBwcFER0fj4+NjdTgiIiKSjQwYMABfX1/Gjx/PokWLAKhRowYLFy6kY8eOFkeXssDAQNauXWt1GCIiIpIDpMtIvwsXLqTHaUTSzyOPQNmy5vry5eaIPxERkRzAw8ODK1euAGaZqgcffBCAwoULO0cAioiIiORmjz76KBs3buTcuXOcO3eOjRs30rx5c+bPn5/mc61fv5727dtTqlQpbDYb3377bbI2drud8uXL4+XlRaNGjdi2bVs69EJEREQk7dKc9Hv//fdZuHChc7tLly4UKVKE0qVL8+uvv6ZrcCJ3zNUVnn/eXDcMmDrV2nhERETSyQMPPEBISAhvv/0227Zt4+GHHwbg4MGDlClTxuLo0ofKe4qIiEh6O3r0KN27d0/z62JiYggICMBut6d4fOHChYSEhPDGG2+wa9cuAgICaNOmDadPn3a2qVOnDvfcc0+y5cSJE3fcHxEREZGUpLm857Rp0/jyyy8BWLlyJStXrmT58uUsWrSIYcOG8fPPP6d7kCJ35Nln4c034do1mDEDRo8Gb2+roxIREbkrH3/8MS+88AKLFy9m6tSplC5dGoDly5fz0EMPWRxd+lB5TxEREckq2rZtS9u2bW95fMKECfTr14/evXsD5udmy5YtY+bMmQwfPhyAsLCwdIsnLi6OuLg453ZCpQeHw4HD4Ui36ySw2dL9lJKNZcB/MZGcQT8s5WYZ9MMytb/n05z0i4yMxM/PD4ClS5fSpUsXHnzwQcqXL0+jRo3SejqRjFOsGHTtCvPmwfnzsGAB9OljdVQiIiJ3pWzZsixdujTZ/okTJ1oQjYiIiEjude3aNXbu3MmIESOc+1xcXAgKCmLLli0Zcs2xY8cyevToZPvPnDlDbGxsul/vn48ARQC4aQCriNxMPyzlZhn0w/LSpUupapfmpF+hQoU4duwYfn5+rFixgnfeeQcAwzCIj49P6+lEMlZwsJn0A7DboXdvPXkhIiLZ2q5du3B3d6dWrVoAfPfdd8yaNQt/f3/efPNNPDw8LI5QREREJHc4e/Ys8fHxlChRIsn+EiVKsH///lSfJygoiF9//ZWYmBjKlCnDV199RePGjVNsO2LECEJCQpzb0dHR+Pn5UaxYMQoUKHBnHbmNY8fS/ZSSjRUvbnUEIlmUfljKzTLoh6WXl1eq2qU56ffYY4/x9NNPU6VKFc6dO+cscbB7924qV66c1tOJZKyGDaFePdi5E3btgs2b4f77rY5KRETkjj333HMMHz6cWrVq8ddff/Hkk0/y6KOP8tVXX3HlyhUmTZpkdYgiIiIimW7KlCm3PX78+PFMiiTtVq1aleq2np6eeHp6Jtvv4uKCi4tLeoYFgGGk+yklG8uA/2IiOYN+WMrNMuiHZWp/z6c56Tdx4kTKly/PsWPH+OCDD8iXLx8AJ0+e5IUXXkjr6UQyls0GgwZBz57m9qRJSvqJiEi2dvDgQerUqQPAV199RbNmzZg/fz6bNm3iySefzBFJP7vdjt1uVxUJERERSbXUlDovW7Zsul6zaNGiuLq6curUqST7T506ha+vb7peS0RERCQ10pz0c3d3Z+jQocn2DxkyJF0CEkl3XbvCK6/AqVPwzTcQEQHpfKMvIiKSWQzDcE7evGrVKh555BEA/Pz8OHv2rJWhpZvg4GCCg4OJjo7Gx8fH6nBEREQkGzh8+HCmX9PDw4N69eoRGhpKp06dAHA4HISGhjJw4MBMj0dEREQkzeMM58yZw7Jly5zbr7zyCgULFqRJkyYcPXo0XYMTSReenjBggLkeH2/O7SciIpJN1a9fn3feeYd58+axbt06Hn74YcD8oOvf88mIiIiIyN25fPkyYWFhhIWFAeY9V1hYGBEREQCEhIQwffp05syZw759+xgwYAAxMTH07t07Q+Oy2+34+/vToEGDDL2OiIiIZC9pTvqNGTOGPHnyALBlyxbsdjsffPABRYsW1Wg/ybqefx48PMz1zz6DmBhr4xEREblDkyZNYteuXQwcOJDXXnvNOafy4sWLadKkicXRiYiIiOQsO3bsoG7dutStWxcwk3x169Zl1KhRAHTt2pUPP/yQUaNGUadOHcLCwlixYkWGP4wVHBxMeHg427dvz9DriIiISPaS5vKex44dc3649O2339K5c2f69+/P/fffT2BgYHrHJ5I+SpSAp56COXPgwgWYN89MBIqIiGQztWvXZs+ePcn2jxs3DldXVwsiEhEREcm5AgMDMQzjtm0GDhyocp4iIiKSJaR5pF++fPk4d+4cAD///DOtW7cGwMvLi6tXr6ZvdCLp6aWXEtcnT4Z/5kMSERHJjnbu3MkXX3zBF198wa5du/Dy8sLd3d3qsNKFylWJiIiIiIiIiKRdmkf6tW7dmmeffZa6dety8OBB2rVrB8Dvv/9O+fLl0zs+kfRTty40bQobNsD+/bByJbRpY3VUIiIiaXL69Gm6du3KunXrKFiwIAAXLlygRYsWLFiwgGLFilkbYDoIDg4mODiY6OhofHx8rA5HRERERERERCRbSPNIP7vdTuPGjTlz5gxLliyhSJEigPm0+VNPPZXuAYqkq8GDE9cnT7YsDBERkTv14osvcvnyZX7//XeioqKIiopi7969REdHM2jQIKvDExEREcl00dHRqV5yClVGEBERkZSkeaRfwYIF+fjjj5PtHz16dLoEJJKhOnaEcuXg6FFYvhwOHIBq1ayOSkREJNVWrFjBqlWrqFGjhnOfv78/drudBx980MLIRERERKxRsGBBbDZbqtrGx8dncDSZQ5URREREJCVpTvqBWUJqxowZ7Nu3D4CaNWvSp08f3WRI1ufqCgMHwrBh5vZHH0EKSWwREZGsyuFwpDh3n7u7Ow7NVysiIiK50Jo1a5zrR44cYfjw4fTq1YvGjRsDsGXLFubMmcPYsWOtClFEREQkU6S5vOeOHTuoVKkSEydOdJaUmjBhApUqVWLXrl0ZEaNI+urbF/LmNddnz4YLF6yMRkREJE1atmzJSy+9xIkTJ5z7jh8/zpAhQ2jVqpWFkYmIiIhYo3nz5s5l7ty5TJgwgbFjx9KhQwc6dOjA2LFj+fDDD5k1a5bVoYqIiIhkqDQn/YYMGUKHDh04cuQIX3/9NV9//TWHDx/mkUceYfDN86WJZFWFCkHPnuZ6TAzMmGFtPCIiImnw8ccfEx0dTfny5alUqRKVKlWiQoUKREdHM2XKFKvDSxeao0ZERETu1JYtW6hfv36y/fXr12fbtm0WRCQiIiKSee5opN///vc/3NwSK4O6ubnxyiuvsGPHjnQNTiTDDBqUuD5lCty4YV0sIiIiaeDn58euXbtYtmwZgwcPZvDgwfz444/s2rULPz8/q8NLF8HBwYSHh7N9+3arQxEREZFsxs/Pj+nTpyfb//nnn+eYeyURERGRW0nznH4FChQgIiKC6tWrJ9l/7Ngx8ufPn26BiWSoatWgXTv48UeIiIBvvoEnnrA6KhERkVSx2Wy0bt2a1q1bO/ft37+fDh06cPDgQQsjExEREbHWxIkT6dy5M8uXL6dRo0YAbNu2jT/++IMlS5ZYHF36sdvt2O124uPjrQ5FREREspA0j/Tr2rUrffv2ZeHChRw7doxjx46xYMECnn32WZ566qmMiFEkY4SEJK5PmGBdHCIiIukgLi6OP//80+owRERERCzVrl07Dh48SPv27YmKiiIqKor27dtz8OBB2rVrZ3V46UaVEURERCQlaR7p9+GHH2Kz2ejRowc3/imJ6O7uzoABA3jvvffSPUCRDNOyJdSuDb/9Br/8Alu2QOPGVkclIiIiIiIiInfBz8+PMWPGWB2GiIiISKZL80g/Dw8PJk+ezPnz5wkLCyMsLIyoqCjGjRvHuXPnMiJGkYxhs8GQIYnbGu0nIiIiIiIiku1t2LCBZ555hiZNmnD8+HEA5s2bx8aNGy2OTERERCRjpTnpl8Db25tatWpRq1YtvL29+f333zUhsmQ/Tz0FJUqY619/DYcPWxuPiIiIiIiIiNyxJUuW0KZNG/LkycOuXbuIi4sD4OLFixr9JyIiIjneHSf9RHIET08YONBcdzhgyhRr4xEREbmFQoUKUbhw4VsuTZs2tTpEEREREcu98847TJs2jenTp+Pu7u7cf//997Nr1y4LIxMRERHJeGme008kx3n+eXj3XYiNhRkz4M03wcfH6qhERESSmDRpktUhiIiIiGR5Bw4coFmzZsn2+/j4cOHChcwPSERERCQTKeknUrQo9OgBn30Gly6Zib+QEKujEhERSaJnz55WhyAiIiKS5fn6+nLo0CHKly+fZP/GjRupWLGiNUFlALvdjt1uJz4+3upQREREJAtJddLvt99+u+3xAwcO3HUwIpYZPNhM+gFMngyDBoGbcuIiIiJW0IdYIiIicqf69evHSy+9xMyZM7HZbJw4cYItW7YwdOhQRo4caXV46SY4OJjg4GCio6PxUbUiERER+Ueqsxp16tTBZrNhGEayYwn7bTZbugYnkmlq1IB27eDHHyEiAr7+Grp0sToqERGRXEkfYomIiMidGj58OA6Hg1atWnHlyhWaNWuGp6cnQ4cO5cUXX7Q6PBEREZEMleqk3+HDhzMyDhHrhYSYST+A8ePhiSdAiWwRERERERGRbMNms/Haa68xbNgwDh06xOXLl/H39ydfvnxWhyYiIiKS4VKd9CtXrlxGxiFivZYtoXZt+O032LYNtmyBJk2sjkpEREREREREUqlPnz5MnjyZ/Pnz4+/v79wfExPDiy++yMyZMy2MTkRERCRjuVgdgEiWYbPBkCGJ2xMmWBeLiIiIiIiIiKTZnDlzuHr1arL9V69eZe7cuRZEJCIiIpJ5Uj3STyRXeOopGD4cTp2Cb76Bw4ehQgWroxIRkVwuJCQk1W0n6KEVERERyYWio6MxDAPDMLh06RJeXl7OY/Hx8fz4448UL17cwghFREREMp6SfiI38/SEgQNh5EhwOGDKFJg40eqoREQkl9u9e3eS7V27dnHjxg2qVasGwMGDB3F1daVevXpWhCciIiJiuYIFC2Kz2bDZbFStWjXZcZvNxujRoy2ITERERCTzKOkn8m/PPw/vvguxsTB7NowZA3nyWB2ViIjkYmvWrHGuT5gwgfz58zNnzhwKFSoEwPnz5+nduzdNmza1KkQRERERS61ZswbDMGjZsiVLliyhcOHCzmMeHh6UK1eOUqVKWRhh+rLb7djtduLj460ORURERLIQJf1E/q1oUejSBebOhQsXYPFi6N7d6qhEREQAGD9+PD///LMz4QdQqFAh3nnnHR588EFefvllC6MTERERsUbz5s0BOHz4MH5+fri4uFgcUcYKDg4mODiY6OhofHx8rA5HREREsog0J/1OnTrF0KFDCQ0N5fTp0xiGkeS4njCSHKF/fzPpB/DZZ0r6iYhIlhEdHc2ZM2eS7T9z5gyXLl2yIKJbO3bsGN27d+f06dO4ubkxcuRInnjiCavDEhERkRysXLlyXLhwgW3btnH69GkcDkeS4z169LAoMhEREZGMl+akX69evYiIiGDkyJGULFkSm82WEXGJWKtJE/D3h/Bw2LjR/Orvb3VUIiIiPProo/Tu3Zvx48fTsGFDALZu3cqwYcN47LHHLI4uKTc3NyZNmkSdOnWIjIykXr16tGvXjrx581odmoiIiORQP/zwA926dePy5csUKFAgyedWNptNST8RERHJ0dKc9Nu4cSMbNmygTp06GRCOSBZhs5mj/QYPNrenT4eJEy0NSUREBGDatGkMHTqUp59+muvXrwNmcq1v376MGzfO4uiSKlmyJCVLlgTA19eXokWLEhUVpaSfiIiIZJiXX36ZPn36MGbMGLy9va0OR0RERCRTpbnAuZ+fX7KSniI5Uvfu4Olprs+ZA7Gx1sYjIiICeHt788knn3Du3Dl2797N7t27iYqK4pNPPklzMm39+vW0b9+eUqVKYbPZ+Pbbb5O1sdvtlC9fHi8vLxo1asS2bdvuKO6dO3cSHx+Pn5/fHb1eREREJDWOHz/OoEGDlPATERGRXCnNSb9JkyYxfPhwjhw5kgHhiGQhhQtDwrxD58/DkiXWxiMiInKTkydPcvLkSapUqULevHnv6KGsmJgYAgICsNvtKR5fuHAhISEhvPHGG+zatYuAgADatGnD6dOnnW3q1KnDPffck2w5ceKEs01UVBQ9evTgs88+S3tHRURERNKgTZs27Nixw+owRERERCyR5vKeXbt25cqVK1SqVAlvb2/c3d2THI+Kikq34EQs178/fPGFuf7ZZ9Ctm7XxiIhIrnfu3Dm6dOnCmjVrsNls/PHHH1SsWJG+fftSqFAhxo8fn+pztW3blrZt297y+IQJE+jXrx+9e/cGzNKiy5YtY+bMmQwfPhyAsLCw214jLi6OTp06MXz4cJo0aZLq2ERERERS6/vvv3euP/zwwwwbNozw8HBq1aqV7HOrDh06ZHZ4IiIiIpkmzUm/SZMmZUAYIlnUAw9A9eqwfz+sXw8HDkC1alZHJSIiudiQIUNwd3cnIiKCGjVqOPd37dqVkJCQNCX9bufatWvs3LmTESNGOPe5uLgQFBTEli1bUnUOwzDo1asXLVu2pHv37v/ZPi4ujri4OOd2dHQ0AA6HA4fDkcYe3J7D4cAwjHQ/b1aUW/qqfuYs6mfOon7mLBnVz7s5X6dOnZLte+utt5Lts9lsxMfH3/F1RERERLK6NCf9evbsmRFxiGRNNps52i8kxNyePh0+/NDamEREJFf7+eef+emnnyhTpkyS/VWqVOHo0aPpdp2zZ88SHx9PiRIlkuwvUaIE+/fvT9U5Nm3axMKFC6ldu7ZzvsB58+ZRq1atFNuPHTuW0aNHJ9t/5swZYtN5bl2Hw8HFixcxDAMXlzRXvM9Wcktf1c+cRf3MWdTPnCWj+nnp0qW7iklERERE7iDpBxAfH8+3337Lvn37AKhZsyYdOnTA1dU1XYMTyRJ69IDhw+HaNZg9G959Fzw9rY5KRERyqZiYGLy9vZPtj4qKwjOL/X564IEH0vQh3IgRIwhJeNAGc6Sfn58fxYoVo0CBAukam8PhwGazUaxYsRz9wSzknr6qnzmL+pmzqJ85S0b108vLK93OlRvY7XbsdrtGLoqIiEgSaU76HTp0iHbt2nH8+HGq/VPmcOzYsfj5+bFs2TIqVaqU7kGKWKpIEXj8cZg/H86dg2++gSeftDoqERHJpZo2bcrcuXN5++23AbNMlcPh4IMPPqBFixbpdp2iRYvi6urKqVOnkuw/deoUvr6+6Xadm3l6euLp6ZnsQywXF5cM+fDUZrNl2LmzmtzSV/UzZ1E/cxb1M2fJiH6m17mmTJmS4n6bzYaXlxeVK1emWbNm2f7B9eDgYIKDg4mOjsbHx8fqcERERCSLSHPSb9CgQVSqVIlffvmFwoULA3Du3DmeeeYZBg0axLJly9I9SBHL9etnJv0AZsxQ0k9ERCzzwQcf0KpVK3bs2MG1a9d45ZVX+P3334mKimLTpk3pdh0PDw/q1atHaGioc54ch8NBaGgoAwcOTLfrpEQfYomIiMidmjhxImfOnOHKlSsUKlQIgPPnz+Pt7U2+fPk4ffo0FStWZM2aNfj5+VkcrYiIiEj6SvNjVOvWreODDz5wJvwAihQpwnvvvce6devSNTiRLKN5c0gYxbpqFRw5Ymk4IiKSe91zzz0cPHiQBx54gI4dOxITE8Njjz3G7t2701xx4fLly4SFhREWFgbA4cOHCQsLIyIiAoCQkBCmT5/OnDlz2LdvHwMGDCAmJobevXund7dERERE0sWYMWNo0KABf/zxB+fOnePcuXMcPHiQRo0aMXnyZCIiIvD19WXIkCFWhyoiIiKS7tI80s/T0zPFyZUvX76Mh4dHugQlkuXYbNC7N7z+urk9eza8+aaVEYmISC4VERGBn58fr732WorHypYtm+pz7dixI0lJ0IT59Hr27Mns2bPp2rUrZ86cYdSoUURGRlKnTh1WrFhBiRIl7r4jt6E5akREROROvf766yxZsiTJw1CVK1fmww8/pHPnzvz111988MEHdO7c2cIoRURERDJGmkf6PfLII/Tv35+tW7diGAaGYfDLL7/w/PPP06FDh4yIUSRr6NULEuYYmDUL9EGkiIhYoEKFCpw5cybZ/nPnzlGhQoU0nSswMNB5P3fzMnv2bGebgQMHcvToUeLi4ti6dSuNGjW62y78p+DgYMLDw9m+fXuGX0tERERylpMnT3Ljxo1k+2/cuEFkZCQApUqVSvGBdhEREZHsLs1JvylTplCpUiUaN26Ml5cXXl5e3H///VSuXJnJkydnRIwiWUPp0vDQQ+Z6RASEhlobj4iI5EqGYWCz2ZLtv3z5Ml5eXhZEJCIiIpJ1tGjRgueee47du3c79+3evZsBAwbQsmVLAPbs2ZPmh6VEREREsoM0l/csWLAg3333HX/88Qf79+8HoEaNGlSuXDndgxPJcvr2hR9/NNdnzYIHH7Q2HhERyTUSSm/abDZGjhyJt7e381h8fDxbt26lTp06FkWXvlTeU0RERO7UjBkz6N69O/Xq1cPd3R0wR/m1atWKGTNmAJAvXz7Gjx9vZZgiIiIiGSLNSb8EVapUoUqVKukZi0jW98gjUKQInDsH330Hly9DvnxWRyUiIrlAwtPqhmGwZ8+eJHMpe3h4EBAQwNChQ60KL10FBwcTHBxMdHQ0Pj4+VocjIiIi2Yivry8rV65k//79HDx4EIBq1apRrVo1Z5ub5zQWERERyUlSlfQLCQnh7bffJm/evM6nzG9lwoQJ6RKYSJbk4QFdusDUqXD1qpn469bN6qhERCQXWLNmDQC9e/dm8uTJFChQwOKIRERERLKu6tWrU716davDEBEREclUqUr67d69m+vXrzvXbyWl+WVEcpynnzaTfgDz5yvpJyIimWrWrFlWh5DhVN5TRERE0kIPq4uIiIiYUpX0S3iy/N/rIrlSkyZQpgz8/TesWqUSnyIikqliYmJ47733CA0N5fTp0zgcjiTH//rrL4siSz8q7ykiIiJpoYfVRUREREx3PKdfgujoaFavXq2yCZJ7uLiYc/tNmwbXrsHq1dChg9VRiYhILvHss8+ybt06unfvTsmSJfXhlYiIiOR6elhdRERExJTmpF+XLl1o1qwZAwcO5OrVq9SvX58jR45gGAYLFiygc+fOGRGnSNbSrp2Z9AP48Ucl/UREJNP8f3v3HR5Vlf9x/DOTSkIKJSSU0EEIJSBNdBUCKAREEAu66iLu4grBhq4ruwp2bItYothRf64irmJDRKmKCCEQKQGkhKJAqCEkkELm/P4YMxATICEzuZnJ+/U883Dm3jPnfk/uMDm53znnfv311/rqq6900UUXWR0KAABAtbVlyxZt3bpVl1xyiWrVqiVjjE99WYrl0AEAQFnsFX3BkiVLdPHFF0uSPv30UxljlJWVpRdeeEGPPfaY2wMEqqV+/aTAQGd5zhzJGGvjAQDUGHXq1FHdunWtDgMAAKBaOnjwoPr376+2bdtq8ODB2rNnjyTpr3/9q+655x6Lo3OfpKQkpaenKyUlxepQAABANVLhpN+RI0dcF5rmzp2rq666SiEhIRoyZIg2b97s9gCBaik0VOrb11netUtav97ScAAANcejjz6qSZMm6dixY1aH4jHJycmKi4tTjx49rA4FAAB4mbvvvlsBAQHauXOnQkJCXNtHjhypuXPnWhgZAACA51V4ec/Y2FgtW7ZMdevW1dy5c/Xhhx9Kkg4fPqzg4GC3BwhUW0OGSPPmOctz5kgdO1obDwDAZ3Xt2rXEclRbtmxRdHS0mjdvroCAgBJ1V61aVdXhuV1SUpKSkpKUnZ2tiIgIq8MBAABeZN68efrmm2/UpEmTEtvbtGmjHTt2WBQVAABA1ahw0u+uu+7SDTfcoNq1a6tZs2bq+/tspyVLlqhTp07ujg+ovgYPlu6801n+6ivpvvusjQcA4LOGDx9udQgAAABeITc3t8QMv2KHDh1SUFCQBREBAABUnQon/caNG6eePXtq165duvTSS2W3O1cIbdmyJff0Q83SurXUpo20ebO0dKmUlSVFRlodFQDAB02ePNnqEAAAALzCxRdfrHfffVePPvqoJMlms8nhcOjpp59WQkKCxdEBAAB4VoWTfpLUvXt3de/evcS2IUOGuCUgwKsMHiw9/7xUVCR9+610zTVWRwQAAAAAQI319NNPq3///lq5cqUKCgp03333af369Tp06JCWLl1qdXgAAAAeVa6k34QJE/Too48qNDRUEyZMOGPdqVOnuiUwwCsUJ/0k5339SPoBADysTp06Je7vV8xmsyk4OFitW7fWzTffrNGjR1sQnXskJycrOTlZRUVFVocCAAC8TMeOHbVp0ya99NJLCgsLU05OjkaMGKGkpCQ1bNjQ6vAAAAA8qlxJv9WrV6uwsNBVPp2yLkABPq1PHykkRDp2TPr6a8nhkH5f8hYAAE+YNGmSHn/8cSUmJqpnz56SpBUrVmju3LlKSkpSRkaGxo4dqxMnTmjMmDEWR3tukpKSlJSUpOzsbEVERFgdDgAA8AKjRo1S//791bdvXzVt2lQPPPCA1SEBAABUuXIl/RYuXFhmGajxgoKkAQOkzz+XMjOl1aulbt2sjgoA4MN++OEHPfbYY7rttttKbH/11Vc1b948/e9//1Pnzp31wgsveG3SDwAAoKJ27Nihv//97yooKFDz5s2VkJCgfv36qV+/foqJibE6PAAAgCrBlCSgsgYPPln+6ivr4gAA1AjffPONBgwYUGp7//799c0330iSBg8erG3btlV1aAAAAJZZtGiRsrKy9N133+nGG2/U5s2bdcstt6hx48Zq166dxo4dq1mzZlkdJgAAgEeVa6bfiBEjyt3gJ598cs7BAF4pMfFkec4cadIk62IBAPi8unXr6osvvtDdd99dYvsXX3yhunXrSpJyc3MVFhZmRXgAAACWCQoKUkJCghISEiRJeXl5+vHHH/X111/rtdde02uvvaZrrrnG4igBAAA8p1xJP+6lApxB06ZSx47SunXSihXS/v1SVJTVUQEAfNSDDz6osWPHauHCha57+qWkpGjOnDmaPn26JOnbb79Vnz59rAwTAADAMgUFBVq2bJkWLVqkhQsXavny5WrUqJGuuuoqq0MDAADwqHIl/d5++21PxwF4t8GDnUk/Y6RvvpFuvNHqiAAAPmrMmDGKi4vTSy+95Fph4bzzztPixYt14YUXSpLuueceK0OstOTkZCUnJ6uoqMjqUAAAgJdYsmRJiSRf06ZN1adPH9166636v//7PzVp0sTqEAEAADyuXEk/AGcxZIj09NPO8pw5JP0AAB510UUX6aKLLrI6DI9JSkpSUlKSsrOzWXECAACUS9++fdW0aVP985//1Icffqjo6GirQwIAAKhy5Ur6de3aVTabrVwNrlq1qlIBAV6pd28pIkI6ckSaO1cqKpL8/KyOCgDgI7KzsxUeHu4qn0lxPQAAgJrkvvvu06JFi3TXXXfplVdeUZ8+fdS3b1/16dNH9evXtzo8AACAKlGupN/w4cM9HAbg5QICpMsuk2bNkg4fln76SfLhGRgAgKpVp04d7dmzRw0aNFBkZGSZX8Yyxshms7EkJgAAqJGefPJJSVJOTo6+//57LVq0SE8//bSuv/56tW3bVn369FFCQoKuvvpqiyMFAADwnHIl/SZPnuzpOADvN3iwM+knOZf4JOkHAHCTBQsWqG7dupKkhQsXWhwNAABA9VW7dm0lJiYqMTFRknTo0CFNnTpVL774oqZPn84XpAAAgE8753v6paamasOGDZKkDh06qGvXrm4LCvBKgwadLM+ZIz3+uHWxAAB8Sp8+fcosAwAAoCSHw6GUlBQtWrRIixYt0tKlS5WTk6OmTZtqxIgRVofnNsnJyUpOTiaJCQAASqhw0m/fvn267rrrtGjRIkVGRkqSsrKylJCQoA8//FBRUVHujhHwDjExUrduUmqqlJYm/fab1Lix1VEBAHzQ999/r1dffVXbtm3TrFmz1LhxY7333ntq0aKF/vSnP1kdHgAAQJV7+umnXUm+o0ePqnHjxurbt6+mTZumhIQEtWjRwuoQ3SopKUlJSUnKzs5WRESE1eEAAIBqwl7RF9x+++06evSo1q9fr0OHDunQoUNat26dsrOzdccdd3giRsB7DBlysjx3rnVxAAB81v/+9z8NHDhQtWrV0qpVq5Sfny9JOnLkiJ544gmLowMAALDGtGnTFBkZqWeffVa//PKLdu3apffee0+33HKLzyX8AAAATqfCSb+5c+fq5ZdfVvv27V3b4uLilJycrK+//tqtwQFeZ/Dgk+U5c6yLAwDgsx577DFNnz5dr7/+ugICAlzbL7roIq1atcrCyAAAAKyze/du/fe//9WYMWPUunVrq8MBAACwRIWTfg6Ho8QFpmIBAQFyOBxuCQrwWt27S/XrO8vffisVFFgbDwDA52zatEmXXHJJqe0RERHKysqq+oAAAAAAAABQLVQ46devXz/deeed2r17t2vbb7/9prvvvlv9+/d3a3CA1/HzkwYNcpaPHpV++MHaeAAAPicmJkZbtmwptf2HH35Qy5YtLYjI/ZKTkxUXF6cePXpYHQoAAAAAAIDXqHDS76WXXlJ2draaN2+uVq1aqVWrVmrRooWys7P14osveiJGwLuwxCcAwIPGjBmjO++8U8uXL5fNZtPu3bv1/vvv695779XYsWOtDs8tkpKSlJ6erpSUFKtDAQAAAAAA8Br+FX1BbGysVq1ape+++04bN26UJLVv314DBgxwe3CAVxo4ULLbJYfDmfR79lmrIwIA+JD7779fDodD/fv317Fjx3TJJZcoKChI9957r26//XarwwMAAAAAAIBFKpz0kySbzaZLL71Ul156qbvjAbxf3bpS797S0qXShg1SRobUooXVUQEAvFxGRoZatGghm82mf//73/rHP/6hLVu2KCcnR3Fxcapdu7bVIQIAAAAAAMBC5U76LViwQOPHj9dPP/2k8PDwEvuOHDmiCy+8UNOnT9fFF1/s9iCrsy+//FL33HOPHA6H/vnPf+pvf/ub1SGhOhg82Jn0k5yz/ZKSrI0HAOD1WrVqpWbNmikhIUH9+vVTQkKC4uLirA4LAADAcl27dpXNZitX3VWrVnk4GgAAAOuUO+k3bdo0jRkzplTCT5IiIiL097//XVOnTq1RSb8TJ05owoQJWrhwoSIiItStWzddeeWVqlevntWhwWqDB0v//rezTNIPAOAGCxYs0KJFi7Ro0SJ98MEHKigoUMuWLV0JwISEBEVHR1sdJgAAQJUbPny41SEAAABUC+VO+v3888966qmnTrv/sssu07M17N5lK1asUIcOHdS4cWNJUmJioubNm6frr7/e4shgufh4qWFDac8eacEC6fhxqVYtq6MCAHixvn37qm/fvpKkvLw8/fjjj64k4DvvvKPCwkK1a9dO69evtzZQALCAMUZ7c/bq0PFDah7ZXKGBoVaHBKAKTZ482eoQAAAAqgV7eStmZmYqICDgtPv9/f21f/9+twRVVZYsWaKhQ4eqUaNGstlsmj17dqk6ycnJat68uYKDg9WrVy+tWLHCtW/37t2uhJ8kNW7cWL/99ltVhI7qzmZzzvaTpLw8adEiS8MBAPiW4OBg9evXTw888IAefvhh3XHHHapdu7Y2btxodWgAUKWMMXp/zfvq9EonNZraSB1f6ajwJ8N16XuXatH2RVaHBwAAAABVqtxJv8aNG2vdunWn3b9mzRo1bNjQLUFVldzcXMXHxys5ObnM/TNnztSECRM0efJkrVq1SvHx8Ro4cKD27dtXxZHCKw0ZcrI8Z451cQAAfEZBQYGWLFmihx9+WAkJCYqMjNRtt92mw4cP66WXXlJGRobVIQJAlTnhOKExX4zRjZ/eqPX7T85ydhiHvtv2nRLeSdC4r8Yp/0S+hVECqGpFRUV69tln1bNnT8XExKhu3bolHgAAAL6s3Em/wYMH68EHH1ReXl6pfcePH9fkyZN1+eWXuzU4T0tMTNRjjz2mK6+8ssz9U6dO1ZgxYzR69GjFxcVp+vTpCgkJ0VtvvSVJatSoUYmZfb/99psaNWpUJbHDC/TvLxXPjp0zRzLG2ngAAF6tX79+qlOnjsaNG6d9+/bp73//u7Zu3apNmzbp9ddf10033aSmTZtaHWYJWVlZ6t69u7p06aKOHTvq9ddftzokAD7kH/P+oTdXv+l63rNxT/2505/VIrKFa9srK1/RkP8O0dH8o1aECMACDz/8sKZOnaqRI0fqyJEjmjBhgkaMGCG73a6HHnrI6vAAAAA8qtz39HvggQf0ySefqG3btho/frzOO+88SdLGjRuVnJysoqIi/fvf//ZYoFWtoKBAqampmjhxomub3W7XgAEDtGzZMklSz549tW7dOv3222+KiIjQ119/rQcffPC0bebn5ys//+S3TLOzsyVJDodDDofDrfE7HA4ZY9zebnVTrftZu7ZsF18s24IF0rZtcmzYILVrd05NVet+uhH99C300/fUlL56qp+Vbe/7779Xw4YN1a9fP/Xt21d9+vRRvXr13BSdZ4SFhWnJkiUKCQlRbm6uOnbsqBEjRlT7uAFUfx+nf6xpy6dJkvzt/npn+Dv6c6c/S5KKHEV6LfU13TPvHh0/cVzzM+brig+v0Nc3fK1g/2ALowZQFd5//329/vrrGjJkiB566CFdf/31atWqlTp37qyffvpJd9xxh9UhAgAAeEy5k37R0dH68ccfNXbsWE2cOFHm91lLNptNAwcOVHJysqKjoz0WaFU7cOCAioqKSvUpOjradb8cf39//ec//1FCQoIcDofuu+++M17EmjJlih5++OFS2/fv31/mDMrKcDgcOnLkiIwxstvLPaHT61T3foZcfLHCFyyQJOV89JGO3XbbObVT3fvpLvTTt9BP31NT+uqpfh49WrlZJllZWfr++++1aNEiPfXUU7r++uvVtm1b9enTx5UEjIqKclO07uHn56eQkBBJzi8/GWNcY0gAOFc5BTm6a+5drucvD37ZlfCTJD+7n8b2GKuuDbtq8PuDdTjvsBZtX6RbPrtF7494XzabzYKoAVSVvXv3qlOnTpKk2rVr68iRI5Kkyy+//Ixf1AYAAPAF5U76SVKzZs00Z84cHT58WFu2bJExRm3atFGdOnU8FV+1d8UVV+iKK64oV92JEydqwoQJrufZ2dmKjY1VVFSUwsPD3RqXw+GQzWZTVFSUz1+Yrdb9vOYa6fdEb9gPP6j2pEnn1Ey176eb0E/fQj99T03pq6f6GRxcudkloaGhGjRokAYNGiTJmUT84YcftHDhQj399NO64YYb1KZNmzPeg/mPlixZomeeeUapqanas2ePPv30Uw0fPrxEneTkZD3zzDPau3ev4uPj9eKLL6pnz57lPkZWVpb69OmjzZs365lnnlH9+vXL/VoAKMszS5/Rb0edt1kY0maIxnQbU2a9C5pcoLk3zlW/d/optzBXH6z7QBfGXqjxPcdXZbgAqliTJk20Z88eNW3aVK1atdK8efN0/vnnKyUlRUFBQVaHBwAA4FEVSvoVq1Onjnr06OHuWKqV+vXry8/PT5mZmSW2Z2ZmKiYm5pzaDAoKKnOAabfbPXLx1Gazeazt6qRa9zMuTmreXNq+XbYlS2TLzZXCws6pqWrdTzein76FfvqemtJXT/TT3T+z0NBQ1a1bV3Xr1lWdOnXk7++vDRs2VKiN3NxcxcfH65ZbbtGIESNK7Z85c6YmTJig6dOnq1evXpo2bZoGDhyoTZs2qUGDBpKkLl266MSJE6VeO2/ePDVq1EiRkZH6+eeflZmZqREjRujqq6/2qdUhAFSt3IJcvZTykiTnsp7TBk07Y/2ejXvq3Svf1VUfXSVJmvDNBHVv1F0XNLnA06ECsMiVV16p+fPnq1evXrr99tt144036s0339TOnTt19913Wx0eAACAR51T0q8mCAwMVLdu3TR//nzXN94dDofmz5+v8eP5ZijKyWaThgyRkpOlwkJp/nzpDzMoAAAoD4fDoZUrV2rRokVauHChli5dqtzcXDVu3FgJCQlKTk5WQkJChdpMTExUYmLiafdPnTpVY8aM0ejRoyVJ06dP11dffaW33npL999/vyQpLS2tXMeKjo5WfHy8vv/+e1199dUVihMAir3z8zs6dPyQJOn6jterdd3WZ33NiPYjdE/ve/SfZf9RoaNQ1866VmvHrlVEcISnwwVggSeffNJVHjlypJo2baply5apTZs2Gjp0qIWRAQAAeF6NTvrl5ORoy5YtrucZGRlKS0tT3bp11bRpU02YMEGjRo1S9+7d1bNnT02bNk25ubmuC19AuQwe7Ez6SdKcOST9AADnJDIyUrm5uYqJiVFCQoKee+459e3bV61atfLI8QoKCpSamqqJEye6ttntdg0YMEDLli0rVxuZmZkKCQlRWFiYjhw5oiVLlmjs2LGnrZ+fn6/8/HzX8+zsbEnOhKfD4TjHnpTN4XDIGOP2dqujmtJX+nnusvKytHTXUkWHRqtrTFf52f3c1va5Ol0/X0l5xVW+q9dd5f45PJ7wuFb8tkLf7/xeu7J36Z559+i1y19za8zngvetb6GflW/XE3r37q3evXt7pG0AAIDqpkYn/VauXFniG/HF99sbNWqUZsyYoZEjR2r//v2aNGmS9u7dqy5dumju3LksSYWK6dtXCg6W8vKcST9jnDMAAQCogGeeeUYJCQlq27ZtlRzvwIEDKioqKjXuiY6O1saNG8vVxo4dO3TrrbfKGCNjjG6//XZ16tTptPWnTJmih3+/F+6p9u/fr7y8vIp14CwcDoeOHDkiY4zPL1dbU/pKP8/N62tf1xMrnlDeCef/sbZ12uqty95Sq0jPfKGgvMrq58ZDG7Vuv/O+pd2ju6uRvZH27dtX7jb/86f/KGFWgnILc/Xm6jd1aaNL1adJH4/EX168b30L/ayco0ePuq2tzZs3a+HChdq3b1+pZOKkSZPcdhwAAIDqpkYn/fr27StjzBnrjB8/nuU8UTkhIVJCgvT119Jvv0lr1kjx8VZHBQDwMn//+9+tDqHCevbsWe7lPyVp4sSJri9hSc6ZfrGxsYqKilJ4eLhbY3M4HLLZbIqKivLpC7NSzekr/ay4t9Pe1qQfS178/uXwL7ri8yv0w80/6Lz651Wq/cooq58vrHvBtf+mLje57i1aXg0aNNDTlz6tpDlJkqT7frhPa/6+RmFB53bPbXfgfetb6GflBAcHu6Wd119/XWPHjlX9+vUVExMj2ylfurXZbCT9AACAT6vRST+gygwe7Ez6SdJXX5H0AwBUe/Xr15efn58yMzNLbM/MzFRMTIxHjhkUFKSgoCAlJycrOTlZRUVFkpzLinri4qnNZvNY29VNTekr/Sy/X7N/dSW/JGlQ60HacmiLthzaokPHD+mm2Tfpx7/+qEC/QHeEfE5O7acxRh+lfyRJstvsGtlx5Dn1/7but+l/G/6nBRkLtPPITt0//369cvkrZ3+hB/G+9S3089y5q63HHntMjz/+uP75z3+6pT0AAABv4tujUKC6GDLkZPmLL6yLAwCAcgoMDFS3bt00f/581zaHw6H58+d7/L44SUlJSk9PV0pKikePA9RkU76fovwi5z00bz3/Vs358xyl3pqq8+o5Z/el7knVc8ueszLEErYc2qKth7dKki5pdomia5/bLRfsNrveGPqGQgNCJUnTU6drQcYCt8UJwHqHDx/WNddcY3UY5bZr1y717dtXcXFx6ty5s2bNmmV1SAAAwIuR9AOqQosWUvE9jH76Sdqzx9p4AACQlJOTo7S0NNcSnBkZGUpLS9POnTslOe93/Prrr+udd97Rhg0bNHbsWOXm5mr06NEWRg2gsvYc3aM3Vr8hSaodWFuP939cNptN4UHhen/E+7LbnH8mPrX0KR3JO2JlqC7fbP3GVU5snViptlrUaaGnBjzlev63z/+mnIKcSrUJoPq45pprNG/ePKvDKDd/f39NmzZN6enpmjdvnu666y7l5uZaHRYAAPBSLO8JVJXhw6W1a53lzz+XvPDeTAAA37Jy5UolJCS4nhffT2/UqFGaMWOGRo4cqf3792vSpEnau3evunTporlz5yo6+txm2JTXH5f3BOBes9JnqaCoQJI0rvs41Q+p79rXrVE33dT5Jr3z8zs6nHdYzy9/XpP6WH//q3lbT17Av6zVZZVub2yPsZqVPkuLdyxWRlaG/jX/X3oh8YWzvxBAtde6dWs9+OCD+umnn9SpUycFBASU2H/HHXdYFFnZGjZsqIYNG0qSYmJiVL9+fR06dEihoaEWRwYAALwRM/2AqjJ8+Mny7NlWRQEAgEvfvn1ljCn1mDFjhqvO+PHjtWPHDuXn52v58uXq1auXx+NieU/As2aln1w67i/xfym1f1KfSfKz+UmSXln5igqLCqsstrIUFBVo4faFkqQGoQ3UObpzpdu02+x644o3VMu/liTpxRUv6vsd31e6XQDWe+2111S7dm0tXrxYL730kp577jnXY9q0aRVub8mSJRo6dKgaNWokm82m2WX8PZ+cnKzmzZsrODhYvXr10ooVK84p9tTUVBUVFSk2NvacXg8AAEDSD6gqXbtKTZs6y/PnS9nZ1sYDAACAGmf30d1aunOpJKl9/fbq0KBDqTot67TUsHbDJEl7c/bqs02fVWmMf5S2N821/Gb/Fv1dy49WVuu6rfVE/ydcz2/5/BYdKzzmlrYBWCcjI+O0j23btlW4vdzcXMXHxys5ObnM/TNnztSECRM0efJkrVq1SvHx8Ro4cKD27dvnqtOlSxd17Nix1GP37t2uOocOHdJf/vIXvfbaaxXvNAAAwO9I+gFVxWY7OduvsFCaM8fScAAAqK6Sk5MVFxenHj16WB0K4HO++uUrGRlJ0jVx15y23tjuY13lV1Nf9XhcZ7L81+Wu8kWxF7m17dt73q7eTXpLkrYc2qIHFzzo1vYBeL/ExEQ99thjuvLKK8vcP3XqVI0ZM0ajR49WXFycpk+frpCQEL311luuOmlpaVq3bl2pR6NGjSRJ+fn5Gj58uO6//35deOGFVdIvAADgm7inH1CVhg+XXvj9XiGzZ0vXXWdlNAAAVEtJSUlKSkpSdna2IiIirA4H8Cnf7zy5hGVim8TT1uvXop9a1WmlrYe3akHGAu3N2auY2jFVEWIpP/32k6t8QZML3Nq2n91Pbw17S12md1F+Ub6m/jRVl7a6VINaD3LrcU7n8PHD+mnPT8rdl6sDxw64ZjT62f1Ur1Y9RdeOVoPQBmoa0VQNazeUzWarkrgAbzNhwgQ9+uijCg0Ndd2j+HSmTp3qtuMWFBQoNTVVEydOdG2z2+0aMGCAli1bVq42jDG6+eab1a9fP910001nrZ+fn6/8/HzX8+zfVxFyOBxyOBwV7MHZ8bGDU3ngLQb4Bj4scSoPfViW9/c8ST+gKl18sVSnjnT4sHOmX36+FBRkdVQAAACoIX7Y+YMkKdg/WOc3PP+09ew2u67reJ0e//5xOYxDH6d/rPE9x1dVmCX89Ksz6RfsH+yW+/n9Ubv67fRE/yd0z7x7JEk3fnKjVv99tWIj3H9PrcPHD2vulrmau3WuFm1fpJ1Hdpb7teFB4WpXv53a12+vdvXbKS4qTnFRcWoR2UJ+dj+3x1oR+SfyVWSK5DCOUg9jjOyyK7cwVwVFBQqyBZG8hNutXr1ahYWFrvLpuPu9d+DAARUVFSk6OrrE9ujoaG3cuLFcbSxdulQzZ85U586dXfcLfO+999SpU6cy60+ZMkUPP/xwqe379+9XXl5exTpQDtxeEKc6ZdVaAKfiwxKn8tCH5dGjR8tVj6QfUJX8/aWhQ6V335WOHpUWLpQGVc23iAEA8BbJyclKTk5WUVGR1aEAPmX30d3KyMqQJPVs3FOBfoFnrD+yw0g9/v3jkqSZ62dakvTbn7tf2w4778HVvVF3BfgFeOQ4d19wtxbvWKzPN32ug8cP6tqPr9Ximxef9WdUHkWOIn295WvNSJuhL375QgVFBefUTnZ+tlb8tkIrfltRYnuQX5DOq3+e4qLi1K5eOzWLbKbY8Fg1CW+iBqENFBYUJn972X/6G2OUdyJPOQU5OlpwVEfyjigrL0tH8n//N+9I2eX8IyXqVrRPfjY/BfgFKNAvUAH2AAX4BSjA/vvz38t2m11+dj/nvza/EuXifX620snO4uVr/9jPKqlnpILCAgUGBEq2KjyuBfVmXz671DYrLVy4UNu2bVNERIQWLlxodTgV8qc//alCM/QmTpxYYjZjdna2YmNjFRUVpfDwcLfHt2uX25uEF2vQwOoIgGqKD0ucykMflsHBweWqR9IPqGrDhzuTfpJziU+SfgAAlMDynoBnLN251FX+U+yfzlq/Y4OOal+/vTYc2KAfdv6gzJxMRdeOPuvr3Clld4qr3KtxL48dx2azacawGTr/tfO1PWu7fvr1J43+bLTeu/I92W32c2oz70Se3vv5PT277Fn9cvCXUvtDAkJ0fsz5ahPeRh0adVBM7RiFB4XLZrOpsKhQB44dUGZupjJzMrX18FZtOLBBO7J2lErK5Bfla03mGq3JXHPaWEICQhQaEOrqi9HJZJ/DVP1abUWmSEUnipR3wv2zklBztWnTRnv27FGD3y+0jRw5Ui+88EKpWXjuVL9+ffn5+SkzM7PE9szMTMXEeGZJ5KCgIAWVsWKQ3W6X3X5un1dnUkbOFzWYB95igG/gwxKn8tCHZXl/z5P0A6raZZdJwcFSXp702WfSyy8zagIAAIDHFS+TKUkXNb3orPVtNpuGnTdMGw5skCTN3TJXo7qM8lh8ZVm3b52r3CWmi0ePVadWHc26ZpYufvti5Z3I03/X/le1/Gvp1ctfrdDymYePH9b0ldP1/PLnlZlbMhEQHRqt6zter6HnDdVFsRcpwB6gffv2qUGDBuX6I/5Y4TH9cvAXpe9P14b9G7ThwAal70/X5kObdcJx4oyvO1Z4rNx9OBubbIoIjlBEUIQigyMVHhSuAD/n7LxTHzbZXEnMY3nHZPOzqcBRoMKiQhU6ClVYVKiCogJXudDx+/OiQtfyoMXLhqLq2FR6CUxvWJL1jzMS58yZoylTpnj0mIGBgerWrZvmz5+v4cOHS3Leb2f+/PkaP96aJZEBAEDNRtIPqGqhodLAgc6E39690o8/Sn86+zetAQAAgMpYt/9kAq1rTNdyvWZI2yF6cumTkqSvNn9V5Um/tfvWusqdGpR9fyt36t6ou2ZePVNXzrxSDuPQm6vf1N6cvXrvyvdUp1adM7522+FtemnFS3p91evKKcgpsS+heYLuvuBuJbZJLLHUZkWW9JOcM/a6xHQplQAtKCrQlkNb9MvBX/Rr9q/adWSXfj36qw4dP6Ts/Gxl52eXiinYP1i1A2u7HqEBoYoMjlREUIQigiNc5cjgyBIJvojgCNUOrF2hGZAOh6NCyc0/MsbIyKjIUeRKBBY5ilRkisqdoKqKesaYUv2sTvG5K3FXfD5ripycHG3ZssX1PCMjQ2lpaapbt66aNm2qCRMmaNSoUerevbt69uypadOmKTc3V6NHj/ZoXCyHDgAAykLSD7DCVVc5k36SNGsWST8AAE7BRSzAM9L3p0uSIoMjFVO7fMvOXdDkAtUJrqPDeYf1zdZvVFhU6LH76pVl/f71kpz3gGtXv12VHPOK867QB1d9oBs+uUEnHCf01eav1C65nSZdMkl/if+LwoLCXHUPHDugOZvn6KP1H2nO5jkllt602+y6qv1V+seF/1CPxj08GnOgX6DiouIUFxXn0eNYxWazySab7H7Ve4UUh8OhYP9gBfsHe2SZRZyZzWYrldh0R6Jz5cqVSkhIcD0vvp/eqFGjNGPGDI0cOVL79+/XpEmTtHfvXnXp0kVz58716LKiEsuhAwCAspH0A6xwxRVSYKBUUCB9/LH03HMs8QkAwO+4iAW435G8I/o1+1dJUoeoDuW+EO5v99eg1oP0wboPlJ2freW/LdefmlbNF9YKiwpdS4u2rddWQf6l72HlKdd2uFZ1a9XVdR9fp4PHD2pf7j6N/3q87vrmLsVFxSksMEz7j+3XlkNbSi09GewfrNFdRmtC7wlqXbd1lcUM1HTGGN18882u+93l5eXptttuU2hoaIl6n3zySYXa7du3b6mlQ/9o/PjxLOcJAACqBZJ+gBUiIpxLfH7xhbR7N0t8AgAAwKOKZ/lJzqRfRQxoOUAfrPtAkrQwY2GVJf22ZW9TQVGBJKlTtOeX9vyjAS0HKO22NN019y79b8P/JEknHCe0JnNNmfVjw2M1rsc4/e38v6l+SP2qDBWAnDPvTnXjjTdaFAkAAIB1SPpZgCWrIEm65hpn0k9iiU8AAAB4VImkX4OKJf36tejnKi/YvkAP9nnQbXGdyaZDm1zlqrifX1mahDfRx9d+rNV7VuvN1W9qfsZ8bT20VYWOQtXyr6V29dtpQMsBuuK8K9S7SW/52f0siROA9Pbbb1sdAgAAgOVI+lmAJasgiSU+AQAAUGWK740nqcL3fWse2VzNI5tre9Z2Ldu1TMcLj6tWQC13h1jKlqwtrrLV96rr2rCrXmr4kiTJYRwqchRV6b0NAeCP+EI5AAAoCxkGwCoREdJllznLxUt8AgAAAB6w8cBGV/lcEmj9mjtn++UX5WvZr8vcFteZZBzJcJXb1mtbJccsD7vNTsIPgOWSkpKUnp6ulJQUq0MBAADVCEk/wErXXHOyPGuWdXEAAFCNJCcnKy4uTj169LA6FMBn7DiyQ5IU7B+shrUbVvj1fZv3dZWX7lzqrrDOaHv2dle5ZZ2WVXJMAAAAAPBmJP0AKxUv8Sk5l/h0OKyNBwCAaoBvrgPuZYzRziM7JUlNI5rKZrNVuI2Lml7kKi/dVTVJv+KZfo3CGikkIKRKjgkAAAAA3oykH2ClyEiW+AQAAIBHZeVlKacgR5Iz6XcuWkS2UHRotCRp2a/LVOTw7D2ksvOzdTDvoCSpdd3WHj0WAAAAAPgKkn6A1U5d4nPmTOviAAAAgE8qnuUnSc0imp1TGzabzTXbLzs/W+v3r3dLbKez9dBWV7l1HZJ+AAAAAFAeJP0Aqw0bJgUFOcszZ0qFhdbGAwAAAJ9SfD8/6dxn+knSRbGnLPHp4fv6bTm8xVVmph8AlMY9kAEAQFlI+gFWi4iQhg51lvfvl777ztp4AAAA4FNOnelXmaRf7ya9XeWVu1dWKqaz2XZ4m6tM0g8ASuMeyAAAoCwk/YDq4MYbT5b/7/+siwMAgGqAb64D7uWupF98TLzsNuefkKl7Uisd15lsPXxyec9WdVt59FgAAAAA4CtI+gHVQWKiVLeus/zpp9LRo9bGAwCAhfjmOuBe7rinnySFBIQoLipOkrR+/3rlncirdGyn465EJQAAAADUJCT9gOogMFC69lpn+fhxafZsS8MBAACA7zj1nn5NwptUqq1uDbtJkk44TmhN5ppKtXUmv2b/Kkmq5V9L9WrV89hxAAAAAMCXkPQDqosbbjhZfv996+IAAACAT/kt+zdJUnRotIL8gyrVVnHST5JSd3tmiU9jjHZl75IkxYbHymazeeQ4AAAAAOBrSPoB1cWFF0rNmzvL334r7d1raTgAAADwfsYY7T+2X5LUILRBpdvr1uiUpJ+H7ut3JP+IcgpyJEmxEbEeOQYAAAAA+CKSfkB1YbefnO3ncEgffmhtPAAAAPB6xwqPue69Vz+kfqXb6xLTRXab88/IlbtXVrq9suw6sstVruxypADgq5KTkxUXF6cePXpYHQoAAKhGSPoB1cmpS3z+3/9ZFwcAAAB8QvEsP8k9Sb+QgBC1r99ekrR+/3pXQtGdipf2lJzLewIASktKSlJ6erpSUlKsDgUAAFQjJP2A6qR9e6nb70smpaZK69ZZGw8AAAC82oFjB1zlqJAot7RZvMTnCccJrclc45Y2T7XzyE5XmZl+AAAAAFB+JP2A6mbUqJPlN9+0Lg4AAAB4vVOTfu6Y6SdJ3Rt2d5VTd7v/vn6nLu/JTD8AAAAAKD+SfkB1c8MNUlCQs/zee1J+vrXxAAAAwGvtz3Xv8p7SyZl+kpS6xwNJP5b3BAAAAIBzQtIPqG7q1pWuuspZPnhQ+uwza+MBAKCKJScnKy4uTj169LA6FMDrlVjeM9Q9y3t2iekiu835p+Tqvavd0uapSiT9Ikj6AQAAAEB5kfQDqqO//vVk+Y03rIsDAAALJCUlKT09XSkpKVaHAni9/cfcP9MvJCBEbeq2kSSl709XkaPILe0W2310tySpdkBthQeFu7VtAAAAAPBlJP2A6qhvX6llS2f522+l7dutjAYAAABeyhP39JOkjg06SpLyTuRp6+GtbmtXOpn0iw6Ndmu7AAAAAODrSPoB1ZHdXmK2n23GDOtiAQAAgNcqsbxniHuW95ROJv0kad2+dW5r92j+UeUU5EiSYkJi3NYuAPgalkMHAABlIekHVFejRjmTf5L09ttSkXuXTQIAAIDv88TynpLUqUEnV3lt5lq3tVs8y0+SokOY6QcAp8Ny6AAAoCwk/YDqqnFjafBgSZLt118VuGiRtfEAAADA6xTP9AsLDFOQf5Db2i0x02+/+2b6nZr0iwllph8AAAAAVARJPwuwBAPK7W9/cxVD3n3XwkAAAADgjfbnOmf6uXOWnyS1qttKQX7OJKI7l/fck7PHVWamHwAAAABUDEk/C7AEA8ptyBCpSRNJUtC330rbtlkcEAAAALxFkaNIh44fkuT+pJ+/3V9xUXGSpM0HNyvvRJ5b2mWmHwAAAACcO5J+QHXm7y+NHStJshkj2yuvWBwQAAAAvEVOQY6MjCQpMjjS7e0XL/FZZIq08cBGt7TJPf0AAAAA4NyR9AOquzFjZIJ+v//KW29JubnWxgMAQAUdO3ZMzZo107333mt1KECNklOQ4yqHBYW5vf0S9/Vz0xKfzPQDAAAAgHNH0g+o7qKipJEjJUm2rCzp/fetjQcAgAp6/PHHdcEFF1gdBlDjnJr0qx1Y2+3td2rQyVX2RNKvQUgDt7QJAAAAADUFST/AC5jx408+efFFyRjrggEAoAI2b96sjRs3KjEx0epQgBqnRNIvwP1Jv1Nn+q3dt9YtbRYn/SKDI1XLv5Zb2gQAAACAmoKkH+ANunVTQffuzvK6ddLixdbGAwDwCUuWLNHQoUPVqFEj2Ww2zZ49u1Sd5ORkNW/eXMHBwerVq5dWrFhRoWPce++9mjJlipsiBlARnp7p1yS8iSKCIiS5Z6afwzj0a/avkqTGYY0r3R4AAAAA1DQk/QAvceyWW04+efFF6wIBAPiM3NxcxcfHKzk5ucz9M2fO1IQJEzR58mStWrVK8fHxGjhwoPbt2+eq06VLF3Xs2LHUY/fu3frss8/Utm1btW3btqq6BOAUnk762Ww212y/nUd26kjekUq191v2b8ovypcktazTstLxAYAvS05OVlxcnHr06GF1KAAAoBrxtzoAAOWTN2SITEyMbHv3SrNnS1u3Sq1aWR0WAMCLJSYmnnHZzalTp2rMmDEaPXq0JGn69On66quv9NZbb+n++++XJKWlpZ329T/99JM+/PBDzZo1Szk5OSosLFR4eLgmTZpUZv38/Hzl5+e7nmdnZ0uSHA6HHA5HRbt3Rg6HQ8YYt7dbHdWUvtLP0rLzs13l0IBQj/xs4qLitHTXUknS+n3rdUGTc79/55ZDW1zllpEtOZ8+hH76Fk/109d/bu6WlJSkpKQkZWdnKyIiwupwAABANUHSD/AWgYEy48bJNmmS5HBI//mP9PLLVkcFAPBRBQUFSk1N1cSJE13b7Ha7BgwYoGXLlpWrjSlTpriW9pwxY4bWrVt32oRfcf2HH3641Pb9+/crLy+vgj04M4fDoSNHjsgYI7vdtxe/qCl9pZ+l7Tm45+Tr8h0lZum6S2xwrKu8fNtytQw89xl6aTvSXOUo/yhlZWVxPn0E/fQtnurn0aNH3dYWAABATUXSD/Am48ZJTz8t5eRIb70lTZ4sRUdbHRUAwAcdOHBARUVFiv7D75no6Ght3LjRI8ecOHGiJkyY4HqenZ2t2NhYRUVFKTw83K3HcjgcstlsioqK8ukLs1LN6Sv9LM2ecXJ/w3oN1aBBA7fH07NFT+lHZ/nX/F8rdYwD6w+4yvGx8YqMiOR8+gj66Vs81c/g4GC3tQUAAFBTkfQDvEmdOtLf/+6c5ZefL73wgvT441ZHBQDAWd18881nrRMUFKSgoKBS2+12u0cuntpsNo+1Xd3UlL7Sz5JyC3Nd5fCgcI/8XIrv6SdJGw5sqNQxtmVtc5Vb1W0lm4Pz6Uvop2/xRD99/WcGAABQFRhRAd7m7rulgABnOTlZys4+c30AAM5B/fr15efnp8zMzBLbMzMzFRMT49FjJycnKy4uTj169PDocQBfl1OQ4yrXDqztkWM0Cmuk8CDnTNz0/emVamvbYWfSzyabmkc2r2xoAAAAAFDjkPQDvE3jxtJNNznLR45Ir75qbTwAAJ8UGBiobt26af78+a5tDodD8+fPV+/evT167KSkJKWnpyslJcWjxwF8XVUk/Ww2m+Ki4iRJO47sKHHMitp6aKskqUl4EwX5l571CwAAAAA4M5J+gDf6xz8km81Zfu4551KfAABUUE5OjtLS0pSWliZJysjIUFpamnbu3ClJmjBhgl5//XW988472rBhg8aOHavc3FyNHj3awqgBlFdOoeeTfpIUVz/OVd544Nzu+Xnw2EEdPH5QktSyTku3xAUAAAAANQ1JP8AbtWsnXXmls7xnj/TOO9bGAwDwSitXrlTXrl3VtWtXSc4kX9euXTVp0iRJ0siRI/Xss89q0qRJ6tKli9LS0jR37lxFR0d7NC6W9wTcoypm+klyzfSTzn2Jz2+3fesqd2vYrdIxAQAAAEBNRNIP8Fb333+y/NhjzPYDAFRY3759ZYwp9ZgxY4arzvjx47Vjxw7l5+dr+fLl6tWrl8fjYnlPwD28Ken39ZavXeXENomVjgkAAAAAaiKSfoC36tFDGjLEWd61S3r9dWvjAQAAQLVyatIvNDDUY8epbNLPYRz6erMz6RcaEKqLm17sttgAAAAAoCYh6Qd4s0ceOVl+/HHp2DHrYgEAwE1Y3hNwj+KkX6BfoAL9Aj12nNiIWIUGOJOK55L0W71ntfYf2y9J6t+yv4L8g9waHwAAAADUFCT9AG92/vnSVVc5y3v3SsnJ1sYDAIAbsLwn4B7FST9PLu0pSXabXe2j2kuSth3epuOFxyv0+gUZC1zlga0GujU2AAAAAKhJSPoB3u6RRySbzVl+6ikpO9vaeAAAAFAtHM0/KsnzST/p5BKfRka/HPylQq9duH2hq5zQPMGtcQGAr2JlBAAAUBaSfoC3i4uTbrjBWT54UHr+eWvjAQCgkriIBbhHVc30k6S4+ud2X7/CokJ9v/N7SVJM7Ri1q9/O7bEBgC9iZQQAAFAWkn6AL5g8WfLzc5affVbat8/aeAAAqAQuYgGV5zAO5RbmSqramX5SxZJ+qXtSXcnJvs37yla8ggUAAAAAoMJI+gG+oHVr6a9/dZazs6VJk6yNBwAAAJY6VnjMVa7ypN+B8if9FmawtCcAAAAAuAtJP8BXPPKIFBbmLL/+urRmjbXxAAAAwDLFs+ckKSwwzOPHax7ZXMH+wZIqNtOP+/kBAAAAgPuQ9AN8RXS09O9/O8sOhzRhgmSMtTEBAHAOuKcfUHmnJv2qYqafn93PdT++zQc3q6Co4KyvKSgq0NJdSyVJjcMaq3Xd1h6NEQAAAAB8HUk/wJfceafUooWzPH++9MUX1sYDAMA54J5+QOXlFuS6yqEBoVVyzOIlPotMkTYf3HzW+it+W+FahjShRQL38wMAAACASiLpB/iS4GDpmWdOPr/nHqng7N+yBgAAgG85daZdoF9glRwzrv4p9/UrxxKf3M8PAAAAANyLpB/ga0aMkC65xFneskV67jlr4wEAAECVO+E44Sr72/2r5JjFM/2kcib9uJ8fAAAAALgVST8LcJ8aeJTNJk2bJtl//+/98MPStm2WhgQAAICqVegodJUD/AKq5JgdGnRwldfuW3vGunkn8vTjrh8lSc0imqlFnRYejQ0AAAAAagKSfhbgPjXwuK5dpdtvd5aPH5fGjpWMsTYmAAAAVBkrZvq1qtNKtfxrSZJ+zvz5jHV/+vUn5RflS3Lezw8AAAAAUHkk/QBf9eijUpMmzvK8edIHH1gbDwAA5cSqCEDlFRadMtPPXjUz/fzsfuoU3UmStPXQVh3NP3rautzPDwAAAADcj6Qf4KvCwqTk5JPP77pLOnTIsnAAACgvVkUAKs+KmX6SFB8dL0kyMmdc4pP7+QEAAACA+5H0A3zZFVdII0Y4y/v3S/fea208AAAAqBJWJ/0k6ee9ZS/xeazwmH769SdJziVBYyNiqyQ2AAAAAPB1JP0AX/fCC85Zf5L09tvSnDnWxgMAAACPK3ScsrynX9Us7ylJ8TGnJP1Oc1+/H3f96IqPWX4AAAAA4D4k/QBf17ix9OyzJ5//7W8s8wkAAODjrJrp1zm6s6u8as+qMuuUuJ9fC5J+AAAAAOAuJP2AmmDMGCkx0Vnes0dKSrI2HgAAAHhUYdEpM/3sVTfTLzwoXOfVO0+SlLY3TXkn8krV4X5+AAAAAOAZJP2AmsBmk954Q6pTx/n8ww+lmTOtjQkAgNNITk5WXFycevToYXUogNeyaqafJPWO7S3JucToH2f7HT5+WMt/Wy5Jale/nRqGNazS2AAAAADAl5H0A2qKRo2kl18++XzcOGn3buviAQDgNJKSkpSenq6UlBSrQwG81qlJv6q8p58k9W7S21VetmtZiX3fbftODuOQJA1qNahK4wIAX8KXpAAAQFlI+gE1yXXXSdde6ywfOiTdeKNUVGRtTAAAAHC7QsfJ5T2reqbfBU0ucJWX/Voy6ff1lq9d5cQ2iVUWEwD4Gr4kBQAAykLSD6hpXn5ZatzYWV64UHr8cWvjAQAAgNtZubxnh6gOCgsMkyQt3bXUNbPPYRyau2WuJKmWfy1d0uySKo0LAAAAAHwdST+gpqlXT/rgA8n++3//hx+WFi2yNCQAAAC4V2HRyZl+AfaqXd7Tz+7nSujtzdmrlbtXSpKW7lyqPTl7JEn9WvRTsH9wlcYFAAAAAL6OpB9QE118sfTII86ywyH9+c/S/v3WxgQAAAC3sXKmnyQNbzfcVZ69cbYk6b0177m2Xd/x+iqOCAAAAAB8H0k/oKa6/36pf39nec8e7u8HAADgQ069p1+AX9XO9JOkoW2HyiabJOnTjZ/qeOFxzUqfJUkKDQgtkRQEAAAAALgHST+gpvLzk/7v/6QGDZzP582THnjA2pgAAADgFlbP9IuuHa2Lml4kSdp4YKNavtBSWXlZkqQR7UcoNDC0ymMCAAAAAF9H0g+oyWJipJkznQlASXrySemjj6yNCQAAAJVmddJPku6+4G5XeW/OXknO+wv+86J/WhIPAAAAAPg6kn5ATde3rzR16snno0dLP/9sWTgAACQnJysuLk49evSwOhTAaxUWnbK8p73ql/eUpCvbXamhbYeW2HbfRfepQ4MOlsQDAAAAAL6OpB8A6fbbpVGjnOVjx6Qrr5QOHLA2JgBAjZWUlKT09HSlpKRYHQrgtarDTD+bzaY3r3hTN3a+UUPaDNGDlzyoSX0mWRILAAAAANQE1vz1B6B6sdmk6dOl9eullSuljAxp+HDpu++k4GCrowMAAEAFFTpOmennZ81MP0mKCo3Se1e+Z9nxAQAAAKAmYaYfAKfgYOmTT5z3+ZOkpUulv/xFcjisjQsAAAAVVh1m+gEAAAAAqhZJPwAnxcZKX30lhYY6n8+aJU2caG1MAAAAqDCSfgAAAABQ85D0A1DS+edLH30k2X//eHj6aemVV6yNCQAAABVSYnlPu3XLewIAAAAAqg5JPwClDR4sJSeffJ6UJH3wgXXxAAAAoEKY6QcAAAAANQ9JPwBlu+026f77nWVjnPf3+/JLa2MCAABAuRQWnTLTz4+ZfgAAAABQE5D0A3B6Tzwh/f3vzvKJE9LVV0sLF1obEwAAAM6KmX4AAAAAUPOQ9ANwejabc5nPP//Z+Tw/X7riCumHH6yNCwAAAGd06j39SPoBAAAAQM3AX38AzszPT5oxQzp6VPriCyknRxo0SJozR7rkEqujAwBUc82bN1d4eLjsdrvq1KmjhcwYB6rEqTP9Auws7wkAAAAANQEz/dzoyiuvVJ06dXT11VdbHQrgXgEB0kcfSQMHOp/n5kqJidKCBdbGBQDwCj/++KPS0tJI+AFViOU9AQAAAKDmIennRnfeeafeffddq8MAPCM4WJo9Wxo82Pn82DFpyBBp3jxLwwIAAEBphUUnl/cM8GOmHwAAAADUBCT93Khv374KCwuzOgzAc4KDpU8+kYYOdT7Py5Muv1yaOdPauAAA52TJkiUaOnSoGjVqJJvNptmzZ5eqk5ycrObNmys4OFi9evXSihUrKnQMm82mPn36qEePHnr//ffdFDmAs2GmHwAAAADUPNUi6ffbb7/pxhtvVL169VSrVi116tRJK1eudFv75bmgJVX+ohZQIwQFSR9/LI0Y4XxeWChdf7304ovWxgUAqLDc3FzFx8crOTm5zP0zZ87UhAkTNHnyZK1atUrx8fEaOHCg9u3b56rTpUsXdezYsdRj9+7dkqQffvhBqamp+vzzz/XEE09ozZo1VdI3oKYrdJyc6UfSDwAAAABqBsv/+jt8+LAuuugiJSQk6Ouvv1ZUVJQ2b96sOnXqlFl/6dKl6tmzpwICSi5Rk56ernr16ik6OrrUa4ovaN1yyy0aUZyo+IPii1rTp09Xr169NG3aNA0cOFCbNm1SgwYNJDkvap04caLUa+fNm6dGjRpVtOuA9woMdM7uGztWeuMNyRjpjjukvXulxx6TbDarIwQAlENiYqISExNPu3/q1KkaM2aMRo8eLUmaPn26vvrqK7311lu6//77JUlpaWlnPEbjxo0lSQ0bNtTgwYO1atUqde7cucy6+fn5ys/Pdz3Pzs6WJDkcDjkcjnL3qzwcDoeMMW5vtzqqKX2lnyWdKHL+3WK32SUjOYx3/Vw4n76FfvoWT/XT139uAAAAVcHypN9TTz2l2NhYvf32265tLVq0KLOuw+FQUlKS2rRpow8//FB+fn6SpE2bNqlfv36aMGGC7rvvvlKvO9sFLck9F7WAGsXfX3rtNSkmxpnok6QnnpC2bZPeekuqVcva+AAAlVJQUKDU1FRNnDjRtc1ut2vAgAFatmxZudrIzc2Vw+FQWFiYcnJytGDBAl177bWnrT9lyhQ9/PDDpbbv379feXl5Fe/EGTgcDh05ckTGGNnt1WLxC4+pKX2lnyUdLzguSfK3+ZeYnestOJ++hX76Fk/18+jRo25rCwAAoKayPOn3+eefa+DAgbrmmmu0ePFiNW7cWOPGjdOYMWNK1bXb7ZozZ44uueQS/eUvf9F7772njIwM9evXT8OHDy8z4Vce7rioVRHJyclKTk5WUVGR29sGqpTNJj36qBQd7ZzpZ4z04YdSRoY0e7YzIQgA8EoHDhxQUVFRqVUUoqOjtXHjxnK1kZmZqSuvvFKSVFRUpDFjxqhHjx6nrT9x4kRNmDDB9Tw7O1uxsbGKiopSeHj4OfTi9BwOh2w2m6Kionz6wqxUc/pKP//g910BfgGulUu8CefTt9BP3+KpfgYHB7utLW+SlZWlAQMG6MSJEzpx4oTuvPPOMq+JAQAAlIflSb9t27bplVde0YQJE/Svf/1LKSkpuuOOOxQYGKhRo0aVqt+oUSMtWLBAF198sf785z9r2bJlGjBggF555ZVzjsEdF7UkacCAAfr555+Vm5urJk2aaNasWerdu3epeklJSUpKSlJ2drYiIiLOOW6g2hg/XmraVPrzn6XcXGn5cqlnT+mzz6SuXa2ODgBgkZYtW+rnn38ud/2goCAFBQWV2m632z1y8dRms3ms7eqmpvSVfp50wuFc3tPf7u+1Pw/Op2+hn77FE/309Z/Z6YSFhWnJkiUKCQlRbm6uOnbsqBEjRqhevXpWhwYAALyQ5Uk/h8Oh7t2764knnpAkde3aVevWrdP06dPLTPpJUtOmTfXee++pT58+atmypd58803ZqsE9xL777jurQwCsc8UV0tKl0tCh0q5dzseFF0rTp0un+b8MAKi+6tevLz8/P2VmZpbYnpmZqRgPz+RmVQSg8godhZKcM/0AANWXn5+fQkJCJDnvb2yMkTHG4qgAAIC3svxrVA0bNlRcXFyJbe3bt9fOnTtP+5rMzEzdeuutGjp0qI4dO6a77767UjFYeVEL8Cnx8dKKFVKvXs7neXnSzTdLf/+7swwA8BqBgYHq1q2b5s+f79rmcDg0f/78MlcycKekpCSlp6crJSXFo8cBfNmpM/0AAOduyZIlGjp0qBo1aiSbzabZs2eXqpOcnKzmzZsrODhYvXr10ooVKyp0jKysLMXHx6tJkyb6xz/+ofr167spegAAUNNYnvS76KKLtGnTphLbfvnlFzVr1qzM+gcOHFD//v3Vvn17ffLJJ5o/f75mzpype++995xjsPKiFuBzYmKkxYudib5ir70m/elP0ubN1sUFACglJydHaWlpSktLkyRlZGQoLS3N9eWrCRMm6PXXX9c777yjDRs2aOzYscrNzdXo0aMtjBpAeRQWOWf6kfQDgMrJzc1VfHy8kpOTy9w/c+ZMTZgwQZMnT9aqVasUHx+vgQMHat++fa46Xbp0UceOHUs9du/eLUmKjIzUzz//rIyMDP33v/8t9aV0AACA8rL8L8C7775bF154oZ544glde+21WrFihV577TW99tprpeo6HA4lJiaqWbNmmjlzpvz9/RUXF6dvv/1W/fr1U+PGjcuc9ZeTk6MtW7a4nhdf0Kpbt66aNm0qyXlRa9SoUerevbt69uypadOmcVELOFdBQc5lPXv3lm67zTnLLzXVeX+/adOkv/5VqgZL8gJATbdy5UolJCS4nk+YMEGSNGrUKM2YMUMjR47U/v37NWnSJO3du1ddunTR3LlzS90H2d1Y3hOovOKZfgF2lvcEgMpITExUYmLiafdPnTpVY8aMcV0/mj59ur766iu99dZbuv/++yXJ9QWrs4mOjlZ8fLy+//57XX311WXWyc/PV35+vut5dna2JOc1M4fDUa7jVAR/uuNUHniLAb6BD0ucykMfluX9PW950q9Hjx769NNPNXHiRD3yyCNq0aKFpk2bphtuuKFUXbvdrieeeEIXX3yxAgMDXdvj4+P13XffKSoqqsxjnO2CliTLLmoBPm3UKKlLF+maa5yz/HJzpTFjpK++kl5/XWLJEgCwVN++fc96z5jx48dr/PjxVRSRU1JSkpKSkpSdna2IiIgqPTbgK1jeEwA8r6CgQKmpqZo4caJrm91u14ABA7Rs2bJytZGZmamQkBCFhYXpyJEjWrJkicaOHXva+lOmTNHDDz9cavv+/fuV54HbasTGur1JeLFTJrACOBUfljiVhz4sjx49Wq561eIvwMsvv1yXX355uepeeumlZW7v2rXraV9TngtakjUXtQCfFx8vrVolTZjgTPRJ0uzZ0vLl0ptvSmf4xiQAAADOTaHDubxngB8z/QDAUw4cOKCioqJSXxiPjo7Wxo0by9XGjh07dOutt8oYI2OMbr/9dnXq1Om09SdOnOj6MrvknOkXGxurqKgohYeHn1tHzmDXLrc3CS/WoIHVEQDVFB+WOJWHPiyDg4PLVa9aJP0A+LjatZ339Rs8WPrb36SDB6U9e5zP//xn6bnnGDkCAFxY3hOoPGb6AYB36NmzZ7mX/5SkoKAgBQUFldput9tlt9vdGJlTOb5DjxrEA28xwDfwYYlTeejDsry/5/moBlB1hg+X1q6VBg48ue2//5Xat5dmzOAXJABAknN5z/T0dKWkpFgdCuC1CoucM/1I+gGA59SvX19+fn7KzMwssT0zM1MxMTEWRQUAAGoykn4AqlbDhtLXX0tvvSXVqePcduiQNHq0bJddJr9Nm6yNDwAAwMsZY1RknDNlA+ws7wkAnhIYGKhu3bpp/vz5rm0Oh0Pz589X7969PXrs5ORkxcXFqUePHh49DgAA8C4k/QBUPZtNGj1a2rhRuv76k5sXLFD9/v1lu+MO5xKgAIAaiYtYQOUUL+0pMdMPACorJydHaWlpriU4MzIylJaWpp07d0qSJkyYoNdff13vvPOONmzYoLFjxyo3N1ejR4/2aFysjAAAAMpC0g+AdRo0cC7vOWeO1KyZJMlWVCRbcrLUurX0/PNSYaHFQQIAqhoXsYDKOTXpF+DHTD8AqIyVK1eqa9eu6tq1qyRnkq9r166aNGmSJGnkyJF69tlnNWnSJHXp0kVpaWmaO3euoqOjrQwbAADUUCT9AFgvMVFKT5fjkUfkqFXLuS0rS7rrLqlDB+n996WiIisjBAAA8BrM9AMA9+nbt6+MMaUeM2bMcNUZP368duzYofz8fC1fvly9evWyLmAAAFCjkfQDUD2EhEj//rcO/PijzF/+cnL75s3SjTdKnTtLs2ZJDod1MQIAAHiBQsfJlRJI+gEAAABAzUHSD0C14oiJkXn7bSklRerb9+SO9HTp2mul8893Jv+Y+QcAPot7+gGVU2J5TzvLewIAAABATUHSD0D11L27tHChNH++dOGFJ7f//LMz+de2rZScLB07Zl2MAACP4J5+QOUUFjHTDwB8HV+SAgAAZSHpB6B669dP+uEHae5c6dQ/ZrZtk8aPl5o2lSZNkn77zboYAQAAqpESM/38mOkHAL6IL0kBAICykPQDUP3ZbNLAgdLy5dK8edKll57cd/Cg9OijzuTfsGHSnDks/QkAAGo07ukHAAAAADUTST8A3sNmcyb85s2T0tKkG2+U/H+/kOVwSJ9/Lg0ZIrVqJT38sPTLL5aGCwAAYAXu6QcAAAAANRNJPwDeKT5eeu89KSNDmjxZatz45L4dO6SHHpLOO895b8D//Ef69VfLQgUAVAz3qAEq59SkHzP9AAAAAKDmIOkHwLs1aeJM8G3fLs2eLSUmOmcEFktNle69V4qNlXr1kh57TPr5Z8kYiwIGAJwN96gBKqewiOU9AQAAAKAmIukHwDf4+5+8p9/OndKzz0rdupWss2KF9OCDUpcuUrNm0m23SbNmSfv3WxIyAACAJ7C8JwD4PlZGAAAAZSHpB8D3NGki3XOPtHKltGmT8/5+nTuXrLNrl/Tqq9K110oNGjj333WX9Nln0qFDloQNAADgDoUOZvoBgK9jZQQAAFAWkn4AfFvbttKkSc4lPbdvl156SRo4UAoMLFlv7Vrp+eel4cOlevWkdu2km2+Wpk+X0tKkEydKtw0AAFANlZjp58dMPwAAAACoKfjaJ4Cao1kzKSnJ+cjJkX74QVq4UFqwQFq1SnI4TtbdtMn5eOcd5/OQEKlHD+ejSxepa1dnQtGfj1EAAFC9nJr0Y6YfAAAAANQc/AUIoGaqXVsaNMj5kKSsLGnJEmcScNkyZxKw8OTSWDp2TFq82PkoFhwsdep0MgnYpYvzee3aVdgRAACAkgqLWN4TAAAAAGoi/gIEAEmKjJSuuML5kKS8POeynj/9dPKxY0fJ1+TlSSkpzsepmjSR2rd3Ptq1O1lu0ECy2aqiNwDg1ZKTk5WcnKyioiKrQwG8UonlPe0s7wkAAAAANQVJPwAoS3CwdMEFzkexPXucicDix+rV0pYtkjElX/vrr87Ht9+W3F6njtS2rWzNm6t2gwZShw5Sq1ZS8+bORGFwsGf7BABeIikpSUlJScrOzlZERITV4QBep9DBTD8A8HV8SQoAAJSFvwABoLwaNnQ+EhNPbjt6VFq79mQicP16acMG6fDh0q8/fFhavly25ctV5gKg4eHO2YDFj7AwKTS05KNWrZKzBU8tG+O8L2FRUdkPT+z74/5TEqA2SXULC2UL8O0ZBqX6+ccksA+pMec0Lk6aMsXqMADgnJWY6efn25/ZAFBT8SUpAABQFpJ+AFAZYWHShRc6H8WMkfbvdyb/ih8bNzr/3bXr9G1lZzsfW7Z4Pu4qYJMUaHUQVaCm9FOqQX1lGV4AXo57+gEAAABAzcRfgADgbjbbydl6ffqU3JeXJ0dGhrJWr1ZkVpbsO3ZIGRnOpUP37XM+srIsCRtu5KNJo1PnMPpmD3/no+cPQM1hTvnEttvsFkYCAADgXkM/GGp1CKhGvrj+C6tDAKodkn4AUJWCg6XzzlNBnTrOpKC9jAtx+fnSgQNSTo507JiUm3vycfy4s07xEpJ/XErSz8/Zpp/fmR+eqnNKssThcGjfvn1q0KCB7GX100fUlH5KkjmlrzYf7qtxOJwJeADwATbf/poGAAAAAOAUJP0AoLoJCpIaN7Y6CgAAAAAAAACAF/Hdr+kDAAAAAAAAAAAANQRJPwAAAAAAAAAAAMDLkfQDAABAtZKcnKy4uDj16NHD6lAAAACqJcZLAACgLCT9AAAAUK0kJSUpPT1dKSkpVocCAABQLTFeAgAAZSHpBwAAAAAAAAAAAHg5kn4AAAAAAAAAAACAlyPpZwHWXQcAAAAAAAAAAIA7kfSzAOuuAwAAAAAAAAAAwJ1I+gEAAAAAAAAAAABejqQfAAAAAAAAAAAA4OVI+gEAAAAAAAAAAABejqQfAAAAAAAAAAAA4OVI+gEAAAAAAABeJDk5WXFxcerRo4fVoQAAgGqEpB8AAAAAAADgRZKSkpSenq6UlBSrQwEAANUIST8AAAAAAAAAAADAy/lbHUBNZoyRJGVnZ7u9bYfDoaNHjyo4OFh2u+/mdumnb6GfvoV++p6a0ldP9bP4933x73+cHWMl96gpfaWfJx3LOSblOcvHc4975P+Qp3E+fQv99C2MlaoXT46XJKmw0CPNwktVhyFF4THelDip2oxz+bDEqTz0vizvWMlmGE1Z5tdff1VsbKzVYQAAgCq0a9cuNWnSxOowvAJjJQAAah7GShXDeAkAgJrlbGMlkn4Wcjgc2r17t8LCwmSz2dzadnZ2tmJjY7Vr1y6Fh4e7te3qhH76FvrpW+in76kpffVUP40xOnr0qBo1auTT3/53J8ZK7lFT+ko/fQv99C3007cwVqpePDleglNN+b8N78F7EtUR70vPK+9YieU9LWS32z3+7bXw8PAa8Z+MfvoW+ulb6KfvqSl99UQ/IyIi3Nqer2Os5F41pa/007fQT99CP30LY6XqoSrGS3CqKf+34T14T6I64n3pWeUZK/HVKQAAAAAAAAAAAMDLkfQDAAAAAAAAAAAAvBxJPx8VFBSkyZMnKygoyOpQPIp++hb66Vvop++pKX2tKf2s6WrSea4pfaWfvoV++hb66VtqSj+BYrznUd3wnkR1xPuy+rAZY4zVQQAAAAAAAAAAAAA4d8z0AwAAAAAAAAAAALwcST8AAAAAAAAAAADAy5H0AwAAAAAAAFCjLFq0SDabTVlZWdWiHcBdtm/fLpvNprS0NKtDgQ946KGH1KVLF9fzm2++WcOHD3c979u3r+66665ytVWRujh3JP18VHJyspo3b67g4GD16tVLK1assDqkSnnooYdks9lKPNq1a+fan5eXp6SkJNWrV0+1a9fWVVddpczMTAsjLp8lS5Zo6NChatSokWw2m2bPnl1ivzFGkyZNUsOGDVWrVi0NGDBAmzdvLlHn0KFDuuGGGxQeHq7IyEj99a9/VU5OThX24uzO1s+bb7651PkdNGhQiTrVvZ9TpkxRjx49FBYWpgYNGmj48OHatGlTiTrleZ/u3LlTQ4YMUUhIiBo0aKB//OMfOnHiRFV25YzK08++ffuWOp+33XZbiTrVvZ+vvPKKOnfurPDwcIWHh6t37976+uuvXft94VxKZ++nL5zLsjz55JOy2WwlBpq+ck5RfoyVGCtVJzVhrCQxXjqVL/yOZbzk5Avn8o8YK8FbnPr7MSAgQC1atNB9992nvLw8jx2zrAvWF154ofbs2aOIiAiPHRfVzx/HZ/Xq1dOgQYO0Zs0aq0MDSti7d69uv/12tWzZUkFBQYqNjdXQoUM1f/58t7T/ySef6NFHH3V7XZw7kn4+aObMmZowYYImT56sVatWKT4+XgMHDtS+ffusDq1SOnTooD179rgeP/zwg2vf3XffrS+++EKzZs3S4sWLtXv3bo0YMcLCaMsnNzdX8fHxSk5OLnP/008/rRdeeEHTp0/X8uXLFRoaqoEDB5YYwN5www1av369vv32W3355ZdasmSJbr311qrqQrmcrZ+SNGjQoBLn94MPPiixv7r3c/HixUpKStJPP/2kb7/9VoWFhbrsssuUm5vrqnO292lRUZGGDBmigoIC/fjjj3rnnXc0Y8YMTZo0yYoulak8/ZSkMWPGlDifTz/9tGufN/SzSZMmevLJJ5WamqqVK1eqX79+GjZsmNavXy/JN86ldPZ+St5/Lv8oJSVFr776qjp37lxiu6+cU5QPYyXGStVpDCHVjLGSxHiJ8ZL3nUup5o2XGCvB2xT/fty2bZuee+45vfrqq5o8eXKVxhAYGKiYmBjZbLYqPS6sd+r4bP78+fL399fll19udVhuUVBQYHUIcIPt27erW7duWrBggZ555hmtXbtWc+fOVUJCgpKSktxyjLp16yosLMztdVEJBj6nZ8+eJikpyfW8qKjINGrUyEyZMsXCqCpn8uTJJj4+vsx9WVlZJiAgwMyaNcu1bcOGDUaSWbZsWRVFWHmSzKeffup67nA4TExMjHnmmWdc27KyskxQUJD54IMPjDHGpKenG0kmJSXFVefrr782NpvN/Pbbb1UWe0X8sZ/GGDNq1CgzbNiw077GG/u5b98+I8ksXrzYGFO+9+mcOXOM3W43e/fuddV55ZVXTHh4uMnPz6/aDpTTH/tpjDF9+vQxd95552lf4439NMaYOnXqmDfeeMNnz2Wx4n4a43vn8ujRo6ZNmzbm22+/LdE3Xz+nKI2xEmOl6jyGqCljJWMYL/nS79hijJdK86Z+MlaCtynr9+OIESNM165djTHOMd4TTzxhmjdvboKDg03nzp1LvI8XLlxoJJnDhw8bY4w5cOCAue6660yjRo1MrVq1TMeOHc1///vfEseTVOKRkZFRqh1jjPn4449NXFycCQwMNM2aNTPPPvtsiTibNWtmHn/8cTN69GhTu3ZtExsba1599VX3/oDgUWW9/77//nsjyezbt88YY8yaNWtMQkKCCQ4ONnXr1jVjxowxR48eddUv63fIsGHDzKhRo1zPy/NeWb58uenSpYsJCgoy3bp1M5988omRZFavXm2MMebEiRPmlltucf1faNu2rZk2bVqZ/XnsscdMw4YNTfPmzc3DDz9sOnToUKrv8fHx5oEHHqjgTwxWSExMNI0bNzY5OTml9hV/Zu3YscNcccUVJjQ01ISFhZlrrrmmxO/zP/6t+cf3/h/fx8nJyaZ169YmKCjINGjQwFx11VWnrXvo0CFz0003mcjISFOrVi0zaNAg88svv7j2v/322yYiIsLMnTvXtGvXzoSGhpqBAwea3bt3n/sPpQZgpp+PKSgoUGpqqgYMGODaZrfbNWDAAC1btszCyCpv8+bNatSokVq2bKkbbrhBO3fulCSlpqaqsLCwRJ/btWunpk2benWfMzIytHfv3hL9ioiIUK9evVz9WrZsmSIjI9W9e3dXnQEDBshut2v58uVVHnNlLFq0SA0aNNB5552nsWPH6uDBg6593tjPI0eOSHJ+g0Uq3/t02bJl6tSpk6Kjo111Bg4cqOzs7BLfJK5O/tjPYu+//77q16+vjh07auLEiTp27Jhrn7f1s6ioSB9++KFyc3PVu3dvnz2Xf+xnMV86l0lJSRoyZEiJcyf57v9PlI2xkhNjpeo7hjgdXxsrSYyXfOl3LOMl3ziXjJXg7datW6cff/xRgYGBkpzLLb/77ruaPn261q9fr7vvvls33nijFi9eXObr8/Ly1K1bN3311Vdat26dbr31Vt10002uZeCff/559e7du8Ts3tjY2FLtpKam6tprr9V1112ntWvX6qGHHtKDDz6oGTNmlKj3n//8R927d9fq1as1btw4jR07ttRy0PAeOTk5+r//+z+1bt1a9erVU25urgYOHKg6deooJSVFs2bN0nfffafx48dXuO0zvVdycnJ0+eWXKy4uTqmpqXrooYd07733lni9w+FQkyZNNGvWLKWnp2vSpEn617/+pY8++qhEvfnz52vTpk2ulSNuueUWbdiwQSkpKa46q1ev1po1azR69Ohz+CmhKh06dEhz585VUlKSQkNDS+2PjIyUw+HQsGHDdOjQIS1evFjffvuttm3bppEjR57TMVeuXKk77rhDjzzyiDZt2qS5c+fqkksuOW39m2++WStXrtTnn3+uZcuWyRijwYMHq7Cw0FXn2LFjevbZZ/Xee+9pyZIl2rlzZ6n3OErytzoAuNeBAwdUVFRUYqAtSdHR0dq4caNFUVVer169NGPGDJ133nnas2ePHn74YV188cVat26d9u7dq8DAQEVGRpZ4TXR0tPbu3WtNwG5QHHtZ57J43969e9WgQYMS+/39/VW3bl2v6vugQYM0YsQItWjRQlu3btW//vUvJSYmatmyZfLz8/O6fjocDt1111266KKL1LFjR0kq1/t07969ZZ7v4n3VTVn9lKQ///nPatasmRo1aqQ1a9bon//8pzZt2qRPPvlEkvf0c+3aterdu7fy8vJUu3Ztffrpp4qLi1NaWppPncvT9VPynXMpSR9++KFWrVpV4o+VYr74/xOnx1jpJMZK3tN3XxsrSYyXfOV3LOMl3zmXjJXgrb788kvVrl1bJ06cUH5+vux2u1566SXl5+friSee0HfffedK0rds2VI//PCDXn31VfXp06dUW40bNy5xIfn222/XN998o48++kg9e/ZURESEAgMDFRISopiYmNPGNHXqVPXv318PPvigJKlt27ZKT0/XM888o5tvvtlVb/DgwRo3bpwk6Z///Keee+45LVy4UOedd547fjSoAsXvP8m5XHvDhg315Zdfym6367///a/y8vL07rvvuhIuL730koYOHaqnnnqq1GfmmZzpvfLf//5XDodDb775poKDg9WhQwf9+uuvGjt2rOv1AQEBevjhh13PW7RooWXLlumjjz7Stdde69oeGhqqN954w5U4l5xf4Hj77bfVo0cPSdLbb7+tPn36qGXLlufwE0NV2rJli4wxJe71/kfz58/X2rVrlZGR4foSw7vvvqsOHTooJSXFdd7La+fOnQoNDdXll1+usLAwNWvWTF27di2z7ubNm/X5559r6dKluvDCCyU5v0gVGxur2bNn65prrpEkFRYWavr06WrVqpUkafz48XrkkUcqFFdNQ9IPXiExMdFV7ty5s3r16qVmzZrpo48+Uq1atSyMDO5w3XXXucqdOnVS586d1apVKy1atEj9+/e3MLJzk5SUpHXr1pW4l5IvOl0/T71/UKdOndSwYUP1799fW7dudf2C9gbnnXee0tLSdOTIEX388ccaNWrUab8R6s1O18+4uDifOZe7du3SnXfeqW+//VbBwcFWhwN4BGMl3+ZrYyWJ8ZKv/I5lvOQb4yXGSvBmCQkJeuWVV5Sbm6vnnntO/v7+uuqqq7R+/XodO3ZMl156aYn6BQUFp70AXVRUpCeeeEIfffSRfvvtNxUUFCg/P18hISEVimnDhg0aNmxYiW0XXXSRpk2bpqKiIvn5+UlSiXtn2mw2xcTEeP09pmua4vefJB0+fFgvv/yyEhMTtWLFCm3YsEHx8fElZlhddNFFcjgc2rRpU4WSfmd6r2zYsEGdO3cu8fl96mz0YsnJyXrrrbe0c+dOHT9+XAUFBerSpUuJOp06dSqR8JOc96295ZZbNHXqVFcy87nnnit37LCOMeasdTZs2KDY2NgSs5bj4uIUGRmpDRs2VDjpd+mll6pZs2Zq2bKlBg0apEGDBunKK68s83N0w4YN8vf3V69evVzb6tWrp/POO08bNmxwbQsJCSkxpmrYsCGflWfB8p4+pn79+vLz81NmZmaJ7ZmZmWf8FpK3iYyMVNu2bbVlyxbFxMSooKBAWVlZJep4e5+LYz/TuSxrQHjixAkdOnTIq/vesmVL1a9fX1u2bJHkXf0cP368vvzySy1cuFBNmjRxbS/P+zQmJqbM8128rzo5XT/LUvzL+9Tz6Q39DAwMVOvWrdWtWzdNmTJF8fHxev75533uXJ6un2Xx1nOZmpqqffv26fzzz5e/v7/8/f21ePFivfDCC/L391d0dLRPnVOcGWOlk7y9z4yVvHOsJDFeKou3/o5lvFSaN55LxkrwZqGhoWrdurXi4+P11ltvafny5XrzzTeVk5MjSfrqq6+UlpbmeqSnp+vjjz8us61nnnlGzz//vP75z39q4cKFSktL08CBA1VQUOCR2AMCAko8t9lscjgcHjkWPKP4/de6dWv16NFDb7zxhnJzc/X666+X6/V2u71UYubUZQ2LVfa98uGHH+ree+/VX//6V82bN09paWkaPXp0qfd2WUtADh06VEFBQfr000/1xRdfqLCwUFdffXW5jw3rtGnTRjabrUpXtAkLC9OqVav0wQcfqGHDhpo0aZLi4+NLjSEqoqz3f3kSmjUZST8fExgYqG7dumn+/PmubQ6HQ/Pnzy/zWx7eKicnR1u3blXDhg3VrVs3BQQElOjzpk2btHPnTq/uc4sWLRQTE1OiX9nZ2Vq+fLmrX71791ZWVpZSU1NddRYsWCCHw1HiWxLe5tdff9XBgwfVsGFDSd7RT2OMxo8fr08//VQLFixQixYtSuwvz/u0d+/eWrt2bYmLdt9++63Cw8NdywdZ7Wz9LEtaWpoklTif1b2fZXE4HMrPz/eZc3k6xf0si7eey/79+2vt2rUl/tjv3r27brjhBlfZl88pSmKs5MRYqfqMIc6FN46VJMZLZ+Ktv2P/iPGSd55LxkrwFXa7Xf/617/0wAMPKC4uTkFBQdq5c6crKVP8KOs+fJK0dOlSDRs2TDfeeKPi4+PVsmVL/fLLLyXqBAYGqqio6IxxtG/fXkuXLi3Vdtu2bV2z/OCbbDab7Ha7jh8/rvbt2+vnn39Wbm6ua//SpUtlt9tdS7hGRUVpz549rv1FRUVat25dhY7Zvn17rVmzRnl5ea5tP/30U4k6xcsnjhs3Tl27dlXr1q21devWcrXv7++vUaNG6e2339bbb7+t6667jpVEvETdunU1cOBAJScnl3gfFsvKylL79u21a9cu7dq1y7U9PT1dWVlZ5/z729/fXwMGDNDTTz+tNWvWaPv27VqwYEGpeu3bt9eJEydK3IP84MGD2rRpE2OHyjLwOR9++KEJCgoyM2bMMOnp6ebWW281kZGRZu/evVaHds7uueces2jRIpORkWGWLl1qBgwYYOrXr2/27dtnjDHmtttuM02bNjULFiwwK1euNL179za9e/e2OOqzO3r0qFm9erVZvXq1kWSmTp1qVq9ebXbs2GGMMebJJ580kZGR5rPPPjNr1qwxw4YNMy1atDDHjx93tTFo0CDTtWtXs3z5cvPDDz+YNm3amOuvv96qLpXpTP08evSouffee82yZctMRkaG+e6778z5559v2rRpY/Ly8lxtVPd+jh071kRERJhFixaZPXv2uB7Hjh1z1Tnb+/TEiROmY8eO5rLLLjNpaWlm7ty5JioqykycONGKLpXpbP3csmWLeeSRR8zKlStNRkaG+eyzz0zLli3NJZdc4mrDG/p5//33m8WLF5uMjAyzZs0ac//99xubzWbmzZtnjPGNc2nMmfvpK+fydPr06WPuvPNO13NfOacoH8ZKjJWq0xjCmJoxVjKG8RLjJe87l8bU3PESYyV4g1GjRplhw4aV2FZYWGgaN25snnnmGfPvf//b1KtXz8yYMcNs2bLFpKammhdeeMHMmDHDGGPMwoULjSRz+PBhY4wxd999t4mNjTVLly416enp5m9/+5sJDw8vcYwxY8aYHj16mIyMDLN//35TVFRUqp3U1FRjt9vNI488YjZt2mRmzJhhatWqZd5++21XO82aNTPPPfdcidjj4+PN5MmT3ftDgseMGjXKDBo0yPV7Pj093YwbN87YbDazcOFCk5ubaxo2bGiuuuoqs3btWrNgwQLTsmVLM2rUKFcb06dPNyEhIebLL780GzZsMGPGjDHh4eEl6pztvXL06FFTv359c+ONN5r169ebr776yrRu3dpIMqtXrzbGGPP888+b8PBwM3fuXLNp0ybzwAMPmPDwcBMfH1+iP3/8/1Tsl19+MX5+fsbPz8/89NNPlf/hocps3brVxMTEmLi4OPPxxx+bX375xaSnp5vnn3/etGvXzjgcDtOlSxdz8cUXm9TUVLN8+XLTrVs306dPH1cbkydPPuN75dQxwxdffGGef/55s3r1arN9+3bz8ssvG7vdbtatW1eqrjHGDBs2zMTFxZnvv//epKWlmUGDBpnWrVubgoICY4wxb7/9tomIiCjRp08//dSQ1jozfjo+6sUXXzRNmzY1gYGBpmfPnl7/gTxy5EjTsGFDExgYaBo3bmxGjhxptmzZ4tp//PhxM27cOFOnTh0TEhJirrzySrNnzx4LIy6f4oHhHx/Fv9wdDod58MEHTXR0tAkKCjL9+/c3mzZtKtHGwYMHzfXXX29q165twsPDzejRo83Ro0ct6M3pnamfx44dM5dddpmJiooyAQEBplmzZmbMmDGlLrxW936W1T9JJQb15Xmfbt++3SQmJppatWqZ+vXrm3vuuccUFhZWcW9O72z93Llzp7nkkktM3bp1TVBQkGndurX5xz/+YY4cOVKinerez1tuucU0a9bMBAYGmqioKNO/f3/XBSxjfONcGnPmfvrKuTydPw40feWcovwYKzFWqk5qwljJGMZLjJe871waU3PHS4yV4A1Ol6SYMmWKiYqKMjk5OWbatGnmvPPOMwEBASYqKsoMHDjQLF682BhTOul38OBBM2zYMFO7dm3ToEED88ADD5i//OUvJY6xadMmc8EFF5hatWoZSSYjI6NUO8YY8/HHH5u4uDgTEBBgmjZtap555pkSMZL0836jRo0q8Xs+LCzM9OjRw3z88ceuOmvWrDEJCQkmODjY1K1b14wZM6bE+KygoMCMHTvW1K1b1zRo0MBMmTLFDBs2rEJJP2OMWbZsmYmPjzeBgYGmS5cu5n//+1+JpF9eXp65+eabTUREhImMjDRjx441999/f7mTfsYYc/HFF5sOHTqcy48KFtu9e7dJSkpyjWcaN25srrjiCrNw4UJjjDE7duwwV1xxhQkNDTVhYWHmmmuuKfG3RkWSft9//73p06ePqVOnjqlVq5bp3LmzmTlzZpl1jTHm0KFD5qabbjIRERGmVq1aZuDAgeaXX35x7Sfpd25sxrAAKgAAAAAAAAAAKMkYozZt2mjcuHGaMGGC1eEAOAt/qwMAAAAAAAAAAADVy/79+/Xhhx9q7969Gj16tNXhACgHkn4AAAAAAAAAAKCEBg0aqH79+nrttddUp04dq8MBUA4k/QAAAAAAAAAAQAncGQzwPnarAwAAAAAAAAAAAABQOST9AAAAAAAAAAAAAC9H0g8AAAAAAAAAAADwciT9AAAAAAAAAAAAAC9H0g8AAAAAAAAAAADwciT9AKCaat68uaZNm2Z1GAAAANUSYyUAAAAAKImkHwBIuvnmmzV8+HBJUt++fXXXXXdV2bFnzJihyMjIUttTUlJ06623VlkcAAAAp8NYCQAAAACqP3+rAwAAX1VQUKDAwMBzfn1UVJQbowEAAKheGCsBAAAAgHsx0w8ATnHzzTdr8eLFev7552Wz2WSz2bR9+3ZJ0rp165SYmKjatWsrOjpaN910kw4cOOB6bd++fTV+/Hjdddddql+/vgYOHChJmjp1qjp16qTQ0FDFxsZq3LhxysnJkSQtWrRIo0eP1pEjR1zHe+ihhySVXrJq586dGjZsmGrXrq3w8HBde+21yszMdO1/6KGH1KVLF7333ntq3ry5IiIidN111+no0aOe/aEBAIAag7ESAAAAAFRfJP0A4BTPP/+8evfurTFjxmjPnj3as2ePYmNjlZWVpX79+qlr165auXKl5s6dq8zMTF177bUlXv/OO+8oMDBQS5cu1fTp0yVJdrtdL7zwgtavX6933nlHCxYs0H333SdJuvDCCzVt2jSFh4e7jnfvvfeWisvhcGjYsGE6dOiQFi9erG+//Vbbtm3TyJEjS9TbunWrZs+erS+//FJffvmlFi9erCeffNJDPy0AAFDTMFYCAAAAgOqL5T0B4BQREREKDAxUSEiIYmJiXNtfeuklde3aVU888YRr21tvvaXY2Fj98ssvatu2rSSpTZs2evrpp0u0eeo9b5o3b67HHntMt912m15++WUFBgYqIiJCNputxPH+aP78+Vq7dq0yMjIUGxsrSXr33XfVoUMHpaSkqEePHpKcF7xmzJihsLAwSdJNN92k+fPn6/HHH6/cDwYAAECMlQAAAACgOmOmHwCUw88//6yFCxeqdu3arke7du0kOb8xXqxbt26lXvvdd9+pf//+aty4scLCwnTTTTfp4MGDOnbsWLmPv2HDBsXGxrouYklSXFycIiMjtWHDBte25s2buy5iSVLDhg21b9++CvUVAACgohgrAQAAAID1mOkHAOWQk5OjoUOH6qmnniq1r2HDhq5yaGhoiX3bt2/X5ZdfrrFjx+rxxx9X3bp19cMPP+ivf/2rCgoKFBIS4tY4AwICSjy32WxyOBxuPQYAAMAfMVYCAAAAAOuR9AOAPwgMDFRRUVGJbeeff77+97//qXnz5vL3L/9HZ2pqqhwOh/7zn//IbndOrv7oo4/Oerw/at++vXbt2qVdu3a5vsGenp6urKwsxcXFlTseAACAymKsBAAAAADVE8t7AsAfNG/eXMuXL9f27dt14MABORwOJSUl6dChQ7r++uuVkpKirVu36ptvvtHo0aPPeBGqdevWKiws1Isvvqht27bpvffe0/Tp00sdLycnR/Pnz9eBAwfKXMpqwIAB6tSpk2644QatWrVKK1as0F/+8hf16dNH3bt3d/vPAAAA4HQYKwEAAABA9UTSDwD+4N5775Wfn5/i4uIUFRWlnTt3qlGjRlq6dKmKiop02WWXqVOnTrrrrrsUGRnp+lZ6WeLj4zV16lQ99dRT6tixo95//31NmTKlRJ0LL7xQt912m0aOHKmoqCg9/fTTpdqx2Wz67LPPVKdOHV1yySUaMGCAWrZsqZkzZ7q9/wAAAGfCWAkAAAAAqiebMcZYHQQAAAAAAAAAAACAc8dMPwAAAAAAAAAAAMDLkfQDAAAAAAAAAAAAvBxJPwAAAAAAAAAAAMDLkfQDAAAAAAAAAAAAvBxJPwAAAAAAAAAAAMDLkfQDAAAAAAAAAAAAvBxJPwAAAAAAAAAAAMDLkfQDAAAAAAAAAAAAvBxJPwAAAAAAAAAAAMDLkfQDAAAAAAAAAAAAvBxJPwAAAAAAAAAAAMDLkfQDAAAAAAAAAAAAvNz/A2orxPRwvnB1AAAAAElFTkSuQmCC", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Loss component summary:\n", + " Final total loss: 3.0273\n", + " Final relation loss (unweighted): 0.0417\n", + " Final boundary loss (unweighted): 0.0000\n", + " Final collision loss (unweighted): 0.5219\n", + " Final relation loss (weighted): 0.4172\n", + " Final boundary loss (weighted): 0.0006\n", + " Final collision loss (weighted): 2.6096\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/tmp/ipykernel_1914/1963872995.py:269: UserWarning: Glyph 128204 (\\N{PUSHPIN}) missing from font(s) DejaVu Sans.\n", + " anim.save(gif_path, writer=writer)\n" + ] + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "āœ… GIF saved to: /tmp/spatial_relations_optimization.gif\n", + " Frames: 40\n", + " Duration: ~8.0 seconds at 5 FPS\n" + ] + }, + { + "name": "stderr", + "output_type": "stream", + "text": [ + "/tmp/ipykernel_1914/1963872995.py:293: UserWarning: Glyph 128204 (\\N{PUSHPIN}) missing from font(s) DejaVu Sans.\n", + " plt.tight_layout()\n", + "/isaac-sim/kit/python/lib/python3.11/site-packages/IPython/core/pylabtools.py:170: UserWarning: Glyph 128204 (\\N{PUSHPIN}) missing from font(s) DejaVu Sans.\n", + " fig.canvas.print_figure(bytes_io, **kw)\n" + ] + }, + { + "data": { + "image/png": "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", + "text/plain": [ + "
" + ] + }, + "metadata": {}, + "output_type": "display_data" + }, + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Observations:\n", + "- šŸ“Œ Fixed assets stay at their initial position\n", + " └─ Table at origin (0, 0)\n", + " └─ Microwave randomly initialized once, then fixed (acts as stable reference)\n", + "- Objects with On() relations are constrained to stay within table bounds\n", + " └─ Cracker_box, apple, banana all remain on the table surface\n", + "- NextTo() relations position objects adjacent to the fixed microwave\n", + " └─ Cracker box next to microwave (right), apple next to microwave (left)\n", + " └─ Banana next to cracker box (right)\n", + "- Combined relations (On + NextTo) work together\n", + " └─ e.g., Cracker box is both On(table) AND NextTo(microwave)\n", + "- Collision avoidance ensures objects don't overlap\n", + "- Converges to a stable layout with all objects on the table\n", + "\n", + "Visualization Legend:\n", + " šŸ“Œ Solid border = Fixed asset (not optimized)\n", + " -- Dashed border = Optimizable asset (moves during optimization)\n", + "\n", + "Relations demonstrated:\n", + " • On(parent): Keeps child within parent's bounds (hard boundary constraint)\n", + " • NextTo(parent, side): Positions child adjacent to parent\n" + ] + } + ], + "source": [ + "# Create a solver that captures positions during optimization\n", + "class VisualizingSolver2D(RelationSolver2D):\n", + " \"\"\"Extended solver that captures positions and loss components at regular intervals.\"\"\"\n", + " \n", + " def solve(self, assets: list[MockAsset2D], capture_interval=10):\n", + " \"\"\"Solve and capture positions at regular intervals.\"\"\"\n", + " # Initialize\n", + " all_positions = self._initialize_positions(assets)\n", + " \n", + " # Identify fixed assets and optimizable assets\n", + " fixed_mask = torch.tensor([asset.fixed for asset in assets])\n", + " optimizable_mask = ~fixed_mask\n", + " \n", + " # Split into fixed and optimizable\n", + " fixed_positions = all_positions[fixed_mask].clone()\n", + " optimizable_positions = all_positions[optimizable_mask].clone()\n", + " optimizable_positions.requires_grad = True\n", + " \n", + " optimizer = torch.optim.Adam([optimizable_positions], lr=self.lr)\n", + " \n", + " # Storage for visualization\n", + " position_history = []\n", + " loss_history = []\n", + " relation_loss_history = []\n", + " boundary_loss_history = []\n", + " collision_loss_history = []\n", + " \n", + " # Optimization loop\n", + " for iter in range(self.max_iters):\n", + " optimizer.zero_grad()\n", + " \n", + " # Reconstruct full position tensor\n", + " all_positions = torch.zeros((len(assets), 3))\n", + " all_positions[fixed_mask] = fixed_positions\n", + " all_positions[optimizable_mask] = optimizable_positions\n", + " \n", + " # Compute and store loss components\n", + " rel_loss = self._compute_relation_loss(all_positions, assets)\n", + " boundary_loss = self._compute_boundary_loss(all_positions, assets)\n", + " col_loss = self._compute_collision_loss(all_positions, assets)\n", + " loss = self.w_relation * rel_loss + self.w_boundary * boundary_loss + self.w_collision * col_loss\n", + " \n", + " loss_history.append(loss.item())\n", + " relation_loss_history.append(rel_loss.item())\n", + " boundary_loss_history.append(boundary_loss.item())\n", + " collision_loss_history.append(col_loss.item())\n", + " \n", + " # Capture positions at intervals\n", + " if iter % capture_interval == 0:\n", + " position_history.append(all_positions.detach().clone().numpy())\n", + " \n", + " # Backprop and update\n", + " loss.backward()\n", + " optimizer.step()\n", + " \n", + " # Check convergence\n", + " if loss.item() < self.convergence_threshold:\n", + " if self.verbose:\n", + " print(f\"Converged at iteration {iter}\")\n", + " # Capture final position\n", + " final_pos = torch.zeros((len(assets), 3))\n", + " final_pos[fixed_mask] = fixed_positions\n", + " final_pos[optimizable_mask] = optimizable_positions.detach()\n", + " position_history.append(final_pos.numpy())\n", + " break\n", + " \n", + " # Ensure we captured the final position\n", + " final_pos = torch.zeros((len(assets), 3))\n", + " final_pos[fixed_mask] = fixed_positions\n", + " final_pos[optimizable_mask] = optimizable_positions.detach()\n", + " if len(position_history) == 0 or not np.allclose(position_history[-1], final_pos.numpy()):\n", + " position_history.append(final_pos.numpy())\n", + " \n", + " return position_history, loss_history, relation_loss_history, boundary_loss_history, collision_loss_history, assets\n", + "\n", + "# Create scenario with table and original Example 2 assets\n", + "# Table is the fixed anchor (explicitly marked as fixed)\n", + "table = MockAsset2D(\"table\", width=2.6, length=2.0, fixed=True, initial_pos=(0.0, 0.0, 0.0))\n", + "\n", + "# Microwave gets random initial position, then stays fixed as reference object\n", + "microwave_init_pos = (float(torch.randn(1).item() * 1.0), float(torch.randn(1).item() * 1.0), 0.0)\n", + "microwave = MockAsset2D(\"microwave\", width=0.8, length=0.6, fixed=True, initial_pos=microwave_init_pos)\n", + "\n", + "# Original assets from Example 2 (will be optimized)\n", + "cracker_box = MockAsset2D(\"cracker_box\", width=0.2, length=0.3)\n", + "apple = MockAsset2D(\"apple\", width=0.1, length=0.1)\n", + "banana = MockAsset2D(\"banana\", width=0.15, length=0.08)\n", + "\n", + "# Define relations combining On() and NextTo()\n", + "# - Microwave is fixed (randomly initialized once, won't move during optimization)\n", + "# - Other objects are On(table) AND positioned NextTo microwave\n", + "\n", + "# MVP 2D Optimization\n", + "table = MockAsset2D(\"table\", fixed=True)\n", + "microwave.add_relation(On(table), fixed=True)\n", + "\n", + "cracker_box.add_relation(On(table), NextTo(microwave, side=\"right\"))\n", + "apple.add_relation(On(table), NextTo(microwave, side=\"left\"))\n", + "banana.add_relation(On(table), NextTo(cracker_box, side=\"right\"))\n", + "\n", + "assets_list = [table, microwave, cracker_box, apple, banana]\n", + "\n", + "# Solve with position tracking (balanced weights: prioritize relations, enforce boundaries, avoid collisions)\n", + "# Key insight: w_boundary should be large enough to prevent violations but not so large it prevents relations\n", + "vis_solver = VisualizingSolver2D(w_relation=10.0, w_boundary=100.0, w_collision=5.0, max_iters=400, verbose=False)\n", + "position_history, loss_history, relation_loss_history, boundary_loss_history, collision_loss_history, assets = vis_solver.solve(assets_list, capture_interval=10)\n", + "\n", + "print(f\"Captured {len(position_history)} snapshots during optimization\")\n", + "\n", + "# Plot individual loss components\n", + "fig, axes = plt.subplots(2, 3, figsize=(18, 10))\n", + "\n", + "# Total loss\n", + "ax = axes[0, 0]\n", + "ax.plot(loss_history, linewidth=2, color='black')\n", + "ax.set_xlabel('Iteration')\n", + "ax.set_ylabel('Total Loss')\n", + "ax.set_title('Total Loss')\n", + "ax.grid(True, alpha=0.3)\n", + "ax.set_yscale('log')\n", + "\n", + "# Relation loss (NextTo positioning)\n", + "ax = axes[0, 1]\n", + "ax.plot(relation_loss_history, linewidth=2, color='blue')\n", + "ax.set_xlabel('Iteration')\n", + "ax.set_ylabel('Relation Loss')\n", + "ax.set_title('Relation Loss (NextTo positioning)')\n", + "ax.grid(True, alpha=0.3)\n", + "ax.set_yscale('log')\n", + "\n", + "# Boundary loss (hard constraint)\n", + "ax = axes[0, 2]\n", + "ax.plot(boundary_loss_history, linewidth=2, color='green')\n", + "ax.set_xlabel('Iteration')\n", + "ax.set_ylabel('Boundary Loss')\n", + "ax.set_title('Boundary Loss (On violations - HARD constraint)')\n", + "ax.grid(True, alpha=0.3)\n", + "ax.set_yscale('log')\n", + "\n", + "# Collision loss\n", + "ax = axes[1, 0]\n", + "ax.plot(collision_loss_history, linewidth=2, color='red')\n", + "ax.set_xlabel('Iteration')\n", + "ax.set_ylabel('Collision Loss')\n", + "ax.set_title('Collision Loss (repulsive potential)')\n", + "ax.grid(True, alpha=0.3)\n", + "ax.set_yscale('log')\n", + "\n", + "# Weighted comparison (all components)\n", + "ax = axes[1, 1]\n", + "ax.plot(np.array(relation_loss_history) * vis_solver.w_relation, \n", + " linewidth=2, color='blue', label=f'Relation (w={vis_solver.w_relation})')\n", + "ax.plot(np.array(boundary_loss_history) * vis_solver.w_boundary, \n", + " linewidth=2, color='green', label=f'Boundary (w={vis_solver.w_boundary})')\n", + "ax.plot(np.array(collision_loss_history) * vis_solver.w_collision, \n", + " linewidth=2, color='red', label=f'Collision (w={vis_solver.w_collision})')\n", + "ax.set_xlabel('Iteration')\n", + "ax.set_ylabel('Weighted Loss')\n", + "ax.set_title('Weighted Loss Components')\n", + "ax.legend()\n", + "ax.grid(True, alpha=0.3)\n", + "ax.set_yscale('log')\n", + "\n", + "# Loss components breakdown\n", + "ax = axes[1, 2]\n", + "final_rel = relation_loss_history[-1] * vis_solver.w_relation\n", + "final_bound = boundary_loss_history[-1] * vis_solver.w_boundary\n", + "final_col = collision_loss_history[-1] * vis_solver.w_collision\n", + "ax.bar(['Relation', 'Boundary', 'Collision'], [final_rel, final_bound, final_col], \n", + " color=['blue', 'green', 'red'], alpha=0.7)\n", + "ax.set_ylabel('Final Weighted Loss')\n", + "ax.set_title('Final Loss Breakdown')\n", + "ax.set_yscale('log')\n", + "ax.grid(True, alpha=0.3, axis='y')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()\n", + "\n", + "print(\"\\nLoss component summary:\")\n", + "print(f\" Final total loss: {loss_history[-1]:.4f}\")\n", + "print(f\" Final relation loss (unweighted): {relation_loss_history[-1]:.4f}\")\n", + "print(f\" Final boundary loss (unweighted): {boundary_loss_history[-1]:.4f}\")\n", + "print(f\" Final collision loss (unweighted): {collision_loss_history[-1]:.4f}\")\n", + "print(f\" Final relation loss (weighted): {final_rel:.4f}\")\n", + "print(f\" Final boundary loss (weighted): {final_bound:.4f}\")\n", + "print(f\" Final collision loss (weighted): {final_col:.4f}\")\n", + "\n", + "# Function to create a single frame\n", + "def create_frame(positions, assets, iter_num, loss_val, ax):\n", + " \"\"\"Draw a single frame of the optimization.\"\"\"\n", + " ax.clear()\n", + " \n", + " # Define colors for each asset (extended for 5 assets)\n", + " colors = ['#8DD3C7', '#FFFFB3', '#BEBADA', '#FB8072', '#FDB462']\n", + " \n", + " # Draw each asset\n", + " for i, asset in enumerate(assets):\n", + " x, y, theta = positions[i]\n", + " \n", + " is_fixed = asset.fixed\n", + " \n", + " # Draw rectangle with thicker border for fixed assets\n", + " rect = patches.Rectangle(\n", + " (x - asset.width/2, y - asset.length/2),\n", + " asset.width, asset.length,\n", + " linewidth=3 if is_fixed else 2, \n", + " edgecolor=colors[i], \n", + " facecolor=colors[i], \n", + " alpha=0.6 if is_fixed else 0.4,\n", + " linestyle='-' if is_fixed else '--'\n", + " )\n", + " ax.add_patch(rect)\n", + " \n", + " # Add label with marker for fixed assets\n", + " label = f\"{asset.name}\" + (\" šŸ“Œ\" if is_fixed else \"\")\n", + " ax.text(x, y, label, ha='center', va='center', \n", + " fontweight='bold', fontsize=11)\n", + " \n", + " # Set plot properties\n", + " ax.set_aspect('equal')\n", + " ax.grid(True, alpha=0.3)\n", + " ax.axhline(y=0, color='k', linewidth=0.5, alpha=0.3)\n", + " ax.axvline(x=0, color='k', linewidth=0.5, alpha=0.3)\n", + " ax.set_xlabel('X (meters)', fontsize=11)\n", + " ax.set_ylabel('Y (meters)', fontsize=11)\n", + " # Set limits to show full table (2.6m x 2.0m) with some margin\n", + " ax.set_xlim(-1.6, 1.6)\n", + " ax.set_ylim(-1.3, 1.3)\n", + " ax.set_title(f'Iteration {iter_num} | Loss: {loss_val:.4f}', \n", + " fontsize=13, fontweight='bold')\n", + "\n", + "# Create GIF using matplotlib animation\n", + "from matplotlib.animation import FuncAnimation, PillowWriter\n", + "\n", + "fig, ax = plt.subplots(figsize=(10, 8))\n", + "\n", + "def animate(frame_idx):\n", + " \"\"\"Animation function called for each frame.\"\"\"\n", + " positions = position_history[frame_idx]\n", + " \n", + " # Calculate corresponding iteration number\n", + " if frame_idx == len(position_history) - 1:\n", + " iter_num = len(loss_history) - 1\n", + " else:\n", + " iter_num = frame_idx * 10\n", + " \n", + " loss_val = loss_history[min(iter_num, len(loss_history)-1)]\n", + " \n", + " create_frame(positions, assets, iter_num, loss_val, ax)\n", + " return []\n", + "\n", + "# Create animation\n", + "anim = FuncAnimation(fig, animate, frames=len(position_history), \n", + " interval=200, repeat=True)\n", + "\n", + "# Save as GIF with proper path handling\n", + "import os\n", + "import tempfile\n", + "\n", + "# Try to save in the notebook's directory, otherwise use temp directory\n", + "gif_path = os.path.join(tempfile.gettempdir(), 'spatial_relations_optimization.gif')\n", + "\n", + "# Remove existing file if it exists\n", + "if os.path.exists(gif_path):\n", + " try:\n", + " os.remove(gif_path)\n", + " except:\n", + " # If can't remove, try a different filename\n", + " gif_path = os.path.join(tempfile.gettempdir(), f'spatial_relations_optimization_{os.getpid()}.gif')\n", + "\n", + "try:\n", + " writer = PillowWriter(fps=5)\n", + " anim.save(gif_path, writer=writer)\n", + " print(f\"\\nāœ… GIF saved to: {gif_path}\")\n", + " print(f\" Frames: {len(position_history)}\")\n", + " print(f\" Duration: ~{len(position_history)/5:.1f} seconds at 5 FPS\")\n", + "except Exception as e:\n", + " print(f\"\\nāš ļø Could not save GIF: {e}\")\n", + " print(f\" Attempted path: {gif_path}\")\n", + "\n", + "plt.close(fig)\n", + "\n", + "# Display the first and last frames as a preview\n", + "fig, (ax1, ax2) = plt.subplots(1, 2, figsize=(16, 6))\n", + "\n", + "# First frame\n", + "create_frame(position_history[0], assets, 0, loss_history[0], ax1)\n", + "ax1.set_title(f'Start: Iteration 0 | Loss: {loss_history[0]:.4f}', \n", + " fontsize=13, fontweight='bold')\n", + "\n", + "# Last frame\n", + "final_iter = len(loss_history) - 1\n", + "create_frame(position_history[-1], assets, final_iter, loss_history[-1], ax2)\n", + "ax2.set_title(f'End: Iteration {final_iter} | Loss: {loss_history[-1]:.4f}', \n", + " fontsize=13, fontweight='bold')\n", + "\n", + "plt.tight_layout()\n", + "plt.show()\n", + "\n", + "print(\"\\nObservations:\")\n", + "print(\"- šŸ“Œ Fixed assets stay at their initial position\")\n", + "print(\" └─ Table at origin (0, 0)\")\n", + "print(\" └─ Microwave randomly initialized once, then fixed (acts as stable reference)\")\n", + "print(\"- Objects with On() relations are constrained to stay within table bounds\")\n", + "print(\" └─ Cracker_box, apple, banana all remain on the table surface\")\n", + "print(\"- NextTo() relations position objects adjacent to the fixed microwave\")\n", + "print(\" └─ Cracker box next to microwave (right), apple next to microwave (left)\")\n", + "print(\" └─ Banana next to cracker box (right)\")\n", + "print(\"- Combined relations (On + NextTo) work together\")\n", + "print(\" └─ e.g., Cracker box is both On(table) AND NextTo(microwave)\")\n", + "print(\"- Collision avoidance ensures objects don't overlap\")\n", + "print(\"- Converges to a stable layout with all objects on the table\")\n", + "print(\"\\nVisualization Legend:\")\n", + "print(\" šŸ“Œ Solid border = Fixed asset (not optimized)\")\n", + "print(\" -- Dashed border = Optimizable asset (moves during optimization)\")\n", + "print(\"\\nRelations demonstrated:\")\n", + "print(\" • On(parent): Keeps child within parent's bounds (hard boundary constraint)\")\n", + "print(\" • NextTo(parent, side): Positions child adjacent to parent\")\n" + ] + }, + { + "cell_type": "code", + "execution_count": null, + "metadata": {}, + "outputs": [], + "source": [ + "class Relation:\n", + " \"\"\"Base class for spatial relationships.\"\"\"\n", + " \n", + " def __init__(self, parent: MockAsset2D):\n", + " self.parent = parent\n", + " \n", + " def compute_loss(self, child_pos, parent_pos, child_asset, parent_asset) -> torch.Tensor:\n", + " \"\"\"Compute differentiable loss term for this relation.\"\"\"\n", + " raise NotImplementedError\n", + "\n", + "\n", + "class Asset:\n", + " def __init__(self):\n", + " self.relations = []\n", + "\n", + " def add_relation(self, relation: Relation):\n", + " self.relations.append(relation)\n", + " \n", + "\n", + "\n", + "\n", + "class Solver():\n", + " def __init__(self, assets: list[MockAsset2D]):" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "Isaac Sim Python 3", + "language": "python", + "name": "isaac_sim_python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.11.13" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +}