From 9d002032d13778e41a4520650e9257e8f88a6792 Mon Sep 17 00:00:00 2001 From: Remi Cadene Date: Fri, 8 Mar 2024 09:47:39 +0000 Subject: [PATCH 1/7] Add Aloha env and ACT policy WIP Aloha env tests pass Rendering works (fps look fast tho? TODO action bounding is too wide [-1,1]) Update README Copy past from act repo Remove download.py add a WIP for Simxarm Remove download.py add a WIP for Simxarm Add act yaml (TODO: try train.py) Training can runs (TODO: eval) Add tasks without end_effector that are compatible with dataset, Eval can run (TODO: training and pretrained model) Add AbstractEnv, Refactor AlohaEnv, Add rendering_hook in env, Minor modifications, (TODO: Refactor Pusht and Simxarm) poetry lock fix bug in compute_stats for action normalization fix more bugs in normalization fix training fix import PushtEnv inheriates AbstractEnv, Improve factory Normalization Add _make_env to EnvAbstract Add call_rendering_hooks to pusht env SimxarmEnv inherites from AbstractEnv (NOT TESTED) Add aloha tests artifacts + update pusht stats fix image normalization: before env was in [0,1] but dataset in [0,255], and now both in [0,255] Small fix on simxarm Add next to obs Add top camera to Aloha env (TODO: make it compatible with set of cameras) Add top camera to Aloha env (TODO: make it compatible with set of cameras) --- README.md | 17 +- lerobot/common/datasets/abstract.py | 5 +- lerobot/common/datasets/aloha.py | 9 +- lerobot/common/datasets/factory.py | 28 +- lerobot/common/datasets/simxarm.py | 21 +- lerobot/common/envs/abstract.py | 80 +++ ...bimanual_viperx_end_effector_insertion.xml | 59 +++ ...nual_viperx_end_effector_transfer_cube.xml | 48 ++ .../assets/bimanual_viperx_insertion.xml | 53 ++ .../assets/bimanual_viperx_transfer_cube.xml | 42 ++ lerobot/common/envs/aloha/assets/scene.xml | 38 ++ lerobot/common/envs/aloha/assets/tabletop.stl | Bin 0 -> 684 bytes .../assets/vx300s_10_custom_finger_left.stl | Bin 0 -> 83384 bytes .../assets/vx300s_10_custom_finger_right.stl | Bin 0 -> 83384 bytes .../aloha/assets/vx300s_10_gripper_finger.stl | Bin 0 -> 42884 bytes .../envs/aloha/assets/vx300s_11_ar_tag.stl | Bin 0 -> 3884 bytes .../envs/aloha/assets/vx300s_1_base.stl | Bin 0 -> 99984 bytes .../envs/aloha/assets/vx300s_2_shoulder.stl | Bin 0 -> 63884 bytes .../envs/aloha/assets/vx300s_3_upper_arm.stl | Bin 0 -> 102984 bytes .../aloha/assets/vx300s_4_upper_forearm.stl | Bin 0 -> 49584 bytes .../aloha/assets/vx300s_5_lower_forearm.stl | Bin 0 -> 99884 bytes .../envs/aloha/assets/vx300s_6_wrist.stl | Bin 0 -> 70784 bytes .../envs/aloha/assets/vx300s_7_gripper.stl | Bin 0 -> 450084 bytes .../aloha/assets/vx300s_8_gripper_prop.stl | Bin 0 -> 31684 bytes .../aloha/assets/vx300s_9_gripper_bar.stl | Bin 0 -> 379484 bytes .../envs/aloha/assets/vx300s_dependencies.xml | 17 + .../common/envs/aloha/assets/vx300s_left.xml | 59 +++ .../common/envs/aloha/assets/vx300s_right.xml | 59 +++ lerobot/common/envs/aloha/constants.py | 163 ++++++ lerobot/common/envs/aloha/env.py | 311 ++++++++++++ lerobot/common/envs/aloha/tasks/sim.py | 219 ++++++++ .../envs/aloha/tasks/sim_end_effector.py | 263 ++++++++++ lerobot/common/envs/aloha/utils.py | 39 ++ lerobot/common/envs/factory.py | 5 + lerobot/common/envs/pusht/env.py | 51 +- lerobot/common/envs/pusht/pusht_image_env.py | 2 +- lerobot/common/envs/simxarm.py | 99 +++- lerobot/common/envs/transforms.py | 31 +- lerobot/common/policies/act/backbone.py | 115 +++++ lerobot/common/policies/act/detr_vae.py | 212 ++++++++ lerobot/common/policies/act/policy.py | 217 ++++++++ .../common/policies/act/position_encoding.py | 101 ++++ lerobot/common/policies/act/transformer.py | 370 ++++++++++++++ lerobot/common/policies/act/utils.py | 477 +++++++++++++++++ lerobot/common/policies/factory.py | 6 + lerobot/configs/env/aloha.yaml | 8 +- lerobot/configs/policy/act.yaml | 58 +++ lerobot/scripts/download.py | 22 - lerobot/scripts/eval.py | 15 +- lerobot/scripts/train.py | 3 + poetry.lock | 479 +++++++++++------- pyproject.toml | 3 +- sbatch.sh | 3 +- .../aloha_sim_insertion_human/action.memmap | 3 + .../aloha_sim_insertion_human/episode.memmap | 3 + .../aloha_sim_insertion_human/frame_id.memmap | 3 + .../data/aloha_sim_insertion_human/meta.json | 1 + .../next/done.memmap | 3 + .../aloha_sim_insertion_human/next/meta.json | 1 + .../next/observation/image/meta.json | 1 + .../next/observation/image/top.memmap | 3 + .../next/observation/meta.json | 1 + .../next/observation/state.memmap | 3 + .../observation/image/meta.json | 1 + .../observation/image/top.memmap | 3 + .../observation/meta.json | 1 + .../observation/state.memmap | 3 + .../data/aloha_sim_insertion_human/stats.pth | Bin 0 -> 4434 bytes .../action.memmap | 3 + .../episode.memmap | 3 + .../frame_id.memmap | 3 + .../aloha_sim_insertion_scripted/meta.json | 1 + .../next/done.memmap | 3 + .../next/meta.json | 1 + .../next/observation/image/meta.json | 1 + .../next/observation/image/top.memmap | 3 + .../next/observation/meta.json | 1 + .../next/observation/state.memmap | 3 + .../observation/image/meta.json | 1 + .../observation/image/top.memmap | 3 + .../observation/meta.json | 1 + .../observation/state.memmap | 3 + .../aloha_sim_insertion_scripted/stats.pth | Bin 0 -> 4434 bytes .../action.memmap | 3 + .../episode.memmap | 3 + .../frame_id.memmap | 3 + .../aloha_sim_transfer_cube_human/meta.json | 1 + .../next/done.memmap | 3 + .../next/meta.json | 1 + .../next/observation/image/meta.json | 1 + .../next/observation/image/top.memmap | 3 + .../next/observation/meta.json | 1 + .../next/observation/state.memmap | 3 + .../observation/image/meta.json | 1 + .../observation/image/top.memmap | 3 + .../observation/meta.json | 1 + .../observation/state.memmap | 3 + .../aloha_sim_transfer_cube_human/stats.pth | Bin 0 -> 4434 bytes .../action.memmap | 3 + .../episode.memmap | 3 + .../frame_id.memmap | 3 + .../meta.json | 1 + .../next/done.memmap | 3 + .../next/meta.json | 1 + .../next/observation/image/meta.json | 1 + .../next/observation/image/top.memmap | 3 + .../next/observation/meta.json | 1 + .../next/observation/state.memmap | 3 + .../observation/image/meta.json | 1 + .../observation/image/top.memmap | 3 + .../observation/meta.json | 1 + .../observation/state.memmap | 3 + .../stats.pth | Bin 0 -> 4434 bytes tests/data/pusht/stats.pth | Bin 4498 -> 4306 bytes tests/test_datasets.py | 15 +- tests/test_envs.py | 17 + 116 files changed, 3658 insertions(+), 301 deletions(-) create mode 100644 lerobot/common/envs/abstract.py create mode 100644 lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_insertion.xml create mode 100644 lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_transfer_cube.xml create mode 100644 lerobot/common/envs/aloha/assets/bimanual_viperx_insertion.xml create mode 100644 lerobot/common/envs/aloha/assets/bimanual_viperx_transfer_cube.xml create mode 100644 lerobot/common/envs/aloha/assets/scene.xml create mode 100644 lerobot/common/envs/aloha/assets/tabletop.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_10_custom_finger_left.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_10_custom_finger_right.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_10_gripper_finger.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_11_ar_tag.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_1_base.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_2_shoulder.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_3_upper_arm.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_4_upper_forearm.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_5_lower_forearm.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_6_wrist.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_7_gripper.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_8_gripper_prop.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_9_gripper_bar.stl create mode 100644 lerobot/common/envs/aloha/assets/vx300s_dependencies.xml create mode 100644 lerobot/common/envs/aloha/assets/vx300s_left.xml create mode 100644 lerobot/common/envs/aloha/assets/vx300s_right.xml create mode 100644 lerobot/common/envs/aloha/constants.py create mode 100644 lerobot/common/envs/aloha/env.py create mode 100644 lerobot/common/envs/aloha/tasks/sim.py create mode 100644 lerobot/common/envs/aloha/tasks/sim_end_effector.py create mode 100644 lerobot/common/envs/aloha/utils.py create mode 100644 lerobot/common/policies/act/backbone.py create mode 100644 lerobot/common/policies/act/detr_vae.py create mode 100644 lerobot/common/policies/act/policy.py create mode 100644 lerobot/common/policies/act/position_encoding.py create mode 100644 lerobot/common/policies/act/transformer.py create mode 100644 lerobot/common/policies/act/utils.py create mode 100644 lerobot/configs/policy/act.yaml delete mode 100644 lerobot/scripts/download.py create mode 100644 tests/data/aloha_sim_insertion_human/action.memmap create mode 100644 tests/data/aloha_sim_insertion_human/episode.memmap create mode 100644 tests/data/aloha_sim_insertion_human/frame_id.memmap create mode 100644 tests/data/aloha_sim_insertion_human/meta.json create mode 100644 tests/data/aloha_sim_insertion_human/next/done.memmap create mode 100644 tests/data/aloha_sim_insertion_human/next/meta.json create mode 100644 tests/data/aloha_sim_insertion_human/next/observation/image/meta.json create mode 100644 tests/data/aloha_sim_insertion_human/next/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_insertion_human/next/observation/meta.json create mode 100644 tests/data/aloha_sim_insertion_human/next/observation/state.memmap create mode 100644 tests/data/aloha_sim_insertion_human/observation/image/meta.json create mode 100644 tests/data/aloha_sim_insertion_human/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_insertion_human/observation/meta.json create mode 100644 tests/data/aloha_sim_insertion_human/observation/state.memmap create mode 100644 tests/data/aloha_sim_insertion_human/stats.pth create mode 100644 tests/data/aloha_sim_insertion_scripted/action.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/episode.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/frame_id.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/meta.json create mode 100644 tests/data/aloha_sim_insertion_scripted/next/done.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/next/meta.json create mode 100644 tests/data/aloha_sim_insertion_scripted/next/observation/image/meta.json create mode 100644 tests/data/aloha_sim_insertion_scripted/next/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/next/observation/meta.json create mode 100644 tests/data/aloha_sim_insertion_scripted/next/observation/state.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/observation/image/meta.json create mode 100644 tests/data/aloha_sim_insertion_scripted/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/observation/meta.json create mode 100644 tests/data/aloha_sim_insertion_scripted/observation/state.memmap create mode 100644 tests/data/aloha_sim_insertion_scripted/stats.pth create mode 100644 tests/data/aloha_sim_transfer_cube_human/action.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/episode.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/frame_id.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_human/next/done.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/next/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_human/next/observation/image/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_human/next/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/next/observation/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_human/next/observation/state.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/observation/image/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_human/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/observation/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_human/observation/state.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_human/stats.pth create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/action.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/episode.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/frame_id.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/next/done.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/next/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/next/observation/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/next/observation/state.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/observation/image/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/observation/image/top.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/observation/meta.json create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/observation/state.memmap create mode 100644 tests/data/aloha_sim_transfer_cube_scripted/stats.pth diff --git a/README.md b/README.md index b346a30fa..5ccffc359 100644 --- a/README.md +++ b/README.md @@ -59,19 +59,10 @@ env=pusht ## TODO -- [x] priority update doesn't match FOWM or original paper -- [x] self.step=100000 should be updated at every step to adjust to the horizon of the planner -- [ ] prefetch replay buffer to speedup training -- [ ] parallelize env to speed up eval -- [ ] clean checkpointing / loading -- [ ] clean logging -- [ ] clean config -- [ ] clean hyperparameter tuning -- [ ] add pusht -- [ ] add aloha -- [ ] add act -- [ ] add diffusion -- [ ] add aloha 2 +If you are not sure how to contribute or want to know the next features we working on, look on this project page: [LeRobot TODO](https://github.com/users/Cadene/projects/1) + +Ask [Remi Cadene](re.cadene@gmail.com) for access if needed. + ## Profile diff --git a/lerobot/common/datasets/abstract.py b/lerobot/common/datasets/abstract.py index d6a51246f..514fa0388 100644 --- a/lerobot/common/datasets/abstract.py +++ b/lerobot/common/datasets/abstract.py @@ -81,7 +81,10 @@ def transform(self): def set_transform(self, transform): if not isinstance(transform, Compose): # required since torchrl calls `len(self._transform)` downstream - self._transform = Compose(transform) + if isinstance(transform, list): + self._transform = Compose(*transform) + else: + self._transform = Compose(transform) else: self._transform = transform diff --git a/lerobot/common/datasets/aloha.py b/lerobot/common/datasets/aloha.py index afc28b1cd..3b53fed1e 100644 --- a/lerobot/common/datasets/aloha.py +++ b/lerobot/common/datasets/aloha.py @@ -73,11 +73,11 @@ def download(data_dir, dataset_id): data_dir.mkdir(parents=True, exist_ok=True) - gdown.download_folder(FOLDER_URLS[dataset_id], output=data_dir) + gdown.download_folder(FOLDER_URLS[dataset_id], output=str(data_dir)) # because of the 50 files limit per directory, two files episode 48 and 49 were missing - gdown.download(EP48_URLS[dataset_id], output=data_dir / "episode_48.hdf5", fuzzy=True) - gdown.download(EP49_URLS[dataset_id], output=data_dir / "episode_49.hdf5", fuzzy=True) + gdown.download(EP48_URLS[dataset_id], output=str(data_dir / "episode_48.hdf5"), fuzzy=True) + gdown.download(EP49_URLS[dataset_id], output=str(data_dir / "episode_49.hdf5"), fuzzy=True) class AlohaExperienceReplay(AbstractExperienceReplay): @@ -124,9 +124,6 @@ def stats_patterns(self) -> dict: def image_keys(self) -> list: return [("observation", "image", cam) for cam in CAMERAS[self.dataset_id]] - # def _is_downloaded(self) -> bool: - # return False - def _download_and_preproc(self): raw_dir = self.data_dir.parent / f"{self.data_dir.name}_raw" if not raw_dir.is_dir(): diff --git a/lerobot/common/datasets/factory.py b/lerobot/common/datasets/factory.py index 29f40bc67..fd284ae2b 100644 --- a/lerobot/common/datasets/factory.py +++ b/lerobot/common/datasets/factory.py @@ -5,7 +5,7 @@ import torch from torchrl.data.replay_buffers import PrioritizedSliceSampler, SliceSampler -from lerobot.common.envs.transforms import NormalizeTransform +from lerobot.common.envs.transforms import NormalizeTransform, Prod DATA_DIR = Path(os.environ.get("DATA_DIR", "data")) @@ -84,6 +84,16 @@ def make_offline_buffer( prefetch=prefetch if isinstance(prefetch, int) else None, ) + if cfg.policy.name == "tdmpc": + img_keys = [] + for key in offline_buffer.image_keys: + img_keys.append(("next", *key)) + img_keys += offline_buffer.image_keys + else: + img_keys = offline_buffer.image_keys + + transforms = [Prod(in_keys=img_keys, prod=1 / 255)] + if normalize: # TODO(rcadene): make normalization strategy configurable between mean_std, min_max, manual_min_max, min_max_from_spec stats = offline_buffer.compute_or_load_stats() @@ -92,11 +102,10 @@ def make_offline_buffer( in_keys = [("observation", "state"), ("action")] if cfg.policy.name == "tdmpc": - for key in offline_buffer.image_keys: - # TODO(rcadene): imagenet normalization is applied inside diffusion policy, but no normalization inside tdmpc - in_keys.append(key) - # since we use next observations in tdmpc - in_keys.append(("next", *key)) + # TODO(rcadene): we add img_keys to the keys to normalize for tdmpc only, since diffusion and act policies normalize the image inside the model for now + in_keys += img_keys + # TODO(racdene): since we use next observations in tdmpc, we also add them to the normalization. We are wasting a bit of compute on this for now. + in_keys += [("next", *key) for key in img_keys] in_keys.append(("next", "observation", "state")) if cfg.policy.name == "diffusion" and cfg.env.name == "pusht": @@ -106,8 +115,11 @@ def make_offline_buffer( stats["action", "min"] = torch.tensor([12.0, 25.0], dtype=torch.float32) stats["action", "max"] = torch.tensor([511.0, 511.0], dtype=torch.float32) - transform = NormalizeTransform(stats, in_keys, mode="min_max") - offline_buffer.set_transform(transform) + # TODO(rcadene): remove this and put it in config. Ideally we want to reproduce SOTA results just with mean_std + normalization_mode = "mean_std" if cfg.env.name == "aloha" else "min_max" + transforms.append(NormalizeTransform(stats, in_keys, mode=normalization_mode)) + + offline_buffer.set_transform(transforms) if not overwrite_sampler: index = torch.arange(0, offline_buffer.num_samples, 1) diff --git a/lerobot/common/datasets/simxarm.py b/lerobot/common/datasets/simxarm.py index 784242cc2..1d56850ec 100644 --- a/lerobot/common/datasets/simxarm.py +++ b/lerobot/common/datasets/simxarm.py @@ -1,4 +1,5 @@ import pickle +import zipfile from pathlib import Path from typing import Callable @@ -15,6 +16,22 @@ from lerobot.common.datasets.abstract import AbstractExperienceReplay +def download(): + raise NotImplementedError() + import gdown + + url = "https://drive.google.com/uc?id=1nhxpykGtPDhmQKm-_B8zBSywVRdgeVya" + download_path = "data.zip" + gdown.download(url, download_path, quiet=False) + print("Extracting...") + with zipfile.ZipFile(download_path, "r") as zip_f: + for member in zip_f.namelist(): + if member.startswith("data/xarm") and member.endswith(".pkl"): + print(member) + zip_f.extract(member=member) + Path(download_path).unlink() + + class SimxarmExperienceReplay(AbstractExperienceReplay): available_datasets = [ "xarm_lift_medium", @@ -48,8 +65,8 @@ def __init__( ) def _download_and_preproc(self): - # download - # TODO(rcadene) + # TODO(rcadene): finish download + download() dataset_path = self.data_dir / "buffer.pkl" print(f"Using offline dataset '{dataset_path}'") diff --git a/lerobot/common/envs/abstract.py b/lerobot/common/envs/abstract.py new file mode 100644 index 000000000..0754fb768 --- /dev/null +++ b/lerobot/common/envs/abstract.py @@ -0,0 +1,80 @@ +import abc +from collections import deque +from typing import Optional + +from tensordict import TensorDict +from torchrl.envs import EnvBase + + +class AbstractEnv(EnvBase): + def __init__( + self, + task, + frame_skip: int = 1, + from_pixels: bool = False, + pixels_only: bool = False, + image_size=None, + seed=1337, + device="cpu", + num_prev_obs=1, + num_prev_action=0, + ): + super().__init__(device=device, batch_size=[]) + self.task = task + self.frame_skip = frame_skip + self.from_pixels = from_pixels + self.pixels_only = pixels_only + self.image_size = image_size + self.num_prev_obs = num_prev_obs + self.num_prev_action = num_prev_action + self._rendering_hooks = [] + + if pixels_only: + assert from_pixels + if from_pixels: + assert image_size + + self._make_env() + self._make_spec() + self._current_seed = self.set_seed(seed) + + if self.num_prev_obs > 0: + self._prev_obs_image_queue = deque(maxlen=self.num_prev_obs) + self._prev_obs_state_queue = deque(maxlen=self.num_prev_obs) + if self.num_prev_action > 0: + raise NotImplementedError() + # self._prev_action_queue = deque(maxlen=self.num_prev_action) + + def register_rendering_hook(self, func): + self._rendering_hooks.append(func) + + def call_rendering_hooks(self): + for func in self._rendering_hooks: + func(self) + + def reset_rendering_hooks(self): + self._rendering_hooks = [] + + @abc.abstractmethod + def render(self, mode="rgb_array", width=640, height=480): + raise NotImplementedError() + + @abc.abstractmethod + def _reset(self, tensordict: Optional[TensorDict] = None): + raise NotImplementedError() + + @abc.abstractmethod + def _step(self, tensordict: TensorDict): + raise NotImplementedError() + + @abc.abstractmethod + def _make_env(self): + raise NotImplementedError() + + @abc.abstractmethod + def _make_spec(self): + raise NotImplementedError() + + @abc.abstractmethod + def _set_seed(self, seed: Optional[int]): + raise NotImplementedError() diff --git a/lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_insertion.xml b/lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_insertion.xml new file mode 100644 index 000000000..8002838c5 --- /dev/null +++ b/lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_insertion.xml @@ -0,0 +1,59 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_transfer_cube.xml b/lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_transfer_cube.xml new file mode 100644 index 000000000..05249ad2d --- /dev/null +++ b/lerobot/common/envs/aloha/assets/bimanual_viperx_end_effector_transfer_cube.xml @@ -0,0 +1,48 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/assets/bimanual_viperx_insertion.xml b/lerobot/common/envs/aloha/assets/bimanual_viperx_insertion.xml new file mode 100644 index 000000000..511f79471 --- /dev/null +++ b/lerobot/common/envs/aloha/assets/bimanual_viperx_insertion.xml @@ -0,0 +1,53 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/assets/bimanual_viperx_transfer_cube.xml b/lerobot/common/envs/aloha/assets/bimanual_viperx_transfer_cube.xml new file mode 100644 index 000000000..2d85a47cf --- /dev/null +++ b/lerobot/common/envs/aloha/assets/bimanual_viperx_transfer_cube.xml @@ -0,0 +1,42 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/assets/scene.xml b/lerobot/common/envs/aloha/assets/scene.xml new file mode 100644 index 000000000..0f61b8a5f --- /dev/null +++ b/lerobot/common/envs/aloha/assets/scene.xml @@ -0,0 +1,38 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/assets/tabletop.stl b/lerobot/common/envs/aloha/assets/tabletop.stl new file mode 100644 index 0000000000000000000000000000000000000000..ab35cdf76426b2dddc433afa11af96ebe0e07c17 GIT binary patch literal 684 zcmb7>F%E)I42EBvJ%Hnz90^Ri7@`m-B8hSaF5m@v6c#rJPXHl$Aa0=Tqpy?~7CSY4 z{rdmyyH&->9;>rWl4uvjQ4;TMRu<*;&@|20{vB&W0qJY?d{9=`o7_N~sr;>StPlPD zvP=v;)0)71Bn%M6vp#_a&UM;cX98;>AsU`wx9qCJJ+^9=ccS$u7gw-AIE|1%J+((i z)`D$$uG~;G$PW-)hwO_26uOtWpDy4uE8Zh1PGoW!C7Fdr*IGML4r$w z;Qqh2n;M>;S-$V@<(!=K+2{H6Z7b=zRXz0^)U1>vyg{`b#flX!Q@Cj1Vnxg5s9d{d z?RsI07A^Xe{{?iy&FN7XnZ1rqwG*!5t`IqUq& z&09<{kU+(k;21VhwOUsz#A|v`v)C*uaW0s#$Ua z3EtMO@jK60F$#LtQ4A)Q)K0UE2~>OurfnkY$+AY)%4L?_%~i}nFs)r5>z}q_Twc7H zVtgionLx#tVA>|Gm&;&0e$pUVovh^`nAWaTf1b2r6dN2xF_1vTmtfi^GLO71Mi1{1 zd}wY50}0;Nt`k@PvSLK$j;0t)@YBu&D!v5MHu3kvITq1me?JGow013gbj*rzWUNUs zkU+(kVA>{Lrig9DDEerafdp@B*MYl7tQg~`dME}GsQ400+r;U!A-nj@pY0i8Ai>+( zRr1;)D@N+l9D|7!t})A)K*g6}+9q5(8%KZFZ{)J%;X@n*)7o|6#sMqF+u@R8Fu_N~ z1S-A+(>9UhPP9ejp48JpFs)r}KJBw&T+(RkpvfV$2-!2gN`F6<>mBo47cvwG|`p#y0{9-qx=(mVIp~1`??F5*))OK9|}^D(4aj zU82~f%YVVRjVJ~ZsQ3~b!zMo0K9N*kNhEa5z%E^ntr${^VjzKvFTpWv;&Uw;N%gKo zLf3HY(lvPBF4ZXp5~%nR9K$9)w+4~a8b~B`P0cRd5{195Ofir^#h2h1Hu1R~jHFgg zBB5IxcIo!9$u}GW2~>Ouj$sqfI!h#U%gHX?&L3@7m0}=)iZ8)2Yyx^25((V{V3+RU zbjtoM#XtfTUxH)U1oW0961peDF5T~n*RL+cKmrwCf@9bO_xiYYqkf`9LifnnrF)!f zay6$Ic0ciS5EH2Q5*))O?B46vAnLt32;H+}m+m>IyxECjKo41>;!AK0n}A-pgU~%> zcIp27Pi^~A4Cv`gRD21JVH5B+5sifI>9b3}m%Lp#l42l%iZ8)2Yy#ejqLI*VEbP+n zSNxvnc#n!k#h2h1HZgbOny_3QCx)I#JwndxdCXI>Ua;CUyNXrr*u~|eQ>P=Ine_Tl zq6C-0qtq9D*Lq^qeJZu6VEMrE=yp+zT?2aCF_1u4`PPTLvE8of)EE7w-^8f+RQsTU z1lB8V*Z%k;qqi=Z7fy_lJq0v8#4<5a=o~WuGTi#b6byLv4!jzHEG%F#V*c1JoLzf&|v{Zr7ET$>p5k zlR|H$Yv3TzHR|#n&(5O3s@SL|6yrJdUW+fD6qS%#HB^wm_R8&=kf)dwxh99sJyzC1 zpsP`b-JU~PgH`{1?I}im>b-WWH90C4wa%y@f$gr_CC=88_is)P&0H#jgFx5F!pgHR zL9jY?r4Pk8Nxj#l>8C_xrCtUqNMQfL?b?Ouoj#3Xy!M89(T7OwW-t!igALTt7frh@^d9nK|()c_Ip&Lw@u}i4KqV$iueW+=o)J(Pp;wFmm zjLP|GIV&mwy``dpgf8>;du_4fIpm!xvqL);t?nSum2d4{Pn(b+)u7dOit&!>t8Njq zqxRF=HY!Nyy32k)cmMGw`lk!CL)VOG?I6&Vxc`1nyc|Jlf1_O#BM#NOJ>Soc%1EOI zs34*1V0)aQ$&}U6DXPo~HQGiv2z1qNbI@};U69HY$m2d$sr`7EM&N26+dt!mMz z8Y)QWKBGMj*L2EiVWhF|2NLMo-S`CD^OQ8!$M@W%u|8Cg(0xXGJaNDuZ$#qRvqS%& z=L!jQEzNccp505-d*x?$JB@Opf`slf+T)@nj^{8EKAaWWp2`Oj=t{KdG?c+~G+N7L z@EVQ1qJo6(Guq?3#q(7(66cx~TARu_66mU)^eogRAvA`}b;_?|{!l^LP=soq5bUGnNV zsM~8(7J%#aij)OF1qmGAce@4{LyV5b^w5gbejtIav9-=a8}&D3Ot_8Ow02DxDo9|S z!tJ7V&^TUtT4*e42a!P6lJ@7Jt>qZp)>4dJs34)^*?sEt{|+-g6`LA5f!cE<9Il+_ zq0hkAiu(+7t)ktaAfd0D{ch0iU_Ya5*&jlyQNIKUbX}Wp4*EWP&$;hI_dFUEB=r5a z-*L9h?_dPinG#xu`d3JxtL86fp%2H;F8ASvHA^m0K|(*r_Pbj7v$c#ZBPNGtqkbY1 z=o;AN4D?00402!eI=w-nf`l%Q_B-deJjIM;M<#{-Nc~+T(DmJuQ_!crOmzwOsiWw< z78N9Py<)#RUuv1$=u>V|=xyq^BZ02@6;HyuL29ZK`Q1Rx?I2M>Lf4P>7(kBuCxvm? ze*ZuMUB^291@AcLscz?YoZ9>QNmP)~^}Icnu`m8e@qD!X9)$$D@IBG(dP;2+zpLea zG|ce^iG*&i>@gY4TF#qkhU+{hZ|gVHPMz$(`(-V6q2fz0?MG0a^UJLR3_!3Ni$#XKnc}^sF zTf3q%@3Ufj$#ZG~6<>nsFL_QTIBSUnZ)?~4hx@Gperv3ArNbt6HRZMZlis7HY~#<^M~bv+ap} zOF1)&iZ8)2zT`Q#j=#Q?^PEWNnt@%q9`nz0qT)+%4F5bQ61s+Cm#&Zf^PH&o5*))n z&xwStsoAC575_XZD!v5A@XvE1p<5hw>Gsj?A!D8s6<>m5*aT)RkA zWBBJekE&_(ag-q_AOCn`u_z2eMsB7rV?Zx4?- z&xr~WSU)=RoJgRH#vj6C&U2!I1lIG;JSP(9qH&b)nDd;dAc5_bGtY?xx@bHoJmx$n zDo9|v>&$Z^fi4=?3XeI@i3$?fe{kkGkw6!X&xOaF=R^ew><2mXoJcraInRg3oadww zNUwqf_UD{=P9)Gp-uUM^kw6!X!-vP5=R^ew{fznNIgvmY<~dP80`nBkJSP(9qIp2j)?%I$6(n>#|2!uW=%N`=-kyQm zg?Ua?kkHr7KhKE-x@aaB^nEbTi3$?>{`==Skw6#CNP|8c<~dP8LO;j;c}^tIMKkN5 zFN%3iRFKf+(Lc|L1iEO3AoQs*&xr~Wx?b_mb0UE*n&}Ad2AJnW1qoe0`sX>3Ko`x} zgm)awbE1NTuIK&poJgPx-xHmAPE?T4?Ug+y6K6zjYmG_Q4^?Ph^-d4xIXA99XY%&Z zBM&{ieW!S|_4gqk{^q$+L?nw&y_^YDd>!xdt|s$MYr9ji zTNHzd76$@?eF=2&HXp4`G~aVAdi39Uf2$p*lYt5nKNr|-#duNbKE+_-(yTmrdMYi#bDw?Ncv^I1iE;eW7x#4waufK7N4># zec~YoDoFgZ;(!%neUB#;gNa52P(?A7@C-cu*F#<;1r5H>spLsCI zmp~V9a}1k!ar(KK_AdL<(P!Eis36fL%LOaOz6AeJ3?@>{iL>07Ko@Uw44WufHI4DI zSjFWx*4HsmK|=PqWZ#djmnjAld)mei@+Hv4+t&TCh;#7@84Z^GyY$xFFas4NMoztA z#W)ysnqn|f{qIn}qi`eDn{mso9?5HPw)D zw>gGQ+`e1iNHlfAvKxz&8>k@BE8%tfek@TGg9)k={RnjNwsk)&V&;(cM$-0+msP)X zU!a1-`^Gn{7{3qUb*W6$YqLJsmp~V9a}1lTAw>gGQ3@I|) z*f@1d(7#=tg`tAP$mVv86?J&-ITKX32m2D};%$y$6I8@`?NTKD7l4W{!ENG{8e9VfM*l^l zf`q;|LoRjud_M;6ZQw_sOW#?W;HP9&)KAOkxr#;w3H^+vjA%$Pn1~;;(T_lvenM@6 zpLTlExqL*Uf`l$B7juMDjL+r6k3g3$X*R*7_Eg_!Nl^J-vs*- z=+ZTYO>phA;^mCoRQpI&kkED4=_gqz1{1%`S`+L`pi9?$Ho>)M)@+S}sos^SAffBv zrn3Vn1`~8Ya{ChK(lxkEaBJ{QqeRQ7HIS$vq1%#6jRGhJ6NTO-$>U3)OSeQe!L8b| zu0IA-t0qxFLbr*>{<<&icCh;E*2{bebm=C zsV{*p-7~O>&;636)XR{lAffvxe`YyGF_`GJuk12k0$sX?V-wt4dXP?V|4O2Qgzjst zTC<;GFmbd^F797B2z2S5noV%8Z^qBdxSuFdK|=Q#r~kf>Vtno=2Kf@`(mhU_;NI(y zQPq}F?^U9Lgzoz$&vck#Fu`@MFM%%IbG8ZYg)>3DaES^Mx(}cH-f4)6<>l|XPe;rty^fG1>LZmKmuL54YuFtkw66r-J;s#40u$iAi=8@_^9mc62?FRUAjg6Ji=lHvEM;Z zL4sF7a13vjEK)zaNT5r%sGrAuAO#x@~sxJPF*>*N+MbURlnxp1Dj>K0mv-FLdc`J#*PhM8-t0 zOaI-!mw^iIS0AB051AwQ9u@BkUHXdHvxBY`g7=A-qFWmvg89?L)l397-Z7~b)c7zuRoHplRe$yfxB$)JJ+ z)%jKo@3>El1iE;eV|d4wEP}_DP(gy~d^?6U;zgrTF%szFZ7YTzBMaku&SPY#AVD>_ z6~j9Y7bAf#-sTve+mB_Nc5)0J>q7+zs==)o-toj333Tx`$MB9>Mso}vvqS|6s`ITF z-f__w33Tx`$MBB5S_F^1qJjj~`Bn_?_->2@x_Fyoc*l?}g2#|iL4sNdD~5NRIz|Fr zyv;GZW8oITW8tVEL9K)p!#my{BY`g7<`~{FeX2tO0(eXx6(p#Yuwr=g1~C%o;%$!M z%}rPY=O$1=f?5eHhByBaBY`g7<`~`_i$!pb1r;QyU9n<#^EfdQ=;CdT;ms9U1m}uS zL4w*9D~2~86(fNz-sTwIoR>v#mJAgns9mvQc=Kv866oS>j^WMSSp;YMP(gxPA}fYB zKNur{F5c!C-W;SwaMltPBxr2Wis8+3#z>%xw>gG4mueB5OGO0<8nd)wc=NR}66oS> zj-f|{zkC%K6<>neL_IG0zX^8fJ=p|hk@Zo9p`v53OP`ZBe;y-&E`3G3IeLrWtUfA8 z=zHUx2M{BHE`4Xca}6wlXD6V7gnq`n^BH0!(50VH@05^s>loPfHo-Kk361vQL=an-Z?B5!E;zpK|zZAbm{|6(n?9;+?k?BY`g65_#uF=~j(rI$5QY6(n?< z=$(HRBY`g6qI&0eSp>D`JY&m>!3q+(ZTHS2i;+N=?iqOJs#yfjRYL^{-AD1xhl`Ow zm+s+s=iFHY&$&Yd3EkK7&g+YjK$q^RdFKx5ULVf{w5}B^Na#MJcYb1w1iEyO(>n)} zd#{l^2ND$|bl=xI&r|D_!8*SZ!+GwwN?zCTZ;-3`kl%xqW8u8UfLnUb zj3UkJ8~E=rWs$!qNa$_9F=Waj`xETavHh~hk*MH)d9?x`mEXujBq~Vo+5;y1#!Dhm zL4sEjFyS}u6Nw5Eye@zV|IsK^kkI$sf7BTXbm`~Ke+*e)E53vJDsX08$Me7Es34)Q zh`p|epIaEyx6Y9Fg)V(Xyg6Ynfr>sS&e39QXQmnzB=lAA=87WqQK5o_zE&}2u&nc7 z1qoht!FSL*BzQ$OAC+H*HxdbS;d_ZQ1}aGK%5sk3%?ax|F%k)M;ro>%MkFdo z;9H-A2tWl1UQ^FUWv|tzL-HOK66nIWS4WIURFJ@TY6lU33KIM^0X{0f+;$`q=)$o9 zXAD%3(A)mm@R$g8>A&mI5AU@KKn3@!kJcWOu`cfC96c&X=&RtLKSu&x`l`p6F|n>9 zD@f=&8)H_+B3MB}KQVqedhc_^1iJJS8e?|JiopsJx)j8i^Rft5kkF;e{#F=XUECMC zbZL$;6KBO>1qoeC_|F``eW6R&N-<^>tr)Bzp=-Vv^PCpJ3KF_T^`C2i`$Ctl!DGzV zS}|BbLbnY5a}97`=+Z4wj9FwW1}jMD7S4a>0PYK2xuF* zew$buXK@~S|M2iTGQXM9n}xN_?`Qh&yH=5?(3Q4a zeAjSKUq31&=vlC7E0>D3DDDeg^z2%M-?JNu3O)Iji^~e`>FY;@1eHyT_AlqSFLY6j zVG(|{Pb4Z-cUdm3?Qlla)djGNZeOIz!#VNIP)_R;6tE-1pUI|XX1d9 z2yhZ#T(7U3HTel`m*O`k5s3=!H*dKW1{3|}4X)%kj{sDVpx@%KV$lDcM5L4W;v#27 zj^RfH;1#9z$~s$a;qWRrj|vqesI9eV|F#whbWy8q5i#}vybARntZnXb;GVvIR7g+fabM_yzk9wK!-E9%gRL0; zJ!IS$y7acr4+hXbdzKz5ItJ(Ka8Li=N5zD`3U(%rBj^~oFLdeq;lI)X6@3ReGlqNm z`cWaFpBVp@7Pv2T>1WrwZo+#WsOYDib5OXauOAf>x^(%kg1~*DOPA)D*ECo)0Og8w z9n9Gt+|$>O3JG1$`>#;IeWB}1eVoJZ*|pnqs>3}<=+?(?g#umWF9f=DYv)~W5UHOl zRCLS9c@^A~@0ovzfrM_U{nrBEzR;z62Hu(d-lIZA_cD0I6ZiD>qe4RWYV5Jsi$9#V zdP`|iWnF>$LYMw~Ory?U+6lUw;dYymBOKcm=TV`8#Kc4^EqZd%cy>GJJ#$o$priU6 z&$kcfB)+)x-va`C+VcQZaKG4UJI@0ZB=oiN>siwIc&`uFyVkLDeGY$j_5kQGy+k+? zRNGm!|EK{H=;BcWzBm4D)R$woN|fc|k_vnBD}&yn;xgzZsLWg2-nC0~{B~=A`$8Ah zJ{DouKJ+B!W8(9ZXes=}(UWLx^Ye;F>%1SRAVE*QMf>LskU$reG>h<-LGO8>LZ#Mn zaoNT_ef_AApjyJB{Z}I4zR*Rrl10Q=UwIX(;jC@02XRkdKPn{fZdyd7zJqwDsQs{F za4Um%);GqNrvwRVuPoYsH6ZQ_T|8F9&#t%S^d1!|)Ye)qZjo_MUq31&sBO2;$(mUc zVEyxdcG0Cvl((1RJt|am8RXu}|Lv%d&}H79>GZXuLKpSBtn={p$h=2|ir(g)-v8~W zkkIk``l6Bg%(<4)*NXem5aWN;a7gHT<3FB=`$Cs~7X01~tSkUOKdk8Iir+bKPhWjX z!jaI=vHw^f?h9SI-1v{&A%U(hrPjAqLj?(4qx!u&2OxniUC#aA&r#7e!{;#o>$&o4 z)f_R9(DjwyID>;gm#*z%9wXyB$cnB-KaZFEAC3wMU4#3L$vBP*UAkrPANN5;w>Y22 zmf)ypG|Fn#K95Fum6!-U%i_yCOMM4f;cd>V=xx3t`hNHmtoRZE0r}{ct?OGOUKSBa zr%nI9^pJR4yX@^I$}dJFDlrjPhQ$67!;0YR!tr$;Nk zguV(kak|dcWy7}x6Xj2Qeo81N+;cvUNF75fI))}3&y{uNHnr2cFDA5$w*vy;DbWN$ zUsh*o;(x}l2)!@8Uw)SCZG9g53r-M^BKyj$uS<)JGRi3VCQxm;Kd{o74AI83bAc+m zdr&2Q%P4X>P}yT-C*RK#|K{y26VCrupn}AMrK5~HO#;=gvxm_b*}~nUME;|FWpuHM z4gy_cDn=Sh4klA=Iu9UXbKyzi*Ao#^R5S!CNc=P_jgh`*ay9a&{zM$^G+8{j5h3?i z4|NdeN>ur*$h|G48vc7XB1T6q6yY;^%k!N|3sjKk8#-?1%KoWTHM1)bhf4n}Zp`T| z)7~oTAkY=-b-w7O%hRZz9=9Um$69}g9Kk(hib^2@6(lOZ$|B1Rr{9md*^-FZm)D5u znS08Ohx0lJbdCMlkim1(tL-J~6Y<1FI8puh=26_DN^C;C5z#3KA*9@5tuUGOIZSs}WJ? z%3-nTaA#TThjb1CU85o{${`)Is0NP>B9cBiDOQ#2BzrAPCs09Rd2mwm{>ZGV_EbT{ z{Y9t6$^@O{e>GD&2y|5}9?x`D&!$dxDoaH6?=FcN{W{3s-6;hsNbFf1WDf3^T_t>4 znusg`SHv#{{nBR9qz(dIVZo)$mx*(!qYd*DVcxwjiau&1=T1!^P(dQr=7#3Hrn%M7 zEqRH^x#Xc}vAT`C*gm#{K-bP}wah~gbE|KU<|JZDiT_0N{H^89zhVnikjNg|%gkFd zSe49}gNVV8o{0q4TFE;d--RK8uFwn}&0mfMs{>Us5wWS@8}YnTOL?LD`!H0H_@(t| zbBoBU9u3VvgmLSw7?ZxG4E^>$2Z65bDTkST*XLDLccvmD=b29;){5q`?vQ6;s2~xt zWSUvESbnwQ?-WGr+!tV+soPwRbl-Cj==y2wB(vJg{7RKbLd4OGag28No60AL?}wp+ z#Lk-w&C|IHsy5+?h=~0nj&WgHQ`z>~H3xyN=A-7Cnfet}6@QOIMEl_Q#<^lmWS!PG z!caltySyvS4(UQv#-*`{sQ)RxQTt?L*<#vx2Z63kBbJ!|HVjcitG=e5ewyTojQGPF z$%n-+hM|JQ#jcyoX9|E2=V_x=BRgbxDm^of^ojYYsRFbj=?`Kj59QnCg@JA`$M< z$&6p~)R&EC9|}VSi8ucqF;o6qTuuJ*3=!#@Bsa1})sy`)cpL<}n)Kgic6(P`bx(De zh-xWQ8W%^`m7Z+7!%#tDLa__x;%g<<$Cmqu*!NFLV@2w^GP&IDAkdYe?@3c!DXBWe z+DSy@=+wr*JGJGC8#}^KK_Y#>TV~NyrRmJK60xm*8soCNw#@bG1_yzzbG`mHQ_0e* z?UO%<7=J0P@n>C^tnv4zFjSCOzU8SY_m)-v++9IL>Otv^0&Qza)o+P|Ko{r2hEFW5 z>?|1)s2~wKBDSZ;kx6dWdg5n-GbR`Z;?uoa#f|@pQB@vl3rZhSftt;OrJQs$F zgV>nRQ)POn+FWrP5i=GgGn%S;^25x(odmdYrA*}+(!YYLK4l{jzn=^=Hq*1ab>y8e zR1yPGzC#kvMVHGksc~nCxLPxg zvHDIE`K)1}Kn01%r&D@5jw`D&-n>mj#pVIVh9S*lot-Hi1iCt}$mCg@FH{{pbAyPe z%%4Q)?q+gc?sNhbB(C*J?WwxHjQXj?Ga|OWdM%FEZz22rnaM$*D>L0u>}0o=EFi@@py8<+u10o)^F6Z7*w133CwW znw%xQCn!+~wN#`bBH^%eqH($QvgtZQpn`-kJAr4=%n&uJdoU5hiysgRb99oKzx&of zpsUX4B%Z+hh1I(CK}4+Sw_hwQ*h#+bSyP~b#FjO2JWV?mR1@lk@KLppV*ISmvc%oG z4gy{ECnxaCcveuwUtEZYE=!`tnFXC?mV^xiDo9MK@yQ&KH@~V>vlPd;u}8d~&`C}> zTH8UOtN4Jlp1YNcsH$W5Jc^v!BnE!$B2%7fDNsRT?DnVTjWofk(Xz@!jA*}H>~M9L zi!Zkqs32jizHR0{5~SW9sq{YxbUjaU%-q)}huT=H4iU$OtrTlEv#OTNLl;AkbBI;x@B$NOqOy68S!$eU%%&fP9yYJ5tzNF?3}QfgFsjPb+b)(s;uh8&;~^On|iIdLeEu- zM|A`$NbElQlldrh4mDwA4I=i;UnK74=_#LgZ|ESXg1X>;5#C=bpA~oE!Ib5Qj3VU-z*n@lL(3SdCMsv#L4C>(K zrbN{EezUlIxtpwzp`1VkiK+4Pm|L4?R%yq$h`6Ixh#hnuvlE6n2y~5|@m9Wyn?W`8 zG$UeR{H@~Nv2OB2ijo2qBz6x^Xr}6xNqt;bn}|%|tHe&aANQ`7aS-UbS<)lhg``*a zk2EJD)!c33kLYgl?9;*m6(k-%IwN}x%Bb#K;u>!Gp4DPjp`P;b&&3@Cx+P1GA0sLrO0 zB;vvIu42%1w@luszCZerGin|lt@^+;L4gy`nr;dw`y(xwA z#OL$KpMIRUHYq|*-B(+ng2W#si^zeEQ>yFb-9*G`KVG!`EkYKW@vVbE*XZ-@ zsbWX;r5Jbzkw6z-1-C0*nz>?Ox8Cwo%kKm#NGy=oV67#MgKM-iHcu$EFD#atK-G(_`PKGkD~-CNK}6t z6+JCe67^r7aYS@j94acd?I*_?5e@=f8Gg?o-@Hnq9w*@#NT7nmpGStt+MScCbNj{+ zQL$90DA%x`Y|^l=KmuKH?k|yde@d>V59Un6PqkW!MrL1`;M<-86(shCoRh9RDO954 z-xHC3NE`9v{l4<>ur3Y)T||owt4f#p5RozSNbxCCggiC7y+8$tAEVNnwQi+W z?Ncx@r`{-Wxom{&yuX!$K-b_z`OJN{)2SB~IuJ1_$xJc6d~dlgNi%^861D%XY<{;i zz1mf`JrO^*nk8h--m;I;&_SRJ+j(cd1QjH(_d%na848J$&HKq)dA=8T*OsQNFXv}V ztd6{yPzkTJ+ZFG6X>t6STUNO^M4*C1(7-?Cva?B*Ig;;r>&9h8NcMg*XSRV30$q5e z-L8fOT8Juh`pWblA_OW(?A{j7+_Wx*8X3g*9G?;-(1lmp?Rxju2od*vA9?eeE&>%K zo^LL0stIY-=&HRb20kT7pbM`wjn?j(F7D>*Eti zC5)U*#ElhMM6R;^WKdEkfv$+M+hx$oM5^ofNkr_WY)qwyezM1haRL=2YNWd_yM0Kc zhSy`F@~b4`ai@OrQ={hjXoL?kXcRUG)#OBTA_*+HNS-xHnhwWuJ0Z?A6G_pVr?PEbF2?(k%RPsY`r zf6E7_5~!(hrdGncNpD`RM56zFx9l}=vOooi1(jl%f%y`vgk|};x-l)W*cseUt{6Mf zL7)rorrY&h!=hq$9=9C7b*w-IiPvR|ne|#EQ~yr$eG-vC7v4>JuYKM?1iy)p6D~vw zRFG&?q^&t`dMdT@IIn!cClLvB;oWq*l58I+ZjA3Ee@!|_pn}B3nG?(_d(x?XBlx+( zClLvB;oWq*#@3r6&R^*zk5A|&P(dQm)J0~lHC z)pwl<>-WShcb=Fb&W0y7PmGUG<89L`y}KK1zFLu3t++d}5Kv(i1f#&*piPg-kOgt)_NKC!ymfx?OEKotB;FU1*!>nYgT~B_l$_ykc(PWK6Ac26Oq?_PU;^d^ke(`ABs;>hE(D`$=wFHk`ub+Iw# z`c|pcmE(ixJdS>-D}pyg$RpIABY`fw3eKyG3KHW}%r)zENv~#a>P|5h4(l%tcIYF= zH2+>8fiAoX&Z~wy(4irGq2nhL0l!DoC_C{*xIPm0kta z=4(}|eLwM{ULP4Sbhv{+7hVPD)kOt~euLJUE4E}-39In6ik)e)xUsjFJbkgRKmuKO z6`WTW6(n#}-8n*!1iGA8_gTrl;y~d(vPi>`0JY#Ffh)H7H_Fgi}`+g1rU3gB;YlR9Dn6q%^KafBd zUIogr)S4(VEb1jk7a1(@*wf`WW48W~UHx6EekF`Y^Ghbp5$^~0lnom95~v`7*&6C0 zKb$XyJnbP@tmy6_(1k}xxzwdUiu*Tu$dXrj3*0YenvkYnUL1T{6dBrH7Ee_}EKXkB z^KajBszm#Em4;T#?%CV8q^kF8s!EvIa%Ra;L849H7o|OKcT`Xn z%0CUq^K-jq_rEHJ^lU4iWe9VeITG`d74h7ATuxoA!E=hfMxbkA-n^c3xyz_@&v~X( ziL^IGWJDVowym5%1&J*e3V5!RDW|H3#3o|=qbnlOY0B`fs^B2dl{Ic|PyT+TRnB9H ziAZV1gzL}0#eLaU7X2aAL7;2>wQQcDdrGN7 zE0Yj$@8?^haFsT4#Dr1;6(nBv&gI#=zl_THl4D?|8VPh^2AkT!_P52hLT#k%R>F~~ zMgsHdZdcq@??j;!&E$z41;qXrEj$Ca*Pv&2P59B(E>DphRn?g?yTb8VpfWi7rPy4u zg?xXapyMe)!rWcWleIx5Rck8G{rDPzt__!kC+P%3?Y()Gh=$c(iB5@H$a6Ic3RI97 z-K>)5^{8;=p7R$G-`;vE?saS_M?45|5a_x;Ce%|^3YGWVbt1|oc`e#LXf98c&o59x zqWaS?&*?uass%rtBqGu8|B2n-w3N%v6?72j$`w-DGyG+knt1RZA|CzqS{yslTvjZY zSD=DKk_qKJ>#iBf{OvRmOCp|$WFakOMl-*IKv&Z<#XMU=!qkHuw}|L7?~Pc!rn$_R zK3JfF#PMvUJd=_e>h@}$^^&gKb8#SfOL=-}UI&4$8N)(6k2_RQuC;fF*wgB*c=1DX z+4xf~feI3hYZmf^_Y6}dw)0$^9}c|`qffPvvD@c%5a^0^EXdRLRH#Zd>j4oL9={WZ zYBra*_GA;NAaQkYZqMsO(ES&SuaT7932`9 z?;6MG`J}PjbvCCMQK`G6)CwL7;0_Xt-zPtV(M3WS-sjcy4T?-Nq)eRhBFQ6(qiETg78` zsG`y@-9&^tcYrZDu$e43Fq?xwSD;zJ6C4$;My%LNMAEmhjl$EK$V^Ey2~?1X^G$hA zti_d7|9IPp82uo?ko%j;Ayu3Ny4D;j;mMhxqG~|jgQQVsPaGq5)h4p(^|S&NBz6=n z?g_tAk!F(bA|mr}mPaEtRcDEkY7_Erte?5`m8QefF znv}*tpet_mUY`DS>QLR@+lN2}iIjy0c*bR^uihuCMMU1cNsNQ7>&rbIQwk)|m90gD zr)b7{YDl_zL{yER#K^ayzKr`_T7e1@uO5y5yyl0$r1LcbT?Hof@LWh+SG~^K*oQy` ziPGCTdq$_KqXq=GAfou#q((@R`towWK!F6h;_mC<8Qsi9b07y3@nK+MV`1$EvecmD z0u?02#B1Z3)Vda}f*4N3nRJPbWOP5u4W?@a`$E^>v08dUe*I2ey88nW(N7Z?&s0NM zXI5%~3KFO4HSx^+<6D)g@^m6zOiN(Qyx&lE_%W@6K-c!LhMsf()KG`h{z}CDy77#4 zS&2h$5wkjS~Hj%WUx>ME@HVj>1Sj%&1R-B{i}nbAR@3u{zoornq&SU)=NIX-=O z2l0ua84xW}7(4FQkq_p^68)Ez^T;aIX*Rbzym_Ujp2&o?)Z_Bq!;yBzKn01)x7&F_ zlGj$x3$>*)$0rd9bm9G{87a4t8u6~xlOG2r5vU-6caui$#-%fgtf?heU6f%slN{%W z4?_isM9~>MFINjS|9AeLkFG(8%SvyQrdCdh{0} zs*g%;bpKFSmig&!7%I5m(B7Fn>zfI6@f`OuUdIbGYD}mv?>2biAkbC!XprZQQBn2C zy_$$&p-GLLck0WFN#BH_g2aN0Sv}A1hN*&$qlnnOIFXUp-B2c(6d;g5*P*m|J-v4s zs_K!=M8rOu&=_{Op}cq_u0RC|Y#E&G2NLMQ_R8(*G&H^OTdP`f%aA3GrzB0%{pN+h zlIr;Wt>L&jf@Ws!N^5Ky=91gpYaOc~kiaz?Zr7rmX^om6T{7+BRbl8l5WLm=W@<6@ za{iHUC-Hl$RK`+ON6u=x&9RyT30!+Zs|SEU1qoacLvP#VQWz~N){_e|ZgZ@BLE>4S zdFIP8g;ZeVOS&IB9w#=Q4sIxSE;#BS(1j~|oCGRJ;Cdq`feI413X0}(-b`Sm=-61U z-+$b(+6jrr|MoOj_Mx?8^-|FLdAotJjlCV3$+GuuItX;(YAz>%3KF=+%t@ev1g?B@ zyF#|U7wxvTkUI|EbF6SfVo|dYb5w&|>f3?AbRKgTJr$e!ww4Q9e{>M&!u5Dg0u>~1 zU7_3ctMRW`+PaOrQ}#m`x^4}=AXk*gsU5L6|H&-S^`XJ9qS=#Fs`#!Bm2ed;^P1S&}27@*s= zE9$J6^lf_?dMw;QplfvD%%1-1OQ?6fQq!5^2qY><;D{cL@4|`^B+!K`Nt`2)s374S z9sJrj9FDNz$St*MIi8BqBU{Qf?}`XikifAsTD=_kKqy+nTYXz`2Z63S>xz43yeqFR zW#H9LIC6&y5;%57wNKTDBH#X2veDwA0ts}z?^4*4w|sdu_$9A0#gRKykifAsx9e$= zMgT%mvp61Wb* z?Rvhhop_bnE!WR$FYs(}?kFCib1o+;NZ_nc=ha05U3i4fxtypVfwMxLR~HF%InNwd zjG%%9&I)y2E1Xq~^M&ymQlC0=1+isPKY1gfr{n4(f%AHuvvF}>=)x=Qoc)QjF_&J< zZe}c(QoS8Kv=Yvsbh{e&A0|Fs>LbhD=^;=-qV}J)%rb@2s^5n6q9+k&e@CcnV0Z~B$=M*}xE)wW+o;j{pLj?((Q|NXb zA6Z)bc9+&092qKb-Yd>%#plg=bx}bAulm>La-s`op3)o3rjp|KKi#r!u}H@ZQzS6n z*XN|73un+e=MLhWBAnNS^O?Rr(+LTjA?BQUhWkPn&a(RYj4dQ^rW@VC$b{mLd4UAFaBY@z^%*Ki;L0AF5&w505frbV z9QWfS$4o$+!2RMCajp}_wZXU+ zx!n3!=CZ~4RJ;Fp750MiTg0YUUF6nZnhI2qz}3T0EbCZSw33QcM^vTS1u7FAsyD-JT zHSVY&;XIE$=}d8Ga%XvDcWr?Lx^PXsbGWu4&Ue z;?ZPN6a()EDoEgcqVEArzbM*1ZYOspDkG3U*Qa{PJStuZ)g(o7ih*BMK?MotJr6l_ zU1aLkR`&j{m_Pzu_!SrDmk{vl2l&K%9IMQAuY>5!L+PmSo}+>UJ_|HDn0Tjna=44U zPBSx+K-Z-TC(P3$^QtVt#VH2fb5xMPXMx^?r|uE!>UWkyCR7qgplj>1tLE#(1=Q0c z{PjJ&=cpio&jQU=+j&IvIo(mN%^W6>Kv$o(AI$KqMbv^U87T(db5xMPXMsj*b6ge$ z_qUV5v{oMpbmd7J-_vP%G1Y4i=RfeCqk;rJ3)FtJ_(xnVPhabq5+aa5*X+)Lo=HVY zs>(eQQVjft5GqJGpQ}->`y%Q>=P-& zI?Kjy!UPiN>R;wB^VpSqG-InE#lYtZ6(sO^bGxe4I3}KM=_r4kQC1*WUb6a$|tRFJ^u&FzZ6>5AC!Q#<)GTVa6&x)x4)XC|s%RE-(L-)O|=3Kb;qd2_ow z|J@YzleCqK(&QINpzHL9xE{AGuCkWmIl}l{p@IZHZ?t;(_5-nPP;2>T{vd$_x|)?v z>bYE|l-m51XGh~#xllpE`Rq=b@t?SRtEEiRD!V`eUHBC+dMko2x8T=W@X6mEwA8GA zJr~VL38SOJXBQPD@R_E0uYpqhySj^(DkzR2J=OYV3qeyNs58bE-FaiGfm%s z_;tT%8q`@%ZB$MmfvyrmP4hSUlINIhg(wC-yQm<6&os?7IDcG(&+91rJ})7VK-V89 zE}Nf56r#B}SttfRyQm<6&or%%s(Dr1=-p0UpPFAFfv$V+@0)Ax6jlogrJ)%3?4p7M zKGQTWW6EvO_Iw+8b#jnE0$q9Xy)m2DE~Z|6;MwZ8mEurck=lSjU?4p7MKGXE&uaM_r&We`un_HO#66mTU6MMF1D^1@?eMK1) z{FWXnNI1(!*I92xg%mAhweWNT33TDN`<&k?!fz8{=}Px}wmIuePL;GBe-#+Z2P#Nl zxuNgk%r!-`d0k||%%K7abdA2S#2i;BNQKnkw{0vRs33vmhTgo29260WI?JeEO9~{= z^(1<|IcRhqtW2Ks_>$`C`Z4BVA&|(=x1qm#hZr9nju?+J% ztx%8&1rq2w`YFCA@q{vJ*h^mXgWvc?1qo+4Uw1#Q(UjIrWa=4LAb~FYrm*vSefW(& ztR)r&_cRMeXQwu*BHckO=cpio<)7A{Z`mzocI_fpwJR!+K-Vu1N1H32@(ARDx}6XNl7uVoTGvSmVdYF zQn&v^=5ej$)aaA~33NpyIBiZZSwt1?!fRi#oTGvSmVdYF?{sg(qsuL1#q@y!33M54 zubYA0iqX0We&@t;jtUZ3{^{FoLq3TOrJBpm(-R6L&=t7jUvuKGB~(Cip5uk(92F$6 z{L?)@8rvu~qp2K`KdwLmT^G~5H{+ctrRo*twU$`UQ9%OBKh1&M5zoj-Yy0l){uG7; zx*BYa>lvB2tXf*@6ve==n4^M(vo7f}IiV3yzmcrc_f;4Y=)$k2Q>FpFk?FuaMUrbyso{XQ0*>qW5$}D zI)=Vd@b;)!y}FZ3{3%!E9AdP=aqLInw|$K0;o_xFjK z#kyG#$90l{&vOVQ&~(;+LInw|$7m(ezvqPKbO-r#Yi5B2x~g=e@7%o%ruICDVqkrR3KCe4(HG1{ z-4QFgwv}&|rxZw_t8dvK&8vy?sf2&>C@0oes33v$nA(;+LInw|$LN0Sej)n5ZzQr&X%m<-les33v$ z7=44T*L(4}dJFmU4{-z%==!)M+I(8AF#VbbkI7(tg$fc_kI{_yF0qXGbDPPDp&!GL zKv$uN!{*CoMb-R*JSKzn6)H$zJ?3_07!cQpq+dSqEO-%y1iG3T=gs%MimUfO^Yo(?f%O=@s})IXgv@Iw zBQo3yLjqk}FFiFA&MU3VQAa2S)>o(?f%TZ%b@ED5qwCB1@=5V4VMw6s_NtF&;O}Ks zt{42fOZcljs37626PNc+ZscrUPex2Q6NUu3@K=JIzp016KZoBv$FHV4zpai6*1^YO zr81K*q~E){T7{lntVK~l0&7>AFFN^vIGd`A%#kmrKmuJ;QWZ3t{*q076T;agtVK~l z0&7?LCV7<;!qcjg{BSa}KmuLgad@A+EbbLRc7DWXKtX-)@^?xNQY-}ly zmWU&eK-cgci_8og3aCV}cvKB*QB;t?+LhKK=b&$kylF0@T6_pY0$o=suQA(gE=1p% z;88WKMNvTlYgfvKSBz~$hc}a>W8VZR(!hsdNT6#$gMH?!9YxiNGd!w>wJ0h`VC_nCYs)4yQe15$H}3l<3<-3-xqQ;B zM7ix95!WaN)}p8&fwimKRVhvq<9x}6GH>*yFeK2`q~ld{iYiIJ^ml?{U@eLY5?H%Z z%eg+#NHD#=?DXHMFeK2m_0a?K+}_e^`YQe!3D%;hAc3_j<+hC!#)l_$<)OAm!jM2$ z+5xZ4oCnL&ZyfR$Xz*9xP(i|3Q`gy)%1F|rj{Gh0-Y_K4g}*XKUkZ71Mu_I^<(s>e z9V-rTWgvdX&G~Cks376|+8eHFL>I0lbP`{y6Y*C=u|9VGUMea`;P0A#y>3Srwkyux zeMJQcY#+bgMxhJaN9S*{;<01PfWK?%tlLpR0_%L|Z?YnRF8p0nXWfnp5?JRuf0Gpn zbm8xsI_q{+kia_M`J1drpbLN3)LFNqf&|w2)NhC1WJLm9_`9agx*ZiHu+De>CMy!? z!rwJ@*6pYufpxy~H(8ND7yhoPvu;NP39R#J%@6!0D-!6!-!*mC?WiDub-wdAS&={& z{;sLBZbt2z!calN*?#=6N#L(kqJo6;E1S5| z8(p}*+DY6j@<9}z*-UQSkjL@8KKv3NehrgqIQX6=DoEhBEuG&4L>GRE&q?6-EKxxM zzisLKCLp@-OMFfOzh{XG68LRP=Qjb-g->4>k{Y3rt%LU^aap=2)VVANBRFJ?g|IvE2AL1H= z$26Af&S!QI=(@kY?f>iR+~cA+vOPX(Pyqq)!37hanE|4UO4KA*WO^Do)Cob#=7PE~hRPo17q`r%chjZMqnBO8;CwpQYv%GG+TjdP*|39J=Jt3ls3 z%DU)WZS3#=O(IZh$y+b$uZ|l-Z`RBu8+qeGm6Rhn+N1y3*@+S)u<{@MHhfp8a`TfM z?eT(+5`kJ+`A@EAi8U;-CR}mL(fadInZ}<>S#>e2T89!Ou(}-W?^c8;zv(z$TUOoK zi3DmL+L*2XWA6xK#K)`223Frg2@+T(k7~+hw^g*?kJCE57wtp>wL*qIr>~wintFE; z*}y7-C_zH54>$K*nDU_`N9#$I3Xwo9tS%>4^2F+$*wYgarRm=c9%_8phn*XaeT5Pv zun#@%+6AqZ?w{vsZT~yki3Dnu4;`u3oXj*Tvr5PY_7zHyz&@m^DsiF8>fz(GR&yep zNT628fh@gr_DIT2yhS#oz59&b#aONP zyig}fkdVg%tDa(|QyiP#OaEP;J|o>ItYl~2WACB_3G8+HO?6ru<>k4#TECf8&l1`~ ztu*CBzqU%H_riCOS2!LhK?29g<1Ptrt31^+S38>&>O=yyii)4q zv%@lsRaK>A1IGg;NZ>em+|I3G%Jq+Ow3wI>ClaXD#&GJ@i-#G;09IcV#{(ru;5gBD zwZsVJ+#}iAv@R{2NTAlTdqeg3`@@Z^6Bm+={ry)lBI-iPFda+)k#~pREweoJO@!DtGA9A7u39Q%H{922ZT=B_3uB?g@ zB=C8q`DX^y!snIdE5zdS16HS%*K?F0flmhXc0zNNZsExStL)NymX3DHfkD~Yq1jPV z{atKVer9Oy+I_iCU%jg%&1jgtS;hNCuFHuMB(VBs^YKYJfr=i%VnvuDr#XJSot1A2@>)>h<%08;!M;=9i)G`G{e{v z{ULcJ%_Sg_2x-2$cPm2KsEyTLI(Rn~+rpV>OYRVTe*G|GPQ?x_eiqF<|FS?qF5+ty)u3WJf3DgQpjnYGQ4KY>}v**Nz6+nz~92@+T# zn6fej9TnH6G1{k<$7KTQ6Jy~X#JW`=RgTdd;9%J&CK zkiaXS-brodDnTv0Lgg{Xc5(dWF>kKsGTtB9Qu8*DKo2SJ+^25aFKb@cLOPzVPMLf} zb&Yix6(3~O%$QNDuFi270|unm*lhb$n~mO%9+2(wxUXFJA(0a(L1Oi+W1=Pc^}zBk z5`qz^b!__os1rvyjPUZ|H6Hiv@xS_%6DV2h`daPaau_Y9jS29o)%US>PM}vZQ4euU z3%>|)SP~>g{r!ZxufM}cUOa)knpFQ^qOWW=i$JY{mrkiix;l*fgHwsP+-1ZT?iET# zuRE0PAe5sdVqmvP+(rxlsVS~lN zB}lya^jWoZo!yxJSqXX7;pYm;1}9KUyL3i9|AyT-wsk!bx7Hvu)eoF@qrp`{MB(#G z#dx4(Q@0c93rTh(XVTsPucpi|32Fn0{o}tCtwEOW| z%wtyMmIR3fzd5dc7h^ZNMAVRt@fRNzabR1hb>o$z>aY%WW85sA2%F7T#BHGDn_qt^ zw6GyZgGw->qS6!7q>os4)i;@kjEFo{gCRe}-hJQgxQ|B5v8 zf2%D{FsAQ`zEpMBTBYm#m7^c_o>IzuD9OB6wDT6krNjYk+e5YdywSt=092HyS{0$a&L~=dU~bEN0fK>?sCcmYRQq8 zla25{_V%tM8|c-kSf6s|OoY+hLnj-9J$eIzh#&6s@y-}f=0gb*H@>Y_Vn1zXJeSYT zMb4=aa>SMPaaWoX*)K+l$%d_K ziZ{AbMgua)RJeo{`>N@ip4{{8S!O4lpqm% zdA6FeErGl`OtX)J`l|1@gS;oGcacb1AFci^y&s*nYEMJkGJz5#@QR@t*wj}o6Z?8w zQePnzy{+JUwP|hQCknRNV&+>uZkHn)W>Izx8-_8z)eL1fI`J zzkFG!rM-~MoP)j~xmCfzk z2Cg!A?iPCMaes0uatkL=f&_Z#aj&U=M|g$S@qAx7@<+x_-)h;gB1ZyGCZ^x3U0x$> zU|Xn#qe(knljFpg<4EDT*my0_JCHe694J8o&n#!x)n7y$NT3#;I`46ZO#eyrE=q6} z#g@$Voc9$gg`DO6tksV?RDewos$ zhD7;jukx#P;YL;rTcf5EF>AtKQ$`Mu3Dny1Qk9awIo#-Rn|ZZ_h}>W5QU)ex`cQ%d z+N1YgiSP~kE~WERvJIqh6{Wq`xI(4s{C6pDr)T<5g2eNKtCZ=p!;HB9V_qc@F{|6P zl!TEofm*nVQXQ|@Lgnh`*HSLzX8KTq#HjEpW!#gYMz4F!2D?g5Qq_;0Ic_JekhpTn z#L`dd5;=hqB+xd0ZfBN?6!!h&XzdMJ$!scnhUcI0dr4D*e@j6EzX349|J|dA8R0hA zw<7+T+2c0&_bC2t#b!fEFoMx^&d;w0E35X$J9fO@Ph;l~GT*1P->BklHhO3hrxz~S z#0Zoif$NG%kTqK%fm(9p%qvcyS9n4q+Vi+y$uCrt_rBeHImG2-XE?Dq=9bJ)!xOHs zC6hR{q}ss zVwuF$+>L&(Fmlwwm`vj0)Rytg2KtL!mfxU}bc!r-z zJXg7G6C+T9XAw5_iuW!`0*Tj)pP;ir*?VO4WJ$TGuq~^Vav#4Z*qwv31oojxtoZ&5 zKY7S6%4R~R|Y5*U+7 z#EjUomDxZE67pKhdN=FKzx(4r>$u7^jXbBSY+GO)NZ`6F&7%Ij40eA|XS>*54}7M- z@f|OAg_!@?+-UBR1R+$5*bsJ0?7dQ+ONYFg4tX`Q!S_oh#?;|npO8>qO%SwmCt9L6 z`ycERyPT$1W?QI5`+mBWS97J?#114%Xg^Vhyqd60nYf;zm^Tm-Bxo;Fx3XmCAKxG% zN3T$e_DFRrOEzgw3z5e`3GKb=R+h}#bE2%wEgg3`g;z+>zOQa&$%?CDgT{ecw4bb7 zS+dmQowoD6aFozKwQgm}(5o9mJ_frOQnslES(u)+F@OOT*_c-_j9&AS;RT_v1A zE!yALtt{EBqsv5Jp@i}VI%FDzZTg+?oFBz_pjSvx&O*1cWE<`;k;a^Rg<6yg(XA|5 zxAD4&10|GW(XA|*)gvDF%qw39wSffXcXTUDM!6zk1LHs~${Xoc&MPXcr65p3`6!*| zxv(X3F5y=RN|2yjn4tZ6wV-jJ7UkH$s~wS@#9fOL%H4@*(Y8N77<2?>q8`Saa*!f& z_WhiXAQF_16k|i*yw1N1aaaUuQT`Lg{5eloVFM+UOBL4=+NM2#Wp6)VtgU z67-$}%ucvl94MjpGGL8Duh`0rW6r&j37n}tQ~N>hS`sAa zy%ShDAG>o2M$jTq3)lH3PZ^C*7CmT;>*2GNF>Olldr&5I$6V}<4L07yOLHZ0=2|Y{u{}q{9;wouEu#u$|=b=G)J&vyej=yi6BsdgzS}nBy0_p%mxyug*&XK4O=6D L5+uyeJY(`Nju%Ka literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_10_custom_finger_right.stl b/lerobot/common/envs/aloha/assets/vx300s_10_custom_finger_right.stl new file mode 100644 index 0000000000000000000000000000000000000000..d6a492c2046d3850ce7c7d650e951701b93bb87d GIT binary patch literal 83384 zcmb511#}fjw6%i=2@oW>C%8L-R3(KD5+qn~_WB^EWd&o^lM=j-XM?M|KSzb}|S z!*GNmfr>jpv_^Qz7<-YRZRJw2AOAezM+}QV#hoD9Cc^g)p!4vmnqWi>66&bP^?3V5 z>-;`093f*Mfr>jpF>Io0wXRl-op;W}AVJ&8Rp;gfE5@&F`^p$dpyEytZ4+fOHMC-k zY?jK21Z^wVxIO2s7`}Hp$rwZ|shci<2vpn&qHQAEnesea<#GWJa+lBuqLu4w*f}f4 z`rOTB44c@oj0jZR38HP{R)viG`HOSQ_MNGt5kxCjnm^B2F%tEyFJllvcaR8F+zFy> zBFl(-jEJLiJ7@&a%60n2-&TxHIcmxnNTA|Q5N#9xJegy~XnMG>6A9W@u7yueS}{&E zt14q4fr>jpv`xHC9p8#k{OM39611&cM;;uvVl@4!vW$TQD((c)HgWDkk-c=SUL6?j zM1r=JtMtvIR*aC36axuV+zFy>B6Lra7>bc9WUvzn+E%X1w~tsc`gEx-V<3TwJ3+Kf zB)=bH#mF-;!ifZJD_5IuhpZSY2iK7?kU+(qAlfG4RY>fl^Z5HqxDyH5R<2Ez4_Yw_ zC2TBXAc2ZIL9|VL%2mLMk*aX86A9W@t|@!=TQRa8Y9nJHfr>jpv`sWCQr(J?;>yt0R*ZaGKExnF+sc(?fN903ziNn#fdne<1kpCp zy-lPQqt1*qF-Xw1a*h4Vuwv92F-FEf0u^_HXqyPD|FaciO3ETJNYJ)&4UDv7j2JgX z#y|oUcYa6BNTH;A!Vb zs3(zJ>b(j0d$Wvz1S;+X#jpu@YdI3?jUtzN|Ff6aDPtgkiaS9uYywIjj)W>1$fe4$ z8~ygk7)YSvPEZV+fKrqrp-MP%sq*;aFsF=x1S;+X#jpve4LB02q$ZcDSJIX>Weg%} z^&Jr)YaEV>J3%pQf@-yup`!z2J*W|?#vzxgAID9l7*G##RNM)QVH4kL=O|g9YlNyf z$))P~<6{gN0|`{z35sD8-&+|`vR%TFP%Qv*srE`#o){Se2~^w(ieVGqTT4;0eZ`Sb zEg5pDmRgBH(J}@RqlWcZP6R6M1jVokyPeo@xoq`mgldtIOSL$!E#4+$Ac2ZIK{0IN zdwX}eY`t9{$wVSp%AirS(l zHceG<5fv%YmCta}}p)X}C{P(^S0`tjMI4Ve} zcg1eEA4)uey&g3o`pTXG8iB5p9sf4NYXykp8*9k(xFmZMew!x*)|I^pRFF{birxRn z`REMe$0kI_ui8~3&^15!jF~1lK*Z}%SH?&y-$CyT69f0jUJ)utsCUKgM_p~1iubNC zG5VfgLybUJtrus_J;eh=iIGiZjBB#5R&w#gz-ZZ5Lj?)-uGsy-v3X1Il*cDV|8lat zMxbjzm-FV)YyqO*q4qL{pX{Y}t1~I^mh5w)f`ock?0#*<3w8MR;gh1Xm&vFR=&Jqu z1@lmn0CDzuZyBSA>^m>ZFgb9j>^q}^gnC!({`t=N9e6;!$75Q{kO~Z@Q>mAcBProQ(0n;1iGrH zxM1cE^A~;nH^>>htQGw^3wf1rYddXDWns$~9Po-FsQ=(>3eXau^FZarttX8z(^ z@Kzav-obOuS%EiY&4~&U>V359+ES--a_=XzqT3g*t`X>3mi?^Rrij02*lL%IaaEQj z-6CfP?vgD4RFF{Rirr@DzwQG|HhXsTy5X%g0$ux?oHi5X^cRO4@0BrpWtkZ9d3K;7 z+a;(Vp~^?Q?GrwE4ddzNMDwRr1{EzcvSf0TV5NT4gM&0lb>s>*gdU8_X0 z-Hr+p*oJq6Hl4gCCUq72ejtIaWc?1qJx?G7-9o*lhj zK37PfEB}Ur@a%pnpV&#y?%^-t92F$6Pvr+g` z?_iR`!5kGNuy5!HEtWsnnRn8x=mzpVM*>}AjD1j+G>{`jRF-(1&B;+g0{gg*(8eFb zo!d9hjGigWDXrl>b;%PZjL}g;OEgu*vNMK*x5!z>5g!Aye8PTO>xr+q4Qa&}H zY;P+^il}U_He(G#1qmE;aD>Wt)tPGl^yp@?{y+j@gsjhFBgoZk ztpRNYIuB|y$n%In1^27Y$sQx?@K;~wk}XrB17*7e33NTJY(m?I?gzDf_Q#qqdSwLv&eQL z66k8&VL!A*!{qxxZP9pgBo!4T)VpGjy^haY!pU+^ik>UmyGWpGKVH2b8%62;v=qfe&5cCZ`%kql)21n$`HY!M{vdbO|&;963 z%>FNS{{snhed}}t`Zx(?xl4VV%yNVt6(m#{Y>(+5PCO!J#}d0Ag#@~=pXdm!F6$5K zt0k7122_wxb%~vuz^vuGnMR1pbJDiznRe=A|6R*kTA5K)+zFyJ;(MO+$G(VGE*0A| z&xwjVL9}O{6A5)xL{Qce3EEb!Qv(lJF@EGZ6@iL7LG+J2ClQpjM1r=J zD>};|D~4yD6BT!YXwN(+611&cpPwAIV*JQ+jvDr48D&OMaVLoWk>~8lzAU3WCla)+ zTqSP&WySE!bE4u-5bc@gM1r=JE76@}Rt(QPCo1j)(VlruBxqZ?=07=M#jr~T7~gfG z;!Y546EIG#5kxE3>xZYT7@m1fRNM)oJ@cGM(6(|#oH%X8@XT|f;!Y6lndd};wv{W} zgtJzRA9>Cl<8Jv=W)u~7g6JQ4&bFry`BR<~3EEb!;MC`>7@m1fRNM)oJ@cGM(6(~T zX>!4e;hE<|#hoD9GtY?xZ7bL2Mi;FZo_S7G+zFyR^PEV~wsKWZaLJ0{ndd~sogmsX z&xr(WD_5iDb_~xvCo1j)(VlruBxqZ?)ZabxoT#`HM0@5rVJE}iJ#U_QPE_0pis6~(L_$4@jE>(_s<~dPuCn$zzo)ZaG!jVgr$DVmkRNM)Q z;hE<|LY36yQZRsit!`Qsj`+xsFn=5RJ-d(o>MmZtjs7X z?gYj7k>@0W@|;Mh78$uz`|(GfQxT}R6BOe|o|6d5b0VQymgG|H;2(KTMWEtNP>dgW zP9i94iG*q)lS{SdJ@cHXxDyn^GtY^HYUz_p^-Js#ddzd8;!aQuo4`CL5~{~SF4e#C z%yXjRPEZWbJg3YkhNwKJdZVZ{DRYw{appN)3KHsFi8asZBG4s!$gbFWo)Z-$)Vt!D z=R^WsvfmyOd!7>&B-Fd&ndd|TU2^;(B=$TfDoChz#WT-|1iIunN=WQ^PE?Rk?}}%h z6A5(5@t}~{^PH$4q23kGJSP(9lH*z-vFABaK|;MNo_S6r&?U#`LSoNzqJo5aS3L8a zNT5rOGls;T=R^ew9M{nEoJgQcj+chSp65gb2^^o%^PEVaOOE@7#GdCw1ql_;GtY?x zy5#tENbGq|RFF{D%`?x51iIund`RqhPE?Rk_un(mi3GZ2J|QIbJSQqhsOQ)-&xr)O zWL_jB_BM-ClctA^MIhP#XKh}NT_YkJZEf# z<;ryl+6X+r?6F1Qa zqLr)Ze8buFCI$E1(e&A+IntiEO)J@RIi3$?G72I#d`1tx? z8H0!>voq#(C(uRP6vHM~4qp}X_Q9@z@V${vRFLR!{h$>i)x&c#1`*L8wk>xj&_&x6 z!zS)-XdW|T-0tNWk_~pEg2cZokJvFXACobNkay6_oj@0DTQMwR@W?~7wlAvNv0+YB zka$1*m=$CC+Cwr15&s>m7T`{xi?%6-O?WNeTFGm9>1C;340ob}ME&L`tr)A3KD((J8Q+Ld+V}{LBxZWZ~ff~bkR1&u!*lL_Og;kpZb?P8sS6* zi5K%PSTRoi{Yb_jB156>0qz94Xq#f##G7-k*{Jhv0_1;ARFLSB^|BS?YGW_?o)ht< z$h_t51iEOOV%S9Ks_A%4q7*A`Z>r}+1qo;Gt5%Hg**-D`5rsb`4{#^YMcWj^CN3r_ z%y(Bfu=MWSASWtFjF@`eigE5mRvCkc0S6l{cPG$A+Z4kliZ>47KRwyB{KoNoPE?Ti z7IDLhF}ZY68H0$#MYb$;C(uRP6vHO&JqY8uYW=kQ_Tp4dRFLTDeanh*C1;3?K}4aM z7X#c0bkR1&u!)(2+w*?@n*yp|eH4QV5}%vgwqp23Hj*)j$WZ992Z1iyrWiJ{Or83wkd{93_UQAHysof5WF!m1{EZxCA?$B zC^{iZ#vmfui{@_WVOWj$Upr_Yaa@@wkjZ#K58xJP35D62m5_^qElexW6oYI4Ve}vg@ztb20`I@>&JB6X;SU zpG{CH+Hm)x21l7)`CmYLT z?aWa@Le=dzqMyhZL{O>VPM}M*3~Yj08AQld21f-6)kaCO?zxQdyo{Z;*?j6p=jqSL8;r4i^-Ej63?-cF=eA4dfV)n=?ao?;NuW>#qr z0$r-bX%p0X9Xztya@l(2s34)*zMFcykTHm;{=T)pJAp3Ma<&O-g>MZDqINq+1qs!L zfBycdj6p=)c@e9AffsqZ^}H9F^G_D2I_xk1iDmD#wMs& zG_GPK-@kWhW9P9^Tj7(~dnPi}VtU8+ZB6V$t_TkF#@*}LPYAfft(gTMSEV-Vr^ zm@}_CfiBe-wF&B_ri@9OSN2jlDoCjQ?v_m#WsL7VVJ{+3aVMyDwh4OwWDQOIXD?a} zMm0Unr&aYX)%vs&js9-W_$9j{P(ea%s}=z5-HH(v8$m7=+s^!83{-HxSZh-&gZ}B~ zLHj}%*1;ALr3hN1MrTMlI_08vn~H7EL$*S=#UKR<70+&w(IKfAxG!|6b5iZA9|Wyx zqobniq^ftRRg6cgpE)W>sFs1<-o^7k0$q4cdJNnz9-*qW?Y;rVKm`d}QAg)zXL#cx z(4}f^yN`neDoCh0*zS2DfeI3|29J))&TYpRFI%Gcof6V(Z@xgOVz=4 zPZ$YQkf1eq6vLit5Ep?iRR`NWdL&RmLe;4DI0F)>AVI74=&0;j7I6{iQZ?%L5f%%v z%Mw(OpjCSm!=5dIF_1u)s!_j>`#=m-kf4 z(M2n`h_EvzNT5P%$;d^y8{AXeM}-8fb|YHNT&5`Y8-@Eqm-@SBn*kLh)V7-I?1~{b z>@%l*p-Ua1Jr9}u>ZnjrSApgTVJpP<`W*L#E_FBU8NYN$sy;^o zUFzwv+i(~I6(rPCY0vn@7)YQ?y#;n#6l0)*gnGN|8NV0<33REq*=|!KfeI3;#IRfX zcvPq$p-LiqjxfeR0$r-)vwJKU0~I7xiE7Vhz!*rNOO@c?`)XDYyJd+A5~^nSF)u?s zB}kx4)kNQWkPrhEBvcJ&&o99}{4z_#3NT7m*s;TXHGI0^;QY{0!M~?(5NT~LT zJi+B3G|BG9E; zwf6WG5~v`d+S>N08WN}=p<3kjT(!6ebg3SIJvxX4DoChahCSylE&^SuFJg~!B7q7L zs>foFy&{1M5~@dL_c>+X*&5mY-gge68j|V{StOUAfn_{@ekS&77kWoQG))H0>*En^o1iEOO zVz|b_ErQ0vQ9(l15>^b?czdh_x@enXxW@FIbU$cJ9~C5IEn(jeE7Kse0I?G2qHXJb zsN94_P;LShBxEgN#c<_6VkOW;+Z4l;V0tr(QmM+FIWZ(Q>LtQhVDy40O@%{8!M(Ch?MkWkN2o)q$UE-RzWW{hN z(4}f3*W4(o)uL!_6e>ulI?*-%O4WlJfi6{}y5@LUF=&n#DoCih-8GNQis4S6OSKGK zbJeUEG*=B3Bvc#4H6PB3;ZC4SwQyW>?yMLz=MEJlR9nk6ug{9%PM}M*)Le51snr)n za|cmDLbVxP^AlA&Q6tc$TAZ#qkgD}cGa9WDnG_^c+t(hamRaOj33REJvrWjHFq7wD z&E-S|3Dt&o%@>W8K$q$PxaOo<1kFiB1qsy`am{;;l|Yy3$++g$S_I9lMFk1fr*h5T zjg>%`>XEtT2y?ntG)EW}BvjwfH4iyf0$r+S>6+_o5#Q%JTlbt4B&f$qwX;344LxC5 zruv2`ZyvyN25?dLfv!EQD-F3 zrJgs>F=TbE=nkr@K$&qB&vnn$)s_GM@suE;u86(9R@&r0)sFi?pi5m5&zvwS>YOM? zi?Kbj0M=Ec<3&PUg;;Y%7C{OU>RQE`!LkTakf7CvbO${%ytprPVHu;J2P#O=>O+d* znc+nOU07D?F;GE*Rv%If&wMQs=)y8zkAVsjwEB=@c;;)7Ko{0sdJI&Mz#3I2P(gy$ zn9xyqWO$>HKo_QO(0$tcI z(PN;31g&tyuTLYqP(gy$`O#6?>j$l({d--D1iG;Is>O&x z1qtj^YlIgnNYDyLIx5fHHWKKmbc6e_V1YAoYNt)>W4kWkyMY*P&KvZ%mLgNx>U;`)~vo2gA^oGi^DZ@z;(}YU+7XT zoLFZkSTRUJLbak|oikw(q#&VMXP$Ena9`+Bt-)C5epoR`K|-}MJ?9$WzR;ywwXPW{ zUaAyD1qsz!_MAC@1iDn~+_P7N3KFW-Z}-)%Ou4j*jw)T6Y%68Y#H2nl^-N`-!`i0) znfkkzS58x_apd{f1Sv?!*cR=1R7jvpo}Wc{T&pNlA^aUT^D@>#HG&*uvF zg)aH*T7>J_jrx8Eqfn7gzU88K1@{#9Q6VAUO^fz?&v9Sq^749Z5wYEm9|{t(jIjvM z@(TBbE?M%~F|74C@wO(*f zaUT^DvQ1>sp6x5#7rJCi%_3Z_KG#v9qP8i!gnNqnsE|poY{~2LYI1*J?H5ofvz8=QdF?}QK{M>Di{e>u6WMV$92pmCAh~Ndii|)I1hBGnj!WX@pM$As2Ybx{&7!n9~Ba+w)2>+t{oM+ zR4p3oSf5n_kfLg58Y$F|s_yWcRtsQ5g2j1JiH(SDB-K??ham0zI@5|R4_klFqfkLY zZimn{lqHDUbLB?3ToaP6`o8TJ!wVJMuloC>;)(R5auK8;A>V@UF>?No#1B`#3M)CC zN8fpagnrLa!Tri#e+stGe9`|%{BTLa_(8}!n4iks?|0BTUb<8A4qDsa@A>!haKE~E zwn$L>kz#m0S4f~sK9v^X`Rt-1pLWaj{r&hq92FAOo~NVodrfi77aSTU&1 zz^76tP(ec0J{Ik{UJVI!(P#qQ!C31-mm+IUYn$p<+*8~~g@mlBE!v*RAY9SbvYT&EQgGE5q8Rw#fhOsF0AY8jJR5Ek)tJ&;@@t<2-W{3E4WcV%T$v z=)7Y&a}!-^+tp4~gf*T>cZw7hgW8|}e@8`xx(cq5I~7Cz-}Q`|=u-E?)uvWN6e{Wt z(%2jBDeh~9gnD8;$Kh~a=u*$FtN-CTDpb_dPW>9(Q`|>|gnGL?$H;JB=u&U9$B0)H zDym$eJ|ONX?xR9Nm0hv*Qh(e*bp0rmVi`5Co>A(*BB4rD&(SE{7rIml?$JN@LPgaE z)bGbVxu3aef8;cgP_>WeND=M}U8=Tojb%iscMug-bJ7?I?kVo0LPFKlcK%$B;#e(! z@1r=btBWob!*g~5wkEv12AcHFdwCrR!S;%NRHz{F{`v*0UD7V~QoFU}I&)Nzz_y(p z0~I9Xv-|xB?G~9T*S+LF`wmjuM{Ub1A57bnV^OVFoluH9;pLTI{<3wL)fSDLP%fgU zcgZc(n2b)?SJXZdFR!N3rMBaWf&0~orsDeG`2WjMsUuNmuI{<(sG?B8W2bHVXzjPw zBBY!C*;kSFg)X)2iowb2KAtFD>aLlzO;fKLFXa=MY$8oMSoX!) zgK*t*>+0Hw9)phL`;%{7UHi-r7aGr=M)l#@-j`*WoYB1W2OqKh(EvejaIteff_f?E zGsf^&7kxwy$3WTtIP-ZPdzP;k_nu#qp@PKYWh43hrat12*+V7q>cklKPu)Je(UuT~ z3KGB0O2;!qq!J^3?I($CMJKX9PDgSU%rydCyMD>dCZ|p<7N71biK1J_vs%%S+&8!? zLj{Q@$?nG#DV0{FJl{nUM`|r#!zT9P`;J%C2y~6Q)Xus2MOtzGVP{E<{^u9AYeX;p zbA}Lx3KDlpo6dGcGKfdVn@b{d$ZEEyLTLOPxoQT3t>OJNF-D;z=hy@LVyCK-Z|tON_CF{Y8-)WhF7V z*k3F%X=fh&M`?x%5-(yl83RY<6`@6oN+KrWH2bMvM}DJnF^xc1sUe23bW=VtdS_ut z?7wu1h0N>7`@Am2P(fnd>1)Qf;e|y|^Q@9cUi${S-K!nHHMM|7plfQTr^cd_Ma1LX znI(~U>vgvI*LM7E_M!|GBo{Avxvlai^xiCWoi5WwSn9n;@l277&N%&QG&5opM$4EycJg?09$Y9NLj{S5ZB@;J5tYT7Uh?-ELa*%l%Hq{;#_ui6 ztr6(TR=lRUu38o040B52=ht7@t;l9P@oImD3KBaKH89&Gt1eQc*&vByr{nQdADi-n zC39*7x~|S>Yz9B6E?VAND~UtB;_*pY!}*)?xfv=*JQ&!@Y_PMYxI1xyBz%W?@nj3a zdDR_xGy+|R-?T6X?5ZJ3wO=oZCveO2cLmxDdFszF z9Mq66nwXBEf<(gVJdEJ-*Z)AE%eQEMb8OZy@i}E3N%U@%lvh03kmu=>o}q%o z=&@bRpBvQ`x90biM3R6M{6Lv7ez<2UjX+oS7LjK0Obx_fzXp={v@I!ry0{@PIUp@V z1&M@*I+&xHg^G&<21%mim=wH7@-Tj_ua8EctKh^Q=H>MD#rtecByrv^8BZy%RfR#m z3>73sCu(C(Y+Xm3Xf#X`EAFP?iEcLFUk4=D2y~U*+1VVGrk>~@&_WVl1|;JP>o(+N z2Bu=DAd#qQb8}{g+VWbBkVJ=SKD@@(2E5?Fq#A*)%J_MJS0bGNS94kSM|sx~&ntG9M9trl^Zlp7 z_|A4o87jEn#FcB98wS>p*J_d^iXTtOyML?CA2*Aq5$NjsdtLKvyjtRM&3=+-)Gh^| zFd&Rysgj7Hf<%&i%-lP&n%Gxrx+L~bPsN)quFnJeehfkaT~j_*HS>O|A?}9{m&Ek^ zKKydlFy0|^JcbGqNkYn)$0k=1JALO!BC>I6zCXA=PoDX|AdLXmipG`9L9eTc$gQI# z@$tD2U+QeYyBzuugbME0+bCpSo-4$L=kp~|I-4*5<9a=wbmc>hKv&G>lIHQJRmAh% zR5DE6nUY^_-GJ9+FN07)!kgzdA1n$M%TD|*3GchU{Mvwe{9Wc-IsvYWDGQi6?h6sI zpUSK1BUAD2U+VL6zdi^;1^1gYCZqXw4HNU%Qs4RE`ZPQuRXskp-zAMe*NbjB%sw}R z#p9#1B$201YW~wN_4&0MH-b<>B3V!>Gtst6V%mgNk~lLUEe~E+m#^M_N+Zyf^l*Cf z&}AmNp7})*Su*+Z4#n&9&)ye)Vk$6HGzQEzJ+p1f&2zBJjvAXJdZ(D$xU{A^j#JI@YDjJuki|5-nj*Z60v zMxblO_Lqk9V0rQHgO!qq8kLq0xL=pAyuCXJ6(lnDIb*QvrA4QBdnD0xwI6?dr4GNg zeXT~I>tfG;j5N-&qV0=yk_g+Io^Kr*%6B<71fhaNx)g_v%RZ&Wsl#+0orYxKOIy|9 z+XpYv2z1d{&9Dh&g*}RM=*$<~ z%fe7WVnsj-DUFEzT*}kTQ}m7hGmfQaE?J0ZyUu(X9o3BQo>wMTQ6q~4c|M~kD-FZ()EXobl(b#F-?6XakbljEX&wdd}@rZMxe`o#6_cUucBh@v{aHv zcHjlueyA1i>F{HyAh9p!U8DWB;$r&5B$6o9`yDHsrzOv`&sQVRl{WCLQMPPJ@!z^c zl1P5y4cpwQCHHON$527SNEP2KFr~Bz$oq-P#FC#`+M~^R3DZ|2&{fZw%-oT^tY{PR zP7+;bePoqVx8T)6{1_@oJU{1ab{tz?WV&-t62Z;A_~yaQc)dNo8iB6PD>IuL@&}3& z=Wk0QI?Fc}xW5^nm&cExg2dAsxy+1U+ zK!%f&$g)lLqlSm`!3q2rDoE@uUeXM?9xTpu+A9hFi3xf4_f7c8RlXX5t^_|-G~+E6 z^8MH)iPmNU9=~c+9)2r5Lj{TO!@|57SXGt`)B-p@I5E$0urc>u=&KRvnh?LX*&;yuzf;ZydeXQ&`?cxjmVZr4xZr{88u;&PZbcP?ne(@gT!2y~ro(A1o{ zuBJ#+ncAW;FO%?B`x^0jv(hqDkib^I-Zwx3UDy|qy`p_5*n@GMd9lrD7?!nn2VHiq zER{{{{9U$SphR_qj#z$`c}?oT&m{6;s30*i@``hC$E>2^a~dOiwCEgLm828@uePs7 zpbN`Kz1&3wi34l=jX`~L2=A9PMwX-2RaT>K2fo(f%aA}9mXCV5iwY74s`NK1tn!!7 zZeAH>g6sfNaVh<&G<64kZ7GNt&9s36hW_|I7Qsib(A?3;W)KA!u+LPj*_ABy`h zB+!NBqh9W!g2aIMNzJTx%8E|^J(4ka!FYUHv1WWjRUd`~y0CoI%Ux8EnDQv2nf6(r zI6L-&jB%rO0>0*cQ~s)v4?_Z7SU&3IE-Fa$%~-%3k%^09M`%>7S;IuU`RXRTb~_)2 z1iG+%)XQB|kSI90g4wZCWiezswZcb>B)n_i#=KZ}ABF_Fuzb|ZT~v_RShc2UoU1Oj z*Pkb2B+ZnR&#cjiCy4Z6NT3VLN4?xd1qmG2&__RzKo^#%j?h2&Gq$XC8-Bn1m!L(> ziWnms<`y*v1c;!3GRE6vx#jpp0fFVCUW%fEL~zMOMrifyvK}li-zY41kw6!gkB-o+ zUf0?0yaS(KJOx7q2`ud#p+$ClX6<&g;Jg2N81(#Egt4l3KJm0cY7v;Rqw)L60CA*B zW`XDD2%Wp=CEMDkHDB2Jt9Ir{?8#ooIQk@ysCgonJdd~tbm3Ky{ivs}SdyEq`2CKb zf>1#sM_^AQU+n-&z+itA%U)V+Zq}3!t=;yH=iUXm->%2FVLFb z`8z&C1qpM_IAhe>ydrzY>=yB(Hb4ShSk5~_XAFJ8CiiO1^IT2BP(cDqZCU!yt}=)%G$>TO8#k#mjAeG7@;wFv~?Cr4n*(MWAb!?@*(U%oSDLLs^;lZxZm!)53Y%n>T|{L1NFHg~qu&g=FiM zYJ*(ozp;2LoAdgEUuguoiY%FCR4q|Jto(=aI43eC;O!oT^B2b+1)+k(^~&pwcH0We zwkWmRtLKz?gAdJlbc-(K2E&UfgKeOl6TkzkeBw$FO>(seFjmISmi*9**BvG?VJf3)NGd>~kYY-|(WRL&1 zG5k_7QK4G`N#rs=vYWG7@B+=f84~Eq`D~vNv!#eQUX|`(!kJ#Y-u-5r-AKStL4vov zW%zU}A^U^zB!RUv66nHu*AaSl@He)(Omp6Ox;H}w39LosNKu81%?!?iPpaF!IiBX3F~b9rx` z`bJ~E<WGhyjWJ} ztR&9wPQ)|GEZM{T-!uYUSJHhp5}hw28WjCk5?v;FbFZ+*yh@*UL8u_{>nR^I; z6b~mJl|+&(3HjxDO?lFX-Wq|fB5zWeDJxbGt75K5BGuExd}4woeDj)w3>72_%ejPR zqaZQ4z#&Os%MuB6VVhBoE#*ke%_dFwN}r?*6(q0)=m=euD?P9MHI%1cygCR+PjT!O z-+xEw+E!`!vVHaVtZ=<#K%!~CLq<2*((j(;m^_cT2y|g7A@jBW`tp@&>+@93T|uZI zF}}oQWAV+>;%iH~R*q3A`5$@1izE2HXjGyDD^ zRFK&5^s#aAU|BJJHMPPMZt~$tribxP|DDwcbT#dG!?5^U4ZiyJhk~rTp84t+Vh>xlEUL(-e{f~6!pmdc)>f14rc%Mk- zQpbn!2Mu2Yp@KyH6aMCX9xQs~StE)4i<9zvjz&EBL@$N}x)xl?X1;z9BnmZ&mc-D& z6g<~`nYB#uAqW*Dx)v&GW(yGFThHZ^h=0MG4?Wh1U%8!-A%U)=>GPSr_Ht46_%=zf z-pP4`$_@FGb6yM;B%&siGsBWq5i_C}Nn&1dZ(crEV}7YfQjI{@$9l!hM>9fXtM5;W zu`(Hd{A)w*=a-0~g2XTPgUyN0s|x?bze)mokVv2l`-ZYde+scAoI(ATS1_Gbs>=+IBLs77dgdqXzzn=#+d6z--z7n)Ac5I4M`&CG zx-b{!2<_7%HQ)WH9)CPH9((t6l$`fSb0BkuU}hYTR?qOFf&^x;<0jCB`DjOI)x^np z{>@=LVXgGq+z*_ifk&$os33u}FXAT9g>xz5o>_x)W=^aLHH+n}D$bXqG311+Ke586 zoAJ}T3o=xYNWD7Le7(4`s5+X;#B{UYvTdbX@Xx0UX#~2A{ngBD4TY#PmD&tQpn}Ba zYs^eBo{NKbZb+h2&X;V|h?ac)r(z5VbUhj!XjXMHk?-OyNz}ail0EF$k`I4egrR~& zy^ST!8J{YOs~KNOB1hC?womq*tM4qS5$O8drKp*&Vns3NEwx_fR(-ajfh?Jg@?r41iGzKlko>us;x=E1||M6S0)tZ9Fb?JV4eJG+%) zs31{gZ)Wp&x-z2N$P|)D+5ZNsy0$G})1$mbpzG3nKQnvB(n7SLp4X9zH(7?cawcGn zvJ4d@7Q9bsj*6E3lI!Uuu`1zZ)-`>5p0r~{jX>AxbBWE{-HVGFLo-MseEJpE_IW$L zCuuo`3KAbTJ~#4|FC_9c$uEforH`?5&pYx|vqCfiT{~XgFy1FCC|({fAc+cljm62DD7z&3_;=7YxzjX+nIL#EN8V_uPaY$-{+O?Qa- z26g65J_IpTkZ93pi}6X0;!OCfq9pE2*voqE>B5^0udEU1+U38@sD3NAIF_C=qfdRD z?Ae+weC|cYP(k8)nyE&O+&M(#xt}Dl^wTDmXBW-9YDwZs z|IMtyf8BV?+k&Bj#MZDdW80+6V&(5mB(c5oQg%YlT<-FsmPVkf!}795&aIh5`87=? zQT4(ynG=rSRZ~}Is35VlbP6M+fS)LmzoR4$ZlBEtw&=x^H?OA==vv^s>D<#jz37;> zlO+7o&1DO__2S=J)?%n2;WJ~3^T|hF5kInzB*y(cn*G~5l0U!MP$ST_u5>ZyfF{1; zRz-&-3S=0|ZcdEkQxDZ;s339eV&%O%yi$t1gN93DX8F!+dwU1}JUCn<(3NcVPS#+6 zkGS9)C5gwcyRw1P9XwUzFop^eCwHXek9VdJDZ@udV#U$EEI5mUZ|h%IBhZC&>-BOM z%Rwx6m%S-#e%xJ2RI2z=mT>9IJY>xaw&tVmm1n3Ru{c#p^I4w?a%Lut`^@flgAI;o z%U@*-(g<|TOIgf(_`HI+QiDcVkU#~A3HkDw7xR=8ey?eaY-hpiZ2A4RJjXu9kU&?q zgn7&YeanhmCzDBH+|%nU={Z>@uCByTL1I+VEM~t=rNpP6l=;~keSuA^*`5cU4ABU5 zP0E_V^iNt!EMw^;;XU*sYf_;-58uccDoF6zNz8#Wi-=j>10*r576bEAUaiB+BP>t)PW)`18VnUAKHPa{JgQMpOx;ZL+ZW2|LJLQA=GPX~ z(Fk-I1zs4NqYDV%_QfPIZJNp64erbvMbu)bAW`N1O(R3ZkP>DoBKFoNYMLWD{?OG?WAn{Db-A zh~S;Qn`s2P3N;;T{1cc}j2+iV5(nllVh{30@YmfNF;tKU*wWhgyKP1>x>Gwz4B9)L zJ;>jSFELta1iI?}Q`xAsEQ8ovzr7?TCZEa1RqVwNC2z)1LE@L_3`U*1X+`_gy(N(; z%Lw)@b0j}IyS+xBYw)lS&Wj;wg}6$@oCYJ=wepd?^Wjzu6(kZoTH<{0Ybr5)5Ut?J zFt`o-|WxYJm!~?3>74*e~gZqmN~ij zulHC)#r=yCCK-ZtghdS$aP9ZKH8ZC*|P0F(( zIr{Qk*#|IGkT_W6qBAsaYLWER&yx7HPAk^f=);rLjL-;l?cbTm*t#*b7~xMuqk=71 zl{tNQhA)u}6(nA7D{1T-pH7Ub+Dj6j{vOT}e(ufh{M1Dw&{g-(I!3v|>BZ8)Jtfhk z-%$4LYHwcQeh-EU5}(EmF&gE_Bx(<7OGnjr8he+n7oXEgK8dg|bamMv=U-jRB+^Z9 zBZ*|ir?Mm8dh){eIx|#|7?OCY;r%F^=-4|<5({tq#(D?F2Pgc>UM7p+h2ynns36fd_g}`92f4*@|EiK0%-6CDvh=BSD_kSc)p_*a#=5q7 z#HFcKBvF6L8a77~=Y3l+RFIe}zm)ZIPCi+GP${~+%}zGyQ5Sx`NSH>T>wbn8#<48< z#i(CsCP&n&9jxi|E<8)qMhq1sN-g?k*@CW79yl)?1@5guI<4@Gp2y~U~ zpWb{>xtQ#w(ox+TbdD7p(w>)0Q-h&`1hzQzb_ps-VEe%lTI}prHsEU)?t8W+8?)=B zaXVdrXuQ0#m{{YRF+5)ZA!?Tq7+XINRFDXpl*F9zs*p&$m{yfKPgR!HETb%gd@_6vJ-y9Y0Qy%+P#dERLKC5QN@Oqh6`{G@THcTTaTPCbF= z=Lj9%eg)ed+MO@H)?PbvB>0+pMxNvT;^T24&m%4ZU3e87p(lr~Vsm7DUVUskh6)n3 zYuqsEh53u;?JCO{Ltk!Z(XYDj9YdRF1iC70dS@(OoL{v2k7k$-Exeljm#{mp+Mx|Y z1&L<&E*itGr7x77xm<$iVb3@AhB}nPUG6$%%bxlYL_&fK8mgE z-HXrk)d_U9I`ymJ6P-c$*X=HeSEc)~BSm}jVvR;HRFEkDbfFP`GQD`-n0j8-uD4-j z10wn6uR4LQv?WFxn_8t6*H6*P;?ybYv3X-6`IuZ|87fH3Tsh3RusyZd^NRXWYeadr zWqcn#bM!ckK-Y|bCPr9-RH9aXYBRJ9D9qX}=)=R_PGqPcv9)hiBkYgl!fVfXNxTa4 zVQ(fn_#dgJXau@GJqR$~txP6XKA0ehjl&bO?(G~r!SQJf6(lZ%q%cm8ODxN)>5{0v z_k2*_7Y@GX^bCza*NupOoR7~Y5mOUPmBjfA@!7h|U9^NeB3e8ZgcvnLbBKa3ZV<####S0xo)$4wM?4P~1_ z&I}TfeR+>BW3{V`L=C@3&Te0lieU}t%;O@^g;!d(`u<7E{1f%%V}F^*P(k8-`4UEh z7AeKEX>_e>H7d^b=XLOLJH}`Px(ZznGQP}8DcVI4QEo^vb|jgDFZ*jOLj{Ry!99(d z=hKJ|gXw!@Ti=ASDz_tfi>D(r0$pY64>7)EN-J^&5V7-p16KK1B=7xoBtr#>ajEAT z4Z36yv$s-NvT$fW_E(4Ae01}lH3D5&#yCRDwC~H_H0aH}h78k6A0)8klPf1v7h}5$ z_T_=;hH5Q+{{eqGmtROBj1i*+J`0Y}M7PSaQ?DGn%9X*|Q-Z|HBzK&js``jkm8hl9 z)1_xq6McvGkVNub1K90xz4;$025JPl{;WUE znCF*4B+N`i*#-Ss&;Gr+v+Q7o3KDG8O5;wGEMnO%T9317+a&h&bWh%WYj2G}SKomf zjFsE72=6LH#Lqm5-9FfppS#kBp@Kx4n}>|g33G}eXX{Dg-x&*7z4tx%q%mDJ0$o^Z z%lq+UJ{$b92Vc3eyH=kgfvp<(?Dpu$o>X!0x5Ha%Jz?zQ#+&#sCfmf6;`fu(+kRBE z73(m=!5jYGnxTROjuh%6kVv2lMRNSjTbLesA87fHN+%HFH#{LO;l$@<@E_f4!1iA`G9y8uHD=y|2qSa0~^9&Uv zaPF6!y|X9*KM@qpeUp3(LIPb`{jM9qUrLBN*=T(f&OAc}37p9#bHXR$^Aa<{`S1b> z84~F7+5OCz@JA`(m5OqyIP(k@ByjGRBlN<@c-*)pS35bq84~FFTFlEl6H-QO@uGQs zIP(k@Byc8|tes(n0ut!LwFmmlGgOekxnHs#?B-zJRUQ2A1fg111~W1EH6poYG}%Np z>Xhu`oZ;GPSzHI(CvfbZRsGV4YDQQ2v>z?|8@oNH7f*k;I70;qT;b{n9Tl^Xh0N&1 zFLf%b5$LM?E~~S`u=FDN9qK{GzqX!L&l1769LvX0K>}B}IzoS`vySBqh~TM35sg4s z_&*DrN5^IqeIBQ5`dF3i@%oyS2UQT*OU&GuPDhFOhe zjEY|uvtmUec>i7Xv^);FFzXa|J_?Eb7k)LKrp+nFuc{$qgpb+CE`RIBb2qH5<)hGr z*|WIwYDjz?v(MQ0-e1oB2$V5qC)>kb9P7ew$+1`57rHPD7P^ zmod(z*w1Qp>CBrYtght;(S_N}xbvJyRO<1~sME2q{IU^cUt9nA7b~8$6Zd;xRm*dt z3$wCu=WCIenJle&u5C$CCne3SX&iisEzQ@S*Pa}tg1m7ZjYxR-=^JnDoEg%gCjIso*^v3 z?%updL?pu_NpNn2k=x-X?%e4ikk&^gP(cF69P~3s0$p(*6=p3lABjh+XDv}d;_NT; zjn)e?i)+hT%d4C7%0QNTes7-kdOz*V(S_$E>+=_rS+9pZ`O79f7%E64ow~@#{UNgm zE=DnMgarw7;n;~>h23B>yL7!LKQ+E5Lj?&O3DM63V<3%JS|3luks=(?!I46J+y@mT zaNJKH#lcZPbm8cZJ_3mf5*SaeyZcg~1#FGv$5V{fMj&yd8Am_k9v4Ld$E@|SaNHNV za1=N0@m(Zv>|M?_ESi)}z2o3NubQNd@1hGwqxDf|98bi%iQ~!o=pZUc;GNY=AAAR~ z?812tanFE20!MCTZem1Pw)BCVrFVRYHUk1(IA24b`+*7)IEzG%k!>x_*8b_>^-DxC zbm389St(b=mkDGQ8ujH(8}(s03kB;doH?S;#X$uLth@C7Abz0a+l6oGScoBkF8qeA z{%u@Tkof({C}ZWTT%vq3nh&?8#c{UzcqiWGbwP#%y6_ve`nPdWL1IJv#YSl30FhxC z&Fia}5>%g2cnmkBs&Ai;4w>X-^N7+i3I!8nHzVO6&ccb$ryz`ykKUoR($TE zJPZkR;Wun$=>y-!MFoj?C;iQ~X9Go=S+p*7%F#D$)Y%q1e)~KO33TB%Z1r#BqJqS! z>}AY}skpeehQ7&hpw&nAW=eD3UHA=K{oA;x zAW{EnxS8(cPonAHv}$YUl!ScH=q7yQr7R2ybm13i9ii6>CFBX@*GPh{W@D%zf!~*P z8;64uSu3fvu|6F4!TIet2846#USHAwVs`^5;! zR!l6&nn}jUmGc@abhsT4kSze*7rJmQP~5A8koeXhrMWLrDbX}_DjB25(OWEYx3;|3 zeOZO>wVwLc*_Nc5_#%a$@S0gfd3+g7?{ubZxlzPbIX~PUyn5S#hu0LSj|! zf@aL%K#}3xTUj!^O#YO`UoUHeu|>62Tj;_yW^u1RLn3#PvgWY2L2@M$t?o~{_CL1& zr3%NP}szh`Y9H|J+77SLAFp$k{=$##3S zcdS#=7W`t3LfYCsByc67{)-4$8er+8k5l8?B^(RIQ6pTHq>t~Sf`mS{gsTT|CNYiy z;kp2Qb~GwT;CPTe27qG=IExv_1N6Dhs31{(!cL=eksKn$jr#Iw$1wmT(1qgxa{krL zg)C*F2;QP(M}`U#$G19-67zG2D&Z6Z=Vc&)E`6L~effp#;@2L$f2+<66(n%}gq*WI zd?FjWt0&L;xvw_M0>=Zer?2-|u+M?{ujfzCJ9`eyB<^3OxgVI1LInxTY{~kgU^Gj% zt{XobU4S8hu9NZ77^xP@Zvx(^B4gmUSW!Vj&v~tzbc9_<(}m~EpNk=ZF8t!E{`((T z_u<=xzYC(*=cpi|zk|3&5pxCjKH};_J^z6U68LWFtAuc-J-&~){zqRufC>`$Zt71v zzC}1^7oU86EdVM=;Ot*HhaR4GB+!LVzCNoM6(n#Lvp#PL33Tai6wZ!D1qprLQe01B zy7tA5{VTG`UP@(wZ-L&UM+FJ&tH=FDp$p$;M`*7{hgj{BU3lXLc^SGe2KLqUF#uGM zX#Av$QU0R*R&jUAc{Tlbf~{H8i6{FOz>q)}_SN+<0926ZQEi5ir+~k>CBF(K=aDTx z#{vp=d^Ab~j}^ez06lh6K8>uda^) zpn^pCURR9ztg_@Adxr!2cvo265`z#%6aV? zA-}oITl45uIT#Y?!oIpb27n3@&B~@Quazq!w!NfTNE2uL#~$2m$&ItfiCQ;>tg_@AmL+FG6SMR#PF2|Wei6iFFwhq8Lu!PJ3|6p*jLxb z08l}q*V7v2qH0w|R|kFN|M}ebyxo?jyj9k$3<-2$UtJ#qKn00iL5<9d|JIOe_5YAD z`ae&|Tefb(@14oSkU$sq)%7s|RFHVIsjYcrMs2ZdD*c*ARM8~-ci+am!Ga7733TaW z0Ig3X=9$Vj<~iqQVyGa2zZj#JiCC&(`yuk%PsWkx9HR1Z`mO@x5*Etyy=)$kG>pgmGmtczne@jgNl`$mHg*|V*N3SXH8)f)gV*0O)A%QOJdFwrT zRFJ^m64QTW3<-2$&s*=&qk;tfmYDu4V@RM2d)|7F9u*|;x5VU13;2~WB+!LDZ@ov4 z3KIBRV*0O)A%QOJdFwrTRFJ^m64QTW3<-2$&s*=&qk;tfmYDu4V@RM2d)|7F9u*|; zx5VUV6#U8<66nI7x89>i1qu8uG5uG@kU*E-qrX$^3oALZ8Q-!wul5ZgB=EPy^m$9z zo4|eoelJD;4hs_K!udt|yd_kS!0*23-;+TCT{yo;pSOex68QZZ{ku3wpbO_0>GPIQ zK?1+SqkrEA33TE7B7NQxDoEh>g!JzeA%QNOU!>1lLInx@E|UJeB_z;=^NaL(OQ;}$ z-*?i#8-)bA^m$8Dc0XdLKeXb#j+NHFk%9z%pG9APj{REfvEsKg^lx$?fi7GpuCG5w z1qu8Hi0nJVw?&XZ7p@bR?L=6AjtUa^Eff74DM+9T*NN-v&rv}FzsaJ1>jepP;i_-> zOMf5EGuFI4|L~wPLj?(aZTNzU+u7E4axL=j;S5(^<4R^+KP>0VEq~LyLN3{+PFUm)n{=fu&)Pc+LjqmckJkI=s30-!)?dc!{DsA#*%@SvpH4hv z@4B_&<*WX`zRo;6iYn{F?ZOfkK@f~6vLz6KATca6wCPG$q7je|ghf6?9Cp+Xo;WST zrqUwLz@VVw4DdV(C`u4#!k}y>B%J~zhzJgd5JgcO5EX=h=qP@W@7%6b)q9&}_(S{2 zId7f2RNcCDPu2b193Vk2K1b`%=d_S`W5~&hoTIm!|Jfeh z;&ZhAd`=6Ax8JKh4qaSYbSc3MbK+f7$}BS9~Y!TQ)v z3khnw$x0Da-$>AlW3WE9(?WvUZo29l33_o1*2i{QNKo5NSA8QvFOI?b*iH)xYP;#G zZzSl&F<2klX(2(SHeL0N1id&0>tj1DBy`m`>Qs}U7e{T$#MRU_^7r3oj9heB`+AvQ z8B_m7S8$<)1l3&hFQn%@)2n;5s2 z6c~>sTbfP-6&R@I5~s%k{TLF|X3@1E=tTtvouD2IEhMPTBCQK82zpV0K_{rkLJJ9M zv*=n7^r8ZTPEe19782BE(X}AxMFj?(pdJe?B&f}zYeCS9dI~y0Jr-I>P@6^9f}j`m z6m)`mEVPiIHjAzWK`$yW=mhmxXdyvu7F`R1Uer_232FnjkHUCVHkW4{Xp_@Ig0Xe26zZce9u?Yk zjdfZ`Ft)ChLVXm*qtd*t6;F#sKxtmrN})aq<0X|RTR*K0n9JT;B~Or=<~=MV7+cp$ zp*{-Z)i>H(Cs$^huYb5)VsseL)abi(ka6Vb(JWd>=%u1o3iVMKuYN@rtLm?&S$t-h z#K@b|#CYW5AfxxoC$nhL2(47qN})aq6>D78sLu{*pzDMrfs?Rtoh|7_V;5Jy!Ab zdqlBP<>;SJYiv~AGT0c`>Z$-OBp6%Q=cMim?`ZBP=n>rlrJipMSGc}&nhj`9<8r8R(w9t zNGkd^>+HjAtlxi`ZGOLdaWJW}g|)LPU_P{eX^^TbIzbBwD#qxjFsLb->mLBI!G-TouGvTb!@IoP#K1?!=Yn~8U(hcK4ug>Ghf?-j^B22 z4?=xMIa)~YJI^cc9LYT)xie-sl=X4FK;f#e@p1GyZ3j#e`aY1AIj7SuE`8Fd)BKaN z7bouxW*4NI8(zw-m@r{a@WmmiW@ctih0nJ&=<~^Xd*8dC?wMT?T)8~O9RKzb zDb*)y?$pi_hoIMWrz?V=J)L6iEm|SOfK{vAwxVU|I?=X!IK|x1vnW;%=Sbm@PyRVI zXQ@a$Q?V`BUUoNrETvdtgx5#3K6j2quN}!df-eP9%$n>CLUcZ0x%HqWt@yp*@6uDu zA*0@nE7c>%_a}@&qQTV4V4b!pX63Lli81Pz58W872fYUW?)~72mMLbd#uY-mKDWM0 z(DLQz4}y0$OEHH|w&F^4rM4n*>fsMvTHXr#yhFlz&}-)Z?n9~Wo7eI-r$1=fe&0Xc z+OmGKE;{Q4_llxLC#v1^O}-7EvBa&p&*xc4yngEew{OCsZ5hv^9v(rjqzxaV&%17H z=Ek5UuhA#&xy0C#+n)Fi>fyy8F}<~DnAV=hlDlh^v)XAZ9*bVlqla*PG<#~jdwtOI z%z(r0b;l!#rgugG#uBeoBwibP*c~Ng2Jm$~HwKSIFZFltZje21fEL5CkO;RsjPWY_ ziKSY9I0U`EoOcLgVru`0J6_Rp@A6MD?y^+rCl+X}>%<^2ZPG!E?W3yy;PyFdNU#29 z58(dsOYcwJdeE{gdq3_`EY&sNCa18^ol@xp@3j{?bVciW77}~Me}p?{!-emo2R(vb zywAr*(TL9%F(SD~dZ=qqX#;*f^XhEpx7g&js)zmea44r?$vcYZ(6}m-mPCY78MH@g zMfhU>>|-eliTO!uVll+!zYz3telO@=CysC|>R5~sz4W4GYahnPpoN6|t|cPbdOhL@ z*GpQY_P46Jw3W1x+g7fH$8`wR>hb+yAFH-M5W_B&PSm!p8-sISmR74r#Az$liW57n z3Od@5PS3hM7*TUXIe(*0*}YQPbHmH(;q!?2dXR8tmj8OUF#5y!F8&Fb#pS2IE;Ewf zY-HX)b-H;lx!gE^sIl25Ec@Fp`O%o$uc=x6H>EPRPKbto>+FBNM{zkVB)E&DyeTWh zrSw$))ZRKlFYewe3dCCqqXRp(^)K#IT+W?0Db@QK>HZs}9wam`t>)E2T%Fds~Yfhqi$?k0PmDVzc%aOJ^F2uQT zx_?9*L9evzGGoClN#>}>m6E{x(!!{(wcmez=i+i&NG!~~COCFXvUz(zX{C^$g+%gK zQ-c0AoupK|mQR=TuuuKo|WNHYDrxSSRe`cCOhg%~)arGI#iPS8u= zPd{fqH}SXku|fS`T8_jD z%a<1O3yr%@&FQt)SQofhvm$%%9(4~{X{Pqw<(^Cb7yJ9qvA@eqUkG2DnVE})poN4! z!u@r6QOD)^va5W?iom6s6%~8;*vF!3i_bURYWZMp?YTSYtEHVBf)*0gn+b<*DHvar zh@cmBbL^4YAy^Og8cQ1vooxH*YKNeO1T{2bgj*^S^rEtdsCk^~p6bM4EAr}MX|G%l z68bfmoP3X44<3tN`q{4Te~C)PQG)R#mzuoG?QH+vjW(s;jUK!=d7( z9o9IdqJ;$YUlg$_EfGO4s?vl*|JgRtjX?{~M8=jc_1=5Ntq0FIs#NlvmVKRfKjjj% zkf7qRtnW5Cmyn>>Z1WN8!bbzl_U1yl8xq*E5@VD-PmFjmytx{^ICGMBAd_bq-@Nx->5*Z1<^3C$7(;s}ne8u3Ge`C*F~(16 zVBYl8G?Vv7nPuEG%b0xYccq>B>`lZXGSv|nakIV~jC-CJsOUEa_f)KZPqFAFj8 z$77`}-$7eBJ&R@1S^s}0;$x7opS(h&`^28?)<1cBlnVChw~8^Q>8iMF zh9X|r-ti4ZFbhC}Eh68s2=V*1|44}^=%rt^EEO#z^wxcN>MX-p@OA1}b+XG@l1ROb z=x?r1Husn0o1K1JWT-klwq%B!SBe-rY}FfzpoPT6Au9qS&NegeC{uf2Drmnl7Z6{FLJCYRNmUgtY5srYGbSF>?M?Y*Ojb~Te@HK*mw50fj_6pF4$ zK~wYcQcXLbx;nm8Bvy_{ub4BWz1eS?()v{~ULKVdi@{^j>-dbSXi;WsbIWqIgMcDV z|9Vp_1}*Fl9?2%0)@8e^-n{+e#-{3L_H1lssjjHVi^jTg=gM)e3FnH^uXCA;Mhm-t zld1?>oa<51m&X{@sz=9of?gbB+*0`zK?@1>+o_XHWc_(jQ6j?e;@!t4P7Ij3MiI2| zxcbQ0Ja>vGn|e$vKW>B+6NW35`{ z+FCmX$9~tYgw(G4MATU#-5w+CG4V3Oa{ewW^uc59>Y(JgEacTJxv}lG^42W9 zQt5=6MLG4DSGNlF@GK-`z0~qDadqFF;m5}$3jBZ_bo3I*Zkx*ErvtTOY#Ypmx*itR%bVxL5t)jEGL7( z*s_1(bARM|yIU#}k_)lCOx)}5-K_PwQ!08%?#1#larNsx>-GmNlE<;UOq|yuv0PEY z7$hWbWOKTNj?&7wXtBoTMt?!&x!utp)qmI>=YFUfP`8tlIG z>9x*yMT_LmF*2}J=N7NTc;#8*32)pz@Je$xhN_2SAtCPvxTBJ+)|Mn=Eb$0>$$JMF z6VG0%bjK1}E-Tq*yNXWYs7~4O)<29|%oqEtq-qFDQqxX*u+kp??^x}Q~@>zy6X2{4H^nN?D5A~LXJ;U&3 z8EQ5us~pmkB&uuYD>mWe)O?Y6FQiI*Cul~7&cQ99uTHE)j*j)eqQqirJe{rze#suA>(b?a>VNGs)uCDy31|HNjN zwe!zdpX0Z8{a;Ra=TbEY-Usbjs}sqyNGoWB)Bmv^j6LJnj5jZdC!7{>iP|6u33bL; z&bgow5n7zzc6QM_lB_yk+f$XwC;yi-(mR&=?UaP8hVg{Ab{|jJw8}@x6J#vLu{zn( zgCwTc#@H3qS5g&Gbyu|KQ6Xqiv~yhh@9Hd7eXfX2Y4g<@KrLZgNQh@_?ZhTjt-q~# sa+7^!c@~~mdJF*~K3`2QMbJV*U)feM5)t%b{p>R_QK@)_GhR6K|13{N#{d8T literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_10_gripper_finger.stl b/lerobot/common/envs/aloha/assets/vx300s_10_gripper_finger.stl new file mode 100644 index 0000000000000000000000000000000000000000..d6df86bef815342723e35f4aac53a0f276877bfb GIT binary patch literal 42884 zcmb`Q37i$hwf`G&-xYU3)F^5c9c2a=oZEA8$+!mh4cx^I4WJ?hm7XX*O`c**Tp*&n z2r7sxgDXtmX$&f$h{nJZRFr2FH&D>1AiQ&`&guHq?Yi$DKc9bp9H+SFeCt$*3G~9SB`#mNap}{M zHyE9d*S|1Z`p)Z>v&SwhYxt~@tI8+dcu`h&&72B{qv(irwo*Gb;zH7Zd2U zpx;H=UVZ0Oo}0Lkh#hV^wDI;Aho}ENWbO;-wd}k8l&3dMyguevTRwPxwy!5omXgTJSv$K}E8I@a3d#@_z zuLyDbPv<^^UccD7Z`OZRd*!|R-mfB_BVrNdV{l~$udI;3nvJ3p=586Evi8)rZ-(@u z+&5=8Eq|!OIn+|Hxoyst^c+!H+`5eNasFSoi{Ci<`L^d;4@}Vu%Zg)iM4x+pT{`H5 zJ>z|59GoT-&&$%6UTf+*a$&jOapz>CU!Bo(Y0vk{mG#fb7Bo&bpGVQOgKjIuAMPE` zUR0N&*Oj;Q%?=!&HQm$q{VHO~FK#bAc+YNe^Rk{P#)U+C(l^_E%kuWWy2cE_tvipK6^-Yl)R z`PT7=+t;V)wP3_4*=9YTZ)*I@;<8W7{&H?<@9#Rrea6QO={ZXgD=WHG5wKs;%9zbQM#+GK1B->tzVv$E$ex+ zXly=j%lPs+Zc2sQwp|miw0slxi6i#t96!DE+0u|L8dBe4?iE9f`)8kQd@483) z_BpqfR^HNJ2=!uO!bbZxb>8!fD&l}6y2aaUeoyJ~`+KB*TtK}1>ulm{+eqnNb3*rc zUg?O^*ne0Jjh8jLyzz0osM}}daUQYhRo&wmCtg^3U;t@&7DtpmJw6+}@V{g3E2F5} zrTfRLH~O}5z#6Ne@v_FzlLyATL`%v(ap8yq;`=9TU&=1)k@^-#e16jL*~^n}5{-lZ z(u3-|vGJS@dYZD*cv)ks;qNq7?)$IwByHngwRNuXvPOr;E~xA@ z`YWw-A?6&_Js#Hi!nT+1%j-PXP(s>U#pYw?-n+(serHVEtS797da;I%;XbkMUc1L* zHoLp6`@DK>yAl@=wojDLZ`;3fJfY8XZCfp~cdf>Ya|XH7gt(`-Nc22j4Prs;mVG2Tf@KF zR^Q){q8H9&eIgpVPQ1rME82#v$;T)Y7ZNf)ibm7!-;_qpT{q3%sZY@h=hr^*@g_@4 z%|q5pC!g1#W3APIdAp4BqS1BL+oj#^?UbH)GHHMp&JBHH?}2kmW5;w#x80;c=L{w; zBxJrK8b|bfx^&6zJEfCes87)g=b}E*bo$e!Yj@iz9rjW__c3uHA@eTLn0wnDrSs43 zmhQH3LyBHFTlR?!-@K!==(cX@QU9pdIh=_L37J2N#+&h}rQ25RlkTv*K1DB_!}~XC<~9q#&tj?QM4ifcokxMuA`8W(K8PI|@JXX*^V#D#>+K15^Uo=uH2cJ7is zo*tE=7p^mXLS{=T&z8`Fgv_EuLsr{nM9^6VuLm^@>*yxC+Wu+N^-G_>ctd>0W1qc% zUN{euHMJ13+K%7a?5%^*f`rc0tj6(=?b&$gtHU`}Nyv+5eLf-UT9Xf*vGV#=!#u0e z)LM<{c0Cy1aNFNo(FQVfK3P zp3r;6wi0$1f___qM|$;wmMAevK2jp-vU>oKcG*>Ndjoksm`EhO#!JIGBiG#o6EQoR zvcgr7hB@tef7sn9b{B$v+jSIrVHgSGsJssN!=UW=1vi^HT-TLJ_P{=^COmr7pzO*C zPwr*sKJ03Lk`%opTw<>RK>%M#iWVe9+tAjR-I+kIz5bqLM~uEDW{n_WG|+;?Zs!il zzUs8Lp?wYXdghiSyXfxsjaQH`8fZac`F4Y{*Sa4b&_J(;Iwe`JAGdGfd;|%jffgjL zd3Inn;HM;@fnF27zcCxTptsQo5=H|pNX$8SVD`qj4+J#OYljgxWcyxysnG}$MguKK z3>){GY~H6Y1T@fV`J2PCbsxROXaotPffgj{zrQkD-23f-26~VO7%{l~@EWM3WpjL`@Z zMguKK>@|Eq)_KZ$h9*aQC43K}*Q=im&i*`Os__aE#3dZ%+BBenUPl}^ zFng%;-;7s~FdAq<;cDxiU0^X|DK+x8c;j8~8_8fZac)a{pMqyDsQKm)zT z&ABXF_{tl`D@Yg(v>>s`h)c4s&au4&Iod1X(nT-r=eaKl62v8`Z*eZuR-za zSm?ZPzpOwIz*mx@1&NCX_xH;xVRt6b3-`+k1Oa>{DO!-Y<;sivI#1Z03G~99v;si@ zUrCA;a3{S$5WrWGq6LY0$p!vBn6Nt&=q2kj)2<2x0emGXT9A1A z{`395Bw=?Z&xV6PuQIa z^unF=0zm*@Ns1OEMx1r7KSm|&&IEelPI`eLfUhJ)3leoR&hf|Egx#4yFWgBl5Crg* zq-a6n_eY)M&lwVSX9B%&=e9r)z*mx@1&K}Qshl_WN!XnU^unFn0zm*@)L%hdNGy2p zY<~`yu)EQK9bw$LEf56om857vV$RiP^E}wiMH6;s0=;nOwm=ZTSCXOyiT?f1&ej~Y ze|PS+tuMPXfnKXmjMT=fK;#-|K|*F90S)xR9ohnsYoG-QnMDOO&5veGkNwF$H!A*?Q;>&`Wj@j7Dt&El9|&NI(O%DSy<}&~Xw)Xqf`sh01vJo0cG!$YZ2~Pw$gW{P1HELY&}h^q z(1L{Qeg-tqOLjbsS8W0H9PK zO*?bv4JYCZnZrjO(y$jr*Bj^aj^Jd4yo$uMvDc?(Ji2=uCk^A$FcY{gp>utXNJ3sk zV)eu!>1Hc$H5wR~hMBGC;}o0c@>Fwx}TpO z`SwzyfpKY=30&{e2~$TTA+I8F#p09FZzpVKp5tI#8fF65?NJ0o67nh%n|3)Y-SMT} zjRwZ0VJ2|@A&P)VLS9AU!;S0Gbr&3LG%zj=GlBakQ3OO1@+uOGzt|xiGy52$fpKY= z3EU5gA|R5GSCQzrvSV6z)>%dav3Kbg!Fu(5hBnF!&XCjYNLU1X_yJ=!9^oPpcjU%hKx8y z1LM*#6EYHsMu`_=!IdcA#(;pU|bqzLS_b{5hBnF z!&XD)K1KuM(l8S;!x4=TfnFH48Zw778W@*`nUI;9XoLv#!m!nlxv0^=xHQa!%s53O zM4%Ujtps0w;v*ycl4kVXUJ z(l8UUvJ?#CyO4w+q7prTS30WaaUjl@#YmJ6_6$x3<8x8eh4Gl9PD}B)b zLf7XhdSTd>mF!Fy4U9{}OvsLfXaJ%63`Rq}iiGU27!CDebqzBiJ1?REgzlFZ4fQG# zvQuO<)QdGV%!KS9i3Sk5?_)I7t4PR>7mw$Wda;IvnUI|@(EvjCuZ)Iz6$#n7GaBl} z8X9IocJxF82;GM>8tPRfWCzk{s26K!mz^a9M>;Hx`IU3AP}iVM|<1Yp4ThEyWsYVU5r! z%>ofA!4@PmY>7Y8TJUOG;jxBVSR-`Wv_M2kumuSXTcSJdQ7@#mEo-QSHA1Im3q+&@ zTaeJOCDxs|S$aOL(OE++tPwi>TOcAO*n)(HEm2Q<3_s9b18b;-HA1JD3q+&@TaeJO zC1%iG$!@e~!WwE}jnHZA0ud>}79=!miSe}OGoSW;SVJwW5js^~AR;B$f`o=G@h$CL zT||3Wtf3ax2%U~E5RnpWK|;fp_=xtX$IxCJYp8`aLZ|!-M5F{;kkGItuA)8a{b)~- zHPpfyp|=$ZM5F{;kkGItUZFkeHrg9y4YjaF=&g$a5h=kIBs6S^`Lsv9?tu5qu7O%u zBlPx2fryk~3lbW(#Hvq*r{gQ{9ZLC#(4t}1i=r0#_JZcUEb--&3nQ6IfQ5Cwe&?OQ(l*I&Xei|2?q5Wfus%` z5v;+42~4j)0w9g4LNC8RuObNI%hrdc9SOguw%#`9Xz}~nDvg8%SOdNMp0kQj8PiHM zRY>@KqPnvNTKrzEN`q2lQ-xlBA5}%DjF&1T{N6|1IaO%!`;RJ(JXPqWy~MxY+I_#O22Lnzycixa;PG;tt&;aYY7x$>Idfqy*~iChSK4H^8%$X_ zOH1}$zo*L=p7|5STSY{UK#NZ}nl*m^@}r)?5V4bhWniB!x7Dp z5}$B1Yy7G6lcl#t4m29h(vpq%@%i$g$!m;;`eBhHRHUDrxdq=9X> z`27s|h?6AUi-e3(<{KTj*LE%c#_?SmcG`2S83)k|zd^z$I3M=1y{N{81b*j;dh_pm z#A)JtP`@vsct5hM{mI7d{I>F2|Q!8jk7DkNkq@${)r3HcPtX`8G;7cp)n-RE^fF^fyB*ccnCJ)|)r3HcPtX`8 zG;6%n`N_6fW>iD3=IrJlpKrILni&%v5jg@aKH+HAxVYQv_q*GUgIqZ)cOXQ%y;w%bw7jG~T+9Dx>}a5QVs7?s*l4ZWJPZT6Vn zZb!8i(BphK0xdq_=t~Y-^U^abho^s?yTR1DudbyXx}>t>ZROr??P|mP{nY$9exr31 zt)kt#x%cn?B6{(d$aI)kXX7v1R({G)0)`r|N#@(JhvxD68kfA-cp$|^eHC9WUJdhi zZu4#j+|B1j;dU$rQpuq(FcoGaxo)t6_7GMqZ!t-zi!b()73JE;1XPha1zT7v^&_D9CV;nAMB<#)vo&>{_ zX9a=)zWlO60!u_a4MP7j^Y$kFn>Z9plm2xbT7SsrHf~N8|5yUO>|fEL@4e57Q(tIr zd-nF`^rb^=21rdLpSLhr?s`ebX?%%kwrR0@NMXeHt?BGBvT zGY>Sx#r>bEB7Q@}WFjULfpH=6*X?>6jf?v~M;d%BTe~6sZtaE`ElAM&F+Pzf;d|BP zsq%@xwT^B5hBQ`?hHvqSDB82VfB*S5RS6T{8UnpItX_vgc%Uua_)%9@WiC-EX$n8t zTT)x*a*Lw#i1@GDo8uL(K8zQaTNKSNpGI}y6A2Mhh!{fzT9Du}WZIRkv=l05UeV1j zzdrkLQXe4UJ`~o^IZRjL2xN)rfqHBb2r| zKd1RxPEoY+bvM&IhjX})a_;9A>n4hrc=Yb?pWQ4cxUBk^7OwT-6U*M+*R^`_2?`x=&`#H33_20D-aB^29YkV5Mf*Ua=M$yJEGr24ak04^FgZhVZ*jna_?h5 z7b3C5P$AfBsOb%~9Ty1E7@BpA7RBmi!&v_uldmyA2=>BOsrLsHawRtRhXR2u5o4+* zw1xW`{}5ER6? zkkGK)=R5<5?F_(-^pf7{eCSwva^vy!jzBLCuaHsS_7biJxp%WY99kUVk9L%J)4N&1 zd11d>O_*|GkS?qb%#;0G+pdy>`L&y@P-zw93K6U8-a zmbbq#yC+$=Us>L6XW@K)_j&3o`SWQ+u*g$}KriXgG^c4E)Ev z<=IAqQ$-q)rpnGNSe;WixolIy{rrmZDDwp3AtI7BO;cv&`B1Nx%*Bhu%S3#=!*TVG zNtz0<+nt8ciH)a4bPsvGnF9{wx(8;KQk7tHEz4M{yDs$njo#Bm#qU^x&?yd z(1LYPBUPkY>|L!B=VHZ ztY5Jq} zN7V1?+JO7u!+T5HmCr3<`*s;EX%_aBxBKA}%lp1;PB~pTcM6?E!oJa+M*d2M{l={}t`_-bP~5#BN5zrVcGd!sf5verHT!jX$k>8U1!%e%ftJ zmY}#3ChTu>pPQUxDaabml~qolm#<-Cs;yD1154Px5>w^J>++b4(o+W%Q9m6q&)dY`4I?8ZgVn^fv0cEA?e&1d@=We#GrOUH$e@?Bf(B=cz z{Tg&R^mASy zat&wk2}+Cn4S7ga;%d#7sLQR%Q;{$^cX1U;p+-J1UROR=!^=76!=#Eev<{GPW%wiQ z+0k z>^n+cnAa=D*@TS9O*#Xh{F!-Ik>K2_7l&bfU7IM3=Q@|LbA~{w3?cKxifVA_>MTR& zJzO6+d$nPm?{#0tavzS!n1h*JnLFO&drV zi1q@Ju!f7PE+e9>MD2W_*C~CLmAhQF-OtDe60T;UtV}*!YpBb}t6l5guT`(xbRUj#?rFF?3g3L;e8BkO<%3pV@_q!Kb+@UqB~q=S zZ_#m{+?n|tKvn^dD@U%LvKk)21o)HgdBv!=ta;L}tF9K6lO@wO@z1-<>tKkt| z&aDN{h~rsqDczi~HD$}ny$y!%u2mCm%)k|WAXQve^y7QEeb@kzr^>ZarnU9i`^L*T zXgDvoM;ahJ4ZR2b`%zmc8_2(Dmmn(9c&BuFqf% zw>#|S4?-lICRTUv*WtT;m_i^DCfqxG_>N+LFbYgys@z+K`Zv}zf*TX=RR<9UF{HL$fK;aYxmoxAx?3(T(q z8hNVR{Hi5$v$FsZOcfHY2ZtIYs)g4BGV?YXGSkQU2ZB=Od%4+UfXGvYcN7wCUJ4o} zRnF1^Gvt5FB_8*ng;^RUbx;-&1PO|?>qOm*V#++z*@eS8xsQrqjWW! zT?0*t>j#_Vo|j%Uw%(TD5>>*@`teOPNR`oW-`0VDAKtxR&GGvAaDNlNIa|_mL}hX7 zGTOrk5RB4=7N6+w*aelHMt?=LXmEfoTUNG}U~SqI>YLtvsyOFJXeqe-Rckm4)-%38 zTAgz&T{lAx5H=f>k1lU~953qjnJJ$M8|~ZFdCxDxWt9*@Kg}6>4f)%kru|M`8YXfL z%7?ty-kenveMheFOV?<)u@>LL$M#m8b2kHMhWSGcf>MSSpK$vRpkWC2hNS=Ar7LwH zOg`M|&VL)UKv4XA`StA92Kc_JXs~<21l6<5?#$b{`FC0HK7-dYkT+i#m;bJ9Ayo;v z(~s}vR$G`_NR`oWary5IyH;6ExOoEJMS;E~PZi!D*v8ykJFLO|l7G(!%gW>&<8?D~ zY(3Q)E-wH3AY45GVKm%a-IR3xO(8BOA@ZEN8689rbzmKF?EyUVAT|nZEn_k}yH>^X1n86017(PN&cR)b$LB0f=yx=4`9s?=)8K zWG{>f@Vue7P*dxQIUdmm`u?nX|WOH>o+g<-yLY)qEWRir=S zFroVajwXUrBs)1cp5uBMcc~;*3=+ljD4jFloJ#LOUMI+vIAW~K?r~QYiAfV5Ze1&C zrZWJnffk=|d73b>TLbBc272K<2=iyXUzO7XXh8x?;gGI}QHq>~Eq7fz=}sCF=oRJqasNM3#8d~QX=6JC!kXu6kF+smWUIBufl|q8Unp@RiTCT+ERD0DR$lGX8 zyTT_`Sklej6D;<2gsVZU%_<_Q+`e0U-HwMF4Yx0fdeual6F9TLeGMcUKEL*9N1zw( z&mcj0fK;Ic34D6;KeKwaoqQ@GJK#Nbf z6*6mdy!`xl>E~Y=4QIipOJ*NV^jO0YXz>ZRre=+=4?j76etZ54kLZO@vv94>8je7V zPq>vgYwSDmu(Yg@JK_J>C`T$AI|EPsaV6S(@tu$wt^{M7rT+WR;!e9mR=|8||}`vmThxiAtp9C6j; zmq_CV)5D>~^d<5v&0n8K$y6eS83MiV*%T5(K0m*ndY{zxKHRtK=|3I;+_NdV&*eGy z#4R>xpx!67y^sGqn+dz)i7`=GaqpAb-UltFmymcdCMKvaNp0_gUgn;cXXdpDwD^SE zlVc6)OH$kWpcn2AnqEotd;%>#L4AxoyJdp!OCa5n- zZSR9#=AO@=hSwtSIj~RQPO9lkQrr8W7w*=YUP<&gRn+?kffk=|JGV?wUy|D12fc82 z7@zj~1X_H;?Lad@eMxG2AN0a|#ea&71X_H;-NCFuokMJY>j^`9D$JcDta^(s5rTdz z!DkZjEto0-G|+;C|K*P|U?~RJ-d!tlC&eqxU z+nhp)NlpkdvAWm6arf3bBK)(1ddANu+WyjmQx$Wnm{2b}JF}<%d;(MDTX+_x=LJov u7f%8vT+i-26uu?qzfG>IM;@zuFMBG`wix%;9w}4$^}@LPch}rG(*Fe~xB)Z( literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_11_ar_tag.stl b/lerobot/common/envs/aloha/assets/vx300s_11_ar_tag.stl new file mode 100644 index 0000000000000000000000000000000000000000..193014b60c1cc7547a828d8549304acb1729ac8d GIT binary patch literal 3884 zcmb7{O==Wj5Qh5%uH0u35!?i$B4lBPQP52wqG1l<4a803(i`Yf#8uoF20?}yTM+aL zdIOIjh}K*6*7v>r6Qd22sqU(${<}N#==ku?Y;k;Vw!eF0_uB5>^_zRMyGMsd4{x8I zp8lTw_i@~0O{|MmSmS&g z1Aami--C!mXHLB_gQ?b$GS3s(zpByj$G*@?nBd4YP8qqX+L7_>AjNjS}z= zZ)1X4b&+OoHg*l?XY^`BSd7kMoI|LUW!vF1j-eX(1Qi*2*ZV} zXp~^DoE~ms-B-0@r>6)w^5vPY)RbOhwPLufgY;)QAw7vTL(iPqZ z-OCqWKj!=?BU}5_nYUY#N;A}ib%@NY9Og!o;ETxLEd;DPa!upL0JnAL$~k(bdhxhpgb5|>s*(*G?Idg1! z5|(?>SUmTuMAU)%4|9iKB~pf!%?9s}I*&<0tx|?p-;yn+h%?osj2Kn}-fDHPCJD7l zIbvAVTg)A2s!16!th3ey%$;{sAyhL(M6d8%kLNo)gfH>iiOd*N1X$8aSZ0zHo>y&J zL6b6KFvAH#HB&^?Ve>|Jx8}4}B4t={HlAUbAc*X)M^~$qVdL))Y>CHEP0EPD9b*h` zqQ^)p_)@EsBL=tKW2h!&#Ng($S4r4Yw7i{%F_MU0K^sTA?fdolbAo<%v5vII?A4df z!{h}vaU5en6e|)FF*K{}TU1^%?ENQWSyhb^I{)5(`XDqD>*h&TZr9h-brg-pqg;tL zyNiCLFSTMvD!~Sq?z%<^)^QG@R_wwAp&E9Y@#+(`^vY`SE%DzOn1Rv$3nJ!G>l@Ca zYLu`H{ny0gmXuzp75axh7NT^QR-I(!G6|Q5S-GzfVO>Cd=MZYe$yTCdr5euJt@>I0 E0ev|q5C8xG literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_1_base.stl b/lerobot/common/envs/aloha/assets/vx300s_1_base.stl new file mode 100644 index 0000000000000000000000000000000000000000..5a7efda2fe330aeadad63ee4ce29e996ebdf2195 GIT binary patch literal 99984 zcmb5X2b2^=_dZNiGE0)2b54?Xx^|k>WCR2R0f~}xTEYURmn5L%B#JCc5Csu^f!(Q{ z77$dDikLt|T2T=Y1(Zeo-&Z`B*TjBrzf2SVKlI8atO$7auD-O=z_Up|H;nef1%`92s z!mZ|1Fke~!rurQFdtcMBJVX}y4<(3*eP%@Q;+;g@&r3_Wwn+T=VU^6(^KYr|?YXwH z*`VV-`g}joo?~q;IaE~Xel3!%YrDg-?}`f}BKA$(M&pv5#7E~#OMWUupjPbfj2QUr zSW*1O`w>ROw6G2Qd_U}1kDs0^cI?Qh5cnjq&vD@_S*lR~-d6ql-w4!-ededaHc%34 zqpunJ%uj{=KuPR#Uo+M}ZX-*U`6452Zv*Q1{8$_AvtJz3uru^aCj)iP3&V_I?HSR446NB2>hS0A1)EpClnksQ;yA3*TD z`gL(*)xQ{mo=VLtueYcb`^-<}wZRCK#M*P;p!ZF&eh^@OObegNoh9z5a~pcq3P!}* z;B{VU%S0-U|1x#h~n4Nmk~F^#TxS{Ai{mBm;@2A&)jpbjrWU3 zUdQi3t=Qk=05RlEV;f2k5&OIq5cwxJOUWFu72XZE;f-!1r$I{WyMk{pHinG&m}W^M zTDdC*4x*>>W(m$K{LF}E<=J!#O z&W;+V=Bl}Sf99>IJ743%*GBvib?5O``W$PIR@Af4MSf~GL&UENRYge<;i35r{#j^4 zWFYONJa;ok+z-dv=BFw{XP`HCQ4(w8K0G1MT@P{O+TyC2BWjy5G`De*PG)`|Z*RLm z{qUZ*FKE>^ix#{Sb$1Cw@aUo>hQ>Cy=dm^hRLLB1KOFlzzjF`KEcu(ND2cU!J?FU# zh~&%>{06=LaU0%P?eDcD86~mLTj6~$;ys!ryv}pqZdExry57v-aq~Vi;tttw?!G%8 zdL9>!pHtNK_V(D*^5}Yq&kx=LL|+pTvCoWP8?_-|SN=DG ztQTJ^_L-l`YophUN2{SE)`qeG{85PY<7)jH)nZ!r*{0T7%F6IZLD`A&_qJ=RbI)UK zxX=E*wsB*B=cl3_G!ulf6KzDepBXXyQZ^CY@KIAWOqMhC;AdZ#J-8!$aQ9}?6T6e+xdCDCqb>)-x;y-xv{d`Pwz*L z-%hC-)5531&-~86rg?Rfe4J6^R#e3&iG6n0isw_s5InXqEq8`{T09fo&-_$g8;n3n z4Bgj^eded~`te{JF|EF4tbg2wUgye>inS3JzJBvU)bkBve@DdK!PTmu1QD^%jJQ{S zK?={5cMiXoFD8i#$Gk~w4-wpt7^1IgyY@!h#ln z*829B2bHcA2*ty$7;U!&hg~Lvkyna zvBJxSZeQ3ZH|=o2u|fo%U1V7vTvIK@v9>*kKrMP&y~jNG22t`LBK8I!=(#=t@N|Cg zjQZb**hv;UyB>Th9IKdJ()R(24BNo(!t;as7wE@)LeanZ0(TkQeQ-qn&n)pr5fQk@ z{BHzm;XDo^aQ;v~bTrD1Yq(LI2gi!FJg=J3u8o3`kOvXeLw|K50)6V>Qy~JiaQ)NV z?e}VxXEwg9);abNXLxXQJJ!EY=U$a_wfTL--Z}dpF>A7Fxh(bz)7vVa+OZODd|7hl z(Q-8yff7W-b_}*f`F&@GKrQ+vGuFoZ+26czbmnL3sZfH5*sjfOlxnu7=DGm`YU!u) zzYDcudp;wEt^TLZ;QVWLGXf>CT{|v}Z97)=LNaDRke#~ujrYCwL_EbIswPNQLBXZ=;zU%tP>1rm%&OWv7Y;PV15i}F) zdovLwG+%uLk1UUhJ61Hh`%dW5MFeUEdtP!=#hnZ0wNpDK2?2cOWfa_`K)<3N*U z-m3MVB#7{=CGPq2|1N(Wb_O32JIUNOVte8<;>~IUW4n*-NrDK^F5x!PQ-7~DepsB^ z;dp!y;rZmWOK7i{5!pB7+I3kjP`fBfXqWJ#6!=Y)|47)n`)-Me-cIeefe0RTFLvTs zVo|~B-f4i}g<5z9JJ#1D>sN;p$3M3b5wkM6A61h-tOlnVATo;-F(UHSKX0sV>Yki2 zs~BUJ>g4pliTv~K2X>CQ(9b)aeM!u+jC&yBMSJ2t*c0KMe{6gEAkIpfSDPQ(=k19o zp`Fu5=+Aohp*?Y*wN$z zo_y0@k~U=a{*)$%CYc3($PpefVzcRe&XQ#vJ)qYh^yAt9!b7vxuHQ$Sb#^|h z+wc&fo*Sy6Br}BDM)u~DWS?ofjXK%?2_QT)Ywi7bkU4dXt=sSr)vDgFj*`p}ZX1(3 z50%L;{$liv{18BRXx5rKtGl^++26Vi5Ak)We$`Qu8NzMjW|hZekJpNbv-=hX5FVPf za1}HmQ|EFR<{!?`c4QSJTz9so8VNR)_nE zYq@?8AUrf{WqtNi_`iwi+nO4B@tMveM#+Trgdv-^vw0cxcu-@N&EGGtPM3hKERKowo)`GDEm+ zw4IPQvTpNS(W3pe>WJ_@v(~aE&nFBSKSj6UA#SF;UL7TwA>20fi6iR2mKH#GXx&D7 ztc?c{z9ch*-w%WP@o}E5+y)}lXV#)8jK;=_`k@eiPyK{@?n^v0BHT7;bPawVwFZ12 zKzL}@qLGfq-noa+Z_t-yhH%@USz_?K(zC=zc;CxfG-IN%x$7ZDq*thclFSfp8#LPm zua7&gWeFfWG;7h!w_|J2L;Rj|E3YVDk{QBngI2BJb)K)}$^gPcvlgvjJGPg22wvwX z$qeDPLA#Ie_A5kqpIM7`B0IJxdWhZQ7w`_}OEN>aZO|?%c;7AkZodG+L$em`sCH~` z_YfI*r}IwjOEN>aZO~~T`24u^^^9tW@IJE^oeXyDjPelAKR$v_9AANY&YlV(~nN-{&ZZRnX8dGXzrDTwesvzDHfx(yGJAzw~LNoEMQ4ZWh|)PW)e5#DFk z(yPn#Z698>l5C$8lw^i*+t53MB-D^AZfe4gjhH%@^JGG>pIt3BlXV%iYwr;~i&}py(C7B`IHuQ-j>BI>jJTz#;Jem~fTlPy2W!fhZzeP%6sLbelQ z{ZI(9`nc!5#6u&(ZG%RaZBa><W`sDN_nIYUZbY#LioqdG& zy{ttiwI8dYS_3!w5ovm8Qy_|y8NzL&;j4q>%%is>n?lK`#(eB$fuYK}~jf7~jp}TylKvCJbPlXUl5HaXNd%J4gID1#( zYC@FT(nV(dx40a6xor>uS`!+yv(pb2vc=`~ggCj~l0&walcfq(384hPx6{h7ef?x{ ziYIc6YTrLIT`;mdn)O+3$foSOLMTDR zcN50jt4mIfR#s8Ye{;`}Z^l0x`L_Si00Ol}mz-etIxs2P>mtwgwDF1Zc*#MLLwTPL zp#%{NJ5IEZ${x{O&-2_}*nF0}U9xAS&vT&w0<}7BoMf-d(I$HTGk$}0y3UsGlx`K- zxN2YsC5Tw@?Iio@#KzGnPw{LoetwS3Uc7W<&Fabl1Zo|sH^uHTzG$@Xk34tJ?V2NB z`J-$kGPh*_fm;2anPOk6T0GjfDX))k(Ih!_(a&j4QvDE05RtdVRJ%{bYw7N6-~DQm z%$Is9Ep+U?ctoI9+_9mz1X_a#C2_d4*t*Q3M|Gk`Edi6^tw(VHEUYaZWckGw;^RcW3N)YkNkZE?8KW?Y* zesVeWeEF)mGBNL)X{{D~6X-c=ja)s&{{6dV(Vt#_i4fOH&z679$w+&7L8(9+sD*FV zu?k;Hlq>Jlj^r+x&p-(xIweiCzk56}x@ybI)W(}lX3G8_wTgUKxLN>#S~x=;tHHXd za^2GDk(-~@Gf;vETsMxjpzTySu=0XPk@Hmy)JpzqjNRni=IEuIE6pHc>5Jp#ju$sY zvgWr8lpq4vKdq>S)-_OTK#mc1*M*Vjk7ZYyK}4BfM@aL+`;q!@b~aFg z2;9f04q(|Z`O?{QksX)n7^s!FYoOhz{Ke?y94pNrqF#}Ka#59^BgXTVff7XE?n-y! z68p)H1OJJXoL$jCt!TO4_7`_EqVH^dIe6|`i)Bwa`r%x%`|wrbF4LITFdUEE6d4; z_J&XkPqiRoXRmp3`k|$1pSOB1{%FE9yG6qK^d$+a%$v2Q*#pb$NzdQsWiz-llze@j z{NZ@BwEio8jzFK{k>&cbE%RIg7=l0_3Yr9Sug z#Q*}ea3^xCg1P3&7ur0L_Vc}^A?)p>&eQBQ1*7S^#;-83J?eSMc{2V~hxl%LcZN`c z2yD->)^DFD?YfVJX7p<0y^jQV9|`YkZq=NVWs;q$D#CpKL;PyXjvlThNrH9{!S zPpA-Yo}FgTePTdDqu06T(>|LgJ2d_>e#?cA;}L;cMJrCXE4;8y^b;=<;^VtX@}pH> zwkp=-y%0(e@$%T|_UUGiCmipvgb?d#tiCJ#R;%>M`vM5mD)`oP`@Lf3zO+Xd6Jp-n zc`|uwme8zPPkE!Oo?VYs0*@}X=UDS^CCTP*Y>6+}=s*Z1h`{z7tF4_R3tg!b|BQJ& zgj)I?B=F1#A|~BVlKTpbYx&x9{|)p5pM7=B>Grc{bIVXk9;-LA&Xebt?>JoexBVfM zAVRm1?v9m_cb+_(Ywh9q)q4X7)XJN4y4|~4q4d8~xsB)lNRs`E#iiD}`(6koh?uc| zn%yWmFMU%jK5LUA^WyRBQ1)Z+)nqXUQ_%o-**(-jA;>H*pLd zEAOZCcBtW#-jugxY8VJ4z1c%6GZ%^C-Vnp zA|h}#lOJWxlV3+xh5Fjdy`4INtvkKfCa`U&-=NxKsEwbKWNNF;q1VcG3!wxNhw@Cb ztL{3MFeWGO?H_$OPkz;@N~m=2>8%ifTDTKA)=b(Np2_+|sDk6~qH3KZ0@o(h4n8_h zX3uCBpFDAk_s-RBfC#-)C%Bg76HAh0#g4n;$2;c&2-LzgPgSgR;><2zFVwTXf8wa| z(Pv2lpU&8xW4$qOuI#sGN~mk4oCZn|f$cfg=yQ; z29Y0C{J=ot$k=fK1Zp+uG|~QGe~<7UzYvnOMJsv8u2cLJ1;{kstNQgrec) zKd>J)t>j!eI;Dv5(B)bolptc&;VJgy@8iO4eqKe0FN=|n^VZeSPnVkp5UBNQ^QpE~ z^IC%IN0m%Zl4o9hKeQ|Eqj;1c0%yKs?I1s@OVxv+W%Vxv5U8as9JSKOW+*yY7ERb{ ztTNYx@U7wd9~~ZU_niN3c)}g_wg+?{EuX)C!Z@{Pdk7_nm~>^JJ$>Mr@G#|VS9@}l z99I8~k@!tw0D)Q!)(^1D-S{HB^doK~cb>s=aF-iKo0{n%lpx~J@SgUmO&Q@r!&Ut1 z>>&B(oI6Hp_oM&&=&AR=GwZuZ`k9Og(h z6OV>^$@jAq6tmBrh(`o!-Hvv&TX)H8UR3`1w=Ex+%NpbtqZYOZw1HY<_jR-{82QYH zTk_mBR(6rYa+eU#HR>2b2_h~vY-d0DULo^@^61}g*I6$3t)!TFs#*YnTC-=jwcqVu z#BB0D&%}qCSaMSN@?!6j<{^|I;`s8gJ@S*{lp*E!@zP&yPd9m@dz`59UhMz^wQ#;U z){1KVPb~0LKbiG~yGGytiU0z&aHSDiNy#4cWPkcP@^Tmv(M63byVOK%f@xV|1!LJykX+x4>w#x1xa(L=>P1 z%bLd$!?j=K_pyKGH2K@zVMdmR8V3-lg{O~WjoOkZ$L_0TBz;xPKnWraQKabKE6u_~ zRHP{Pxvc(5GL&aa(>3ONj7QquIh$wqMLCz{& zL$F8RkpMSU61~H z1xv>DDlgchM+9o&9^+Uwn#apOPt_6Z(W3+rxUV?YBMBk-@H4dpd-Nzl#Pt6p*vS`4 znXX6w&Y)&;^t1+oJ$gi-7Vbojb@)a|zHqpfV2>VqYd&Y#J%*Ms+2_Re9IIpXM)K08 zrh+|slpq4zqgDH#+OkIuL$F6r@4}{cqTUC+3!BUN2BkD9LMwJ)WPJo(>v z!5%$I5b@vKRqPHMnwhRgKeuE9dG75Nf<1afpjMyVwd_AeHZ)z2e(WQS<>zyo2=?ev zf(YZ&D)yP(%}m!z9XPPDOzF}@ut$#w)LJsWo=yKu*Q0+jqn^xoyrp1|9-o~?)~4}N zql@i1R%O{hzIL*iV2>Uph`{#9yKB`*cFf;Yuy==AG%IX+4{Bxv5zEUxDhEw|RIo>n z{lI7cb9H^Y-{Lx^>(S2_O=Rkj#)3V1lpun}$)qwo7|6KU;jB-o=z2_ov`Xhsl4Ez)6YS9=0<~yP*)$*Yyt*@} zmF(H7o?wq2C5XTsgCg76!m?A*8iGA~lpq4v4XyJTE#<&-^#ptLC_x0S70Sv?Y%Ze> z8wmF3QGy5@1zLmon@W1`>YXD3wSsHVYSc{L*w#p}M~^+XZ`HNwpUECQj-g{6pWRF@ z>DoxJM~@Oj;F~3{sMDje{>CPPJ$jTN0_PiXAsufdw`Ff8*rP`YB5*ZRY-vDsS!rij zut(3CN!ojrb;o&4+EtZph_E&ut$#)L~wkZc57`}R%zKl%JgP} zJ$gi-7Or{6I&rp+OluM^*rUhZa;%+B2W9VKdye(n&>Hd(^@Bb7fCLcO9@$qnu12~{ z86w!Dw`v}Vo=h2RvPVCl;Pq(b{C!RK=r6pI5tYMw>e`P#mt>c}hx!Zl=uv`*-yh9t zXV2BcbUpfZS#!(Dkv@VwdPJbs3%hdI(MX&p}0K#P8Y!*JxUNU=Dk98g+}d6*P}mw zp@jUsP#3`-JxUNU;c#I)bi1wTdi1SJmY367S%N)!M4(o}+2Z!z6=Cg1)&HWB>^iQk zV2>UphzQID>%te6<%X4Q1bg&|KrLKpj%986K2mJ)Fu@)@zBPRRrE9+*J@eWS)Ai`X zOHw06N{$ok(W3+rpI=Ie#5oep$UK+N1yM$pVp`o#!f#9ucVZ-=q1XXFs2! zJ^G0wucqxTmZUs-lptbL*=y;gT1?e5aaZ0*THNU*<%VM8ywo6_OF$sJbFZMex5uEwZmcCj@7ky^R(k<<|>aKC5YhsJb5#E z-~BDTH*I?IT;;z+c8wh^Z5(Wg#$JJRU&(SkjC zM4%R~e;TV7&qdzsG)%BZj}k;2EqgIKWA{MQ_2~cYc{x%pevn{~9ucU8`Uph?sUb zuf11xHeHYY{N6(HWQT5oJ$gi-7M>*(%eYonepR8JV2>Uph`^J?5bV(h zPI|Ba5KX*;e^!<6JQo)1(FY`e2)0q_NEJEe15>a^kG2S&I6(yG=P6IGJbKR0Q=Ub6 zker{V+=}ubgF6G~=P6IGJbIKMg7fo~lhz(R=jSO;uRMB0pcd{iWW7>;p7Qj{qelrM za9?pO&d*bxUU~E=K?LXLDKn!zdd|;No?dzMh(Imei5!db^OUDo9zFJ!^YfHdQa&fP z=UAMd-(7N^^5{{52yD->I6qH$dgam6`$&NIk>I@#&d*aePJ3RQpQk*%^5{`QPv|2! zKTla~?a_07p7Qj{qeld4aekh1gxaI${5<99l}C>fL~wqd@}AmD<@`M5>6J&12-Mo2 z-`q!;YwgizUdl%J1R-B)wJiYSh5rJBqpQpUA z_UJi3PkDOf(W3+roS&!6wf5*aKTmmj<6J&15=7v-aV*ZyQ=VRV^e90Dt`*`)q5M4M>6J&15=7uAI2PyU;hp;{6}5tEkn{7D zr&k_5_WXF)TYD)Zt~`1iL&xI$Jmu+?M~@Oj;G1Vi%+QJmu+? zM~@Oj;A(a(&d*bxUU~Gi?Y+T%F`>49(zkCLxN}TVtbCo`FYCID~}!}h`{z7>(q>8M%$dz1XuPCuDUV&)vQs< zb8k|AQMk^{u_jmczm{)uxIOt%Ze{2_p7BQ#SlayD6qy*?;$q;>Nq* z&Jm-ivL6wsbzo@GaLf8rOt-TC!n$8W&&MSRuIxt%BF=WamN2Hd=STgw%9o-13zEd= zRN0RbMBrSYy`=5IP>B2}uIxtyYT-(AtR7u98nd6BA}&&8KfX15|6SkS8NR;nY16Ij zuR3O*vEb+NqBm9cqXZEv`=o|zJvLOweV! zv!5A>uRSfevL7Xg*s=JV@XYJ|bsH`I^SyEBn_+@0`w@X!?-joq&c62vy1m7D=YIQc z8za{a5?tAj5=7+Pm=V4@yr=0__P=Un5pl%^2(Ii$1Zs&l?}y_)?rFM}{fBSl5)01s z5nS1i5=8t;H2`+4Zl+t=KV@@XQ9Gfx;L3hPpw@u~xy+VHT}-#Kf7O;a@#e7}f-Cz` zf{0yIHE@>VS8iqhh=Ik$!p2<%SN0MW@S zAS=bMxUwH5h@kitXZ&>3AfrqbQQK-QxUwG+{w&2o-;bl9VWQ4 zAGNZ*6bUb<*aBDf2NC}kO*IZK8Y#H4A0>#uUCFV!=YGSu(`20B%6`=9ac*-sd&U@( zEBk|pe)Cotxz0=wT-lEjMBwg9mHnj_7+Xe96{V=MAGLaQNDNP$JJICI{vcvqt=`74 zpQnk(sIng=h`{rT?k?4>V|4gAQT#}i{is#%_h#X4Yo?f7*&jsgS)9ixHg}fb%6^m} z0#6^h=QV3XXx+zi1XuQ>HGx(Jq8;m(F&jhjv$>)YRraF<5y3WQw|_6RHhYrb%6`ngK(zoWYJd_%;7;UNTmwM004i#L5=3wffS2ucEUp2dS^yO_Km=;xPDD`y zssW%{02MXB-cqK?^fJ}h9@RQi4FJ^wsHg!-5P|KHl|eNCR12V@2K+Ago#?s@liTFF z46Xr)*8os0fQlO6v-8OEcyW~lw&z$}139=3!tI~C_x0*08n;ZM-8|JfNB9$)Bq8v#dC`1 zgIiz1H2_o#prQsSK?Lp?j>Rd^bS$m`pjrSGH9!d>@Xb0F z*8os0fQlNR1Q9sj=;s!w27qb-RMY?^h``nCSX=`@wE!w=z?L2FyQ~sQ4 z0H_u~MGa7b2(~JDw{|N`xdwo00aVlg5vYZ0p6)?X4FJ^wsHg${Y1vG zoMMg32jEK(LH7zx;sel8gDL&{i)*{Hi+L^|fR8{ey7h0qemO(m9+-BmkI1;3OEjmb z0ZI@-xBgAy1JF@}H;(iWTXx2Yh|34yOAtY~{!QWo&`|^80}#XqARcr10DK7|=*FQ* zd;mIXKzsm#_yEKhmk%I@04=)pZxSDXjvAcWZi&I$%ZZ9EAAm2x@1?`pB zh$BZTh~q9FfGAczk@RCDh9Qg7^T8Z(KeA|2@;~e*gW`4Of%+ z0K#t6;JIB-i{!DN8GT$n0AGR#y0>p;>71(HAn^f+bA>)I%D8+0J_5C>&mUnfFTOY2 z)8hjWdAsg2{!38DZPaa4Z#P+VJ+{?&iJ}IGKrQS37_(qxdDx8_{C0P$ z*p#@;*g#POlpuoc?VGDgP7b?KgMV_*5O2pnYy3)414N(}-JCZ29+(tES!q~*d;i(=UfFM2qV+lnK@Viip?(Lhs#up9yd;nt0A7u^c@&Wj5pcdVhH?LGJ z9`^YF#N0(chkkJR0DK7|=-$5Bx1x8Ch4=u(BdMoCbzMFHAAwpNOJ-le=K~N&%N`6Z zbol^$2_iTW&2ciH4?t9SY;UNV%Lm{iIPS{+2=Ai7e(Zc{u9(oVU+7nt55RvaL~t~i zJtlW=Cq4kNAn%(Y!{r0;5vWD?_RT-PYZmtT0K~mH8KIRfAApZQEqqUk4?wKFQ`^Yp z@&Wko0}*s1-*g^N4EuZlV(>?;jLR+`fR8|};M}dhZmM{F>2%{amk+?7iHN{eKsQ<2 zP8CBdFEAc)`2hUZ>E6EClss;Z8Uzu<2OxI7xXH*uQ3I490#`HT4H}LU#0Ow}>GA>i z-}_{a5oWiAkuXOMf{3!ejt~hK-ZwaEfD%LmcR1n$5X;Y=GdOC1T6AyUBtC$!<^%Be zF~=f40I{&j&xYm$@Fj@AGg0vY2;u`UO1OLg{`bb0}#XqAQrlO0RFihK)?y7_y9!lQdLFR zwEkmdt`oq_8NsNNu?`2c(gXTm)M*BMZ5J;CP#5L9mv(tH3u0=0ts71tS1 zy+KIx0rGJ^ysy8^S`2c(gA~<)> z`CFe4Kv2EGVZJ?p--TLSXK=51n}$9gfS`JVG|dO#_g0UUy2Fj_DLw$Qb+@EyJ^;Um zh`{#L-Ecwm2HxFperxJ`^*c~Z5kUmk8Bo2!AkKGgEZo}zTxUS_2CXz7 zfGxXysG*a!Z5+y+dSHgHZhT;PdRBsT{d;q=#5x7ezJ^(@W1|iJ{ z;IAk|;96090D|fb;x!+DzwQu$qu{=CsyFaBAbbRB1=k?g8Bo1JyygS&d(L$RXK(+} zK=T3kW2pE51l1eFYd!#9f{5TO;W`7VH#n^M0Q`532wXRc4?s}8L8|5h@Mj_-f;$7( z8Bo1Jn&t!GeOIwP>AhBQMd>%F_87$nAgJCTP4fZxyAL9`&VX|3={_HTpn8Ke%?IEk zPz!e=#Rnj$-XKl$0r=}25x9aCAAq2GgH+82;ICRl=$$&<=K~N_Z;-0_0DJ^$;hI-` z0D|fb(lj3cpEzoK^eLnGudqGE2Oy~4AWicD_+x?yY)|n42;u{XJmm5Ln7PNi6V-eG zCh-A8`S!plsxu%yfT+(0AS&mX8OdI~O9&-&@6t!m{YbOM#$i#P4?vVYFfekIZVw;= zwdmHrd3=A5sC#?h;Qd)5zD%2l<^%90h@ktC=0ioBMSVU1aV|bSqWJ)P1ZvT(f3xVc z#!;USKoB25~AcF2enp3`yi~4*3;{CU- zrv2#h0r&{iqFeta@d0RFHR1yh#0QY3`2c(gB5>v_J^(>{0BM>Jz(=5#_M_BFQ+xoT zaKhHeW|t4Ze`|ER-+%vfQ`hV<|J|s2d*I3Lqs7AeCn6_YJ^){W2)eg#&KP(m>hl4J z;q}i%o^$yCd<1IIjbpRyjW41;AAle}fJif!55Siog6{2`#0L;{Zx8f4J4n1S=T79P z%Lm{iP>XI(o5TkYb#D)h_^FQ={bepW$K?a?C5XshyPNq|N)FrQ12`7yCG0E(#_j89eq-dbeLes|d;oGD@d2O&5p-|gBt8J! z z6dPPwPIdVJd<1G~8{YQ$00i*?$bVfv0FDAH2_kg-%62{a%1cZ^d;l`pb44pcbA!iVr{#A3&tN%Lm}^aEPFL`{vrm5~DsJfcWF?u*knT6(4|) zKrK9d6d!0@d2c1J^=rD5fN;I_y7d)0iRS2Oy{x zKx#e!UxEmoSG9dU0710?l0AC-F4WSQaogtu5L62wH6MV>NI_K(I@_y87u!>O0D@`( zq~-(gdx!{Z&(8@<%?H3aVfDQ_53FWJ5WzJ7R0|+AAAsL;e0Ht@pj@u)^8pB|1(2E# zz?UFG*Ba=t;u-*|1(2E#z(=4K*8ot4+4lJW1l0ma_UKW92(AI3?6~do0SKxEkeUy` z|1Q+hS!6x0xCVe~0i@;w;K~yvL4?lysu`;I00h+nNX-Y}?>Yd|vp;mAW5+8t|S^%l}0Q{cojJvJ*0Q@mj zd;o%K0i@;w@Fj={&JwNxpjrT_`2hTPjtE>giVr|gEr8T~0RBuwgsxi9Z;)#Ms1`tK zJ^;n*!q%OxtWp-BuGi3SkZS;_7C>q~0Dt#E1lIsi-rM&100h+nNX-Y}BTx%>BE<(F zs1`tKJ^+86BLY{j;sX#=3m`QgfWK-Hp)0nuWyv)FR0|+AAApZQEnM@84?s{YfYf{d zTr1()&TbW}I!mxU#Rnj$7C>q~fY_J-0^1{gh8tH6;scQE(YLR8Bz!7mu&wz3!o&w) zYd(N5@d4PbM^AhJg7^R=d-Qa>-gQN#xzhz~$&J^){W2%Py2^8pCr1CW{zz(=5#u5{GaQimj z?f1i{UmIe(9=)+7)gV3q$sRpQ5OMBON|^WnY}cdz==8e=@c~Ho=n;WhH~!udCO!b$ z=L0Z^4?watV>BzyFTK&_QMW`>Cmz;-?Qo?8YP#0Q`} zdXyl-iuMQ-AAt7ge>&INAU*))(IW!2ZqI5QCO!b|(Z6qZGKddAdGv@tt@E!o2ooQG z_UMTZz#u*V<sp2 z9z7y-y|CKhux(-s?cF>?d;rR$M+qWyMYG;_{|xU95g&l^=n;WhCBAPKCO!b|(HBVk zB1C)u%A-dFYT>9;X0&`QjM^OrEJcdPJZW&K|nM z`^$WzMEKgH}}cTw(HSxh@gZKah@c~H92cUirfMaiX;sg<#pJ(2F z_UQF}PG#Nco0`gl4DJk^pJ(2F_UKW92+q$_c3gY(oS$dje)i}Qfm*o7C_aD?<>{42 zj}k=SzM}X5Ld@IG9z9ABp>Kd{kDl}M%-hc%Jt9yGcOu0H5F$PR<gP6^qilk9Gdq&n4dwt4}C{j+wGj6XWoAH=uyHMeGkF; zdCG5VkDl}M%-hc%Jt9zx^YfG=)E+(O=b5*kJ$jTNLf@~}UMlD3nYW)kdPJaB(Uxr* zQs!EF^qik(-hTGz@!2_#PB}X@y4arL14w1we)i~5f(UF+@d5DNaOK^h7QF*zicm8n zh~WG@^Y*hxkNv=B=lneLuDc#R=jWNXpFMh%AcERp?gTwnoS$dje)i}Qfm)oOXP$W1 zqv!lQ^Y*hxj}k<1ex5Sd+N0TR@d3m$Z$EqVC_x0iS;Yr%n0fozqelrMaK0%%fK=w~ zXOA8wh``mX_yE!?B+IN}lNm+NaqcT^NvJG*MQG5Vt%-hc%JxUP4`FYA#Ymc7u z^UT}N9z7yZ3s0MeMZpFMi)Eu9R^f2HhQY)|n4q%m(ld-Nzl1h(f`oS$dje)i}&KhG@e?9p?6 zp4pDsqv!lQ<<_-F&-r=g?Prf3C5YhsJY_VrN6-0r=Iv*X9ucU;`FUpNcRhN}&r_aW zdGshj1n1`|qoF-|&d)P%KYR3uKrPPCGdsWQ(Q|&DdHdO;M+qW0KhNy^u1C-LdFJhB zj~*q6;QT!0C$vY;`FZB;XOA8csKxntX6JV^qnw{--hTGzQGy7Z3$*)Cex7;z*`r4U zYT-(w8ez)MGjBh8^!V2B{d0bv8MR%Hp7ZmRr&k_5N)W;MdFI!5J$la1GjBh8^oT$$ z&d)P5xa-k#ex7;z*`r4ZA~-+K{Q9m(&-r=E(<_f25vaxad1g3wJ$la1Q=VRV^e90D z=jSN{uRVIs&r_aWdGv@tEzZv~zrLHJ=luM)#M{p~dPJZW=jSOit37(o&ogg7=jc&_ z2+q$_K3#kCoS&yWz4GW0fm)oOXU2IqN6-0r%F`>49wmt2{5?BM4%R~8^_}O zJoEOmM~@OjaDJZh>Dr^`{5(O(5o_YJ( zqeld4;XX!r9Lmo#Z$EqVC_x10=b2yM_2@Z2&%FKY(IW!2@bn?elJfJ++s__7N)W;M zdCG`ukDl}M%-hc%Jt9yG&l0+8N%?u^?Prf3C5XV2!Lc|$&%FKY(c?*v7676hi}Ul$ z+s__7N)QojgY)yu+s__7YT=0!L~wqd^7P81=lne6gl)>FDGxHZGjM*MdHdO;M+s-F zJp||HDLbw`dd|-?Z$EqVh(N8t9>aI_CG+-kjvgh5z@13l)tAiM&mKKW5J6cPW@gtO zJ?H0{x1T+FM4%S#MCz`-WZr(x(PM8pPv~WPu|0KHUovk$=jc&_2y9Q?)tAiM&mKL$ z3#ggk-%wERgR}5n#*}_*i}Lf#+s__7O4Pg12+q$_ep`F=oS$dje)i}Qfm)oOryQa7 z=s7>ny#4IaqXZF@^JE@+?WJ;lo_YJ(qeld4QP!F{`?W{U`FZB;XOAAAok!No#A18u zuD)d6e)i~5f(UHS=WqA&wf^_=tl;;c@9IN8I6u$4{p`_WKk(T(KTjE0?a_07o_YJ( zqelrMc%1mj{JZ*+dHdO;M+9ndexBLjU5}pg^UT}N9z9AB!TEX0Tx*Y>^YhHx&mKJ@ zP>bgj&jmpMR&Wif{5{lK=j-k4%FPXQWJ$jTN0^h8< zt1p?ipFMh%AOh!`x~nglx1T+Flpq3Ev%0GPzPB=NvsEPz%?*x~nglx1T+F>@C~6d^+g6`p|RE&ogg7d-V7uh`{z7 zYvj1OBIQo6_~eFhMxTY#%y;r%Pe}WInW<~@)m_w_i>8@1`Z)=Wuk-JvUR>Qp?Ag;a za&>7Tff7UnZ;XVm%@x1Zf3DRNWwRNGK&{tzO*7xE_Cvy|(cH$-LP=uWyr)||fAd}l zC5U+D#5D6i;$lMM-}pB`w|_TRq~>lLKk@r)1|qOe*f!NC)=d(>ugqC( ztc^d{7fAtxk|092r*EIBrDBT#|}J%;-CgsmJ&B5~xd z!^fKZ6F{KW!!)nf_H)wfs(EF`cNK%1HZfX9;si<%5xg-noaSzoo4x3UTbzLi)Y9)i zo#!;=AZeETn73_eXPPA_(K9BUXCHnO<%Dm}6-#sf*`nH>tbsNVfg?h7GV2D4s;!%Z z7JQvyV14UT@l(wWU28^5{jkDYUHU%G#dqh3qlYJ?-K$=Le>uyqltsj+Nz=?JGipZv zd1op0BT_F(RLWB;E!nyfLIi4I{~YVp`AH(%u+nLBOPvm(1QFOLLYzzz;XewdJskS4 zw+7YtAR^dvqu6YbW!~E#QTA?y$eIDe0|?X_Jb1Es?$c4xzSsG;e)s)C3~7IMj=b5et$`9m40>at zx$@l?qMcVT;($Fv{8+bBbqGJM7<|cB3rlS z4j@pg=IiUQP z0=2Np-?8>qnj~79vm^J@MjQCnu!bJTjeiw!lK6bj^AYnxcLODez)^6lxoby@`XB9# ze7AYHfm--fLBynOqs59}cSoxA7-*mb5jYBz1*p_dkv#ESX_W#jn`0|?Ywv#Xn#k(SFgp5isQ ze0~QpxNu?l(1i&GN)Um!M;zt9<-uNkdGl@@hmdao-XM4;B2J4|!a$`ZD_x0nC4rC3m+t}Ipg zbOn%EOdLbXv5f8}YGxFW4f8e)j1?mA%~EtQsgD@>*h8{a-fRYH zJ=ypvbLh1z(JQ5vm_fvr&i#pn_OHkXm+A-JIU;avI@bMHhKYG!d>uLSUTy=maF+-o zj$WE2W);d2`K49qzz&C}0q(AJM!h#%~k);ycG#((X#wyw|s+?OLw~s$Vv8>}n|4dPNB$g4NMi+CM6? zebPv>^@<48!WrXOwW-$mc=pDUtyh#FA~>(?x0{G6eH%))UJ-$P!nP?hdZ@9Wf08XS z{9f|lnVnF1@xe9_ff7VydAz-Ob!{2jwJZ^V5=2l0fw>KJyySl&P>a6bq;Jcl4U`~) z`ok=OIx>N6AOf{$#hTPdy=oDG5=4-<&77G!4tMK~M&ib@M-9)nW ziW1u0Oqw-nhr@58I{oCv;$~uF$<`}M5P|)p`#7VjiUmW9$%5Zx7+A|S>uTw zi`Nz3f7(*ML)I%w5P^N7`{$?Yidzd?N`tIdlprG5b7yZ^@#(O(vUlC820lBE!ow$W znYCZ*W;a#VYmEYh#k4gYr1*Bcff7Vu#U9n%r4$kyR&)}4% z7}XXGll#beMFeWyEFBGBxjfQ#t=Bfy&lz7d7%sbz^@lG2G zg%z!im9zeRj=jC{=L_Kh$rEkY zdhIr4wvqVABzcdlSCk+ED~uhh+TA9`s{1o!SF&Cafm+EMtnk`}Q?&JZ;e#^9#-r0@ z6|!DYf(WdXcC2=foC}>^JzKs+)+-`VYyaCd!z+`fY3p^y)P*X_4zhPKvAk|)S|MFeVbq>Vgry|;JhSvs_Aev+(A)+$(Wi3ThW9g9@ zWQ#Tpj1?mAJrPIz`r$^j-wfG~tXI@ZZ@4i$e&z(5t=Ax;T(%dCqZOyfPsw^k2_kU5 z(QLnvV*EX1g1ku9D{A4I4Zx)f`MI_-|NF%Q=Lc#bnxat@ccu8NvR?6><1FF0E5$9f^~!NqioYuB6(xuW zRswR|mEy0;dPM|k;f!%Cj=NI)RavhnK}2v~aom;SugZEw1ojErrY!R9616C%sH|7~ zUaV*gw(-k>-8DS~N)W+uSBi~l%kuB#bE2j$0=1}r>9JLt{dNH#ff7W}82Z(}j>U0TioYuB6%nY#aaW3T zYU`Ebt`vWjY`vlc5j4l3K9S?D6n|CLD_#b1^6iV~VJ>D~^9-{e>v zccu8NvR+Yw2<#tOuM~Hs_^agDD^@3P+?67d%6i2oq)Y?FT`B%5IrfSYL~z`d{7!AX za@>{TuaaZ0h(ImupJQ>{mEy0GW3MPd1op|XIPOaESIMzglprG5bB?=G{8e)76`vhP zf#a^^OWSVjmE*1yf0Z12MF}FXI)zw)Deg+~SIMzgM4%SOUCGi@@;;)ipuP8wTR?|^#g5s_ee^s$pM4%SOT`5AStyhk_Qv6lL zUQvPwtO}&q62)C9{;FcHh(IllyHd#mjzw`e?n?1j6?;Vl$6YB- zs;pNW5y#@VE5%<`>=h-5!1qMiaEiN9{8hzXQH$fQ6em^IYY@S4SBk$%j=iEJfC#Kw zj=NI)RdVbVwQ$Yj40SAyyHfmBa_kj%I6Mt-uXHSqyHfmBa_ki)h`=4(u{iEZ@mI;Q zS3EyZ3(=0naaW4JD(e;BInEM}yHeazTdy2kdZccu8NvR)B^S~z1U z;ze;+ioYuB6(xuW&MS_)Qv6j}uZX}tVcRP9Dk-L@tXKSAj=Oqs%3vF;?IBQt2#&i3 z;-WqRC5Yg-YasTTDFU_l`}y1a_^yvY2_m>Z+@@OdJUpX^hBXE4dnyyR zu|q5QX8k&{`GxO8h(ImupJSE0*iv3CP*=)br#P?Xj|n2MPma}fWlK5bSY5f}L%M4T z( znAvUOa*r~XJ6Xu{`^!3S+=^UF=n_Dn)|fvA+rP*!qGf7w8~2k2%K`&GjVx$0&Oiww z2ILrFcU>5XGABLV^BOZuK9qDaa_OU<0R(CdeSM_8G5&D$l*;P=F>thOmPj^Mh0z8| z5J61&c9V0Pqs*=ESh>fJl{G)#7AZFU@c;s~PJA`aKKse0=r@A<@!hwR z87M(Sv5AxHC1;YN!}c?x`>Cn&`44AC&K|B7K%iFItO@p_DjTEMC~8EtQI%%MDPIkb z)U2D!KnWt=A*O}B(Xr9Fl!0dkXgN-!+T6zteE@tJ!kG z_=RbU2i6K8P>W-U>|MI+{7mu5a`2?NkwX{y7&xNz8w&P!k0(a?w;8Zcj&-Ng4Eb%g zx{*19EdwQpz$c_%?XjoHey7SrPRC88r;2?qK2;F$1$n_WD%47A9a2?D{`0cW&weiN zoH!y>DNA1P>Ss!)y_x592qlQ%SOELHZY5xpyx^t9RL`FxwF^_UcG`M&4-j>}9U3x%u!2`N5;7 zBP&nW4IoepSF>aNv2&PoCVdk*nvx^1Y7w!h##45IVotQ1st|IXe^TyV`$uH|`UU|6 zYT>TrSnY@Qk#7xpNLKkZdtmoL#EE>p?S2!o*`rcJXQcJQ_B4dtqWmyOXI3JH`TLR*=pyP|%e(|5{mBXtYyqGI5y769eXF>3d7@AxD^;r+`N}>1w0=4+`r&VRT7C_y5 z8IcLE_7+8cn_!>>5tMI>5}%Ce-ae~Gr+>Nm{lyuw01$y%eEQSwV7eASm`?w%lLm_u zZO0iXK}7Q6NVGlumaWT+b8XJa$oSF2M7zs90|?aO)1P)Z)3pFTnX@xeaKLEM=h4vy zN)SO=xo8*qg&mjQCmWsqZ;u%(R?m4nfIuxi{pqYXT?^n2o&ICLog^lAc*;NtBKY*D z)5vr!06zW63J`1oAOf}c^rwB;bS(fr{mBXtYyqGI5q$d7S#P=)0H6M31qikPP=W|P z{pn;gT?>Fuf3gAuTL6eaEk6C}{4!k&AaCAtX?Iu87X2xsh!R8;{=Qk1SfEVz&S=Km zg=xjVnk`0CXa;$Dy>P8;w zIzwD-X&ER%1U{i-HI9^t^s=Xk$|WZnsD)1zMDXcPR)Am&0H0S!xz+xNBSJhAbo!GO zAlL#x2_kgFTkWWn1)$TPtN_6l03uLJ$HMh4%BMeB0fH?6oL4wwa1}TfpZ;V82(|!F zf(SnS>9jUo3xH35vH}EK0Ej>>T+NQfr$1Q%f-L})Ac9YSI;~CD0^rl1tN_6l03uKe z_ZT{z>GUTnK(GaX5=8LnPp7r%S^#|dlNBJ?0zd?6;qFRSIGz4v1qikPP=W~D=jpBt zo&ID62(|zafm*odJ67m+uT;L7l1isD&J3Jm36#O&8y$_51@LzNrbe$rUBrn&g#=0v zp|e@aesHV`4W2ukKsQrHP+cD)Pz&dn%8VZ7n<-q^hY~~tXJV5)ZBzMX%1E*q5P^Nd zwyE}f-ijTR9~4~Ihu^ESeJ00Yf^D?Tm6P*>3V{+t=&Ysb#(nZ$dyKP|3V{+t?9XrR z;~OL{S1~0<=VyjMEuCZ4Z7i)hmb0&38=RL_5=2mY%ps)uL1rL z=yl#8+42!6K?IFq0^cBUV@uUX?rOz1Q`oXZ1Zq`qGw#~5Y<8?^(2ovmi;FB+C*dh`>HMmUT8RH11TA zc$X|olprG5^Sy86GoIO+DDF{g37;KDA!H2;|G8nZwk&_TRmSM}?KDxBVoNANM6V8s z;fZr6nr>{VUTQbvofgx@eTpq10=0gfu_QdX;zVs(&O0#6xboFRF_21Nn9t(5)r61%i10;KXRR?fXVoQiXt+{i)3-{VONL!W}-~4S%s@O+xYzZZZ*w!y2{LGO)+OphGKC9SJ z>iy|rbzmufkOmFp_P zWLcsF5oZqNGCS_+rY%d6y|nl@Uk6c8&|(`}2T6k9?BYLVB+ab&$;Wjk`;$o+R8agbt5IHH^X$Ox~Z zUkc&a684EKnf7s_*px0JiDFAAK?FXbV|_xEvK{7i5T8(N3AOO4f(WZw9dRO|m1s+r zB|b0tpIi~Gc24Xc-D7#Au6W{HOR<+MOOzmjd{M5H)|O?1Q+37W#Vy5gvMdpSTI8j2 zCAmIvdY=Bq*bo^iDwAc2^9pAS&S_#p-1W8bLWg0Z4Ox~bLBwa5(!&YAd6wnLkKQ&~ z{5(diAj=XFsD*2j;#c!ijC-$65J$+eLZxeN@Q801QGk^jSY`qGeujLFQs%fS`U~ZwvlCt2-L#8lDJ-8&Th=9 zKU>@-%MvAszgU5D}b- zl(iImYh)Z*mWaSUVcRNeDJUDK>?{0U%I@*)3T1@_+hA=Eff7XM8yMQ^Lj+0?LD@yV zF`_NY|AqK}jhzRS6-D#6mmrdJMida(1s0UdhC97?M7SXAk_1EqNv|ZyL0B>hDi{c& z2nb5p1w}!L3wxU#5XD3=paQR?tB9y5iV6Z>Rd>(a-(2{==kpxSxo*`nJw4N1T~*To zwdhMDuS&T^87M)5>%(PwUoE|QAc0!k$GMK)S4)pT2@?Fi`8jIOlJk|6w-kHGvqS>5 zY-&^2sBJY@?dt6}PFWpZZYt?~rB{w+{$jHNq=KP=W-l7O{D@tX?rft3?E_8sQZqNT8O#=CoQw z@Tw7BF@h2#uuhQ>triiyYJ^vepacnj&HwFxzc`guT^#$Sj)nJ*Pk~m8*gOMRuNaXt z+liG`%8D^_Mp`IA0#8_`?D>NBB4>RW@psZ7AAwr5TEyl#%6i4f9W}a$HneKQdhmV= zB}mX}5t~;Q=oKThT14=w5neHZ1ZvT05u0aD>lGukT14=w5neHZ5+rD~h|McK^okK$ zEh2c;2(K7H2@77@H^gjb9pfm*a$#O7Jwdd0|( z1c|C|K4xF~R|fTpk}k#(;Q75CAqk*EIqh=md) z@T_lIWjb%DNPlg;Rr=h2d<1IIH$CqJ@<^!j&)r4Gd;hf#Y#wUiTcdBn-ud46+#;bf zC3}g3v})wfZ)wE{yjvvjDNu&x$A03=EuUL9tr$TqyemIZach6^lYPW05$t231POc! zkx>6BqeTX-8W~rtv#;h@TUsrm)&uAjBTrQvEhY@kwBGMM%t8qgcy2uTK367++pjdY z9(ud6k3cP2En=^wRU>-6^Q8C3i!xu|VZHaoNDC!M&^J%}?^7*<+NVxgk}0lr`7%&x z$Q?ccwP>}7&1)+3dguO>+r2RG>A;G|X+M3CAYt}xP&=$dLbO^$@Tw7BF@gkYamIk7 zWNq7NwTR$VBfMe+C7dzf$e3+AUWsNvd^%0=su5l>f)XS+yTb9a9tUZ)h~QNtykZ0i zS}kJp>JDD-jL(p=wfiOtUNyoiMo@wTzFGPv+-suXRU^D&1hr_jh|Q}zc*TgHpw%LR zSB>zB5tJZ-eKQiG)gppdjqr*Q)IuxaCup^Z;8i2MVgxN5js|Ee>9n*h9R#l$;T0n& zK>}@lBt)x41g{$56(cx)pcc}RP}hUcrFJ`d%DTQ~ka)fLm|$Bv5BJf*EA00sj1GP{ zX@t$E=xklsCO9jif76+I!5Pi|T{pZrCGZ4FkSJR4Qrc~Ij#D(vn*6d?*6js9$c`mY z>-pwSrS%^%))3`y)XsYINZs{Jpah9^=T`5&abvt8c%{XFPPz;vP>cS)Ct60^qjlq- zyWo}KNs#E??vFi}D!cXQzP?v{;_>~e9(XO(q9>9UeO4(Q7w4>N{&dQ~8`Jq&c@iY( zG?zR&CC1i!%0Be;qMWqVvr|UI5U6!@*y_9iKMpcA-&5zMq&r_Plzfc{lpyid$*ep& z?Z(!7<1X7shhwAN{~4BM?+`% z#fFA>_oEWozs=iUCze31!fgUh+kdMV!tN7^PuyUsc7+lo7A4xw#v+vrQLWU4_!~*B zZz51@+~iKqOV3{m>T|HB_Fb^6_s9k*HK~=L1PR{Rn06u#>Xz848|Ik1vhA7M^L}it2$UefJAxM;wk4=r zV*4T+ng@6OwuQ?;0<|_=8tNpjpKZ!`b?KYUs=xl2B2a?FP}*Ibb_O@ZvVjBNU3fI0 z+7%M0)jVgkQ}X+QhKMx%YE%1%cG6Dxv?n4+kodgnIH%*`OKJLj{5EZQ_L1<%swEnHCGZOPK_Mlyi{dO-rdTUj9t_(CuK&; z&MVZe@LH&4p1LVx=NK#Jn}OjS{}O=`B=S!k;tZ{@%n&ycAKQ3n)|$8Yu8=@2(|Qb% z`=v-M5%)+Uv@0b+;>E55oO~U28{*;&WWGu_Cb9u z(5l|4tMkU`tEP-E<1@E@6e_PQHA?nXww)SxS9170`|m38?Xy{3Rt8l)P=bW9V~VD; zejA<0`sw}@v{y=kMC-E+9V=fWL$n!NI^nw;MeFkWz-ytFvB!oOBS$2huTd|736vml zAb%z2m&Udsl13Cr_^a8B_*eq9%(!BRPPvP6K0jG**T>WnQGx{SAgGJcryQBKaZ0=qsU0wqY`p7gW^>+xpWPi#K8o$G-FYMF7~l(FiUyIZ8> zEmU?FB}m}j`joBRUcUL(j2+7BLjtw%Yz12H{PwWTneDs0%XftYY8ju%+|`(?!#B4m z&`S|0LE`hzFYP%%mQ-7x$c|oFUCwKd3<=aSo|+-bRj!-W?YhtFQxYV$%(7G1M(Q%y zv#b^MEZI*~64Wvtry=g{Q#Zb5{&@6WZz9SU{3ETfSC1#&?G-=ytmj#>C#(q6qWZBH zZpxV7d2#Zey`J7>JWEf41fCN}tNZ6HN^bo6>|MsQ^a#|V_Y@@0(v)$z)=N8=tSppc zJWEf41fF+D`%HXNq2;=6<Q1+FvKQ zw&aaz`Liz`%v81n3DhF1WRquU%E%?pGAHU;dJ-ha1GLGrG{k%4S=OBId6pi5T4XD2 z@+=J@$g^w^^(;LJ6668eK6#?GM=S(Ez}|p&}M6-J!mClmVsI{2HWIWn!6g( zW@gK6ms=|WB}kA5XtVv&p5>%v8@85t=J#g&&XGVZ@+EBYEKM0To4&QB`LMx?KnW6b zZjCy>M%$7fCJk&d;m3e#S4f~1`9wB(mZpq8ZN9qK8M<>5-xW%bAP>+^KYYpfaDS3# zc{u7>de=fN^6l(q&)sc2%QH2TYQGlsEIo;zm|(ZBIxI!ko?7Z)>hGiPBQGOy`3$;w^ zF~q=%;;q7C9#Ot1N{}F*(T?k|+YobG?@j3R&G*WdAc0!s0ovqQ8X}|jj|l~TE24ZK zBv8xr8@G%}r*_pCxO|uKEV&OV2@>R4+T>XVwPzVlP7Kt(t*o_8dzK!7TI4_4t507w zWjJw}&6_tVuPil67FM?Hes}9w)_+$|EIXUE;}y@d^vXcOSU6j^lF^k;Wc5n%JWIA$ zN`l1UGY##{`5GBw(^I7r3Y9DFdX^r6TEklJ65eg$d6sN~_*`77B^HgWR| zbE;3t>NoIT9jj@puL#sKql77=@S(v;3fO58h24oqjO+ z7}XpJ)WTdQ%{=?-+nlp~_wEW`_YDC;hB^CU6%J<;aQFR z9oWB0hzZ+iuLzVNL30)zo*(J$vn|gD!tT!8o&*V+G3jitU~ks5Cb!7HXOLnVdcoub!=pHCGZO%ri{W-?n)# z8J;=GvnKIcsKt8}@k~U$9*1U3N}f5%vnEl3gjwNczJJh+Ny#%OdDbKnsAX1(neQLG z;}FlB@uufPueU+)*R}SBOPww<9|L`v6&W*DzgS-;yZQ4a=*x-7>*CJ{c zb6)dj-r%73rpS9IjtKm+TJ2))Nsu@(eY~@NW4&NqwTn5o#4b4rffkp&^@HkKsD*Df z60)XGlj+r}21e{t-@JI0p=u3C;M=6R2A@omU%XQ?aPX|!#hjm&Y8goQ-}%&QljWBa zP6o2Z$6I*s_!O!=JJ$JNQ7AZ4?VwzK(|GB;b%!-SeYAxVBxv7iXG!NtLA?^`M#BkG z^r>m>zc9#0pw@y%$2h;28XA1zXI?E^{Oj@Z+a(>XGmYC=C_$pehEYz}FXjZ_RC`Bn z%9$v0-haUAGw)6xfm&a^Jl3f(b9iu|S`AqFk%{u{v_V$Ae)%nwATf2uNT=V8SA*l! z8pR5eM#~C==3D1K78Xj7c%l0+XVs>+g8Qqhb;5f`%1;(%Sr4?0^AV_Z^x|OW^yxjp zOKPoUv4p|$Kxpbr$?} zHu$$%Sv+BKANi8?v-RY-#uiGDINh(eQ}NJ+;E#j39*6q&kS(ed5`{Mw_7SL6u~K*E zIL#TIuht?zbG@6a)1|Pe+3_w5B}nA|sGC#g?|k;j3tYyc&qDIdUsXf}QO!r7)}dD( zZ~`=Ebc0%p{KEP6vfJXyqUDqV7D|vPRHvg8`m&h)<|d)hR1Zw?A zr{g^~KOEF+`!0)w+ffjyYYs61L$YLsccH)WWQKrOUHG%GAEMaI({-Zd#|#+KK9 zXf77-Afe``VGE^Gb-zrO!)OlguZ0f=P=W-_%i`TO%>3OCpG}rUXb$iBgdIKtwP?l` z??z(g^?i3@vfPwe(CU_0&1d0oG(hW0c6Upr>@%~HRfE3jqXY@G`Lr{|>P(q)?s%Zs zkjlRC1GSKj@Lt~1oo7k2|9CGHHLH+j8}i;OY8Iov9!Q`B39~;-bk?L-21<~i8I-)A zOmt@EEeX`3S(&_N%`M762@+Hv-XkYEGt(;r3Dlyu=dA$uKP!|VLC=rR)H5?PU#7iY zexg~E?89MOLaP>{{bc^8nVH&$v!6H}&e%$OZIcg&5+v|FMMAtsQ9hdW%RU?usD-Uk z?GZ0&uOc<$7bQsGn~j9_(hf9t(_BvW;gG;OVcE1ws6;E7B<_*lK6*J|-nqlEjJdAE zb9`Q3+RmGRn?4EfIVva<9~Hv%X@;=+wboqsRncdTaVM5OiWAya!7l1+LQv`~Ts?xR4v zY*y|evpy;$AK2w5P^;vM$DH?8{+;)66N}1t;FI2Rl5-_|Ju|=6@LP;!f$5XkcjQgJ- zNnUtXxYy^mDZ-T?fxB(cZX~Bh$^6Ny!aM1Ga2YOvTKxAdOE#EiHR8i@a`&Y<;RVz3 zE5en;5?$oW=6xKrC(3Vj4hpYZqswq5NZ_t9kx=g$6XoO|`-P_#^b@GXcQvf&Q+c{w z4bPY?>y1bZKYi#1p8)1bVu>w<2Ic9toA?#&KvOJ#ctIIc4~{VaKLZskw@R(It}Vu@gnJMy$;5QnD9(;ee;7p}ji z2v>rHKjxfXdYWw6{)63YeYkX&KrQ}zG{a(uRF`nG9~hsRD+TpkRXZ|O{Zp0^_Sls8y%QGOd52bt0@=iF+;7;=7`D71Zr2Jbj{k{x{_Fe+H_D`pQ7z1%9RfevaDCUwyPvaU<^k&fCJ;?rJv?lMJDQ&=w1u8_^zm@ z1+~3u`r1g@V@{U!(>J;dSAqn_aFNgl14qfF@4aDF{!byd*Q#rw7MDT&Kd9|h+==0G z{g!Q3cd}O~i6zKh1+~5ES8=eEdq1_-9`o##k|1F$pDE+*jRWQV&5v7ykKE?kL?uB2 z^ZN^l z+-qlLgL%@-Wa7MNMI~VJJ3wZkZqqVE7pB-BY@XJEiV${dhHzMD_{^)H0rdt@~ilj%l)4mAaxo*(;PF zVf+rz7<`~+!gy) z|{9C_w`EGNC=m$+sdOOR#^11ZuGd#bxMc#l98!Sc3g4lpw(#6chRl zwr)BgT|db-3HFDW z(DsUbEAp`f`&TGIg4Sj5xd0}Y!M+uFOv?Hofm-ZaaT)px77?i~!M>F%!Tl20ABx`9 zti*&s$AeSFaI#k@K?2v>(yqYiivzjCr;5+XULk>6>_KrE`dK~oSw8E?u}tv;#e*n8 z0#^XjK1GjT4^+R9DOyrIhy-e}2gPORcV2i#qLq?9SrjLGg%Tv#gJMFr#3vGHFY=BP zMPuq8C_w_(KGPY8wFX$d22T|2DIP=uwb+B=GIaka_uCxnH1#O9S13V(Jt!u0AFLBx zWqtbHDDm2(1-TD;5+vADVnSPnJEmq?tzRA~oP)|TcoHOVojA32@~!?nK3v%=ycTM) zZ^dP3dsTvbt0yZC7PYm#@+3%*=jCoz!mbeKI-8!)-V6`SM~}C z)FOKvjN0}~@``nyMgz82C_#coiC}cZ`7F7RNFLima6E_-Byisb%CMBZUBv(1U2r^z z1ZvS}XGh1u&9lpjj*~N#y+R2RG@{zk(Ya~GYGP37cFJC%1PR=|fLbE?R%@q+l)XX% zwa7EDqdr3t`Bo2hOcRyJUZDgD@;*3QWb9RE@~y6%NEQpoUZDgD@@hEOWb74rOTzV* zkU%Z+qWEk;W3PBFC(mX0bMeu5x5dT9l@7XNqWSH$H+_OjEWvFwhRBPyUAK&WYle7b zAi=+}7eqq;`94vt7TI^aQanoBG7O>0(0$M)^4;6gM-c64VQ(f+refM!u1ED|TjNm@ zLnvBX2A6o}mwX9G&~Hx*ZA|o8z18AKJW65+MQeNIKC6A_ZukhIJuS3+k$+p z30$>FYpP!hiHEbRiBa`c4%s76i)}93OYJjkq4?&R>19RH3o3`~NswT>&Q@Hv-K2+m z2y0Lwv45b7wmk_FxRRYtysg|r-2PD^@!f7efm%F1@z|pK;DOJ2i=I2KSl#BR9I_`t zg2zA}@w8<)7dJqhN;zW<8?SQ6o&*UVnR!&z_UiPqfnvebZ$pyd+B?Ws-ck}f$OZj`wng{B zxfI`YY_&LW_5+nk^(3(b+cIq#rc!)Uu0nhubG6FW+O7l%j&C@+(Cg1RTH&b0WQ08e zwfL^s`so;l?V%p0;^J81wi5F@kJ}Rej<&>D!j;^DFyBA^7r|Ztw{W)%_EC6@^4}Gg z!4ji|MBc3l9{JsS$2#$7t=q0CV+Plruj@)oJyb6;e>bh2iNu$)O1;&hOI9r5_6hzw zkJhdSFhi96qh{SskNi^?C3s!)chf((3?}A=a@WQZZeQWQ^Vq9fI}_V>wyOI}{>=p0*`?SM|elspjo&B3vz|-KQQ2nO^ID z`SG5+>9u>fZ!|K>&3ZM$!9kg)5fytf+b>NYFWSHlN9) z_rYQ+I@)@{v_gbi>?$)yhHP|9!ow0N{}!d$Q2kvgEz4q%8ep@)_`2sAc?JNB8qLE435x z#jD9Cu}JeB$GaA4agKq%*yz!~WF{10G7w5) zG85{$CSzglisKuKb0o(&C_%!1)-T656z52eagabQlX)@EYWP>x#9gyPvK!eelptZU zJLU}zYe-+=u7_lCvR5cUg7@&Ec*LBY$?*-vIg(=>Bv8v_sZ2|3p8s}H_-c3g8QCk8 zAYn3Lj`kTE4JafE^y(pV$X=lYi4nfj295ZNmvP|M^Q9UXsgd_!@Lqv;>8;Wxz$2dr!7W;BshJIEY-%y+*ImST=66~2V zq2FMu-~j7yI$`w@vR5cUg2pXHXnQs6ok7;s`zOjj$zGuZ2|OK~&J3gYhT5Ar&)(QJ& z^scJ>cS#mXkiaoGO8haoxQ{?Bv@ublY32u6C_%zMp1U<4GvvIFKrOVD(K3F|-jRh8 zByiM@5_fF>%txRWj$KjWxi?>~ixMRKVxqpLBjM+ z^DWgSrXN3A8wu1h?bu{%U1DjA%kd~d!o2esBJTNfJ_5B&+cjUX+%ith>y(8OBusmY zA?E(kH320^m{w`>)NUDFuO0FcsAXEd$)3AJ<%YBBp~UnqmB+`jqpiJEu@>u1PgPo` z2dnF1{i4MB_a?cPLDdimVf*If3*VEv^x|AXy+JoKVQTI@ zH#h&_y>stbxsqED(JZI03?$h9Wv`g&Xl4TLO1(i>!dfwevh%*XQuRQBy>gSeb;w#9 zk1VzfS7Po22{Rh}FM>w_lXX^QXxn}(!i)y2g@npR`|6=;?!GC$E9zZtZjsxSX(eVB zlJZ{pudK;lDtWIwS4sJ}O!D8ghs=3C%J)gm^`Qg_|4HMV=c9a| z^Zb0_A5LV-vGjcqB}m{&>XFd>-LK~!yO1d}>H8oOsKsrV%g~mA^L&)=lbq{A2@>41 zn9!Et>a~I4uQDdegY4XpceN4ESjMu3&}!bddSW6eGnx`aMq5pY$kKpsl@HF z)}P(w7WzJj1Zt5tz;kO&yW%__<@;2w4<$&DH^4J~P21%>ALaX0t`8+haGsAcc_!D# zc|OYbsazits71a6&qFqSkn?<$?^C%xlpsMK2hWZ+mVxtpYmOzWTpvo1pbVQsnLHCa zn;F>3`XGT?k-^uNCveG3v0dW(=DTG3!P-oD(Y7L54BN{-oF_qo zpDaHWZ5jCb{BQh^8|xr}TKx9-U1`hU5>sdH%;L7g@16TIzW-YjG{YtfB}iafh}Qg2 zkGrywKrOu6D3MU6E&Fg@&5^kE)4f=s9s8o*b4LPOPqd7-wVL_})WX&iB|fd%lcQ~~ zui0IxqI!F`-%+9ta1V|C7hJ_5DSVnoZRQ+g}sGCaG41luZ>X`ASl zalUVDAAwqE`J!b|1i20+NU#NEnHNE-mdIHgBv8x!yB7~Cf+9$d0G~l!*QNbLmwwN4 zG~rnQ?2p(MBB5HjW$LkSQo80sp6R5lKKDT!chQ%iFF*gx<=Iqn?x=k{)5-HPkiapR z_IepoO%X%e-tQw&3rAG;efYl_a?vj`3r9}+9poBwfAkZVI!xeMda`=6{MjgpArx); zxglQey1Wh&^xMMx$F=1GvCr=ZHy_KKcv zHauOAKrMRGiqQTQKPV<>?jS!aCE@3T&y780zAN3MkU&Wck#{q(|FQ3~kU)=veQPFk zk8;ak0wpnoD#K6Y7Fw8%1o|k{KU5jUFEKS|0wpnoD#K6Yf8h-GDDPTszhf=;@4831 z^+19pF@!2Z6Etf;y+N8ez_Sfi8T_WGcd6gpyRa>IwnT&z^3^jvRYmls2djwQ^jh0D z4vIInG;}Ssk|1HMb~K`ATOtPj_jVtFT4rR3W>^%FFyNkeW7}1J$5?6=58j$s+G0XH zN{}$4T}&C2NnMKsYTdf#*H_igLJ1OPe2jTkl}FA>KnW7Y8;E&UliKF5hXiUFk3+qi z=o>6@V+rTT*k@4B2cMf6eWIB=^>jPef1mSkJl-h@5@vjiX6_WR;Ygm3KrJ)+m`K=+ zYU23N(VS1@@lHvQFyo`jmqzPR{=ExzkU%Z&RtF|BcY>l9c01ms&eGKB{?JSZR70O zS;i5km)Z|33Oc`hTFHrvd&R~*w`o7J{%vKw1vO-kMN5)Vg2d#*0jJXBJDkfUme4$a zHQR!6YkIuQ&7Pl%1Zp+^E7>{m-CfSSw8ccsJs{+{arNXqbKmz7sD-<9M?$Sn2IP*7 z4dkIC_ot!+iOR1ua}E@VcfQKEfXY}ftCe)dHWY;~LAn z*{$TnZ%6Gw315>bzAj!V66(9Qfvj*YAa8p$=({TnS4LPA_Te)XuZZZ<6HTXy+=ff9*>itJT ze=VyjFBRz^Z|}Y>2PM6?mvK%uZsQ#IVX2K*iiA2|s31p<&X5P^t?}Iz5_ZR8&YyYh zo&P?%jNZrNf0mIw(>u#v^VS6LTB!9-RzaskgA8ZzQ_G2Xuw@Ck>|(k+|6~^nCAjZ7 zUMUiKxj=?|Vtfht>(+D&cdlQ0M~3rLZb7I0tmQGS{Y9&@tXit99C~7P0NXAS8*|z_ zJ$n{&K7EMmQF~y9TyU*|EU_rt*LG10ds-xvFRNI1<+7>rwb>hTDvd0kx4+R?=Y{W= z+M#+E_WayxoO%bi+ju0@(ms~kcJ4H}_tkfjQG&#XWxMy(`0qIL&MyvKocmzA>2h=5 z1*u4&R#Mv1J@2QDH!ZPC$!WPyj+ib#UcTQ)pcd|E9tlmjCq1`S_H_BtZLL#Lf<)0i zRrWMIG~V<l^@5((5AeC-c9C1Zl=gD2OnOnsh+zTcMGjuIl$-0R|% zBB3Si(*yPCt|kt;&v#cy&>f~lYu;w;v_K`Q`N0qN`v}y+UDG3>YK<2M-lM1c!jy%n zC_#drbXxR%gc=+RyhLws+r_QPNTAm8>KD?gCh7N2ds7`KW{r4ts(j$|rW}+!Kcal_ zd1^7-2k}ag(26y+tl95Qk*620_1zT`e@<>1?EBql(+Ag7Yijjto+;;FT@%1-p;job zOK?H^QKk>hKa^zcX)r-H{=AEY65R0}uM`Qj%Sj3^qrC^K?CWCTKK&oQ*Cns{1EZXc z)VHyPQm-x6H2e(RRkbE-11LeF{P?DM$EhAG`f?wfzo=IDD%E_<59@qw7qzgb(dk^P ztBO+vI;cK4YV)8J30;qXSWi?c;uu$h!VP{%_AF+gLoy{H|i{%wwc{P^+A*%LAAE& zE{*kh?zj+fee0<{hy-fke(^MGaz#*lGc;cHL6jgt@51I$PLG2HdbJhLEvupWAQGrW zW1!6=9{WL*H7L?S6kkzQ^+A--7-;jz#(fa46bWUH%n;jusi68GN|2y2(B@H2kAqbo z=q#%IT}JgmBv6aSK$}NAJq~U;pDx~RRYLVal;H08cqN*j7$_ksoJ&`I5KkzWv!S4U zXT1#72eG};SrAvth`yoDst=+Bi8blP?AA1%>poce_X^^Z;TftAB7s`i(;}hQmrWH1 z*A)w&>$D+<#z32UD360Q2CA`;-vRD0PhU*tP7~*8EPV1o8V6xddnCx_+C0kXciy?( zbn*M+i*rwQqHz!i)S{8V<}piqWb;N$7sCoo%RRD!#z7!Z3wN=nZxh+m#p{XbxpOPF zPDKe4G*;O>%4uJe#z67?@|C;a$!J6;tVDOjM=k#Q;XnVlSNozg28tc)R;J$mWkWi# zASy9L8ebQ$M3#Z>YG}vwfb4dk@2-$AcbKMYUYKe=YR0s{XNULu2-L#8_35N>db+nI zEDofvUzmy#B+Qde)9+&;y}?F_#{#|ovn?43)GC%V&hAhbfdAbC-p(RQY19_-6>-3>RMLO66<_-g~SWrjkbqRY8o7;e9^_tGDVGAO|2OX z*9P!fsP%OFQTB(jOK^koMMa|tqU_-$tN5BO7E16W0lZQqG_BzT@$Al|@UQ#3Sa>!A zje$0gY-${Y_7({})jU&NE!s5PpaqSCAVGr0K$}N7-3PBz&8yH@Snf9(2Z2B>>}iqE z;kXW>M0QoNtcQvRZHfnN6A#)H4^o?Y#m1fT$?NOiR#aY4L%i5&Nis?(9`p!fQEmOs z&uj~dk?HXw_0{>QNT8On+O}?qO%4drc6>c?=hN@|2-L#8^&_D=Cj;V}jSa->XYNl$ z2@+=Xv2`DOZdNPt0gZ(}CrxRE1ZtVl&enZ!=D5aUKaGVy-S-5?gFHeii5WT7b@56x zMy+iinw<-XjAw$ryF$W@)TZW*x>2pa7ox|O{XPP?`tAye4IPWwhiNPvtNP&9OJ&5*>77NN+%*Bb7Ha*RRnT_o zXV|(A#wC>y6Mjz@A3oT{LJ6K$fLEdneSr)ycYF!)+71;DdM8m(bZ1jMXmdP>Ei@7u zV|5lyOO+K}PpuB11PO}tY>EeM9S@crm?5&RRS+*O&-S%l)S`IM>uI#6dQmZ}%krsW zH05Nr4k#Z?zGtlJgNNH+NE=3DA@@N%*EAA(?xkaa#5vPMH_FMN1PK#an0J1;?@NKb zZKsRfl#@XMwM_J4T4KVQDS?`!ri(_DlR*Nt@FdhoX#A;;fqpdV9HyKMN{}#7nCXKp z=B!LzL?hc$%E=&sS|6tWPG{RpFn#dG?v=ZrCE^{*$)JSCRvy{7Z{wBd{MuL2bMw(% zaZUy$Nbu;-W0tl)+d53oz3*}I0w^bg1Zv^=tkl|1EXqx8KV8hCoD52kV4s9XIc*c) zs&p*(D2;_*QBDR4)S{?w553QmNAaMoebGLNO~VIh)M-sQ86;5a{=6=E6c5_k7cCu03SXhI zFpqLFD4}@JJF^zAMA?sFN!EjdCkW2T;EBMqAL%tREOe0n|)D=?i`8- z)jJ@s7EX$#cu-P2D7I5h1|>*v?7^d)e&-Yq$|`RJ#YW1>Ac0yO5%HL%TO!4SlHx(Z zIT<8Si=rhsTbANMN%5fgm~t{GL4sp89_92nNb#Vgcu@RyuZjn~YoQj6betD8eURco zN%5fg=eUXoJqcZt^R4Q-Shk7>CB=hc0_9{-f&|r?Gs33k6c0*@2LYWKe!UO|43Z z!jzLi37*4?SE8NL10`g|bLk>Kd&}Ls0+Z*jkezlBzG}KuXpqva! zkf2D4~qX#P6i3o!k(t$L3wChG3$(u2c3!|%Lh$7=uoCp#RKHk!Wp>~ z56YkHV}ap19`q!fMRf_XxekwVx(`x3DF1kTao}4W4|)V@(MaI%n5Fw5#e;Hip=kjV z4|)V@(fH(@m#gAIxhgR|Fi*#Wo&*URs~jHXbRXoLXk_`y)NwsjJm?Xq#bu1`^ZO<* z9+W%Rt=ye=T*ZT)#1JaZ^xqZ5gK}8M^xPaB55|_E2y=%f5~g@ij-4?r_n?jkJp#2T z#(~p;DISys5*Fw7(D9%rLBc#~6Q5H&C>tgo%U!PHL61PKVw4l@QS-tcFCLU7wiFAu z*72Yxq3F)(LSvzc2fZt)cu+pQx>mS?jt4yn5-(CN@v%uw^RzEY@t~|#t7&+&jt4yg zwJ7Ry-j`kSv@aTLG(lE4oD@E{TE&B&1WzFLKdb4K6Qy|2`kLZFJO!F_q9451C1~P7 zuf0V=b0{ZzrD#*Dyp9Jw2@;$WEjzwx(2EBp#e-I19S?d0YVp?xx2L&tKjLHxZS@5KdfTO+%de_xAZcUc9W%S3`n+ds?P! z+L?m$aPx~+E8!9-i6Qt74e{I6>Ln&wS5+BEn7dM1?)i$kjHHu=i@O9$VhBDr+?3(g zo1YaD^xM-iXYJjBKuHY2=bsy5#C=UlOqf#?Px@05qCGA5yh~k=OLeCgcL|il5DuTu zdGi}Yf_{5i?x~?S6DWxx96o0>N?dE7pz47H{r0rn(@!;#(Q{@Amq1Aj;qZB>nz(e} zr4kFy+NumB=(nfkp1i7wGwn7PcL|il5DuUF8m))h+L55&o|ZY)?iK_}Vu(CGzxL)b zkf7h5mV0*Y%>+tfh&(>I_kR;ads^;!!Z#Bri6Qd%1mgcq5bbHX=OW)spd^M+CoF5C zWYOE^yS>)*)F4YtpI5(4?^3^MbUs->tUe;`4>JuTC_Y_H}sTmmIA zggPP9BTVJJQ`yzEi1xHh?}9Si9)*$^LY=9p%eZu)!gFq~MS^~NTBdiIGN_-=cL|il z5b8|Lo9lrD{r0p>@47`jP!dD%In_Wk>;0;FA4t$|Ps{W!L$v*D^m8tOk{E)|$c~ob zy$>Ylx2I)#SCp9Hz7Led5PUj#l<>+xf_{5i)SJ22MhUMBl*ABx%DEx#yn5%0acP~^ zjKjFN-cIRhjqZE)-d1nbxiik0GvWUGYW~%p&d=@boSpuzUF7!2o5qs?!j&LFzipR} zgvy)+(;B}dB?=}(=1?#*JB|fn~xRGE#)A$wgjMQ&u z><=etM@B5;o!46f5tSgpSE2uR;;i@v^wskHnOG0+u2749J5eI0=16#2{-+yrSC0Ek d@Vb0`{(r7hBs8eNlXzDifm-IbdLog~{{sVW4VVA` literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_2_shoulder.stl b/lerobot/common/envs/aloha/assets/vx300s_2_shoulder.stl new file mode 100644 index 0000000000000000000000000000000000000000..dc22aa7e51355a0a8d0439f85be356c6aa9e1c3c GIT binary patch literal 63884 zcmb823Ak0$|NoB$GBrq1q#U~En9?mt(mnTH;z-F%5kiGbsnDE|h!BO$L-*WD>Xrr-h03IIXBPq_dGp5&whVipZ6ZuUVERt);;}GYAKN)X3l*Oeai>;759>G-w1J0|zKW#mi{swjcD_qtoF9kKA= z&dJ9HG%Tx)U>3Y@YPYJ&5kLNWZ1VHXUt2;It-I{@{`HB;hj%+60}oY{ z7_)eA>93Xdc;b&k(#d7(?y!U^O1$>r#ii%oU+IZ<8`dZ8zxJ|nc&MVpTPxd@PG~gQ z6J45iNxr>pj`dJNvqr7zQ+nES-+SVucMnR=&%R~}Rg{?gYOm5u&fdAk?W_BKYnB}R z^~aV_MTzArQ>6o@?(2zq3$`UHC$6`IDoWhFbNkXx{n~k=?m?>)y?6i05~?UM?TP(L zd)-;&i6c7CN-VneQ%k6##I=>Xmj3-$Pfr{-`liG$&#tzFDoRXi`Af;NiG4gV^Wg4@ z=>y%qQbmbZM=vXx)#wsW?EBkpiDy>7WIa?-qW8`Zl#Cg3g(vRW_vM0-Z@VL?iW1+R zaYo6$ORn|AS1+AiaNPPwtcNN}oYVQI;`^6e=ZU|UXWGuc=x$4>qQsQWm8tWG-{6Tx zb5>?nJpO~dYE@Cf#5LiW`0?eZwXLk*Ac=D~hX}HcxpPX@>Fcle9 zt^4k*w$*Fu4fjMU+bHqPBXLWpqQou5H&)ktb+soZoH-zI+OYPPP(_Ij*FRf**5pe) z(O~w>#JdGWmQY2BPj_2eeZcM)c;bhZUnX8`aFQidQR11EJJftU?sQKax4da`M)R{Q zp^6f7&TCe)=eF*iXm@1S@(*`PwbQ!m~2&kp(RvNqI3MHntRII zdg7G!wtMWqC|PU6KeKr)6^4>ANFYS`O@CbLlh+j?RrMdexv{Ot&Pc9p^6fweXLbjJ!;#Rvy;P)IM?0>RZ#*l@1p7WLH}2t{Ak2icVRnn31(q= zdTujw&&9p=#hK41$IaW_whXFhU99c74eOOSV#2U&a_mpjETM`L*durK>+gx~_f{v5 zZuqSwR8azZee*GodZK=_CCOcrEy{U3s3?JR;qBwz^u*h9`X#^lV74VxQ37Yo*k8wc z;@a3V$@+I3kw<72&d`?qHhW^|vKh(gZ}zZ+DoWt`c(`%HQn#;ST_+|ldiZQhsGY=Uhvuq6Dty2Olc*#LI_vPQJ5mALk*85@<1|{!;9TTc$TozInr` zmQY0rv`S}RbFwFf{=6>nbLMzUsG&2cs_b#BCQ} zm?$Yb)Do&Fffl^@{mVV^^32^5NA26%5~?VHyTqAWuJ**ZId>Lx{-}v1R8azVqE)M| z^+eAvd$s+%d3{T$q6F@C>jn(<#G4J?%2buCvOP;xlrV8=cqSISGp}vCp7-09A%_UE zaMx}&cZm0RcK3@44j(ep5~^rj^bBS^b0vu;%L?i@c+L{4D1qL`-&YRu#MlK*6T7@r zV+mE1Ko2JoyTB8F&p0`8@}_q!p^6gdMU`HEh9_pfc3Yy|d!JfD6(!J98@2HSPi#A- zBJucc-&sNxCD0pOF{Xy{DX#Jmi(BcCD1qEIi3n8tfdzPvwq0fotetyTeRIjpYm&VM0i$6H9v~}+a zbB8Q04r3?<{t2?!+|`s&rFJ3~3y5y0q(m4y?51Q@lHi> zP$G)nVY<)SHEwrT0vRN~lsh0grR9JTJBP;dRXOf3#Le$6{ALyK`ym zGMw$$S4yZ-I{}YrqfSbdoV}0rP$GoWMDoM;;?LCxGrFH@yQ=aXdI^@(2)VFDe^D~{n_s+#5~|crz~h=;`=`3UdA#*dB8+3P2kxjYnSVA~AM7h7RH>bSM_GA; z)L%E8V?C4z<5+CuiI10zT7$k1Jd{wSb^;y~3fC3Yv>IeRlnCQkZ0;Q+N zs8TxtkIVjis_3tquC*RYgmEl3qyFI~10QVVJ(N(Tb^;!aHl9}W?1YilLy0hs#rA2s ztayCc{@z0gRca^T@z~l$-CF-M)_N!r#%N|Kh8*qU4P(qd333xnEy=lo&UyZXK zN`!GNcI%qKRsG+Mdk-a4shxnwtoD0VE-f5mJ(LLJSZt418&v=OU2E^5getWY@c3r) z#LDwFU1vR%2xHS*FF&LD{g+yL4<%Hooq)%PE2=6db-mJhC=tf7Sj*R^R8Ky$srOJq zmD&k-+}{3=%7fcqXg!n&<5=v4qbsTxd}!K5dwnROO6>$Z+7>m-9=NTy^-v;=O}pFv zz3O)=|Mu;b5~|crz+?W3L$gn>KgN0}5yr9Dg-8BeT~oN;dnlnw?F2kZHP^ESP9`{sT zobA2hdwZ`{B8+3PoqpJ>re-;wYtbeup-SxpJeK@ zJ(N(Tb^;z_KfEEk^_FX_hZ12Ni+$SvfSMiVd|2$ZLkU%CC*V=%h_Trtx@@w2I3>b3 z7CV1Y+nT#y_}&~d>?tBP!gC9v*PYA57)RKi1vFm}iM-(7oFM~;Uja15x_PQb&TC3!?hyK{H> zhTFY|5;&Kr)K0*|pY7H|i7w&_+?Ioq&gLMXiStVeH!W@2{#`29??gc=)@T^-v;=-Mx1A0egE7C2;SfQab?;e|NSXN`$fN zGo1BCYww{1?%`BwC*a|G8P-FIFm`>PFRli=w8E<-a`rW4XM;lz{B@m;bHr=BtqKtsdsq3z@B&;Ms{v?F2mh(_J1B((akF!yx>M3=bvn3`nJR0v`S;)p{rq z#_rkq>iU2BHc<&Y%TlSGfQNtDwjN4^v3mz_@XAlUhZ1-ur&2os5C7J{dMFXb?p;RR zN%#%``$`GCTcA=q0T2K7!+IzY#_m1J*|Q$@9!lUH36QpmytATGI{^>>R?T`S5ysK?j8Ovb-uMQx zb^;#QNAADz*^tm4AXL7y^u%})s%Rfh`;1YKT*CEn^*v**hrUD9y6DfjUU+TW;ofp; zUtQl>=6YcNxVM>6Li_O1?NCCqa5UXJ%Ulmtlt6#ZJr(6{hZ35lZwl>N1;;}bCD5O9 zPj|T}4Eq6GSL?(IjehZ35lZwjNwToonIpL1_yN@#Cj`-Eoc^JkP$MG5WIY@g69eg2FRswknov+Wa_rO%&HLKP*nm$`jHv-J5h zN~ofQ_LjF#XqG;IMhR7v&|d%c3C+^y&nTga68iMAeL}PJ`7=tWqJ%z$ZJ*FAeg2FR zswkmPlj-;k3&*93zwX}cpoh1$xZ2d=hil2=RpEn&Mef@EXK}b={~(vdyigDVD*nOo6W4j&x`zz-`0{eR=epjb1_`FF%6~?H`FVdU`3G6Fop_XPbb{^AioLJPn&h>U* zslpg_`JJ5eAaQN=fSJrfEzM%=Jl-5|Xwl?zMyKj`II}<%#;D7$_nZd_oL9_3EzM%= zJQkdDU$>7>AD3!1^wxwbj8T{06gm$Q*jLO#EzM%=Ja+r-)g_;9bl(A}!Web=ZKU%c z@yw{Q46{&6vlu&%Uq1PL=^^p4sW(5qFQW=$)a4hO&V$4*2h1#B7HVl0W9KpH_wy=u z-8v$*WACO3RT!f#zaw=XB(SfTg<6`$*m;cX{AlHn8;08RN)^Va%dcCV2Z`f$exra{ zsHItqoyW~1R#t9UaCxfksSOgUFh*T|bL%`v9Jlj{1yVmWv%X9f#;D70xt#|I+|QYXTAIb! zc`SY4gzPiD+N9n+Xa9^UjO}*#Z_k|v2^tftGc(C{I?1({AZ68h*#;D7&4$gzbwbdJ* zW)^B`7GvkpwCkwsXG@MN`snM^3RGc?x*UPwJV; zjJg~b;yg&4`S$7pW}%j5F?JsK0;1We&y+ng`{0BsjOl@qFV4dg1%}8liyq9v@^Gw- zU#q209{6FIDvVJVYm4zXk?pY0QOtseW-)f#;rA|nHyE!9W7Nf7$0#A^LBh1VWz0e? z&0_34{8>`DcG!0Zs=^p`arR*BlJg+JW6m*3n#I_8__N(^hboLw7gqtsU^x#G>n?AQ zU>0g=7Gvk(uiDD^o4pdMFh*Tm%@`TxJV==SRROb5OS2d|58wJ^Up;rHger_t7p)S; zt2qx6*jLO#EzM%=JbWvf#W7cfG3ugq#V9)GLE_)dtrE;aEzM%=JpA1t`_lcFCRAZ; zx5JF=!Pq|MK?2*sEV~_&h5Jf48qnX>vh`aZP@oE9)WzKnBMzMh33xCI9-772ZHK=* z+kK@9W7NgH9pfOKhY&Glp_XPbb{@W$VLen~jJoK3V05PQAc4LQvrtR37&{N&TgvYE z!$-F7!;zlMLS6KtFlN+wkTBOrhFPekS&W^B@AYM$+Ptbv6~?HG-XKP@Iu8;!9?U{5 z&0_34eDBrnD^(byE_$^XU+X+b{B(HJ46{&6vlu%M-wV$^KK1D`RT!f#dgmDR>pV!j zd&~~D7tYbWn#I_8_@{~Nu=C>yRT!f#o-#0c*?Ew_zG4cdEH=RpGZ4`!j3W-)di{wXzk*z=dS zRfRF?;^`IR&z%PeY&o+~OS2d|5C61n_mwJ)Q5R3)7!~h4NSL<0EwfNdvlu%M|DGZH zV#9R>sxU@fyiLGZedj@9;JxSDw+0-OuUU+phkyH#y}IeG2~`-QF5Ze@1_9?m0{e4a2_Pi9dNdN8^u`_G>ftG@Nddx0>xP6Xj8PYFaWU_Q^B{qJ#Vpj)EXK~mzja0*E~W}&)Wth%%tqoownu0dW9Q-D zo?8!97^5zK1#liDep}u=!z|R&EXK}*zcd`S>BTZt7^5zKb#NZj<0}h?zF&Pfo)N-t zSi;{}kQIIngWp(Iu3T9-ZQP@lP(^>I;BO($!xQu1p@e2d*J@GM6@{tGu51rN>*^X} zoA}Fy`D*g}*9*s9eYYi4Q6l^r2HP>~uGb2`&o0X&Gz)tjqch!h>~QESg~@?GTS65j z!mnZAanpUi(^JL-p&#$+HDoTXk&%opO_Z}?l(tT1Mp;>4vF&5c*tiNn(VZi}YETM`L z_zgN7Ke)pmlM5dkH$9KgEdHM0JbKL>U)X-~qn1!biSYXwY{%NZBMQeK^i&?9S-8Vt z+_v+$;)=e7YyN%45~?T>em?_`r9I9md~u&=^9aqtJs6|OoyW^>cPiZPvlrZ2iJ}Dh z4;ZoTh;vsRUf5>xir(!K@L^qf`4K^Rt`Zu-l=E65&@* z@VN8hiuu`RUe6;m3(r@W%ffj~Z@XsxzH63QLKP*#ueadwK>dH`w;B3M9-&!yPQ(lw z&SUEM78MtzmRdp;CBm=J;4$_84yd^D$R&A%X5o1k^L{vwK2LS8=$l$-300H`zovu7 znD_}5Qyb|v4kp0gx__-e(?>D ze@|Fh@xt}{r<5A+jNQ6l_e6CNO@eYEp~wGkZQ$oKHh!>`qR z5`6Qob@^63vgMXgMTzjMP}#eAgl6fxcQfM99YIT|qD1&rC_MaGl1FG3->SRq@Mogg z!{f86C=q@Y3J-s_=MkF4x9ZMg2X{qTLKP)&b#Z*8`S!zIwRwbQ@vXY^@GXNSR8fNO z$Q|KZA4{mBMED&kw%oUHd4y*19l7)Ht*9kbQ6l_~6dt~%&LcF7@5r5pzZ_KSAaZnx${K&DcKolxhi8l)w`!M{TC#{z*8G&@8^ccH7~fwk@HG z68g?M9rsW4mQY2B@XK{2+e^X=$Rg?%vM8Lzpjmjf5i*KXdcKA15mQY0r zy#3;+&2-$qRm&qZi*KWyhktWt300KPH_++0e>-RiRg?(Fv|!8q8^}CDv-ob=t(AYv zY5P~IC=rg$fro#Snn!4szJWIP5BIj#5~?T>jxmCVeN>8oAUd+88d&LoddV5tWF7Iykj@B{rUNqVw$S>;Q`vsVHvZ2oL@F1M(ufIKyXb+gtU50*l|iga63@aF|)jtIU*Gh@c zf9+j;{?A8ykH;ShG;KA)s0&6(>>Qg+CZ1YIj$(J|}Y#|9|>0WRiegAA#en!d0 zj!@1%`hpU!m7Ax3oLwuftt0-o=IM&byH_s+K?SiA)2=_Ws^zC+{95(9`P)pt<-HQQ z1hcSw?U1Ea``ySR_}Zp=<@g7M#~JZQ3%ZtYUvX{ST6OsTn)1H4d}#L-m0V(MDUaJc4hZ^=RhA6ZX&Ba%Sl^IgggJ_AYOC`4x7{;el%qS)3^wG1t}+^|N~# zVq-vXJCulCA0X;oP+2QM+8zJB{Jwg*?6~sm;M*)gg=<9u$N!u7-kw<0qHg(Jr@d+k zD!ByClJ#Tv@x;?(H)K|{e9sb8a*09x>zS*zjVJo-oG!ogwI?k>C71Z8;=tL!Ugy)AH7 z9~#x6{MSM5EK!14@N;X$vwi+szm@fCw$OS|L6){9tmMv;xl0SnFB$xqCG-f67+0?t zM-6oJyqa_4Lz!E4yU7w%kfp@RE%z0NNARg$$ZD+2=C#IuC0k|U1J9#-C_^5nesN(t<@uoZ28!Xf30 zPdPu2U>5vvY{HiM^)*iy-s;~Xj=KWs}#6!o8Ox136C zgu4&69yb{?8)sXO+qFrUW&1n9-$x0Tqt9^2a7WA--DjpMCRW17xZ|u{=ZLkvr*DTC zY5OJauV8>MYh~vOfBpLYZQV( z_4=F#`&ZkxZ7ae*95o&((0_k{dHQb*t`E0&aXgg3ISNII&>LG0qHySzGSeSTL8;gJ zI@8CwF+#vQY)e4wfBEMb5UQw$u5CKrV5b8!|6Kan6m#6I2iHBvuawIj@xtP_?(#&S zX4i^{P^+z!?GqY`yOr3(x+b}MAv~}A@dyYi zN+8B{!x2xaXk9E1dwu`x_jrV$q6A_tPsjiFaNmsiVIsR`VL!VaR5S}7 zyo;ve2VV0>grK4XVlGd|7oJ#^Y1{LV?9!ql>p?}c;KBQDI=<_i#u0*w5{S9nyp8I) zN16G;EsHU>T1&IAoOkVX{FtIK86~JFftbtF@#PaPDQorFW!X1U@7k7uie|xsy@7Q6 z;LZ!$DnUgF#9W?^cR%;fg7t$&X5aee4C_Hfv*5vJk#xM_&^i%Ru4nnI`O7CtP*DOgm#5=@y}nH zYqx`nX2HX?$9RtVZtTGkf{GG|x!n9VF@1j!xEojxDw+ik_Q*{uy5_Tl5>%8x%;o8L zy6#5_v#*NG_*d&eMYG_+KD>F$`Q*OXR{=pq3B+8Uju-8_JC0z=wC&b|ie|xsPXK1t z(_QhGRYHP_5{S9n{1VspT%3t1)3#d=Dw+ikJ|~z~bmE2xK}89~T%L}9T|F096y{H` z9#k|79(=M$#|z90I3=hkftbtF@pkV#T436elxf>-TS7&%;KApTbo}v62cazq2r5b- z=JIs>%6EThYudz=Y1^#_70rSNpLf#nuXg*PObIGVAm(!0QfJVA8@+h=U0O@CxZJ%j zF?Rz?n6|w@6(txuVt(SGj9;sw+6ZJ}Ikpe)nbPs9&&NdwDq0sYmz&?!-YU!Zy=y(F zXcj!&al-TYD~*4P5LA>v%;o8LpDp#u{aKRITAGFBIN#h`gV|rN%P2ub3B+7(evkU@ zmyEwYtOpg%f(Nb}Jh7(Z*TwcOSAvQXh`HQ+Q#8D-c`CA3t@WUyS@6L1@1AS-d3g5- zK}89~TyEyxd8>Z8Z+)x>70rSN+A;SeT#%_7A*d*Un9I%GdCkv3FI;PB7M8pAc%0c+ z<8C=3`^6jgFE#%+Yjt!@&$myjdTq}!r66!;z?xt=h>jh{)JGFSn<#@B5OHk3ehX!0* zt%nlKg2&R#Q6+s=_4OV~P|>=G*^asGc;t@4RGlr&t%nlKg2%m6N=lmc#cvZ>DxRx43!<##$_Nm*$yeSH6X%?6NG!s325~Ch}J|Lhd!PxcmWvwc;mS$l&wl8y7 z*XVXwf{GG|u@~I40X+QP%_Eov4;-g~1JTpZC8%g!#O`R4@MnqjP=Zt^@+_V*r2P*DOgt}gd%01toFS`Q_d1rJ>Re|Fi| zdniFg>mo)g;hqiP;oB?gp#-zwfp)CRkN9mOm!P6`5u>$pzh;0iZ97^~>!Ad*;DI*y zt(EBM=Mq%3E@Ibe3xWHG^-zLY@W6c~+zx-ou>=*ZihQc$f{NBf%;!Y69p+4|G;O=}P=ZQG$xrMU1o3JsZHopY18FrCC^x z>n7}9DM3XE#JIZLvjIH(Rck$zU=}=Z{fGTTC8%g!#AqelvjIGO>tj8XU=}>s*LHhX z2`X9_F?;0hm$>QwHqZ3lxXhl3Bv2RaF8b<>V`c=JBbL8@SwOhf`GO#e1bfbo=yCY; zvavDzYU%2t7Gh>0K6&n#)bt=2Nh%~!Je}to<6Eq!6l1h<~PW&7Gh>0X3yCX&&C_h zTs&q?o(Ho)JbvlL#TWj1reCYw*WHpCFrm~ERJ1N)_Jf^A@~B_SdbPtB5MeFNLd;&R zBMR@So5@rx&m))x;^B1@i@*A=w_mGSdu=UiwE|ykg^Jci%zm)*c(3lJvbU%1XZICr zX%^z9M@}y8(C0+&apV_;nJ>=7@8_YCOTfdm)Hs4SrMhQ6=+eM?uoekqA!e`EtyTB2 zGs>pT!tb?F4`yL`i@Qe`pY}(oU#o+c6_-u=yQ?LrXkEnYqdJerKL5F_`Kwd&2xfs8 zx~a7I)M4GcNA-K>XTJQ_Z3h*tiUo*~T7e0Y~@BOlbLB9>FXSled-@ebBwL z_t;QzYvzhO@U20pXkEnYaXOFvc5acGc;w4@1hYV}|L6$wPGsi?2xfs`Z_p7p_gtP?-L-oj!7LE7-zcsM zk4N*}=Vo49agHUZXkEnY4LXlD113E^`1fsj1hYV#u;sR@@Ju}Nsa*=D_Ni~r5-M63 zF?)l~W75U9WR6>1Vm*{#76|t395L|G7Ma)o_%V-Q7KoP1%BsR^@V-owO!Lp&-ld{- z5wmaSJkGxE)w2653hZ_$!7LE_FIZR=wmzLp&&ce5$XdHrRJ1N)_6D8D(%F53_DTt6 zk#M~}v{(0RJ3e#es(bT1Kp+dm>~rQ-h3#(Nkv%f=H|=D%gNoKg%$}NCtHsxRTsG?8 zd#r~N%mQ(K`x#Z?9p|Dy7M2~}{~$|H(YlD)w{sp#{=7Bw{T6p#DZwld?5R28&;^fX zhMl{M-3}#~1>(F0S5}30=fie8Dsyh-3wEujXkEnYcR7#KmJKfJ)8mdjf>|Kgi*m#b zCwI=AbLAs>1hYU~eR1QeuwU}foI5kuCEZ$4(YlD)i*gxGQ!jzi{4fMTKqq+wGvDS@2-LD;+;{@$`%mRFpu>%th!8fGt zxNuaZ*3v92XAj5xD${3UgrK4XVlKx>y_IE?PdO{KqTX)iO;A`%v#^}K5A&C^j%;6` z1QjI^bGi8|W6S<2*tJ`$RIBQ35fSo8O8a=$xpNDl6J^ z|7)!W70rT2*pr!e`_FprTpu2>T_u1QjI^bGaF#c=v5s zt4eMM70rSN`x53C-ktA=5LA>v%;n}gnQc=N=6GazJg8_EJlHcx$4j2NB|=b90x_4T zXIl^f{GG|xjY@edghL}8&vZCK}ECR!8>X? z-Z!0z5LA>v%;o9$&Z(ob4gURY>Hqz4sQKFP*qTS~Y*O{wF8$2cpJ81r$33xQ$Mek- z%d@X`%%=bOWvThUC8#KYn0L{D=vEuSED*dunsHt&4$Iy$X<_ACpSMkE-P|?g9x+>f zTPmAeJF7CYcT-DHQ3CPLo35-nc2OU*9S=WTkZrrIVYc|Gx_Jb%;LRhOj{i_~Y_@;( z-<8KUf8X8*sc2oqla76`YQ}?S7>`C{+hi}Bd1Q7_*T?e+X2FAJrTNOD`3c!>NAHzA z{gCr4K}G8#E}Af>>gF>~HXi@{)G|A*#Yx#QPfoOVP9>NH4_+(jc$@hrX1C31m2LQH zy>eBwF5}U&PcR-0S~kxf*1%9toMi8utfg6~#1_Nc2Qw#SPpfH??bPWEOHfe)G4{g1 zfhES{+k^MWp1kSs?2+GY$Rn5q54L>fZx-*-E8Bhf50xvnEwcm_t&12(b7_xbj7Rs< zM%lejsgvF9%7ne+D8Vdvumw-YhyL9wd+iPnR5p0Jt|h2wUBtL)y>QK}G8##=G>l|`pDzY6#+zus}1rPQNf_+uQeMLpc@Cf?4oj z4<|V0MLgzIv@YV!Q~H}RQ*vIVcwQ;NEOn(-c%g9K2p3slwcM- z!oH}#229J$U@yv|umvrsAQQ~S0g#kPcs5{R)EBJEX*?UfSDf=Bpl z;M>F^wuw}7V;K3)EplvT=+fGI6BF0&XdslG(DB}G?31-0~yyN)$ zU^mHeGzM_&#?A!2!s`p;y`}V)L^eedPmbrNZvq19>=RB$h zPbv6r?q`;uf-EH(jy|U<7CXsrdA&XlHR^Ov3%lh?FpD1UI>#|L9%bqQ1zAeK@9?9K z_a1+5`Lyh+TMi36NH7aD?{IEA&aA&*`Lk`dwp9hO64=xI2J#L4cW*W>FaKv#u&>be zfnXM5-r=0bF(ui|+$Y-FwW5+s@P6e8b6zF%yuy7Vm%v#$@m=jptfXL6#DmZrZ6hygoLL zx-rA+LkVWl!`-9Y_0cf%-Q4r-c?ALrvXp?IUgzQUp#-x)^X}ueL$41i+z!-5j6EH; zaC&_x!7LEG`#2B1KB#D2#Jra{Laz@hxdhw!bbQq5lQUo3HzIZGx{HfqvEKF=aNW7( zSkC=szC)fqDMC&k^@6JteVk zK{~b5BdtxJ)NKa|(pb(jKON5{sAyfpT%L|sUjI&_PQhnI8)go)9#k|79=w9hn7D&R zM+hoPAm;LP{IIfx!P_XUrCC_cwkw~Yq6A_tH{XSCc?D}#$?c$`S@2-1osPdVWS688 zRFpu><>~lC*KNS@$ntnl(JXlIUXqR%ul+tkP*DOgmz(F>##0jJyvmw$*Pd5YGz%WQ zC#K^^-F9z;prQm~E>Fi>etuqo_psLo70u#yxVB_ik!Rf zuxC3JtxG@GilV;v$RpTtayxL{M7G=#*bZJ%B;di8@4pFV@p#;^Kb}&tM*awzx6bZJ zLD9O1+4B82!7Nn5*;94^p0?rP&t2<5Me8DF%lF>|v*3ZNAoTFpp!J}lbrG}W3$_DS zZ63iac;Gq@_myu;+!6GO)E1T@Sh0PfulbxOu60 zx^uN~9U$hJk2q|1@ifu3;@-^Pr`9n~6QPnz@SJuY+as6-I@}I;47sOoX2S5ZtOpfj zDZz8vd4QO``jv#%;#%R%w{&nk;DHwIura$^4<4yp0&R>tf+SAfJT{MD7HFP5Zmr-! zf(o*f;5i*0kJE}Du-l=>fOj9#u1)l76+3Lqop!C*CL&9T@Qy=*Yo!FUK(hr8wj)M@ z3bK^I_PM)(pYtQz@3qMZGa|1PGimr4vux~VKM7`vNykY%K6Oe0bA7luIqV!;wGfyi z1%%nVIEv;wcKf++*+-Dbb}?} zPDMR*ZPW1qwjt7oOWMAd(1$yTbRFt5HJA#8RUmDDjV!jwJ7u@fG9imiw{#_PkG;-F{d8n;plB96 z!m*aqm!1?Ms3?J$%gvV@+0%7Qb)aY#JUEKd{03Qid4!;%1Y#~X^WtnATrOk714Xmo z!BLcE?_O|dgrK4XVlFphk-N4omoe^vqFL|=$66k~=FkX1MG3@QZhjNqwS_r?<5Nfc zT7I|I(kw1_V}5EQpeVuE5$oFQ!nLZ@TAGFB97So~Up)|u5LA>v%;n~oA3cjB@2v+F z&4LFu!P*DOgmz!B`{#}OoeK-e1plB96!m*a8zt&@>5>%8x%;o9$rUUoa znJEHAv*3X%%8j+W?%r$4WcG_dQ37#DOnq~40a{Q$Cr6-Y7CbnL(#)Q;h(n^$E=TIjErFt0@Zc!QbbOCf3L^v+B@lCYI{stJ;-t)36DXPm500Wt$6pxP zJwi}X0x_4HuO>V6PMRZ#IkvJ|OS7Z4 zY1=W!mTgO@Xcjy;iZUJFcI9~yf{GG|xjY^3Q2+R(Y1=W!mi3^bS?~zQS`Pf{*a$&I z3B+7(+jesV$7fC3-dJmC7MHuRmZojbBcLe3*bz-Wc$+h36=^Na!g6e%8*4d#!#2l49@c}3X2HW9CycfHsrCC_c zp0gbRn(|}y&6Xcs%JG#T*pJ3?5Wzew5rT>mi1R!!R^NIk!7O-id_%BS0YOFUA`Z74 zwPhr0P)oDm!EqYSLkTKMAP$cpJY+;}P)oDm!OmY zTAGFB94nPiP*DOg?gqg)dUMP>WuLsh+`KOdYiSmj2lD|~;-u2o0s@K>jDz_AQhqzk zUCntYfh;V?9tq|(h!9k?E@JGfU>=r~%!Cls(kyu3$OiK>Lp}{;85rT>mh;i-)^RT33W{RMeX2AnjS}w zMG3^=lb3JXF~^qmP=ZlFYl;5Y^IutW$dS{Jc9ntmP@ zo>$gG31-0q=UXrjON5}JbrIvN4CZ0s^^wwAnuX=KZi0DOA_NsB5aa3!=3zlg&AIe~ zTABq9T>rs5ED?f=5{S`C1oN<Sydtg``XT9@#kX`t&d$~uMZ`d1;2276yAw` zT%1U5T=T9as31!T_O+eIb9W3+y#3(`c?7dSbA*y3zMcO_;^t=OT7n9)lwe=m5l`QL zWpcx=ZSB5Nf?1&1b9Th$6{jROzW#rC9?Sy4F-?x>c=Ddf<4f?nTBvAU#Oygc;^7Ic zl0&|mn@2DU1pC2`_+;iG$+NHTXt#sznuVBSnjFz=eVt@_t6M87xdi*cj%fH%o#f{J z6YW|l!7R`m)8vT5_u4ag>G(!=t*9VN3B<04jI*S9wpnu6lRMN(Ad740`nw?Z{IOed z?+c6VTB!&7z92Ym%B@xE)=tUUPd{M^Dq0sYd$o?3`1G%dMdJ^#Yo!FUKyVb4BbJ@i zHo5-uq1J0IFu1icAyd{rd76|rH9ntN#Wb)_lp35Vc1%e~39I?yt1Cwo9 zFR=s_t&5mFPDh-!`qxB@v7hA;%mTrYR*rahL;d8mI&WEmiq=KUKB^-|4mmNoB>hYt z!7LDHV_aVp$NZ=aQ76^{CavsO6sGpqiihJ^+qID6o|LBMfhZQ9I4_jkB zlwcMJ_68ks@`Q&JG@8=S`@o1hYW1Z|8{dUo=kM)zn>sxrCpGrIh2p95MQ=#>s-wF}od9v@X}s z_4;tOPwmh)xp?E$e>somc4?a&_WM*zP|>=G*;8}G%mb;K6=ZI{ro3&Jlu&)3IEhGYe!KeV}L-JlKoMC#Wcan9I$3>SOOs$msq+(JXkdhm(#cF4$P01QjI^b9p-c zabi(I<~0Zu&4LGeIOf~)JvT=PDoP;ca`W57;Fd|5pCM2*3m)vRq~l9g?-3!WD1n&E z&3Mjd<4KukB2Y979_+7}5hF)+i4atjK+NUoc)cU~C1t*hK+!CCu!m#5F!!q^-=06DXPm5B4R@%tk{}IxkM3D1kU6_MBXtk=c3zMYG_+ z`@H!}%BRnY5LA>v%;o9$Nqv9I$UH@XqFM0ZT{|5=v$|fn5>%8x%;o9$ny>dQm-&_g zMYG_+yLLW7MG3@Qo{q2E>A-TCH!4sx3m&}Bn_pk+913B(~`#-FFmJS=wnxf!og z%JG9*7t3)^4CY};nR!?^t4g3KftYtuI}Zy8&fF3qm<1xdbDDWrQf3|&j-wCOH+K!g zeP!lhNttJSU5jJgkTmt!fVjX0g*EE zuwV`d^WAHxXkEs^JQFE14-4m+2x@5-Dur!{nTI81=3(Jn7J;G!V(f)rzKoQahlTTH zLpeKvOQ2|7#E;^ z2EI+?+*E<0brIue2J^6>-R1mO5rSFp2%m9$+s-+*0!8a0###9q=V8J9gY$Sr2xh?} zyyN)$pq-CQ6|IXHS646(OX|W;c2Cw@@R%9L61pP}$9d%v7ae+PvgH#)EWuj21V?bW zXXoRGU6=gnoGEz(vq1B%?TA};dn|EYylqky#7b}kmm|!a0|_%HM;^f}(7Y!)V%Hmc zB-dUr*{&58WGTTroFh8DSCSlbcT4L*C70j`E=M$dc1ZH&pXON)C71=8cQ{Afbj%gW zk#oXLkgt0wP$C@l ztM@2uhh87NFTq0z-b>tC>GeS+m*AbjJQeNpCugR>JQMa9aNW7(SkC=sJZ`O%l$j|4 zC3nk1;pq6IAgIBQmzWvp%5rT>mh`HSSmE$ElCSPo~&c2P(TAGFBY>Dy- zDoP;c@^pOA-19IG3+Iyw6wQJM+h8+)Vv{IAMG3@QZr+y+Xvmo<%viy&mS$l&?>_1H zjCvy@1QjI^bGh-jZyRR>vgZ{Q&4LH-iTMN-B@lDDIfBa)<>qYXJVk+`S=F0~|mDeazV&A*d*Un9J>%sI$Waie|xs?PEIL z{KoSm1QjI^bGdnTuCq%*X1NIz&4LHp$8`MEZbKpj6(taJxt&2ECG$*_a)dqVvQ0Fj zzDqd@KSEThq6F8zplw@1>?suCz#7jf7o!lUPqmbDVhf=4*=-mevArpT(IbrFYc z;(rm$LM4v$5B4tS#R(LxiLrqI1@P=NuX$5 z#9^BVkL?l6f(K`;aC_IEyO{ALP_!=MuuX)AKX>y8W}#9z`-NYtNmp{0>UzlE%xI9TGqbUI znh4uI#JnaDhwU!zW)~%XPh6UvZJrH6C6@@#_WvT71v=ag5V>pRXHp5S75cfeoy1FD ze4No*nuVBq-EH~h1G^{J4#v}VsN@pi*$xj7caN;dBbWs`Jg-2!(5+wc`R6uRf(o*f z2+#K1?a*Vu`x5D39u~V++z!-*f-EJ%J5KI)D8VeyVcVX&9aNB|M0m#mvCpKx7M?kF zrTHQyoa+N|`0cq{?q=}-F{f37g+qsbTS$U4wdoIL3D4Zh&arh;9xVDZM{O*Gb*Djy1fF76;B$vP%x-a6f9j(lkcRgu$^KDdE z3o)}8yYKWtRP~D|U%2v+*-$v23}U>8;oKrzTens>zr3+SR{MNJm|e$ObocX@1)#SsIDdG!}Nm}&KcG%?<`Rw9MgccD(=yH zA&($yp)Ru!a}0&^7_@cbLY^g5kfqlkD>>rfey1*|+iGvS<-DHhfsu2FF*{J$mV9}7 z(*>_Rc0k_o2uBI&d>Pn|su6EiT+`?9JR%&sq_bau*sss<3LX#aU5tIhns97a{#wo3 z{LK6T{+M%pa|s@Qx8+}rc(age#bXPC~X}V)0=j9-ETRSTp}ECi0yc;->DtA zca>lkXm>qg93+UgGal-|c9#mWI3hEDt)6MspyPGEZC4K^cs)9g&eIR>_>4aj*#dAo zFxmw%TMS3sSk$EB|M|0>N-lwY=*F>NJ6`;7YX`Q8N-zs_I0_rY$d@-RV7p5NS=v&w IQab+s0B?#a?f?J) literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_3_upper_arm.stl b/lerobot/common/envs/aloha/assets/vx300s_3_upper_arm.stl new file mode 100644 index 0000000000000000000000000000000000000000..111c586e18fb0f44cee7e4593d24c71382a6e9b4 GIT binary patch literal 102984 zcmb5133yaR_V$C~F4`)Hs3yrKBL0$IWYrnnr*=ygP-MjQ3I%w#THB+Zf{k_Zo|G$kltf=_xt?qgI$$W5MZS!j% z4kT%qkO9_=Ei9fn}JTL?V+6ZlhA0?J9 zjkW6QPjNPS992rFq?{N~=usVrTG~*;r@hvQ5u>FZR;q|lNs>5Q>VY+!G3WQ3M#1+m)G_FWAE3t2NtVP=x z({AiWgi4g4J&b%euGm(2B~*)Tn7gx-P)U;TEq%fq5YmHrCD^*q;#gQVtCUblIWeHH zY-u1kcJoSblt7DP+SkKM6%i^)5`N_Sde|t*hjEoxf}YOVy*)Y6$oVpm6~q?7<1=J`RF zWVT;=awA$m38bl|9>Y9?BmP+lLM5dH=xAJ-4M!yW6=-VFc39QS#%nj$VeBS+VkrSS z8dsSef18MLmC?LdDrm6{{i+7dJs%y6ah34xr37qv0;T!<&bu(K5(HZpS{w_0RRghl z-lL9CNhtvv5z%Y}##KfMjuL2bOh=`{Xm^B4N{P507*95%a;Uiy9PP-Lb2Dn){C>;7 z$GA%D8A^$`KQPKW)K|G4)Vw%rk+1rgVrs?rZ#7m_)MY;CF#l22(*8&iA9k2O55xgm zx6DS1+&|Z=_WkQFv5~{^^^Zp7x7xnn* z`Y}0`D8UhvB)}=5TI_%CuUHS1ius}sSVGQ^c$6S-mWuguWU!xU+mA%3g8-+5YOz#) zv{xU}p~(nab-LtQ+p%ILINl8dcI7;aBHN zG8^PtBS^=)4DLl6vY$B{s0V6@_W|ruTO<4~V{HU!XmO9?>!GDmNo$0!ht^yPrlG~X zR(b2Hq&33tGWs?=u?71>38tZ?d&XjF@aHFmK0i0trs9w++6wE$dS@Tz(kKbj-bVEy zAB8?YH>VP&LA`pL{7n8d?qYr#KtF2iv^* zdg${*aw=(!@NX<@BS=GQcKRLWSDOv^ z_I*{NM33rA9PMq8FyH>D5~@YpepO?s;M-NA1nngWcu^%(>!qbfyHZ6y5pCssyGoQ8 zIbw8@r~`pERzkJV|7b(+MOhD&ius~-Swf^qC)W?GI4V(swvz-(rG#p+RDQ+r`^1ye z*aIbJUpoL?ze<7#ZlNxE@NVq?Cy3 zVKuj1-^Fg9s08~T^}u+84L?6XaA&EKQiAQ~`aEy%A8wzh1jjM*#e8IMlK3aySZY;L zO29_+{$Vy8(X2%2JckWGO0aviQn_~=mI{(m0yd&?g_>8Q1(aZ^pv5-yGs?Hs1CCHh zDFGXvKo8m*WLK0<3AQe@I2NL}R2wBd@cxlkNhtvv5n&^-2i_(U1V;(9IHsdgMTAO9 ziMSqC^GtY~$Sc9oj(j;cqt?Z&#rsEIC8b2%A69;Q=k)KjN^sU9U-cL^uEKdG&X`DG z^y!{K{YsKhNs@?nI0?e}D~@X22hp~#xs<9|B}&kqU(e+PGSOD5rLCSkxl>7!(EXL3 z!zsbN4|ZWX-jXMGDk&#gJBL%kr@fZWg2btFVtynE-Cyacn&!p559*<_IdOWPnCD7x zALRSPdeEKq;gnGGQZ4mLZj?lXN|J=`uf#^eC+aSYw!NoTLM2Mjp5OIJTV<3`Ew-Uw z2bEAslJNcEcdv4ino)wS8}Guoaw@@5;@7@7U-p0bcLOCZ>B}u~14_^D6xyx4-rhMITzXRedOKk` z#-$sczur#IADCC^-f=#=VLN-7b;e}(j9t ziKlPA-MxR@vHR|JmJydkOW3>necr};W6j35hu1sew1qRfsziwo+Fs;{{1zZKd-q;P zY(4LdoD!%Y;|vgw{kX{0khpCa@V@^U)#A!3Dp|axlV|mw%t4b_3HW=75UzI-|hnnMaxV3!1v97f-e<_ zZJz$B3WQ3^iJCxktY6jKcVT_i-h)OY2<>wnW5raThdVWIH~6<1&7H2wYoGh{0N2mu z#9LQ?;|P_M69e4bET&MZcE`Rj1Eo^Jr@fZeub8TQbaKw#ie{qUwNyG{)Lt>wYr+R0 z>>mkVb|rk;KX)~+g+6Mo5+(fTVLhy^YWqA~p97(ia>9EhSM%DA^(Qr<=1SJlQ z>q4n~NwkE14f*S4lZxUNrctK6a|+`&>u3&K31z&W8CC{HwEXUa{{h zCs-=HO+X(zW$&X*VqV|-k^u$yDD_?bD_N58UO!31zRQ2R1A!gC`Y0v5UoqRxUtx!T z@{mW}JEsz=rJl%kOZKMn*+DQ{=XZX4g^h~-D_U8RI->8Nx&8AojK!SPip zQ9`|)^~e1i!86oh{A%lJyZPtb!vz9RAUMyl)AN0k^bGJJP{)kY(XOLXy^@=QJh=;m zpKD6^v^}S1a0GmbN|ews?Z1XwshsywLbZIl#(6vcjUEK*qmm>MkI?@{#9GPLg@;2O z+RvPsuCJeAqrGeP%`K+bmt&ugwC@IsoS>AHY~i?c6}sPY(6Kg5+&;E3x(?H zHGMa~Z@ds!ZvSuz5o?i%Y-CWXtEwm3*Nhp~&%RVAcAlMON%$Nk^sNhG|9fwa2uPAd zA)6?bv(aI|Ek?wW)(BrJ^o0#8+mqnmR6Eb>Vn5gRkJEMiES=@^V#;eeqE02P6LtMS z__KCTy1cSIUKdsEi>dpc9M`n>B~Lp-B}!PjAL(MM>sjAy zw^!>#q;=TLm#x;cG4`ejJo?$fWjx_3)O#a(v3>!0^{?G~#CO7ru5Kg^vuYC?CFD1r3Z zLk?)E-u;e1TzK!2xletu_r9eBwLqM6VZWA>ue>b~+ugorQ}qr%%meZCffHI-sz;ZO zXi1%OPgE*A_oaHH`rx@=H|*vJv}h>-8~fG|YnitC?m&EZ)^&3`T)T8GOGScOAm(-* z)Nth(BMoDKV4+VbL|_qw(^uFDNhOH1oZb;GXfRNpw}(6V}vfQ^Qa$4IFj z7TKHRdH-}HQNN^ z2U@84Ia}kq!9M+1T3@R3Q+=x!jIMM9B}&jnJW8&zQti3H`eno~RuX7A!s-!^M2xGR zJN)1Xj1ra#%j>4ZD@~IkiBrH@ywa+FQmPS`7(%3TYj? z$x(tCRe$z4*SeS!7;$I?&M5XE=BBst;9oXu`lj<{RSoq+t=&hpys+vH`?}!M`*)e_ z($&>xxAd4tFM8S!*XB-5f1idHC9M(5265J|jQ|ZT&?81%;B1$diW1sW0wwgs)=&SM zV?C5Wn)Ud!$0aQd$KDx;ld4kbp`SnH>Ol!hqQuC?y8?04qQ{$BBS1q7bbbA$&fED? zUG>;EU0Eu$F7wrvzPkGvj`qZo&5vsAGiNK;ACw^9QX;O$)k`;;(Ha37TA-ILJuQ?9 z-@L-PzI}s?+r6T~dUM_dExWz!`=34QzL+EkN|bPE>&=R(7$w05;sKnE1QE2fPUQq^ ztND6+XSx!40_Xbp4x)Lf7M`;e$_Yx8K>D&-r?*rbj!}You)Q=d)xz^+>ncHs63$+= z_D3LUH80hoZ9fvFRF2>%Q6jSU2*xgm&{i4EOSSNvBea~LLW5tJz5?Oh=Cz?edNXgc%owJh)}F=7IN|W<%-l+`h!ke7Fj4^f+(OynH=8jpwoV z`R@5C34#(OkmmDZ>K}#bDx9vMy)-Y?a<(JyQ%Y0^i4x9UM0|hrvxu^Q4SRdXeD(-V9hS-wuDm8uBC_X*Z*FRKkppNi%}ceM?a2Fl_xuhnI)OxWkSO8oMTCu# zrqJikh7wHs`qBH0xM~x3-ww4`iRSCl=zr(0jKIk`#%?(gw0u42ecrEJh*HIb%>(#X z&DYx_VWR{!cc)&Omulg8?0u|t@dY3vC{Y4wJ};)M2b-)8dGYICnbpL z;Fpwe_9B1P`=0i>V8e}FC76!t;k-{N;Y#H^4(6aQNo3CvHcBv~Q1iUzrCP2Yk@xxL zrrHD%?~p?K&|XB~J!(?nvfL&&_OU%&|9)pwU(+(abLhc&b(BdDcy@;l3Ye=g)IUOvi|O4~|_o3W%&BEvBfq!H4Pat zyo{ihD{Z3Y?;o*!)BXd8IYQe?i5b_O+tOjm?Y3t?%~!N6Y&`FjYs&~~`4-{M62#x0 z{Jrt>`>*qa_*x}0r;ltIU!aZjfg3ih-f5>Yf?B>F^zE>*^3V@*+fUy$lq&Y^O6>Uh zNiBDr$+mj@gx_-ZZ0^>#J)xdj38Xi=o$olqUhSL996L3PtJt?wE2@X{)UeSs zVcpz2qyHS&BlvbD&|S%q103f6yl?fxfxC z_OD@Foq5GpP2ZfADkG@n+lrnVHU?k5b<>Z-@#YoQaP#3vD}gcg`6;xq`;400!f*E} zBdF!;K~D`EPgif;^v4r{Y!tPZF+lyL%1V5-+q>uOvb8y?sx@7WSZY&W5r#@~z;k>1ephWA0G~3N~ufy79#_zwd`QgER z?TdSymulhpwT>p8~m4n0r6*exTd1sj+J-iFK% zM^K{qB8@rd_a!n1%Lr=024=HwE1Bo6ttioak>)-q;Y-R0YQYA)o$qt;iH@K|^F^9| zte6@;_lw*=@3<^Ke&uPk%nSZ%cv#`l-dMAi4sWjx%u5&Uu#^a^4;c- zrjKwoC{Zog;OHqQC{Y4wK6h<}2DX2=M;7O$T6oS`;9FM-N|ZpF&t0i1tsb?k2PLWn z8=RZv1SLu!&F8Ll)7Bpu_6H@Z1sn8AAes{dB}yR8=Wgt#ZCqt+?7C4xiE6<{?01LH zJu5*_q6E@>4jU2S<_9IJ#d=`gBueE7l!`M-X+BTXJfnHBRG{%3ZRqz5Hg?%oj-W&d zr1?D2gJlG@U;|^p?-^{gbCfuO63rKBK2MC@GJ;yLfzj@5_;Kq-yCW#ke39n!#EdE< zs0ACCo4&1N);fX`%@=7tPk4qhf?BY_U8d_n`VvP_qWL1t=V+_COwU8sZECmRr!*u_ z&Y0Np*Ja-CR?nN{_6c}SUl|iG_W0frlt4=f~LGO%jd2ToSwjK~$-f>TE&<-1y5!3>mdU8z5j6L}k`KIT-%xrLX25`=*?r7Kpc2j}W3)$B%RUj@+os z2DLz7uEeF9{r26tv2(o*N;F@j5BhSL)O^yuH|JU=ZsBYwK`juN^KpMnSUxY;_w!90 zL5b#z^ve$plK$vD_Q%|pJ(s(2r3AG=EbP)>M#<0huja0~xpSEfYJs2!_kI4%+xO*; z{Jqu@lxV(4|7*({8STrDosxTctNvvKwLs7ZdmHv0H8*wV?Hxgh=8JSiMW3*5$0z~u z*W3bEb0w%n8nfBk*!G!cb9;_zE+bGX&iQyXfQ`F9`zH722ak^G!SzE4wA%|8@qWo} zeLu*xpM6*vK`mFRX#IeV!R_wLeb(W#s0ZOKp``?Rv)7xv@3Z4)n>3xe?;g$u*9;KU zLKpcV*t)OeKW98`i@Ad+j8&Ou5vU!=Kq`FdP=_KmsDbFOf$s|2+`aP2Cl z26gO_v7daOt}oYUUJdoVqB~c3&K0hlphO9zdDkRCEY`eKi?;pBDW!4**FGg^&)=p3 zF|e*{{-fO{H)~$1h38!1e5sV6L;E5r+?kk*-(O7u)%fL6MO%3YeZ0@`63~FVgWXJ>(y3IDe%CwO9|o z11Kf9hHJjG=kE@J2sN+Oyi^O%xl$+E$`O<(fi&+bdLs0B89^=B;M!hJP@?%FjS=JT z2%{ch>{_IEoR@0hId=ozh7y!0fiyVGcSQN>B?nxEt^`l%PcOMVfa_toiF<$r!+3;Xip_aa#7k><`qZ?qOuhu^SgQy|PneAiV8=H%yj z*B{=djWQx}lRPTb*H^ued*Gcj^9Rp)y%slcsipb4=TTdIebu2&2_i_8aOsE`dq7pw zOP6Nz-#(DG-+*a0ln80w{`K>G*he2F2==q)i!`4XQ+u5ML({n=-{k>gh+2uhSdn$L@=ngJg*_03Fb{?oLJoDE7;3pO~rEOPRlpBj~*LJ= zY1lv;`WTZ^f)dRaX+BT%U|#c5Ej-6qKzu_nwcneIszRSTf)XW==5yy6s>0YUBd7%% z7}Guq;=Ot2rj?*X^F^A^ooA>FbI{qKM73Z8bJIt@m@i2Xlqi8TpC^2Yvq6b!xweX; zYs{BanJ=;5R8Z$@9wbU24X@-&Wxk{;c(^ixTCf3M>Dx+tq9Z8Le39n!V#-=K7kqme zK`q#T&-Z<9z63pp)xZ&yXue4Ex$`9$C0L`%2x`FwBcCu5qgBljlxV(4^ErG;v~s%n zL5XTP8&O1+%@3~5o(K{pTsk6b)^Z0>P6RF8OGNR`c5kr4zBC}x^ESKXd9RDEVeFd5 zUA9I{a8a0y!9f%i(s6v0-Al|Yy7apo{tpS`pfrZFocQp>ZzFp0+|1@0@>Y z%13rC>Lc>dKCKZxb_q7DFVG)(5|ES(64V0C=m<{?{rte3wl4G4mS!vvOEoUCK?(9LC8Ef%yp~D{ z#^!)#ERcOm^|2o=DuuO0WSHGOZo#ct+-}5k_G~#pi4ray-92Zt2%ayAk~xNi;{ zob%-bC7LhNy!Y-2)B&-OnwM(fdF)G|tpp`XID64eSs~omRe});v>nCv(S{>X4@flM z$ez1_4I81YGMbla;W^q6J|@vtj-W&dXD@i7VyYyLMSN8MDD8;I`;-wuQePhvF0F({ z*SIl?C>quBrK0z_;g^N@9m0s(vYh}trAKm0+)_z9*DY3*FBn4Qc5tA!0!`J+j#$~2lqPAcE}iU zaa&Of&l!Q?iK*vytJ<$iy(1`rmJ)Hi0ZMiA;j`2BQ$|qBmr!C%@(WMySylDv%IPXW zS_wuH_)<-teL&U4<2p2!64Y|fBTtP|ZTYuD(m!0mn%kTRo>~b;5_lWFH++A%*%=6G zdE4~Vu<`co7p6D=tYauu?Aw)KB!RcFYT4WA!_P|j9+cI9TCfp&YS`HM(x=luf4!k2 zD1nv|j3n?jdcO2=`plDmsMNfWrWVrl$DWw;+j`+`B9@dAprbgie6ZnbF20>wk!|Ox zQIGxGevy9gg-hKiQQxja9B%;PmD^{e?Wc^Oma9kP+kJn0YyC0V)m(k85{xA9HJ{cz zH{EX26Uzu{`L?2OhmFRDGt-6J$A+56zE%lF5_lU|zc(v=?8Ilv2x|Fy(6__J%7O2v zpE&kvPXzA_EhQL9;BDM}UXQAQPvdRddQb>z;d$(-VZ&lAD=pSCp0#1^Q-WT}+pzgj zhdH8oAx$l3JMvc+Z;%f$ShjnOwd{6m3-12l?x-Vzw{tOA`4EHU2u30(fpmOB2-=L= z(!5lQw7-FEFi@|CRF<8!q64ZhX-tlxXSosixe>fYID1kJ3)5oP+3>N#`*-(O7u)*7uiE-r!N;F@j zF?M}is>NV6TMQP)ZW%!>*x=pB#QbmsC7LhNn1enpRpwwBK`q$eO-C1N$$9SDiW1Ei zY3_qu3>JM!89^=B;7!M3N_?UtDA9b8rsqqop8?oOliKvPsN+8`T z;pPV=s>OQvI2N(t2$YI5N@+e%v{hd7VyQsmIa=5686*bF5tJx_G@mDWu#BJgtLE!e=U^=&0{&=Hhq zzDV!p(#E7%6rNPYJsM&^u(cEA4@-VLZu@pftC`y_2!9Jj(ayswbUC8z}gb3X2mL*Ff=FS&9b zXM+;W7ir$P^)}kv_fmSzvj>+E)B?eqz@9kjnqs>0gA2)+?nBW{#f?A}bILN%tK_z%c97Mbt zpwD#UFM{*8QqWL0?xe~=e=5-D#K`juNk1?ThPzh>*;9BDQT<0JqnlIAuD{;+r4k|${ z5L`>V4V{COXue3p+r|B%b5IFtfq+MiM~TisC8z}=xkl+6q(t*YnroM@ht5GIs0AWk z)$BfX9zTei(7fvFd$sVl_u@I%M0cM$K~SOu(!431AZj!()uQbvZh|%(!L?5b+Kb{Q z^1S7(d8rnjbA|JzQi2jCTspcPjdtSwcFjw*@SJO+x1j_jN+6AUYf;=pp11BbFV(_x zuA<(C5|k)`H16L;u>koHgO$;|R143!ih3JLP@)9VyaVlt`xg#KTMU-7p#-&HgX?av zv1(iu2}(3yq;WSgikm<^5K-l9C_ydQ;JO>tBO)l#e38Z-&$z9ubrFN*Y$!o3*xQ-cXue4E-m@pdisMF!64ZhX?l{T` zN;F@jc?a4PVdZo-l%N)DaK}+jP@?&|baXqqO5&p^!Ag%bcNTU7J4zQ*&m`|tM-nBN zlb`2e!|D;|rCNB-eURO)P2Td3BxQu{8GPKtH_4miQ7bCp(h)H(d0Rb61TB<`y=i|@ z=YXc1+=!1PnlI8Z@nQ0wek4&X*CJ6Yz=!j`(wqI!s8#}Lj^ko#@H?01B;FvBs1|H+ zcG=&9?0P_gphO9z`Mj7~-=e8P43^EPI4{-0b9#wl>clu|%Mp|)fi$0^9*Jm zL2p-1P@)9Vd|pghe`r)nBvCC_zbICwl%UsF0%<;Xql6JvzO6!Dss$VI8fD`uK~SOu z(tPgb2V=0@jG{!fV1qG64AkF8+)YEYcma{>LYQY9~1I5(q*{&K<6-kspx>cf9 z^HMF=!@qw>sT_e)(O)rN+Vh0@61G(tK^ivDhCcSSl%PcOMVikOeV)<0R144Jy{PoL zBPdY%MiSM64a{2qZeYG7K~SOu z(tMuqC9YJIsFrK1C~jMPiLZH(D1kKml`oa~lE&Z@%Lr=0M*OZ;N>HNtBF*QnKj^8Q z4N6oCHn1A__Yd*yj-W&dr1>1H}!t`%kd?I*)T~7VYGi#NmIvxoSu&gld^>YhBvtp4xi;ZIfQ; z9Bf3AQi7!|rgpw()aJ*XU)2OcOA`H6L@SBX#ncyr`bUIHl!*Q!qpL^1Y;^`dPu;g! z^T-j0_N%CPZpn}pJ9is7VxXm$ESdTc(uelD|Ct3#p5L-l-(sqipd?8Q>^J_@IZF=z zX3Icq^h3wYaqVApHk6msp7dVeM3FE#PcWqWK~{`Pc33_U4lRK~M`eUORp}Bc6+iX4;@c^9}a; z#`Qq&wML-*p%v=UH?9Zzf^CI$Jz*Lg;wty_XqN4pW`WhG+(4qy2L1H zm7o@EprnbBnCIA~MDs-&eKGZmbhl{iwn|V7HqaMCj;J!?l{TkjHu-j0ZJ!?3+3)>; zWLWkOGgfDxo@ix1?)dD2XFt#4dC!-6W!HJQ!v213DM5)6NLN%GkbQK{I{$;9*5Q92 z*zf;V_Rb!C0SK%#`04yLep{$7RsUai53_c7cIpvG$EA&lX>Iq22-L&3k0-Q*F>&7o z-P0;jg6VH(e4e$t2Jv5~Ha&*(%{BNdh+T z{L+{}NKX+A$5LagJ^0eP7CLvu?;0u z(h3o5th?dKQ9ZP_+HOYoGaG?8?WfbU9+9LKB8!&BSL8%JA|mALw5+tz^CY2?R)}Du z%P)u3oV9FlrpJPgi9R24@@D<6AAe+a?=#=C5$J3LqIzcknrB81%G~s~PUsIIz zYw6zalW_-U$1GT7_2_xpK{an*Hz+gn@+6^J$mzx{hG*L>{?dq-F0859u{bF6+}56; zM2W3`?qMs#3E9QJfjBC2V9kOj2W4*P-YKsVCA5Ua)aEZ7P_wB2kj!`8IwlC!+Vu2) zWd~h)ZuUQi{@ZLUpE{tX?I%O*uefZTSBVlEEc`J$>ZfC}BM*Mxh~C@xuNk#+Nam3v zl7wmj;%75!$NY*THwb zA5)8W^c}yg%5?ku$?T7PE-kF{_2_<~Z=Ah06;GLW*rQ;+*=(#b0_O}MRHB61Hs9{O zPafVU_!8GXVZ;>ReY6##ah1ooQi&2_TowEr3^OY4W|W^f&W37*(O&R#FwELKX01w; z2&28=JwwfDeQL7b4$a?KjOK^SOSQI~{Ydtg&X*TDcEVa4yl5U?RLicd5PVl5;YIWC zqAF1$c+rCQqSu^XQ`4h3DF3i|(Ne-Zs?!?%T#tTN%sQcPOq+jMsb0<=ShGv>p!~GG zlZ0w%X^W{o&mK@SuK$pH-`zVV>Y;?TLgYm)4r}WKp<3F~#niBW_p0f$`{DUN-`qYQ zJWc^S7M&Bx)*W<1ubQ3yJv9IN%JzAcD4{(YdC@$)XhKUyOp*xutGw;6riXo-E0xY* zKKFaLZ*J}2_EztGSBwbR8@jozwu`CT`ag@EW&V>5e@PIk#TM~4!d^6Qd(r7CX^rr^ zzOX~i%Pzctx8JbyF5q1@?1KybeNYLND4~8O+J!qCN~l)YUl*{yP7<20`Y5GK-#_r4 z5ubAD>6g7tE@|x@$GvAdiGQ!*d6|2!wddvUQAxtyah;a0-)~D=dsjoLyaYC40&nzf z3h{ew{63f@sO4?!V1Bp!ofCwY_63g;TF!LkXXT4W5@pts4=PXue4EdDMgMFTZPEs^#m!bGV&4UcW%sxLn0c$$X0EL$Q7xqT-N=4#?T$;=N>B^+W7>A%+iah<{4-|9*`P%8 zMVjA@>`UB(>9rEnf(@pNsc9GXNn1PBT6;MglxV(4KX=5g;p@_^AN5)*K`q$em!@K> zSic{LX4;@c^9}aG*QK$!gVst|3B%VVSC2p(a#L5-JkPeGmgbAJwPE(7b5PV}%!rSv6)%I7X^_YS8!Mi(rKArDNSn0ji@Ph0a!h6*G zsT)>;xb@|^JCnd0mJ+^H!^7L%i`V?--co-&c%w#@D8V$wG2YeQX$Kp74E{HFGA=LG zVorV+zRyFAi{>sFlsT#?c_JLnFWf1x-PY?jWB$PGb9FdLO;ug__~d5>W!{_CDX$VG zGMn}8mu@#a+u;f9ukM?DMXQ8rU9)}feot*UJiFWDAo}ee6Dn!$*1O-SZHH%T9{n<_ zwu`BC@|U-2Ly6>$tit}?W%YQ!q#mjj+AZt%aQ|-C*k`u2)p6EVDnXiO@5xfZ#xr&n z{{6$rwo)RT8o87EVruWF8~Z%8WKe!su)(hu!JZpeuraXVkit)Yf6v1 z`M&pi81 zD4E*SI-y$0Q?*}@&nyh2Ib?geS?i9GT4RXwWg zrwI~Uo$amhKVb&zuAh5qlxpAwh03?DdNisB-ZMe-+rLlqjRnM{lTT{=V$|WS5c>AQ z_b5-SYMgZPDn!LwzVUmMtyg{H5^AY>Ts3pE4R>nm>Y?qEB$gPB-4blrkgBsEjw`D< z>*2LvoBOVa0N@Bppv6A$rPWf|xN79MV!K1DWF$(TI|H!|H>!QUetiu#Y`=n44fQCg zxs#L<+;@2bEz8!Wq?F*ki-h)|?ys~|+%2J0$x))aB_+7`0ih!?x%Y_)?pKPb&9=I? z=KI=fG95pBt6MljcJ~?dt6Vs(4_`(}6s8Q=T_s9zh4bgTB;Nh_iJ3~MmVU>LOEvQO zk(DY@B6#ZX6`3~v@m3$ZV;g^8Rzi0Jv5i$1{5oAFO6blYCjPla&q|djp}T>YxOv@K zl`2t!X}@x^9>sI2D%l@6?GIn&viK^;=l)Ee#7A#!6A_Rop?wpV>iGMg?WU4&#_n#@ zuvESWZCqu}EN=2>*OeE{(=$D!-ln?#5@h59#iah8vA2)g>!BRNnkr-!dY;-RN!j zn@%9+Z=Y)%dgMvALyjd#E5Un**pAY(u_C# zy*@oXFgcobt+26=T55`}6SQ0$v7aC9e@wqP>?Wa;D>o2c`Psb7wb>dH%%E=lUf^ zzahYbcd@fVX)BEFdkf;T8# zi-eo9<)!jt)Z0@6I}X+(S#u@4Rw!+_0|^`2x)x3DB+!cQDwdY&-pwa!4~9Fbr3CLM z!p7MfjN1S63)=7Rt@|6lNb?H@()2NrPt0$8$h@xlJv;b8_lB)stz+WB564Vbi4wuP zy89C`vEL746NGB%7wnkW?5QgsP>B+HUn3?qy?*`aN~o58D~^f9A8**GH4m$(yE&kB ziiwXuIw!3XCG?#tCRQBsaDq@ReQ%42rsXNFweB5I-woAvOpM>6XLMeI)vGlkvDW6_ z+^f({^U`n4+S0L&zJtdnzPPhRvF>WCNB3khxF@4`l|sJm)>F7YV>1djYr2%gtYrgs-^V= z-X==xp+v9|VgY7vbYCuB+H!?>9G%Pj*NSt=z|tLpP73wHO*mDcXV9eE3EB-B zdom9VY7-GEQ6iMqYLEG`&Hs(($#zBw)e7}+ci3FSNFI?jh%p&4Vqgo-?tk8E%b7^W z@1KX-^XK~BcHCAoONm%gO2oT9jc+ZY+TfC9tc#?bU7Ku^SPTBndYQ zmi&BnM}3w0wjU>c^c^l2C~fNHeqZ16N#f8JzKcXX=%Sr8FA&u7wmA|}5BrG-j?pCH$1%pVy94P)`z(u(($R-> zJO}-l_9M}5W<~_9L!!hjBYU?b;-gw6RO^>N;CF@j$fxpBu_POHf|ie>Qrg|}Ud$L1 zdmm`wdAr>tZefgx-mNzq9S>g2=mC`|vHrpz3vr}{-SS?{xCtdx>)?|gEyR%)cFTJ) zV>48u#3rZzs}RS3SQNx!MnNc{THHDLb2z)@y_m5wT6S#(yP4gRh?QB)SQ(Wlfixpx zT&&Du#>$iu)UxwZ^B586l=o1yz!-S4Vx_s-djmCZ$S z_?o*?DWUeFS?gjmLW{a@ccC|3Y(^NB?zxL;z-V_d4JuJ0jJG(Z0i)f;G$^53VYIt5 zhhoZN8WuCAK_yDqiA75yreQH-8dRc$me9pCEM`oD5~>x(aftu0$S{m{7t^2;CBkSA zQ7OUuxEK>9R4a_#5S0=oNrLdvnV~-{GHkI$hPjvqCA2p+TERtHEM}wy-=pBk zQnMc^Fm@$LSfs^bMp~#u3AJ5JS**-r#>%LcwnCB!tAUI8(H7NuXe&f(l#4eAE2q0d z9o9s5J0+}%F213hu$9b7l+d}kc0#q1vo@^Gu2h7m)%m5;5R|P58}x-Y{dI3x6^ZX{$V2~urJ{^NDz!^(7b%9 zczet3=j@F>L@1OH{wzF6z=r?+>D!7C3f_hiUdun{>3JxX`}?&j@is`n2Jgd#nxppa zz1GgDqnc9-ImPGgr35A32EX>Yy{OeZL_x^AL7W$e_=~dJCl;n$y`Ak7VS{z?^%&+P zNy6ihZMGwF_zj=lCPZvpm=lrte;tle5ytBqdL8wFteS7u9-lMm7Q4p;V zjEHE7zXG6CTONIF6=E9f`#>bod_!sD-xPv(XBX1|3BQabTOqDr^d=k;tho|M(<}XV zf?C=Nc02mR>niaL#P0P~+KmLuYk2m~$JcQuUPz-4_}rg`?|a|Pj#&N1*V9!Jdd(5Z zcZ21pJ&OB@7NPKYS0z-7X>ViP4eowo#_kSAgq8|#@oKM_I{3a>(XB~JyjHSKe1|Kh zR$efW^xwFc*j8I1Z;BBq^Z2)~mLAscl{L|;rZFSUxk|fbPI=L;T+NOVB zE1~DROxte?d8#_Pbq^bqz=o!Ia%*3(u}!;Om7pX^xcRZ<&c`>k`LXWXXC%C+5=cV}Hf%nIon?q6 zb2s8u0vj>mW^f=hKB|;pzP=vZSstHn3ttj>YVJ83Gjr zOto3mCgFGE-DI3E>cQv5)WEN55?+)N)$%RkcYx+aKkbqr;@xDNuWzg2g*zYL!p4>D z8FsThgT*wAZseN~_6AIcXa%dezXM%N&7bO`GcBfJ-(8qjIf2$?OoQ!x8es!54N9== zviAw4+HRjKT}*>TfO7BSBuT>C@O$bX&q?jZoBhFtyN9g%9lICa62~;O$zQ&|#56<_ zB^Gz<-NM)d^CkOV(JG-@S8w0DC5~yBGCL+zVz(?>7%P!1l|@>#YD0-|@)GV@S~N!= zMssLhs)aPqeT%7&C)+P{$Pda4ebC*Ak7}-3$Z7Zfne1jay=}1o_OZR9>WM*_^XGbk z5+%^;2^)*l1_{;D(%N4QZP&PnkrpaZLVMQy?yYV2U-I0be8qj8@}Uo0>;lIwMkR9E z;pig^fA0IK)#LbAC+tQ-B}xPvF6zQ|0Kf0N=!w4%${#=7*PMB&7II<)hKuG{#Aptc zD1o%KRX8acwPCkKOYQf5d=&bFd8rn1x@dlFVa6WpkM*9g-xL!1gAye|-^4chs0|XT zrKK&VEYhM6BP~>-1k#Mau-~_|XxBaqrL9;G)k02eL;IcNKdl$_ph}boBR@op>~d}E zgldJE=58lhB+^DPp%NW2YTMrgysqK<+~xD?(xtryuLjSlE$xZS2FG`O?%^XH!M-I; zf;$dR{JVB)y3_0RWdyZA$GauG+1WI#!w)378gN}wd)|g=yMHS2X|7T63irPVT?e@X z2&IAzSE{w|0J!1=q7F!DsgipJzpL@3dUoZ+33vbUZqy%aQQgVJJ2KeV@sdvIX&sii z6^9bo)7E8gdK=?c|2X}xn|5|K*zO?W9kR|^*m&rd1-D$$bFZ=N~Le{HoNRzmx~y(5|)&zuC-Dn32oi4uB}ghTXQbQZq!z2X{=FbD~<(s zqj53fKdyZEt#08|-o<(77c>3d78CPtI4bcQFqKH&BeMtvZ{yi92|~4K!`~w#ap1TC zyKBB$LhhWR7!zmXi@g@jREZM$1v9S4(*ECdRYJAG$`HqxI2)t>x*1|jqVKZ0Thg3j z8-sSKtyGB;x>JjZiKncYu7qmo4lpKWow25?N=VCYIh$;&y}#MG8?_(_-y>Z7hqk(# zgL%Y%q<#EHbS{b$Pu}a&6IM@Hyg}s~PxZ{Hq?BM(fhR1cp{vC-lo8Yd%@bBng!m6f zPy#I_;u~8w2lLgnmD6`U{>UNdS~tzsEhTv0i?=C#sgBrhbkw?( z&<2V4E+=f=%Yu{72tVDlaLw!JAI7foKu?351uF61!Ad{9D2fk;qz%7iOEuV zNjZVt8S9a(xe{K>)BFsHq2JYG8+)A9K0&CK-Xe*Kp(nO)REZM2ACOp`^LKx@ zXQN75BmCVcw$Gp%N`&@}?7rhi-XtS42T5p<2ls5FpmM?g>YzM2X~A zOAuo#?{Lu^N~l)y%cw=ZZ&=ACPPR$^@2SapC^6Nv zJzY%AoY}1@Q1+f4=Vdk`t&q;bb}==5=1d{te3OwD?zs@(Tw6O4^$2Bm5+y=95TWLw z9&ui(rF|3C+_jb3P_1M=Q1c(wy?V1ys)DtNvz{cLvgiC=#c?|!EKM*GkP zo=2s^2?z*hV{L?QUHfm|Yvar$K}ZRw7OJb~)mBto>ue+mN=QqoEC=*puwnV*Uz}GU zoK~EMjdicSA7AzJLzaKkIIHRT!oBrp6)Nhk>u>2S(>HF=sRikg>;J`w1%I9Dh*MJk zYE(%H(Jv+r+vMWhkM`~S3;R*R(ven&&D+~rJE1Ug+)ZX<%}I3;p^_59;+;vH_s<)0 z$RBp<>t8E0)Yn*TukGJZ|5}!5tzR+q>U|Rr$q^excd8sL*iP zRI{fMamFRB5~_8W*>FARY*-KC)_wkh_n)s+8>+=t@TDSA+E%R*zO6oA z?;p+n=ZK8j(0sK;iYX;jqQnPFhg*LmP)-mmWH|`xjTvvrruaYDYkI=-}&9m1=j=R}LyVrup;W)!TedVe2xD(e8a>yD?Yf*zcN`+R*wHQ`bJ- z5D_X-f@8tkI3~ZaRYJA26^g0ZGcJh;l_20tMKioC0QMI(@trHmSDp5ky@kso9 zy(6qY{CtLWt@+vsl_F$hZ$w1iY2f?!mo)t zxfRtDTfg^`i?LNnIpNpfXhzwLtw`7?r#ly#=Al%ki8U$^D2bOSG4APCZRPA-sOW;7 zO!t4B!06??N|b1*e^7|i)@+2o&*|1el_ZH7MzH31>jKgAL!GU)ajBSYxC|?G+=lLN zXF8(o%4>{>B}pP{^&4p34toaL81u%s5+c@0juH}=54+Os0OCw6E@K`ucSc#G9vP0uf6}3GV0YKJ|O+WV&tp6aJQom1?zF@9Ii* z=+Ud9e0A+Aram!ZXCwY&gi4e^D{zG?rcQnLrQEb9-ThjdAAVe6G&IyNbK@21rshvE z60?4k?69V(>CiXNNMrA=5+#t{ti$hCbM$%r`MsL((;7jo)NN0Sjh)}Uxa%2Bua()T zsL1xK>an96uUc9+YvH8rAKqNzdL)T>RC-@B&JkLQ`C7kzZsD}sWYWubER;q&Q^Ud!=I?lRzmIM4m81#xoCj*tF0XKWw_w@SqC1|V+w z*Ye7Z?))+G49E-lQj2N68`Nd4JLs^=FE?B52x$2=Dqfe8r5d|UugsrT?31~3n_f-P z{4g6)`bTfi?d|M&F?GEWM;q}&hvO18S3+AMYTXLV-sD&cdq!8M(sA|m@#kTlJA(ez zm)*B?vL0(})>ip>o{vi6@{MiiO!J;0ZG`#X#2if8i04W%HDi}aGcdMLs*!W%XD>c= zhwOVNP3iwehq-Qyp>KxXwIJK~xh~nwFF;%U?UQYHBcT!{lCu`GkAzB;(E8bp_$eKu zbx;Y_O4j_{x~^^q4m%C?fAeMk5q+*cIQErxYS5{J5V0gl#Qxa+n&5S9)QSwA z*IQhJpFh2PRX$md*bizO7E?|8_o(eP;jr3uUb#5067`%7_0MK^+V#7>=qI}&bkkpI z@pIyJqf3ZbOMBLSbNyqV*5c=??G8-zx#oMq8*{TCZMj{xZBN+P^TnTQ_wKfCrc3W0 zd6g)!N6)`!JHPWq--b>g#(vT{^K5pz%%Jls5`=1vx%rXoi}_C30YBes#0Eq5$c!4( zJ@e5m!JI~IhZre8N2}D`^6 zy~(H7-S*!8)z#h2Yj4tm=cPm}QR3=*{qx7Vq6Y`wwXL(U#fX+#l_=5o#%gySG;+{? zBUEd~GL&$Wmc32|F?zxBX4GThPg`bGqQs3G_H;I$IOo3+s?|{6!`Ya0GYIR!JbrGR zdt{nzb$OSG);@8&v90htCg!|zk`ca5)<*c&m3rh^l7lBr=+Ao8&zoT5*q7?u3nnCM zZhan0lwgazb}tC&k7ku9!M^$RqyI*z7JK%vw?N3aYF3F7Y&YLlYa>)k+c0k3HO24K z{JZmbN7hpcK5ygx9zA>ThhxV_1SCo@?TOp^zg4qf`)uZ**SqF*B~xFUy6s`N5*<4U zK5_T<>(%~t?LnFJ-aFW85KEL$?^;Zqow>iZ>#V_4$6GL zXwznuD3SEL)n-w~9MCc#zP6S>PDtlX|wIYBLL zb=#3`Fe`mg|7Q0k&ewc^oguO2KCLa{iGybUDulL`(*C){zHa@X>yJHlezH=(zUUi0 zpRe5guhzP)5s)asbduO<-SyI%muhMK>~DIne882;{$HsQC46uCI=R-(f4}*Mji>+n zB^y`MtZxStS})a3Szjva^Af^KNXKUv!VNTpI&(wS|Q%U$HX?P zUN9n-koE*h%Tfj3o;i5M>m@|2&PM8piFTafZGcd%>8l=egkL$gGEJ1~10z*p zE499n-@Dstc_oMg2He!75+z>mFxS!kyrk>EEuD?Ob@(Y!D%Gm5U+oDiE&e*! z0@u28E?h8CC9M+mAg=rRE=Roa*Y^|sp?$!$*7y02gI74h{%>nke72M%;`vxi*|@6W zxKcvr3ZMJ+-1lFh%u*{C1;ip^SID&$2X^kx<-j_>miCiZni&&fBY zb(f)p?um-2s>wIH{`g{I-zJqPp*uDEi??H6al|q6uV_+<61p4Y38arqQHc`KxrXa= zoR^@j@ZTh%rxYRW`n=B(@8o(O^c+f-*AwieORp^Od!61|D5jQfSukzn=>v7cwvvN}Ns1?y}{N|PH!5toqzolxvrS{l2 z#Z)Oli4sWj`F|&<_1@CqHpU*aQG&0?4?lm6JK@B7s1nUrzfIb2?7jQl9DdMNDp_jz zZXfd1oQkRA&acYh2ZTzLICSRAHm)|cafMQ?jZm#W8G(BsB$~`dlk0Q+X3BR!XlZF- zBPLX$1m8Kmjn}N!_Ty|Qp;}re8|~jVR-)FQEj%-=lGX_Smiqq4I|A`(B?(BBVA>NX z5lUuuGL+yp1xtuDbMm(=toPFR0ihBl*iWADp2vBg1fg2&4^M2jV#z+wEMKw@Y_LTk zVc#IFrM2I%@!&6M`zfo35?aDy>h0xA9$C-qz=m4qD1i;FUomyn1Mz(yExYDRZ|CpH z{P@jl?yC>pzEq+F=gNO4REzW9e^D&8!TU){AkF7?TD#l%w!dP3c(0GVG+(`6<~&^0 zt3NMrcOX@wMAF8;MzyV)e(|C*Lbdc3S~2z0th-Iymr5l{APrCCYd-wbw!1xX-nq_3 zDM2l+44$wxDt-51{hH9{D$#uD=RI-CjO)_-PJ6=bG?YM^-%r)H{nok*wyb*Q+#YTu zs-%>NzX>mDe{9vUt9NoU3IrueB)>Eaduadk(u>Eqw^a0p5G^c~_ERx6bk3Tn9x5># z5rH&TJ74p`-`&}C`hZi)dQi1ErrEly(^x&dXNbp@65IiJ0=>QG?I*gLYdr=Yy{gqZ zaew7TiS06`T3h+Atk^R$jpzOzvcJU&ZT!Q&B$g=QcbvRsvD1dvrn_(2A2lx{_>ETY z9axO}rv00aTm3HXA=}w&eB)E|_0MTz;=oUH*Wc0J?HQENyQ5lKSM#R3c3$NOm6Q;+ z4&nxOD>aWKO89pwmI{r8mI^f&0`G=i3j|v_*&oS#aR)Xgm@XyaysS=9zDURQ2ygWH zD~HtDNI}FZ@1*wggo{@DoGM?3EiDkcOMmZQgy|-$o3+?N!iZ3b5=qa16%)Pq_V63_RxPc0>jc_L zB}y>uy^q}&t>v9mwV^d9;a6uRRHB6L4BSmXX9IUqRieb7!d?{P&D}}O%biqvAK;zT zcr2j}>F52~(hGA=bYH7gV)p=Kw5xBoCgRw|om4m4u}kGR_H!kEhf9oh^NFz}N$8B? z?Q7gkWo>Z}m9>REj!?ft4x=3%7>#zkDYB)Rj^EYvPO9dmbyC~KRQp%{n4@=4i4q(O z{w?+G?Yc&UN|ewR!JX6}aBAmTSP9kQ2=z8N+Am(Ob6N@2(pGSN?&e2nTdkdtv71*L zny3_Nld6Pj{VDP0g?9Sos~fuF|JptnyYW53_^sHF_FX1D z;QR>)zAq<<{q4EjFwJ-S>nh9-XCo$JEx&eg9fandcNg6^`qEOl^8j~iHZGwrmGwm( zNX<*vL@jMJqcTQWsp67&Eq~iob4n5_QDW@VuiCoHJE`w3-l@q-g#b9>a{c{ zn;-AJ!C!v8*ukUG14=OdpvGyE&9Wky|p^|n}E2l1mfq8EfE1plE_+41Kl0J z*v8S%&NCvGBnj;g+NhW{r-X>LIAZ*1E$*Vqozy~W(MQ^w?uKbZsKoB4wlMlA+2?9Q zB}ydEeb7!@oIc0(iU0EBzgpDS-)}v*i@S%)FGBwG97NUfG4NRyB^1Z}B#HQ)!TXZ) z_qqn7y@ZIh^qs-oJj?S=s-9EZtvT2KD2eXj-JR4t@1&|k3A9MOs$n+SkNvB|Z7S?0 zvlu1y^~(ypw_>-#qUUaYc)$piD1o$FQ7xzF-m5#aEG4MLG4020FyKm+9EsT$xs&Q! z!PyA6SaYa{<^`IB+P1if6?efO2LB%Kigo85cF0*D4S4A#>FAc8N|f+B{jOR66=2t1 zE8GY%J65VV8c?^Tcko8Ml6@BuT{YC7!tI-JzHtW+UkbSt{QO zx_;OYalT#K2kDq7Sb9xg+~xH)Vj`B5608$OdtJUwMMaZ+TEZ<>KjP}$T~|vFww7>r zd87I03EtmL&O7fDK_Dl02JoYQ$EnL-S^I9|#b3N(UNn}d=j3y~N7d!+{%&La15ZUn zxW5~finJ%jZqqBz`@4}ZiR$5R%0|y!sqFr4p7(cE;`8-{*3Y-@mj7Og@oS?!o_EO^ z9Jiq-zHK`{5V543@GWgIqwlSg=l$KNR8|k2+gd{JMR|W$B}pPKZ85dZ19$LFYJS9= z`32tJwY#GQ-r3b}h30ps?-tELl_;U!wV1l)u&<+eu7ql7{k-4htW}8;TBl;lqIcYi z2C81Z*G9DUv#wY6cV!-YlBF_2*S`4ssh%JuN@awuWHF&Dk-NXUSnlseD~q<3t|jjN zZZq%isw7D~TZr#++TGn|-rudSk0nZI&$|1&&Ah*>glgG+uR`MfZZq%iDxq4t_xyVy zzQte}e>czjyGp1QJgPgHn=G#6su@U!o zLGX?b?77vs6Gn;JzeEUQFchB6mMOFTZ|5w$Mv4qp*Q2@=mt(N=iq&wPIO+u;q}hCk(aA1`}3 zK%mz5tF)~ac}%=A;&^z<%9h@{P7N0&NKC7mBWXxnoi9M z?Vs5OA|XM7PUZ^1C%)y3un>G^8zo2-?PbDFVAHAMixQ~iPH!uD=qYbH>m0T-+bBUI z*jB$rpcb|?ow>`}9UfZkChyHhQ(PPEpAVYdwfg7W&uP(aO=fqU*dr%8<{<3}%iY(z zMjZ;*$jbI!YhKeu2@($s(LO&^iEqnpyrf;Y@-=O|^lRD#2-HeR(YDe&%9pkdANab3 zH+2r*_ew~Rxb+D4W?J;oFL-bJ)XtufW#49dkxDHB1Ztfh-a=bf>apd{bocHNExq({ zN5fclY=xRN^c`GxE7#+rstw%}H(u{m`|9a1N|3O3GjlZ)jY}K3$8PTAH9RvlK%mxD z?`R%(&t>BH(hhE)rmeh!ovU+Eg2cVQDABQ;i5E9I?*ERv!Fy@qUtdQF688S@I>*GU z?(N*>xvjnaC%!2|0<}KKWa>g8tw1Zw?drH;x!j^;cTOxhpbzs~g?eo~`)Lm@G**j(b@X#hg! zj9(-CI}P@p(>kbgAD7qObH0@jEET-x9!ij~8G~;`1m>##f zUdX#;e?NECkD1X*G|OB%dUn^F=4Q(L@i~2sV)a%hy78sd=*Lg-8+B+vw5&-%mN#ca zu8R^RZofw9m5(s-X#aDsr_g*w{{;xt;wSM8m;ERce8a+S518-FCjrqm#B-f;L&1X^ z3S_J489^k_%9L9Wp521LXQ39J3YD7{5xZ%D5+u-CmfIW=yUl?FYT?;YxiJ!f8zWK= zK8K0~TKzOL&k+iu6LpG( zc7HXW<9zNb^V0))SWJ%ZO<-y1)Ju~kLUc^26Q~CgmbU0%fj9l-;cMqM*-S*Dw#jW3 zjN%MDxNvRHjjsq{l4Qa>8I9uH`c(Sb)YmpvAWVyCPHSw5YkltW;Z3$@omgivWIkhV zX^z%fq*%|MS0wc8`NfDt)R||XEi-%gc_f~zXY4GyXUVE+R}JuBNob7dQ5h&n0!91X_x$bKDju%E2nwZZc8)gnypTk#7w>8OqDFs zmVFkKBom2wmsW!?tOoL2UJa0@dA}N|2y=UI>3RxZYL+lpw+BM5)Mb zkC@#~R(Kb)&&iS%Ew|K-~kzS*N(7wIvnZ1hyYLS&GdHD9O zXZ9{ikRYp8^6>3l&+J_!P>XC-A=KU_|081l2bLXMVdRh;A$f!qz z5%WKgK&?SX_`WLmA7S%9P=W;cA3|szWVd@}w`0w*wqz|!seHTLGrJunNRV|ddH8m_ zXLdUhs72Pf5Wd~+nca>AYLR^{rSk1|&+K-TAhBzuj!NHdkC@$#1Zv?;-B^h1cIk7r z+fjl9-Ug0^o~oDPwHjR28~J(*?}W#eGLj-i zRlYbIp;(VELBiewKT_mbqzDPrdSj3FhaV~OEK-CLBy24Bks{9`MM$6)MRcUJex%5= zND)equ%7iJMV>{9kU*_xr)Z1#ks{9`MJPeSde)B=MJ!T;1Zr6i`jMiDMT$^@gpCD_ z6!G5n>yMvp%JX}Eeyga=mhaE*y0={Y{uHwM`S)Gj=0vmUcilgKaNrrAFbNWzE?hh( z%CuS;-_7jR_R9Mwzsk@0IdxvNZL@{)+`Z-VqdBE>BwcvLe9E8ijFQdZ{o%%wTW&vJ zuZRhga2g3t|Ft*AmYDdK@;E(Wa_fr`tYvxs?Sn;e;y(-eJD+@*C3$eESYmnj#1FHg ztEMiF6FtuNaDLbGIwj(gWa9RQ)1nKG7siQKU+?75e?pifncz0u+nnDhu1D_VD$eA? z11k`w#dP5plcTGSFNqUXM;~rF@sHz#FbQiRv3c>>XlM+7ZGrQsbLWhvAD-VVgh`T# zlJa~YPSr-xMlqq z=hZ14{ZiQ*WzS`T>o@F)1##l$YxA9MBYOy85-XME!EHFE&ipv>VPV+0rq4nlOp;7+ z4-Ts{FHWp~x}h`nyZ41KNixBs=i7PwEejrrS3P%~vvEYR5GF|`Y>rWa$L`jpll*bT z&tk%~IL%`^k;j+APc^N5-AWxLaY-`4?@gi}OD0u!?m4he2$Lie{5B`rYWx1VP1`kH zAcRSh37fmL9t-P#*K}Fv`wE0)cTbYEl0z`av)tUOS9yMf_ zm$mRMvYEl3wTJQS!>d8Ys#GCRV)fv6+n?KoxO+~c;{DIm%;KIzyAAEcpbZz>S*!T# z3rEwLKnW6@W?w|DzQK99?t(XJtUrHqa}Om*M9wKOzCN!w`3*X`-{2s;}Jo}SF^@yOB)kF6n)q_kBeRd;}CSR07!rDr|8^x{r$+kldwXTN}B&=`rD^N^q z`k*3#TGr=E@VJ_Ae33)r%0mefHm=kPXJYR0MMX@Yq#}_TRU-a=6wzq+y*rlJ`@tRr zK8bd)67NSK4e8&f`rYe>ZQU=9UxGP(>%8;(J=f@_`adl%5KRW>EZqd?ri+L z&xtbe>65&E9C%egwxhO_$0A1JhL*e z=45e5AFwS#qeR-!w=z7lGEjoVnJMjr_N@%>KmVLr%vJ^xsKvi?oiq=!mOQYQ{Qlq) zS|4D3GBbFCQtB7;%87fa^qx!EdEM3DZRMo7#9Q!HJs?zqgr;phrAvs8iv_7nX@XlImnaKVfU1Zo9)kk&yjz7Ep&6BGOAv_?tU*-p^kZFOd% z&yvTA*aAQa5}G!ffmSu|hi0oY*~&l(61dMD3o-F^wOCOyfm)h2+lN*)kJdq6)m)Sy z5gb=c%srk_%mhj*5~*<;j%OXRONz)Y;jbY|`@}5^NheMbsAZs@7h5tN-#r#5RAMv| zoQ{RGRJuCb`@w6im5Nt=E3Lntds_y)DC;>&kkE8m{9BXUx@4Dd>v||b!urOyWIVD< zDiEk;J*z}~T=6L3?+)#7!#P>RYpsoHULkF?bK2f0 ze|7faJ`S(7QYw~IBu2bs2a-nTM5p4-{VKmxVw{r4>yA=vgo2@*DU z`PR}!3DmNgPYIqyxm0Y!p#%vWZ#q*i_-dJ0eMq1djyL)~btA_s?0Q?cv)j?d(|>p> z@azU%8TOy#7{HP${k^`mo+-O&O>Gw?NNma173Z09CK^;5=5;x`J9pfc(_xe#fxSs{ z$+`QzcAJkEHGluT0D)SZ=JiVLDvNeZj0se|Pl*&y;<%y0(kYLalQfG|r%H)$v-#eXrJS;kq|=bWwr??xfHu z)>}B|k!+Dk6pwad)gnW}BuH@Depg?O#})q%t(Ro0hTD*Ldv#7EvzGf`J*`C1Abtl ztsZPElpw)%N)VT3u9olnRH;>I9ZHa}zR^-ScSVIbvGl}jBv8xJ+Jl*o^pbB(T=MgC z>#ocarjB+a zj_w#CHMjQw2}|o;0D)Tf<+qZNs5^@7Q#Z)_G5?ovDN2wa??pqO^}f6_13JyEO7K?xFgwuS!oz^0+{4$iFmQh-1$d(-p` z46r%(QJVg=Lm45Eo|dc2I(Z^`@>-|M%i= zr5+0&`B#8It)N8~-f*wXS9!m!oP!c1Y>v^r?b7n8LR|Rh<7^~Q%jOvM2fx@iT8JNd zmHKlDOOU`wF@4)`!rMhW+Oz6D;h+Qw^4nzWs&|)qEWenEK}T9RC_#dJH6hfyd+JYj zuV>;fLobQP^wo>I7@?l=WA>)d{N{IxQ6t2gdlbTNXpthBoS z(fhfFq|dMDmf_cfCHP!x5#3|4);-s&v;-wcSbykhuzr5lI^OMdaS(v?EryVR$9Foh6GBi?D|(p zv>sZjmkwPkc1gdpGqQ1|H~*94t-*11!-9W^ebu=0WjQE8g8X)AE8XWztuf|>_PWp&~>4CWULLCs50f`rvvV@vh& zGq&+N*ze97IhZ@n+E_ojGdiY@^auaz+q>lV*<8Xa0Im#j%A37;Z}_~`P0Z5gwFti{ zYQL*j6!+%6Y4ZlJLkSX=R>HpCI&MeV|CogHusb-IUyw+-a@1TSSb~J5l^~B^#x8sG z=IgWP?%)3*+TsE1>BmA>y)ap9(ey6qb5VkXrFC^SpL5H`^mP{_Sc_UW%3i7x%{RA_WCMB4FUvek+&p-MhzCt%$L!=iJ}JfT+SV} zX!J-uG-^!QQ{B9Tf;pCr-R@|e9dLV%%K?3uOg<5@AS5`Ip zm*)7yHyX(Tl;`rFifm@!QrUQA z?-xr;_qLy2mMQPxl-~yGfdqN4l843_4z}fQ)f9Nwy*RWOpM_d@TRIl{>B2#o6TjSX zEO6J-O2{!F%r6%D@E=i7jpDQ(5M# z6%<=S0<~GJ<^PsrShHkw&p4 zlpujEEfJOu+#m4>i{!yEE7YRciS(e}EBeEuo21XT{^^xslpsN|6Cw0o(Y(!TWF&r) z-YN?vNZ5R(5f+=_HoQ(z{jzjyAo9wkWVzN+oG-}Ljl;t8MVGATfymaPWr*FHF= zj?`lm*`k(*oxtT$!j^^2N@^{Uz1yBk#r7_)OSq3`?WUGK+3nJUY`3EX39{j(KXhM> zd;{r0_6?9gEo*h%yCb_@Y#;JiN-FNYrbXkHzT}|<`3Ba5rT8rCH72Y#buZP8j}rEA zkU%XgZ7fuK#=oRL4!t)!%i5iH@~uBOs)DUf-|X-6tn_)^0pTo^AYuKl9%OfCn2alq zupoh2mevT1*$kC>mzG$mcr;kq`AxMa=}3guWq;5g)z;GN16qsd8+GcQuHtRK_F9i( zT)ps1AvUgbH)Hi3F9|WA{vCmJ5D8q{W1$|EPRlI1>C_;Oa!RRq-KO}Zr1@TA&}O)2 z{|jPejQ`V3G-D@hA0*JKp})tnsa)3D^LZ{uapbvdAyIrr(tJA)ts1&zI^qMec?!G> zZ*^ab5+v|DJap5$^ghX>bX$+LC_w_hqd}u&+ZM6N>KtegAW(~998yB<^V%=JDXqIF zqh=;bkiaii#6lFskyVYOI7pxtez77L#X$*va{`}4@!cI&F^c1t*R*(qV~YgyKnW67 zLXG0s%E|wt1PLpxMsbip2@+N({pt`zor}<}Mc=^2o7&XmpUc-so-EnB&U|E^U(LSa zwEeC=rxDZU9r6j5AYp0qQuVJi<>lpN^1ce617OdT)8=j2ev9s(S1oT-WRU|Tcu$A# zYO^nkwDt!Q_FN=vM@aoaIxlKxApN`HRw}kKIgPZOF!c$PVA=WigttxSUWK4@uPzd( zMV6%y>TSP~`%dKHA=S!8MKwtTy464MN_Uef>Pt!kyzFaqsV= zxi{0-NFE-M>!Ab*@>nH5_HpSincaNO?wpn}pS{C^&-PGAgKuhzkme5Znl7y8S=h9p`(#Jdf|3_g4K*oqexnz`&yX zrtZM*O*^;ia6!BF?JjCs(66Z9WjPBMF8s6U|Ht1)CuU^q+qqca~_yqo{^DT zaLdBud6{3;%NyOHOF>3PM#%*ork=*%DeTgJ8IceZ)jzL@?%K0H%93i&FUV_{xh;jb z?x9_I(N0h0`NXxQ-;_6-dxFPA{TdCNSkFIGh~G}n&WrXrVu&r>@^i~4{vA%sb93SshR2vb&+vfKhwCMkp|LqnMQ z5F4i4QwUQ}hA?%W!#1b{q;8Y*VcLQrZv5_{=wA0TDP66pWJ245pL0VTiq51QP z1GWB}`$eRo*wAuMCbVXK;^o(u7-KJnELjdOCQSCy8i?I)Sg7U~n- zo;VsE`O0vyp{+WZ(0*ePl5;J^WJ2r7N|n^P)@?GOt;Z)!&c%kdpJYN?s85*E6++u+ zGNHX75~5a-QMLK~-sJgbQOLMst3+e?%#+o+6CEw-UyKUKY#W_vrDw4?e+NHAUwYn%RSLbW(14f_No%-gf> zDzTvwjF-cS{=xa6zqEvEu?-FTHXhx7ee}T0abiOy7%zvlz5O+zT5LnZK2g8M?3`H7 ziDE+~7%zttZI?4q8KGKiL&Ls}-%j6>8|^bnY^Vg|<*@dGza~_RZD`mhsy*MtX_(nl zY^Vg|<#3`$aXu;|REuqB*tc=rLj#;>r&?k|B^WPTzub!3u zp%RRj!*)Nfj8HAMp<&+!l@H~C{}K|67s51i`kF!%S3*dM7#oH#sfq$YT0z<+Z1R_9 zL=aVzW0mqkgLvZO)zG9o_dMtt@*M zbZMU--+QN%_v_V#L72bOfAJ6J?Jp4<8AzxE2@dObKUIdH9ZMoE)Z*{Pb}SO2R4qY5 zB}jlhB6i2l&g^p4ZQj-=H%RFsp<%W$xPFIt>A_7ztoiMO#Ym_Gg%>@knUU=o6bGp%NrGtluM{*xC~^Z>nhJ-8kP78!AC9 zwz0d*!PwSW&B+GUWib*eL4w2j-6t;i?%Sxd@;b4h64YWFkMEfp`*%jRv4Mn2kl?U> z_iePUIVQSf+E}rn64YWFyY|JrwU2iv8?#$BEI~pgNN`xciw*7~^j9o4RDxQ@hU42{ zRn`YWBuJRBAx53Ns|BShSMxzOkdUw`t31D~9($&@MNrN~g7I=#zehrkt$nQpm2R%q zhe}Y3ZBRYs1$CZ*gi4U$uzvT;idu=I?Mfx6#WtwDxqjQd#=WKl36&thVf`KnolyGo z5^C*^_79by7TchH=VDxtsyzN~%8&@o2NEhlg2VdVCrk}G7#C{scheSJX(c?0 zaw`!+B}i~szehsU5_wGIwwpqz7TYjwnrv`BkWdN6%VGWQ6Q)Or4V9o4+c15TY*4RV zf`m$t;IMut;+ft{%vd5eRDxP;!;CRxgGL{VPze$o*6)5kIQKNdi4B#Yma*Z{m}tr> zi4X}ACTs{AsWZ(;tu~O5uqi8^Ka33|DCZ)~3gAU*?Yw3X8!AC9wn06L z*Co^kX_djFXh5h02@dObS;=re=e3XYbCsYL+n|v_)^@U5DnUXeNN`xcb6M$LklRYI z=8TzmWvt~e34<}wCRCD2Bt}soNRj^%art3i3uqayY{HCvG1fBcT?tc(1T&6Js3e&% ztMgcpb50Wd1*2t*!>Yw$s#!C0nz9molq3^omyyPX#>IqcahO_YumZ62p^{|6?3U8l zKti>cHltEJHRmc}EhNksV-v-!rIKXA>=VZM0REudd zuGluD&Q-!%NKj4lEr)GGa*l**F>S_}G&WSiT1c4lhcq^jP%Wm-7-QRzRH=lukT4^L zZ9{Udl4Qc1w%CN&Kti>cHe*SGAZ`9jNH~lHo?iv6y*QarE&fjb1-n!sNSpr>5)LDQ z=U0J^$_N?3D<2b80yc!uld04mg@kG`ZOSk&l~4(5A)%*K0a48P#<)1FS{ycQ!A&Jp zl1!NPmLPl+6qibp3Db@f`6%`gn@}yLO}|NFLnW+*gq~}q<^u`UVw%PnS)&9*kPnrx z77}`{6%au_kWejS!_oDX-LA|CN3&!wUgdFE&$R*@m@0`2wKz=qXY^a2_kkFH`R2xXB7Sq%Vcs@_GtDvk@!dgh^=~t=^ zBvgxO>YK8^N+ndnT1ZeL5^Eoi{=Z^Q)~{E)1+5$2=+2paX`I8KJrs7ooikR#HK$dT z?_z@q{wroJl_V3x8@`1KPMeTasU(>=dF*NK_9;_rLQ;i< zYBAk*-i4(Z8DniiY^a2_keJzHd0vAm&)S68Kti>crf@8U5F08nS`sgZKdth)_w2yA zwhbXvl7?{76KI3-5$Ez@T2mX;M=@6+N;r%Jm0_&X`VdJnK`kcEEhg25#>IqcahTdd z%xWb;s#KCpP}@v;_x7~;SO}Hac`7XE-*ra(?SJegV)uUzZaLEHZm;v= zDJg_%vF%re&W@k{*bPLi`LT7_z2Y9P=8*@5Pzl>e5QPPAd^9_L`9pn(X#Q&R$eEu{ z@XqcNDaW{&P%ZwRkufiR{LHqcbe_0kNO=07iQcp8rU{`Enxa#X-+$%9M0|Vr z{>Y~VcYALyn39WeF`-)g-IO{J83Sj9f7x)SS2lW{5Gt{W!h-WIpB6vZ_eUZ=ZZaeC zW#3_5y*m!35URyCOsk}}TmPPA;j1TH>wWkBe}qs8+ei>p()A|ATeUl%h$dYZN6wyI z)O4vq%C@gs5r{l4saP-c{?n@z5 zi(^WR?ejVu2p2B@uKa>?CJ3PtwviwT3-0{(ljzp}@cc1*&wCM`3dVdnF@;bqW5dii zO`OldvqsI#S=}WdM8Y-_L}9@nH}ucDL>_h4QMO zh-sI97he2q1E*qnk=RfP#>?S1n_cEUF@HD_eJ(i^nYX*G^Ycc(e;}b+Y=e3l?6OlaZ>x$8m0-La9z6UBcmAK%hRl-NXJ!99~_y5(!4L|oadBI0$q+o>_fpU+J`VoazO$7IToh{xBz z9p2UK7H9A&Z;1_+*hFE$bGsjNi{Gysr*+A?4UvEL8s?mQtG_NmLbce2X$wRg%Z`Ts zcw>O`?b@0iO4vq%C@i>c$Y^)hDM0{I&Tx8w7n{uz2IVy!vEw*9CN+MpERvaESc2I6ePr}|Q!~&1J(W-`W5e@z^xa!u6yEh~>*z<kR&hH9}5s#!U6h=hiJ5z9V*!bx7;+pZKF zDq$N5g6{4Lv*Wv;7)LfP_%d(H{mrU*w~X}L6%wk&HmHS~bB3|qyJsJ{rLDKLOODu3 z3EM~z_8up3$|+j#jx4d>wO@tV1f8bI**()p=!#rU4d^`G|6?sARExjsJ|Q5AnMsaU z&))gFu6+YSjG%*G2|c+Fh#*x+s20<@k`0K!hDulq2|c+F zh`QUfWCJ3wp%T_YLeKjDCn4wiOzTQEl~9SX5fJHb0WdBOs}_e7D`YyDuzHkA zk_lbOrlv|I$%Nhx{57FkOzTQEl~4(5A)&Vee@&)?x-^wYtXP8*6~fd_8XHKc7N<&AnW;8Z!dgh^Dl?T(Nit#D7|qVf zIY&aZnATNhDxnhALc;WwG&Yb>Ev9wNm})~Mtc8RbSJK!(LbaIIHDjs`m9Q2PW)w|h z0}0h)TGx!JHdMk|NazaCB8pi{CCLQQUdoFUS!E; zQiX(SF|8}WR2wQ`EhMNm`2}4X8%U@Y)4BpowV@K$LV{W)zo1KF0}0h)ns#J~+a(=+ zB`wfrM%?ow9ljRv9W` zEhKauoSdrQR5s~u!Y$abeSK=_QcFxoI81wTbDI&IQ``ASA!v6mw+l?uX@a>0ut&Ir zgtZc<^$FXl`Ox%MLb#O@ZZcs~mG{?#YB6o{WE0d%5)uxZvJ!hHwTV=jm1U4a(L%zs z=`@5nnNUK`-q;@5FlT+qrK=K?s(>&jFLpk(1|=?&Cv(DvXJp1kkPmZGl*fdga{a%j zDh*+e44A5TvJGQ9eM{tg2%%b#r!++3Gzw3Rg3|pTsnRnmwqfeYCp_u0@_(B0UA(;5 z$jFee+{<&=+>9p(DP5GLArigTvY~MqTC_Nvk+G20a7`07Ou`b9G(-|c@3H1|QFO+6(DA4nop zi)nq^VC94Cq|HYhz9;g*Hjof4%`FqA+=R#|9@FT)B?QPh9BBo8Tf=7bF(bpXMJFyf zRBKubC3LmK@hV|#7=n{?&o$#R(-D*s(PA4K=A82%``qzg5U-S|+F-(jrF2+|`L9?Al|XJWg+Z#)6Pm)5d=$UG_w(GRoEsbyugf=X z9M)cIQY+v6d?IEoBUFp?p<&;K=}}@sC2Rx3rf(V>l@Y4NHZ<&)l^GethDz85hRI&AS_;OJ6hgI3 zK7cSIoaRF$CLa=Jg33+S+J35#Pze$o*6%)HMryI464c_bwo02o38zH0>{PAz?qGTK z!xuXI-|_FBX?^4H-uW3B+hWhp;BYSr$6_yC^pnHi&$@{3=$~5mO?l^fY=e=P#FC~mPqF%mI)!;$D6O)qi2DB6~b5+pwDULrO! zGV+KRytK3TOZR%tvGXDpfm&2XVuMP?i-gY3uIY_f*~j_rk^Z?TL84pTas=)**G zp3=`d-Z|vFF#be~KrN~tvGK^u$ClD-kxT1)+wbq|Gz{0K6;ncj1cd3e2-u)srbtUT zkXj-jA5oNGypX3ntE?;nwV>3Afcl7{1PQ1cBB0JaBv1=l4-wF=Jd_{-ZHx$LyB2|3 z&$}ydi2jjJ)Jij{v1UDwI*NJ ziHP3$dsqBGM2n2pUfnbP=G@cnU=$@t6f_woHfnS~nR323<5cg5#(kXFR}WbPYJJ`A zI4A z+ct7hf`r;TzNwR)4~sx8Es>e6@`-@5%0&qhT5cEa=|u$8hee>4*3+}@Wkf)oJ19Xy z>;K&zR}ca1$|6t;`;FChtsaF0wtN~(7Jrs|&10uYAH@EFeFA&1O`rscu@kH3KY3%< z{1x91p?shXBv5P7jdk-+ZP3+>B}ibr?blY%|D!W&4Rw)@gpOBPp1Gjbd(C<8ykX37 z_vhPRq_ysNHzQ+YzJ^b_^SJw5KmU6qbXL3NnJe$8o5ci5kl^sIx4%fSjHi4=b}h^N zVS0K(wK%3({gg1NdQokt1moq@D$OghVsHLE+p@Bz&(ECn%x<^mn8ohglD;m4;~efW zW^tUq`-FG->seL2$AwTyB}CjO!UYv+2}6sGjEt@o9d~v#Hct3xYu4l$eyUUgDM7;6 z;JsQp!q7qtAC5MVPzl>eLl_&|X8k+4tR!A6H=^??ABOm0-v?P0T{cKrsRYW(HTIY= zIpW|E5pezSo|S|InkCC8cW0 z;s)M@%L;O~-dH4rro|}43H_&a zeXr(Q;hZf6eJujDe(rtDt#QLqw`lBWva!Rd=e@tMTTa!_`#LB=;>I4Iy45!Q;@<-ZSdeq`ew#q8c6AQ9J+EEwHh%p&BHn$vjyL7HZaE{)?(d)k39Kjb7#Ul~ zd*Q@_oaP;D0=4Xs;g#KWyuC$TbDW?0$>^ga1C9o0I}+OUb{(&IW_Hfr-}_mqLIO*K z=JQ5%y=&_C$Z4{%pM&Ltslq%(LgzL-kh?lm*BN&0`A(-nH|Mw6yxYBP#$9g1d86}3 zjQ-HQzr%o}aTf_3k&&>+_I4xdcsqu!&1&;Ze{0;u^5GQfI2H*par=dz1e6sKO^&y8 zKKyY~?(wRfyei+1%y0co#Qi0EY#i;;jFEpr#%t7b+Zy6yB4|xb=ROGu5@_2ReWa{( zOoSF=m7CSBgfQhEM*`Xvr3!kKMW7b6b|RqHdMH5xT00Sw_tf!nuFuYKkN2|()T-a$ zxEorv+Wo!Jy+pt$>S5Zs&b1U^>>>h2Q4b|Zz*tGdOEij3ydx*4lIIO>kv z)-nIS6;~0l===uWJ8of4v#3p=7N#~5%4<{K%YGxA^GHEoD<4Q;DOjVZMW7azbR;z5 zi8|h(V_kBx+w}Kf#IgE>UAnvX*YS!T>ymTMv3?#(px4H+X01`wLoMusHbLvF5?b}~ z`btt|R(e+7hV>kkZin-hm*n0RB42;L%L&$o7J;_O!)^Dnk_DHiCv-G`^&HtSsp7S$ z*f6U*tE{jLtrfBdtME9imgBGvCL6Fq_E3TZjw_WDs0HimBpVnnj!{V4`wu+d!;?bY zi_ktgX76!Of`smtXzxq}?xT=EE!|Vm-kAv8tDyu5-SyGlnF!nuB7s`EH>ABYl@;ur zb5VkX?p|r{Oa$zmEdsS*k4uE^oxfU@O(%E3t~!o{hH39?+n|%XRD!iMwX}D(^ASY} z#;bXvy)zL|Ru+L;T86ZDCIadsiV`HWZfNgJ1k|~Q1ZrtppuIB@uy^)Qg2bq6r?)mI zVMO4$4-%-==+>u*kdq=J_Pu+#o-KK(1t(K+n|Pq_bpe4AB(VQSLe+Z>O-rB__J8v2 zyL4sl`=5?>eyG{56wce?dWyGWd&f9@cN0X-ePJYm6G0|2%<16p;THi>{a=$>VqB=D z_WbiiP1S=lPbmW;NEK-XVYX+TKt_?kkqB%g5hy_d%gwfd1ZrX3L_$+TD>EN?th$^U z;7LlKhR?O;9UY%cKz&eI-P3M;W~1NV=hq1iN|3m8%@NrT`X`Vp&wiv?t?##|5U2$s zHQAV3cVy=K*ROBIHc)~DhxP0v5~_H;M|9GzJ|)pQ_gSZ$J6cXR`H1CdFW?hTpJ=t= zY#~sROmHdq#0Oo@@XCMrF|)(Ifk7W+3Dc^@y_v)QDJK(GT)H%cKrQY6KEZL9#l~bY zi4r7u9Ag{)DJK)BcNvjFpq7q&KEY*l;@(wRTxKXif=5@j;h%CcQU9dXDFkZ4cuY0O z#Ny`fGC{w98I07l4o$?X_WV;$Ce9lBUJ8L)np&UWoQE&k$vJmWf`pcvf6B?k{O7i( z5U8c4?h{-OC$}xjBGN$#5?cTMDJK&-RbNgaP)pmJPjEfV+g}s@6DP(7d=#jJgWesgO-ocg3j{cLif5hO1hSm&Bd~oX!AyAS`a4RwQob+!3 z9C-1?EdKXckl?Ut!A%p{pmU{wKuI#ew13Ze|Jj9Jjg4<)ZJFBKL4w1o1vh47gNYM| z>=Xhe$pq8>J?GkKqrEv_9m*<~4yzX2{L!r?6JNI7F9b@G38wvfPF_pDxqW-q zIUB}gBEezRg70((Sqb4J6NV;&Q}x>`FLJ7)7#9!@Oq}fk|- zgg)>ITwfspBL=M*c=Y)s=Ur>Y;T0qjFm@SY;~_7FKrI;gh~QCl{m+xE8HZQGNWd6u zh$_F{pF*G(jNnA@Y_NBD#F}wB-Eb2E8clpuj~iLClc-oL)%QXc7Gbr*+KUmRA0 zRD;7t{Y)610_hn8kGoIy_U3Jc!m%tK?3`xtdL8}mbFeHPz(EJBs8F`f!BUz z$(FS-`)&fx$lPtkpSl-b*foFY2EKj$WKjdJR?G1lpW9mGpahA!n~%888C~bCnfE`2sBAE*T-O~jQ{R>w{+$zDZeg%Um^+q z`6byHL^jTUy(D{Oj7}gE@mlTb*H=H0`sg*MXPizTUufXXJ-hbOep`z?lt2oFHv11l zG(7&$#{Ovt)q-*}M7aIKLZAfdCXTlKRNXw%Cs2X})W5N@uq>58EofszTt;Q}$B@!3 ztEsF|0wtQ1s)4Kg`j{B8%L)lB^+@RF*~_Ijy}k5MDV8W|Veg_dnO!@C$S!>{3nfUv z+#aJ}tvmNKA+iq7vIx|InVN`xZ@wi&MVC%l5U&esAFK7yuUUQYt`IXS&O#!N1gvVv zM#&|ol=0}cY-Pt%un|WsOkpJSQ$<88wvferCf;lH&2v1VeLgo zfDKyv6pVRUh(Q%MwZOPg3sOkLtrMC^KB}MdP^pgRyqD1#hxblsFA^%6xJ8J04Gy+M z2@*Od`n$V>M_-gwjmUm56A9FUnVNEb!HA(kjJxLi5|k*xyI+in=BR@o3vqSU`)O@3 zp(&*Kk#c^Xw@!%TCr+~n)Y1~+vw=ux(^=yr=Tkd$&q4{V4eeCTdh;|sEAf~>2@=qD z$;NeEiX>Ie>QgKNwXilLp`IgZORBQl)oh7%3vJiIwh#%uwREP~;IS7aNI;l&MU)S! z2R|Q>k{HhV*qiOLLJ1ODhPjNc7Xx;D{)vj}tAfYXWSDbdcLJ1Pk-iW}qixMO> zCV!pi)f+GM(d3**TcQLBO|8G`t6ADxh>c&=Yl#vhv_$+h+=g-cTAy*|^Ep4}PLwxA z`br1xQeC()b7?;RqFWm!P=W-kyNFn`X!Ejk1Zv@13L4=`KFw4DB}l+bL^eiO3@lXw zB}l*wN5t0d4+b_+f&|Q>L>#=YG$2rd1kBn*tn0EfAW(t?kKlKr9-&*fqYX|COW=Q`@O&P{txTd!xxa$*iIrSV*x z?hSrFB*dek>1$DfZ>#auG~JjS-oKu0-21nyJ0XEua86A*&wH>|OC}D#8Y)8x68Hw1 zemU~2m$I0c{_g4}NT3$JfsTZhzPCb%QH@WXt~uv(e4vxg^k;8=M~J(=-cq6jmlYC_ zLK+j#yMMP3%jZ905vYabM(^8q#e~RuE2|W5WgzV_v=<4T`PwcaF8FC+2}+QFQi#!R z;+j{4sBS9cE+xO#I_WpD@A1Hy>@i8osNa&(%VX@(Kd(p}{5?GswRWTJ>YZ&( zD```fj$kcKq5lH=;w3Xos!k7D2}`sT_zgA26bXHEXPt|=tVUJ4`C{mU!L23VJK|Uw z30>Ui+ZJXX^zdyAjOTHfwd0Y{<|_u2D1j0rV3r`_zwZrBOQ06MhKYpsG;bFWC_w_| zE3z^2_6yPys0H&Q5d&^%9}t*xSPdkd6pfp6LzdkDZj3KrL7q5Ya2v zDj-k-tAV6cJz9Iil60v;0@e&vK?o1k@%GZR$01atC&EcH|!CJ%YaY!+7zvArJ-gx|d?A zfJTDKsvX$~lZ|8o=s3LnAsb3u*|T9ON-811Mlu03zD@w5%J-{V;X42%@P^@8Bkw)`d%r+1`=_+!sWW&Bl7NRWUq?G3;Ny_rZ$c#sbwj9)6}BNrtYFXSm^m6b)H7Ssn3#xIrY zL%e=XeZ-J}x*-DU+`+g|3)%t^#xIrIm4gx_pp6j$ZPy}D3;G8U#xIrohl3I%CJZmp z-bDoTL5o1GH)oe>-z38LrF!g_YR1|M_6_B+_O)r;Uc<7U<1+N$ks-l5NR=SLueX?H zuU6Xz5~#)NM~*2YV-OLwF1}7i9v(&eh3A;`4iaBf)%tJG*(T?FS2TKBkAOf4#*6mo zy#1Ymv;=DLeVadau?_P+(PO_<9HVfw^Utq(Rrn{V<_)CBeyJ!yg4fraC(AF@W4}}+ zP|H6%>s8^O@0z!q9{Z)D1PNa0vkl8H)nmU@Bv8vg(d$*g=gGm_T95rwQGx{TKiG!l zm+G-!DiWyWpEGhB1HV*H-`4u&-q=M#!~Pz}yx(OT@?tBQU@f)npU|5(!kmv>lwiD? zC(AFD%gQ29OUuxIe+BiCixMQXZY;l4u5)>@#rfd4P)pl_|NaWvmAt=Vf+a{`zp>h` zMW7b;o8Yy&$9)j{1om^gf0!5XLZAc*UiDACv1^6pmzqML7VjB;@7$GI3HL#?f${R1 z@stLv6&C-fgbm}{SFXN&tz0iTfUI z#=EAR{nd~_E%uw}aqarJ@8M>=Ys%Rt4kbwNe)qH+j>dhzJL7#;uHI)F7i#eiNmrSH zcTG9_C}P?f6_P^X@qN_F-%1ecR2WKa8`VpG}|y32gZmAwF@&hU_y!LkSYl+KGVC$0AS*+Aa|=!ijI68GYhNK+7k>c;uFo zN3KPn7W#Px9&Y98;ikJ(KI^HqYIU4_25rK4xRtYq8%mI{^I?1x%h^W}wXoc50%imC z)Z;lrTA#K`ECp+h5??a25*Gh4e~mI!{L0Mwn#u}hH4kPri@?5FIe}VsuSFX$JInc= znO~De23YSpxP#EO2;b4#y9r#EpacnBqgcLVvi3m<61s}=Z;^3*g#>EpTFde!lQkSl zkkHkjf47b6L?lp4*Nm1gnXE-of&{F0sm_frnfKkRHRN|#%-WeoQT8{GRk8S$@poFu z5&`R7`K=d~AffjBcL0zNi$E>SpXEy?djpgpq2=bkPJsH5->l(Oaa^dS^y$sPwK zNND~0ZziB!$*=XW4UP-7`n6u6`$Q@$XuBRtkofPE<+_6;f_@80_k$LJTCkfW;-5dx z2?&%R0V`)BmY%gBAW(t?_RYXE%&RCqwG8&odP2*4b-Cf?67jvZjGvd+zyIM(C0GKx zdknh?8_&P`d1Zv&<5XDQXI|*<541ElJR$)bm7f|!v8=EZG_`z#ZJioKQGx`Hm6a2y z1t}yO>>0LZ{KInZ)qCJnY7PEA1M0vvZ`jQKWBNN6ytrZEV?v+=346!VvDTW*PkUEe zMr$2?FDh}N7RQv>RRFN=$TOe zC?rq|#xAnKFXEs4)A#d22@?K@%58y9CYX4;k?-e)1Zu$;Y>1;%w#dtVlpvw@{1XsFhF;VlhM^XsX(lYc3u5BxE%i0Km5+vU0@wDm9u{_`NCCmJldO zC8Rcq;8s%QjS}%uL;`A1{2EghvQ6;H_v`VtUzGUau_I)j(ADDQ3E!+Y4 z#Gdh;#n%!g&~{^QHJPh@kZf>2pOK#@GY%4{1tWtY246Nn2$ZA}U3tVHf=8cuzn54u z4ohHUP#+^cJvYRJ6^l~{7~u>d=j}xBDEjo+x5e8DMmQ^87=zc0f&|PZhB#-)KT`@;ZoY zFmdVXV=08T64ui8<`dj@$2LB&gzE(*Nc28)k**)f1`}5{ea)KHI4;z}RX?40)mp>8 zWc&*P;!CD`a#$y-{|~Pp$;O%wuP=G}SkF==%<9$J(Zf2C2=*mwx}kdtfm)bC+m{R_ zNZ9#ckE%{z)NalmRk%XNHLmf3sz~^fRq^h<7<|b@f&{-WDsSDjf_=VxU$Xp*?@J+2 zi{CR%XxOzP;Y&u|XF{OFyp5`0AGOp}k%wD~4J6CKK;_OckQ_&n8goj4Aur&#R(MfkQU#SnK;PwcK3fpacmHb6fC#KhfCO!Zwl#)xy*U z9&TIM!wn@EFV-y0Q41P)mrbvFaco}L7sljFsq!OqFJh9yOXgGMZu1|2Cu2@<#tq7m-d55&fagF0ITYT@dPe&_Cm6+D7E z;a}b_!x;eQD6~hVTRv56T(W;~DN2yQS(MgSH~u6<JE)@CHs zVCWk{9+V)Bf}>N&|Hvie%eeg|T5 zBcbv8d>bW;Rw3bHypYE!MeeiBB8sB-;?_2@XJ-1s0H(&Yq!MJKYYM%w#(V?4sOQeJ+rdQw@(O^Ac3z4 z=oa~C^&nM9pcc%DWW$-#o_+ho21;NabTKCKEN+&|@7q&Sg#^rxWFtIfb=p*+7R;hV z92|XDK%fNHS4pWVh&K=F9McOoidOwcLM?s2JCFVD@D>1Hg6he=e>c&6^M~APz0<}$ zVcj$!fv-a8O#k|0LU@}xiT9b_bD$R9Cx~a55abz_g%Tw2ji-2@2|?axnMj}(zVQq^ zUp)4F(H!#YNT8E$OpO1acVEJPP;N|+fE3dFvETPm^uR|^2-L!IqhF19?oG+ZfSbZu z_^u1mo`?3t<4_3lIBbCuB%l;%Z14WSQ6Wy-y&Ox|MJ-Gr`TQ)IAq4x9!EK*-A8~E+ zJ3CA*&1yT_mT@aNqgR`jD1rOP;8mdi60lpmSZ!E2*PB?@!Z(+6a@TLK5R=!PToWZo zXxM+z*zJjNLY#EwO{Kf|S*pUz}>?90{yV@w*cn$C)F!K_V0t6z==1WJ&=H#(8fN%tN|OQ064AIQeE8J`6NN|1n61`*`r z9uO!&0#-OgT)%Cv&YafkHkdiBGdbFS{QPrZ17_qn%+yIl$0pH$z?wn=Rs)o(fjb^$ z-#%VtST%@Ru;L)1`;KY>ff88NB&CX90+Qbyzv~mfJAJuGqh7xHNNo~>9-d%K}&q?RLg!% zr8aI__IxHvAne+24U~8|b7m{h!nYVnufjCvLoa=WcVI!zA&fbvvQiuQz1^1Z>H$+y zNzQMZJr46>5q3Vvx^q?Ecwt=XHJuz1l?eK0X+_TbWwKAgnA zl$MkaBo-2B{-trJ-pGHH?bu$#CltwqXc>DPrkt~lm$xhjA`!3t+YE+q6U3qwOUr(J zAlKLsf~0ny3~g*2t`jM3Id+rDM+zadw){lSYu6quWo638(n`(8{q=g6g+F~#Qx)g* z`dY71xGjdMbeAvd&8rM5;RZCj+5d*LT_1jGIaNJ{7(P6c=R>VEiZ`IiPVk*hm z%pKdebBf5TG0-w8(Nd7_L~?yxetC_>v$xRB6bh9T2@O=}MTkRnDpM-rh+{r`8{!lV zZ)HDwD@7SnDV63q(m-U&|Gw8+_kO<5vycDvzy9xa`L%w}eSg+>jrY3OKIc69`Wt$8 ztslOjNBs`XTeWW9vU&UZS6|orx&d9fJsY`D|NrBEdrJF!$4j)ci~D@`zZWjVeZKmk z!Gp4P?AM9vg(ZQDZd{=c{n%7kI32187t#;iMffgjV z%sn49YCI8#?97W2;#KDHj$Lp4vek~<-1~`Gcu&I=fvp-fszX;9UDS*CN89yN1lF~8 zPkSQth+=D9^N|gfFzDgv(pbTqXT#{a2v`e-n7F$}kVp&b)#c7%S|#)^wR#M3_*+e& z#Y^0LQ^zo^HzKaDR6WzopatXOX;o@AiTHF-i4*~&=pt}LBL0~>XK^2RHCjlZ7tA?n zyxKR%MVNUGBLVY7#D6bwG|++s%q9`sn)6p2EAY08TO#9wBch3)KL17$Xh|pZ+(i67 zUygO@3SX?@nk^aFbL=hBnizlbeDvh;o1$p(5=-+2hAA>oKUiben)A_Xs@711SiFSn z6-^XgaV~oEnYtGvl1!VLlA8EC_gwV*cNP_(1vC_4#?27ibND(U_1 z_W_(iC@T$F3l8ztzdr|{-ta{TYE`x0-^{-C;W75>4`c>$H9$EDG>xthk(o_{Xt@YM z8o4+257M02Uo5`HrE!s!NQ8gT4T@NItQQhVB%n+Lui29R8ZjO(?zxO2tV+*(Ffs4s z_SG-19uGkQ^JLPZDBD66uJ4$@{sng^ddpftGYaG`RiCx_pp4(L#|E>tMq!XgS?Z5eSe(dbWkQo8E`J*jlYIa>40VUH>Si2$NsA2-e_UlTKI@9X_wv z`nqwOUc|c4i_6r91hvu-jbCcCHG}>!A#vAuh1d&Qt2I9EwClwh+s38!gU5ymqsP5B z8f)&H|Dx4vVH!bgS6)oeDDaFL;^{_ZHynSg1;xZvtJIF7brtp{^4G(2>G=-d%L{gN zZ-W*t3&9#(KkMjzv<#it8lV5G8Y}F%crn3!;8tpa$0_hqBc&mGo4riWRSR7wjy>_t z@>{Q+J_1{nM1sq-qtwdO8W(PDw6(#otSi+j zX|2|{r`@fs4^M2_md8gdNO0NbTe5+7u_nIk_U{YHqr203E?$OKdr}kEPguG2=#dgz z*&?IJWnLjXUN}#h7=3X3*5doCZbb_cT&5iy=8@3E$9Hzy`hy)vBgBgdGgfAm@aQ&w zAf#F)7WOiut5&Rivgl=ZLIgE$t|d=S9TbUeV>5y%d z*dFG3k>FLxXNlJM}50(T&8u!(OH#EY)@)pv~?tKJh%Wgl3v2}BcX|p zX>>Pjn%0`V%=jpR>t`LFLD^}VXisr>$hb|d(ZaM4TsD!~v}z2+_KtrPQ#(rPLN6}M z4%Qk46h*uATG+-|)EF5;jRdSKqwx_%>e}1JDGl7`ChjJgHfvW1+EG8-0i|K~hw?Hz zD#04=2zM9l+W+jYsx-vH^$Njdv**p|4%Cq$jSw#;OvErmGm6wZ=KreZLoDoNB6Sh1 z>OiN#{2kr5Vtc)WoD4b__4#~sv-8$`<^&={I$=LX@|E&Uc|zCXd#mptD*90?M=s z*C%|w`!|dlm0?!N-n==%>yCB{pe3CMG7-`m7bAQ=?PX|-wTo<(vS__D!f2d5Gp+#o zks_#1Tvq*U_%{^{pxiVzDDTsEtcMt5dzmYp@Ff;F>$u{1)wSo^lY zmxY$(CWu(}t7TuhyO`B&-=}f3V7*+HT@dkiAD&?kXxiHPr0=pcLcF-9-pjK>!#-$A z8sistwcoj}j@AC@5sDBC*2`tt1@sBzX1~4aTsN!QqFLLqF7)E(bw;%a)thrCt&)3R z?q=WqQA6w4ifdwMK?2G|l*_GW`)YKxK3Uo=`yzyTUaeV!(87`PtcZW!;2!q!%WGKq zV~4sdSTC1l&qw_G&eXC0=$UCvZTCeQAzrNg&a`5o)}xP+#!I=^*zwo@&i*cbUO(G`Ot!*cop2@!H<@y%ZgBpni)4OX?+#S?AVpkZuBHLfNoFc@61eeXK zB;txQHSId@KaxG^zHk~LUaax1{ZsagykS}kFYxu=-f4t*8I8D0V>@Ul3)XA&RIE((BQE`*R;38)hw?IGWxK{I4r8S(STC1N zv~%VoF7rX7nq+#N&Epb=sLNC^!2yVM#dmLiBvLL}_ zvnuH{Fy}{H&JU>zy;y@zICJ8db8tJKgJ?m5%W~R9{P`a~8k;sJnB8pFG$GV!*{029 zsgsjyk`s<*@Z6IwLM%vd+2^~_oSZdQOkg4|8c2v2wl?BF+h(SVkRD>aM$hzoX8z#V zur0^qtr`!Pekcoiv4)Ic#9#GTz(t4!2`BWFf?lj4Ya!xq zx?qEg5DOAqmgn@d)K0@P>fL|0U25arIM#(;{9M*_#Q#nA@h(CvNN`!6NBj*cd>zQF zKf}JI-g-G})s8|h){wnPKNIfYCd7gSm*siH|HI5~!ThYr_S|7p)u|>H^kNN(F%f?~ z`WYt@VnKq-@;u^SaA0U~PQO9+dnGDZSQmQnbBUGdgjkT^vOJIYw+(qTSiVbLyKc#z zN<%E@#TpXx>2&_ZO^5{vF3aZ%bb!{CCF@Eo z=*1ee5>1{M7+TInhy@8Q%kzl;>7zMOTJ4tX53!&ZYtX(i`R@PzyS@Mku^_=^c^>iC zzV)jp?Q=`^xmeJPH7GKK^jW)nwwn+O5?q$&5&z9IvttymEQwcQK`+*z2xsmeUP3HL za9N&5{L_|9j#1pTB<_j@y;y_dvAIXpeD47lAr>UKEYBnUrK6wV(;!>U53!&ZYshVq z&Zv7IauH%dg3Ize;^&`1{`vjsK<|0e3fR)+?S-Ky-dkdG8OLpDUS7!O>tH_LjSW2+ z*w?S2BE;e)WM;L-po-;!iwB(!uon{I1=^Ioa;yHc?VG@a`4(LHcyW1GUT!G*?`3p1V2!2QItK6VksU>gmyn&NiDwqH4E~eov(8J17e62S z$8DiAJqH+#Wi3_)wya93R*8kZknlg(D0F?{Ohe2FFA4O_e^U`+@e&eabgQnKc6;!H zPS2?MKtjBjZhCmTRjJz3M#E?RhZZg)A+b_x5Rk)=mk=+0KD^)3?Bc!i+!{G(;W83b zj_Z3A&xe2In&66uepB-ybs0i=ak+AMlwJFqXN^W;_?>~+p4Kt6c!_m;iYKhIvkmc6 z=mrFQzLUxH_?F>lk;>)mVvzy^x^!H#aZt`GG6C z2KQ%vuI3yG@nU+*W0Mp8o@#3}+Eot*7xW*a2(hpi614Ko&5Jcgp1UXbSN(6(2=QXN z&-?Qe=bCCoSr-W|Rz{%x;Z-2N# z5n{o5xlA$N+|^j4^pG2a1%KS3`hkRaF=1AZ(WuaMWAL-3w?)x{^>W#)X+!W*=l`L_ zOUT{FwLj7b@nYKSTBEU~$ECq1-u-3`TDXja+`_a*nd8$NAMW;$>bca#gm`h;L=2-b zeoL|7g16QvLM&dweGc~eymzpBpNVONcrk6FXc1#27WP8I#N#3ev3LnN=XK8)wqF$N zdAz(@B}j-D)8p31>C@qKDXAt7E&o0HRM9NO}2 zApB*IC|bCTgyaueqrtIX0(mYZTe@G@9=ULu+Y!HN+p_{UK+YN zbA>wFC6`Di#DWBueZG|;Urq*PGN7@YHINW5(5A@XC8WJrFX$QK_kV&`x4n=7z4$tVQ#|#H*z)v%0Q5s5FoeFV>KmO((>H^>VpR_q#$hD-JOl z6}J48eOu`YDsmzrUaTQ2RBIq17Oa=c$0jxjZMyt1qw!mEX?Dx|8z~JW#EUg#r)do& z#Dev5`No|)tsYI5h(`M|*?&FUT4^95UaTPz!)O2@7Oa=cBjYQxn{8QPG3GreL=fq(RB*cRCa{2Aky%OUWOf(vEr>*bw|M&EEfyHl+#N&^Y;VhuU9wFVMm!Fsv8?#+dX$MTMt zeLlQYOS|2!wn_sD@nQ`pli{&KLM&J>mrHKXPqZFe-)NM0qn$lqR=2(hq+5L`B^(hz2~TUZx*@pH3piXg;-1eeY3GKAT+N&^Y;VhywZ ziy*{;^>W!n2}79Zqco5ZFV-+|tO!CZSTC1Nv@^tSI*KX{B*cp~Ogt`v5DV7JWfQf9 z(C3HJKtjA&!<;Kc5Msf4xol1!Lzq)dX&@n9tYOZ_A_%cyy<9e@s3FXGuGTIR;>8-~ zoG*e93)ahJlMNWcWEn~W3GreL`5Z;>K_tY2^>SIVGy18_rk@Hroqfm}GT4`m7W$p8 zEb-#!l50i$PhGz`iiB8@piiN))N|jiK*Zncf3;$Uh+|#o1=@DRf9zNd7hzgLf8XHL z>+^-Ag+#pC=epRzlJ{C4OnF0TIE3TH8j@>8{BQLeSIBNBk9z&WvrZeVtX~ z!Rj{FgtV8pL){szlr6CsdVhzc)B7S?qy)Hs5 zNYGEkv*dZi->K=WSp34L+4kzuN<%E@#Tt@pMf~?Yy~0I^1qq+8MwUE}_#dyeF!tTo zR(7*VQ>|X11nbFj+O-c> ziT%~2to?Q48K79yrXtCw5ZpL9w70Ye=pY@wa$zYZM8wAi-sM z9`O%}k1eSD_au8kY`W4A3wp7JWKI!(yE9z^NQeaqF3aq0Mh zPTA7EpSM?kwRK6WJS6CMN1b|k+>8bhx4$qcXj+wxb)gqOH~k~x;i*$ygjkT^vOJIY zTL+c|&FCr(v7i@gn0cZTXM2Y(E|79KR4@*G?GW=x(Kl# z!FyhwNBpxkE)JUgp)|yTUaVpE4QZ4c{FsXn3ldzG=Mn#g$xjB&K35uIK`+*jT#G(0 z*^=)f#DWCJM|n=aRlIC|(8MdHAr|yv4HL(xA8Yo{b`fGhf_}?TVj>aWKR+U9;;zzg z2*-;xOgtvyK;}IzLM&J>pC$4<;xBuBR?wUuN<%E@#Tw>ZA&r}!sN*8Uf&`c4IsFD* zwSs^-2bG3c&`ZsS{`7-1Mt)r@h=e&gLrCzsE6*eTKmU3wV9s+rAEqw!Vhzc)BL3mW zDr6ub79=yfPf*Yph2-xyQRbF%jC=}o_bUYY*R%gLM^;_fpY3((>wa-^n&CdMuOJ#eV;(WsX& zdI=r{$-6XhcW$ZRj8i43RgQ%<9Aa`-;_a^C1&tpv8WlSp49xr_NE%2uUi{pQp&=fh z|DWK9-wKq5SbRPt?#voJrG0qFiT@d*)Z=plJvuj48V=!j`FwX~y}PAxIFbCr5dAlo z2!>udmVxT%#Umn_n(q18jF!Rvf941Hi00jByig@O_~H3aJ%r=MSq-meS~Z5a zdiFbk`)U_@2*-;F$p&@L#|@ks$UQKW2*-l;a&|^HmJPIDjK)=M_5}tXx!OZGUYO5m zjb;^R2EOm|cVo0*y?nw^KN3zq3Lae&GJQQ^kju+=zl5y(! zICA@$z>Gg%r5SWASg+4FER*}-?DKik-wJ&9!Tr=KBpfd$c$}PA^5lcN0*{ZmC5;d- zuF2$GbW7!ZzO`%l;Gmb=(pWhbte5sTWWUs7Y2X+V6 z-MUo~VsR70GILq>J<;(2oN zU2fI>H!23lzBzze+E_QY%J}l_C1p`!Z0e{`WMxs6i{y zc=2<|gSEz;BQ6OJ-j%O3#DewmUNN(2G`hBaGEieYzc0h73%&TclOc1@N8UU)a8n6B zaU6@AD3q0GG@k0)B6xPhd#Y7Z7ZYZ^hIrJ?{s`-S93J;@aLCwZG#{wpcyT*Y9R z;)>DeS@mq-nf<@hN<_l(;^!tN8sg(V*96ZF$yWUkb@bx1OLA@9syilM6`Wr(lL*J+ zCR$3QHX1kWnG_hE+(oTI!tvr0j{4=}d`oNis=phUyljn!aJ(?T)BsQOxOVG&;1nJaA29A70Euh!T@I9{A<(|+VU z(d^oNuMZC%`JLZ-f*Ot&=J2}b_r>1|G;c7DG@M%l*2`rcSsr0clOd0Wu`P|rj z7s30-E!*4L^v_zmctjWUqTQ1%Z;jyj;N8Txmx$j@I2I(hO!{G8PD3}b9qU3belB+r zmxdz5f&}O#G;vAKmR99nne^^9r!MruyNH)?ZYfA`S^hd(6EkK6tl2welZKlRFWxI= z{!ObK!m(hzT$aBR*BZ4J)v^vhu$?sAgn03Dv)YXY5@Nx6xh#LZt~GidE^GZZ?TFGq zLcDnO(5Yr_MLg#Y;aIR9$J8ux+p3{71(=4i=c}QL8#V3)8)JDT0919X$mNypYp3}O` zru9o2ZbH29hU6uj+ZNW#W%I5M(<*X?ybb@xVA$X7LId>D{ z#Tv90%w5f_k`y5pte4C3?hM@z-s5`hI(4BJ-om_ubE89o%kp*)P4FJqd(cgY7sX1+ zUQN#(!m(hzTsH4ZF$CAIV~Lv(FTPn&j4`)69xI1%ELbm>DH5r-fa!klIO&+^Cd7+1 zDDIm3AZs8Y7Oa=c6j9Y1Rhsbct~8nOHBE%}5&!Gv{f9c;VepYdC~+8^wCL zY}S?0Fe{NX+=O`XbF)8+AjE?8a@nkWLzo?{N4yiMwUID~UE#d^7Hc5qk|CNfx9 z7kY7QcW$Y?N*uzmAi-r5iHwGciKO8s#LIn4WetaLZl+i-mrdL?8YZ@rhMN#CynpJR zJA`xN#d^7HP6ngFdz{uUX}AgT;+v&82h#}0g7tFQoN$IPCnssR3Gw3GhsM#|gk_J@ ze~EA`STC2EpuO&BaL$lMh!^Kw&P~{87{ak&y+%*H=}3>R$$dz}O_=P3?j6n@*Go7S zte49)((0W{sTt%Pjx^kac=2d`C2}sRG>{N4yyNOtIfQdx z#(KF-D_^~NN)xoBIHx8JHz8hp_c3|9X_Z4b7Oa=cCL=cl*UuEzgLV_oRQ&*dJiHINVs5?nSnBqz4>T}^2qAztqLIk$>eh$fsHHrC5! zIvLFS6Pe&W&g&QJLNB~i>wY+db8|<6%X0IM_|KKji=J*b!^+ySlK#>=Wuf=tI5%v5 zBN*>kev4$pfB%IjCr=L5o>K~xD0$cp9U#ttg__@qxIw2M$xGc}<4Fb#F2(0XJ zvo&c)Nek;jFMjT<-6~Z!y9lu$!DV?K@i#0y9XPeVt94b^45c9!^kNNX4;I`~EQo|y zkl?aBkN5|C*(k{MGlg}b7eALMkxqyO2`m|g31efL9jri}V{3L5^ z7Y!uD%V_i6nKT~ycCL${_9_e3YxE3p<*s?$^SF!^5>jRj8eP6SlSbw>3tfa*uwE|9 z^N8R2coENFocB7`gmtO01efJ`#Q*GtfgBlZi6vq| zFV>(w@ZFi>?qk6m7aTr9 z(hUCitBVi|5?q$&5r6dYya4S#oA)}_gz zb)gq%CnElD|1ReuOnW6~P`7x{BVtq43 zhy@8Q%X9iY{my}yiHS->Ea=4=CRUOLo#!q>EJ$!!o~!dbW@5Y25DR*-hB*yLqs_EI zEZ3&D5W75^kNNjUXjMYcXM2XSdiedJdgMbA9*}x&RV4*7W85bd3U%v z&s~IAkl?a>F0RgVCOBtM8c2wj>4%D0=>)Y(S+HKCX9zl-x#yhwNIz19&}Kf=UZ-~g z+PN-*Mps#|UM|b?h=0}D$9V?TH+o=Q=*7=zEvUU7@waa|$3=(*2`UQZ{)f&`c4xjN5zM{!QAG{k~ltU-Izyt$sva~B~NB)BZk)p;J{e1Z2m z)`edDoMH^$ohe>X2H+yZf&`c4IT25HjB(z>dmZaSFMdu@l;2`c8g!n!2(ci+WqGd7 z^BCuEyw|ZV^y23f=lSkT8g!n!2(ci+WqGd7bGdWM`Jw7UFV>*bF3kHgoe&EWT$bk) zea0=3o3J`-#e!aVr&jN$wkg}D&trTRya}2 z!SAQu_|xGiYCt)Ov_ow2eHcZ{MF@(C{O)Vh5BhJa?dC1k`n}iCsv-z^FF0!Gvg#kl z-GK+GH8~c22aoIR-}ugLplPg-K+8o4((wN~pTDDu-{noeNzUIarbibD^PO1wIlbp@ z;*S9#puMhlgrhcn`mw5BCVdAF{Z2-X(NNzF=XwvhCiHVRffj5bYSWul=_L56Rc4HD zcUM*3L;ZLwIqu29VO=g%WuI@CdS0U5%`{d_%-(#JBG8gf6ed%|_EO8U(g;m!ueXoA znbKAoDFQ9&gl=KP&nI))8>`3o28o0&Yp)ikY^CwlAJti5I|e@SVSZBv&tkU&d1QJB;OpJq4y zbX$N=HY9Xed$lWyaZ`5@q_=0)-#s7Y6B-F!)?O127AlQ4 zwGM8QYi%w4@V-Nloy*;E$Y=0nRj#&}Hqlv-=jMQR}^hq`}1gm#0UWKubDN znA8MkNqNI-M>%6cLYKAIU;Q^LjT_fwkp>f`%QpxzftGZlFsTX7_Bsx=_;Z;qNa(Wm z^7*tzhd&z7U!O4%=%Wd=q!WcnhiF&!Cf1;z2|IP^vi1_~$%D4iZ%4C6&3AqXFoBkI zqA;lm?s<4)S?+lp327C3$r#qizmZO7CQ2MFqX@L56NO1l@C>d$SUbqO7YP|%_L8;G zI6p=jOf0*9iXzaGP823J!7H(2otf&hA0%Xzu$QdqM31jY0|~UG6NO1l@Q#XnFf+)z z7YSMI>?M1%_}^ucdJkUl=FhxqZM38lg-K1Y=Q~%IQJ?)FA-k5nB*x?ht{@F2b}adY zKdZLUl1>yRHNg?C*{R~{vmYcR`mmS8%0BH{kOmVOr^hM+E$KvIQWHGa6(hH(&wh}Q zD9T~9rs4f2XaLQVtrlC$gX{#TO*6Fa*$Qv_Pl ziNd5NcqcW^Y!Kv~g@l}H>?No6xv%-RkeHzJToGtVCkm4(q6?kpX@s24>?OHGs#RUS ztXNhNXh|oe9~{}}bXK4JAR$=>*L$GM`zj`;MmI&EC7qD@;0R6UIsf#>Mnadh*PDAk zR2r#OlD#E!=x5~X&L#4e0qm6XA}TJB{&&s~J3wb$&duarhAiduA@uVVr&>4d~xnrn;Bb3UEpNa(Wm z>h#*zN+Wd|Sf}nfRlo#V(g`^~Xn$L~ejLx|xr@-W_Nut~8>Nvt)lvjn(g`^SX@6U< zRD3bYyB7&v)?Pl}w@M>*I$Hz3>Yc#^TG9zP&zUG7f_}p5)TPVXOSDs2hILoRo7Cq^ zXh|m|FX6Fz_S{(Y*$)!ZDy~;XJ(Vq4b*7I|1X|Jw$**|M>2y|~{U9Nu%k|1yNM(K2 z=f6InayYc46Ot$L+O5_ms&Y{zWR-BevI|n#t2O-V>FV<(w4@V~@A4j;HEo9a><0;1 z?OdYjg7H-@8I6rnSKH(q+XNJ41#!nHs-b%O(nSU91yXae#ZheIQS}Vuyd2`(u zT8bic1~BvYcT}sqgwX7TXE42?Y29AcDvS)gi)5ekPQ_aW{bo(yI!fbA&)PAx6h-Jg zxT{NvA_<|{3vWyA9fg*n2p!vl7ZR!;yrYniGJD~zFXAtK>sj6NrnO^eDT>f%)Y->$ zKNffhq1g*>ukIa%mZAv#i5KoDB&5t0yrYniGJD~t2@!v- zp?cSz>|8g7mZAuq`wWQb2{dzkAQDn$FZ`4$;xA6$ValJ-|9jy=eEs^7lsgxO_wJcR_vMjY_wLz5KWoXQpHtkb zp3}Fr)7`lk5hsW^PXtt2aCB*` zV9v8)bX^3j1tMy0ZqF@JKl#CWeK}vrDha!Z7JIHt5okf8NfW-;s`W-1Jae7=Th+J4 z!uYsa1!HB1<&_pF0xhl%)l~`#xG!$P88?_sqcQhPFGZjQM;hkI5HnV-R0LX( z;If%bB6_`XBFeq@w#tkTuU#31B&`@ChEDn`Mc`Pu2t7B3n78xMAV-Gm3tz9-XCMBY zOaD9y>4?8c*+uFc?76Q-CR*h4E6%)iUMhKeop;_>kvgyZ`2r-+3$y-+|Myvo6tVE! zTT!&=JW=0kuqJv}*y-7d_-fLJQM4e@W-H&@3zHPDXslZOvQiP{r_Ya~1qq!q%3ZC0 z+o6iMuI{%k0=@92N8f&0ZjK^)b>AIDi_YQnT^6+?{*xP5sch-T*?+qKp#=&2T!Y?o zm-S30YutRMu8Tk~s3{ro|5U50>c@_sJ0d~rRL>fJawB>=PrT}_;)?iiyPH5S>7UMC z>)n*0h+A^6GWo9l1WLw=Gh}zGmX#f#i1?Duu2vx-bE7l;gRS0F#GwcJxCr!;wV>}G z=c}$!M3Z4%&5cEWhA8Wb?>O#OO~`mn5l3$C=h8qz*0H{;70mcZ5gSI_<08;YcACCH z9=&0sB5uAk=pxVyb{frKyu_D^czR*~7+R2!J+E)Vm3n-xiM#u{2=tP;qVMN-9r;2L zg;x)tD8x5<{YkvUF0L1~BmUPOKcwf>wMwIlwweJ7Mg_kiWnKtgBB z@;UWQZxvVl*!^b>7lB?n_mxkb^Ec@G`P!^jE&{#aw4<^5_0VzEs*GA4=^MILMy9eN zBy{d8pE~7TwEjI5zsRcb=DRL|KWW5xFmcdNQzr$1+Sy|ArI0|{7H)Q=xd{;S5SQ?w$^ zxw$*(Q$}V}-@Mw^)Ss7(8QaW7pqH#MeIM*O*Qdtnu0iEvXpyzccTRV!F8NZ=`R*I5 zx-^iG9i{KiUryKe+KHu_x(M`={itvBRjPp_~Mo zH29}{Og#0%k5RN-gdhz*%QNRanK5VO@H7p59~?s~Kc#(fg3fa%r-m{S*^66C_G-iE z5~1#G^xs@hY^VE2ihyx<5$0y0=!pN_DmMl?&aWNh{=j{J{w_atV{y?%5~?m2;pEiR zkB{>I4sg!Sa}ReMX?xl|I^vJ*b_i^h>60d)h4c-QryFmjK3Gj!^=xY*K$!30W)G_0 zTt#jAUgWErw`QX8$5mUS1qrh^&F|KZ+1E%BOHPJd1bUhM80O!|r{B4I?dJe%oOrfo z5Ly*BF){2LK5G*^C*t;Drxj7`#nMR72&*Wn2ooR8ZD$o~}KJ3QD$pqGiF=J#G@ ztg>45+y*^2pFkC=zmSDig(LogGf}0{;A~+AT41as2J`Rl@^2w^E6r=l8n?#PDv6@X z3tC0QeWm_X8l$uR-U{<+XSyGA~MWaWxmv?4UCETxr!Pq z$=lW5jQA(sSzc-MoIV0uMBFf8 zrRw=FM@nqPQ8f1`wLfswBmPkb$1B3Ozp85`B4O@SY6nwFq)JU2PSrO2WgfqHZH%)5|<70l$PVaNvY4q1MChiUyx5;&K!rahF z&A)+N$T5*xHOj>Hu74DB?OODLIVU1!qG)!ng>7J6ncoD{^}^~Q;zJXu>uww8+O-gO zU6F`-Zg$i!cAyRH5A)Mdb#lt*B__h%Wp-`J{Z(D@3ihD+Ij5c*Co&v6Qo=>RJ~uzL zEHvl2MCzUMe{Bu1#QfZ`P~{1*YpLgQ8qD3%9d~UKVtWEl20n3oDu1K@+P<9c_|t5P zfny||Cpp)0XO?b4Ws^kYx(G8L>ZcCsZlE;o`E#M`lRMLPqmj}MJH)0o3!=~}iBVpH zdJe6!KphEsV`Qqeq=5ulpjAY8Tea={mJH5!!QvVp^PHld`N@xU%fkndP!`Y=nx5xU zKN^+|sK~JUbn)P}4sUlIHR@P+^w2s9D2F&c^7B!nGHBP%n{qA#NUA_Sf1 zPhYxMX?O{sL%rYGozjl@bN>5Xs#R#Y2tgWObY2|glau>_1e8OY2fwE@p7`Tm`n~Y0 zAJzHpZ5!$b(Q*-jep~(N2Y%+ycP%dgwDnoe9y3-2q*3+osu&a39epc+mWvRiu{W)tt(nuITrmNA6hO#WV^=-XAR1U0kOAatf*BuR%p2hK|RN@ zLITQm#*8;*tVp9>mDXwo`8y}jauI?wwvOtr#>z_oZI}9Hhl~~VoX1GU3N05QXmra= zJlW-|c^#}`uQs<~Wh9#I-rcoLo8Q9mi5Ur4m9#%1=YQ|Ad1o7o{?Sd?*&kklX?ok0 zCbkzvFfCpmwtqXNM?W9@_=W6`OSZ7??c2!4da;G?4|`7$k9=2-G(M{Ne0I6#I$J;e zT+K!c60j<1bhD;Zux93FSu^_=a}ntE`qDj0V@Ym;h)Z`DvzGm8S>5)18b=Efuqufd z(6qJHeRziTN#A8I0=<5{VXx8{_CZr3-np)hHGXkdtNqg>;%GqvcLDtk@40T)rqdL@3+D}P2_Ga~x#JKW{q^AYQ^$Lm;VK>~If z5!HtL5y)Cn)B1XEZx?}Hp&IX~exx+Eiw0VdfM}=t5tn`-fnHw@-{~H!xQrEAkbr2X z=OZrjfdqQhI`O8`NX>a%<{T|ZK(y2A%9eG71bQt#xkG8B)~+pU7cEF&bXEJqmi>VQ zdhLHiYozv|&3ka_vUV}FAOU5H)U?lS+2xDkqDqh(VuaH2m z?j!Ylq++5iF%d0Dz}%1q#a&zCE)wX~a>ZL}K2otgF0magNWdCPsPiK(=LZt#ocUs;MkiXR{VDWITjLJ7B4)tBYq^%;w6Mu zt;(MDNvjz50|_pR7iJ%t@D;yK5oqxeOzW|t(Y3xBad(VI7YQzl7v@B2KCD5JyA**I zFTu2)b6O?VH%sq{@w!5S%i`tE6Pd`ov%VtG;w6~YYnN8Lb!g3*DDMv>xGY|nqpJO3 z^}p_h7!zpm5=`qoNW0d$tW8FY_c;<=7B9@T)jqdkO*DZPFTu2qB@}(E&R@S5<#>ez zm&FTj87f{`3+;Cmffg^pw2p}sMXhNY_7-s5MS{!Xg|{UYcdb%iA65ifyadxaw$u5M zJ-Oz!0X{#F;Ieq(9ZsDe*=sI&O%Z7E5=`^`GvYs6y@vX{{A+NdJZ6sKGmOyGV$2&Q-Wwg;?qWYRbF2>lZY8%Js&;uuMVOG z35*gEf64B1)eQdcSR#M~dW}1!BT=PlPm{)b*Vj}1xZ{$a186}4qaFP%KtWu6epT}G z(=GzN`YqKFwRrD5()jI;OH`|Vn_4o679=og)3+Qyzg!U=|2H>)1bR(xqcf-4-#kki z{E3WwCW96vp8G|giPqWKL_B>usx+$nxF(1eB=EeVcOiYk-G|ug*uI9YZ4hPVJ1fIKes=e7$X|&q-mWx2IH#;SiM!%=pl18j+an+Aeh0}s) zK?3s!ilY7ID2+BVd%FnqI$On78t0mROM7tTb5AJZ4qwk8T9A0>!MGyE7OzFblBsX%qilZyP>Wk8oYIbi$E`^iS9Vj36Ch^z|hN(u#vzFFyjC0!YoCM>~lVV zb)gsZk2D6(y-JPlU5%cKq6G=eWF!97&t&Lz6?i3p1bV?dB_jUbgFC5KJ=psmoR0(& zn2|^P^-sO7_TZ1FmbnP@g7rokbIUJOt(tRcHm<7#60i%1xN5-Ns#RmA9}1ua3A~F$ z{I_+|GdTUkpDqHuU~iH}{RbPWRvl>hX8i7o=YAXbvbP4Aykt@^(0T|u-U0r8lKdw2d?z_H}> zpKruStv(T!6B$ox`V4vBJxb$_?zW3SFF037qfBtIB7VK{?*Lkmz>Fi}-?puc>iMf1 z8{!$2Krc8SN#n?8Unz~^&wYUBpo_q4fW9lfWfP_GT*U@KtP8#1oTojQ*{7|=|H^lG zxeHjVXSN)mpZt9kzBzLRy=l(LCENsBkns6FP_(ZGXELC%9SQUTZFj4-qXh}jBjWde zf~p_g_C6X%0=;lV+yq*Xxbe;RRX?uItVQ$jYN^YVM%T3m<4B+vt_3%N79=uz?pGQ$ zD-I!z3R`~4=JC3%bOjp;^m4CuB+!DyD?|1wjZK$7MjF2*mnw~x_cyYUKrh^BZUQYx zRJ;5=rO~6w64q#6Mrr)@aBCY0^m4}%B+!CHeB~~s(QL~K(&(|U{dOL!_QTrQNT3(S zF*ku0B>L8WTWL(oT22~=Ru7A_#y=l7wUIzCjNonpEl3oLzo|4{*|~r;RwZ{RjofiH zZ6wgkec~X279?7)Oe&4>3nr4r+$kk&?#GV(|HP3%FZaob1X_?d^0TcpZoRxSY4i=( zQyQIWZHXg+UU+J|3A7;b_SU%4cr5P-?epQKS}KipyV}N)KrhTb+yq*XXjxTjv>scZ zG)lbDPHB|+tePwLK`*GuatPmRmm*;y0c9efAK6$JdO`m@1X_@QJ`n-)k&Og;!90cB z1X_@Qxgi2pNj4Jb1?$a2palt7V?@Aew~#!R{`U}QK?3$X z5fHB|B+v`un1?_M5)iwHfGBDqfnE@gJp@{ifEdh#bADJzpckAg9s(^$z*#~BoN5*l z=mqDahd>Jwa3&G~=Xo{~=mqDzhd>JwaJCZxc}X@B=mq%-?OG(zf&}C!M07g)kahId zaIMFTu3$_8FAJu|~Za??y=@js%y*3$$(1s?JYl zFo6~?VOmJU!IJk{Lx&6qd@$t=7XhuZVH6UYIDY$WQ6|vhC0Ik}aNBENXZ3CH*}57J zR(I9Kw0Oa6k_Hn?JFE&Yffg^pw9er=G;e5i8T?^jNT|DuU|PIjRgwl1zdzU_$^=@x z1k*Z)i(mLOyYJ{vGwju)T?EtO1-pwhnE2}JvOy-$;w6~YIox+&TiH);t`=-IX{w80 zTD%}ikOmVQpFba90xe#GX`RFMUy`%^@;B-QH&378BA6C0h<2pG#N4Vi6oD2m!L-id zrd*jHzxrsU;JC>XY$UiWUJ$iOgNbuD^i~8~yadxahx@BZS-bN!1A|{TzR^a4%i;y6 z4{0#5>GINwK#P}PTIX?Y4L)rhBTO{ z^HP09pv6ltt#dfK|Jz;m9}nF3*p5m_a9OrTyU|U?qlN-*^bLcnQ{^ zJxB!a+U6I&kJ3K3kboT(g8grZb`Kp_1X{cVYfvm9f}>B@)%9W&uPh`WGK3)V8G_=K zBGBR`Sc76B5hm`&D2iH0K!giH1UJOAth$OoiUOhu|bK z#IxVER|HzT1Z&V4MFgK}r?b1n=v1?ifDz0iNGA(J0%}Uoopa6( z^?72s<=yD>QHMY;%$y?rokKrW#OJ3D1ki%Sp&QkEQp5Zm=n?wdf1aL0=-}q zh&jzAcCrB>L?CQble4rt^sZ#_s}(7+S4c015Ou{nBAY@HYh0-+%mgjT+rH z58ma{KrfhoB6@t@M-hoDCj`-gM2%YNZMtFl22}bz{UvjMQLTEtpstHRuR0afJAT9b zoyie@^`$ix5nlRT05#AHRz9_A!K3=8GU0utgJ?mb#|rhX;xK;;Ih|@9?o<7^_sZ*C z1bV>^CXLaHD=FgUS=EDRL89p|I+IPj-IX-TRMCI!G-gg|7lB^wim7jv2=lje)88~~ zTBdrw^0rbg0=*!1@qCPHqgwU&<~l*NAi+O%;2lNZpF$eXj~%3lhkDd@5$FXmm^4~! zUZh%e+l%FbXhGt=e|0{m`*Gc0!<5GH5=R3_pw~y$6M7}8u^Q2(OqBQex(&l!8t4V5 z54Gxz^J`SA?my8zh!!MX8>YT*!p!;V*81lL-_>dFBGBvm;Ks=T_L~J?6cp#_FE6eO&~4ZEg92B6KW?&iGIf|2*H^MW7dCPB#7ZK(W%QRekoH z4xj~zU{rkj6nB7t6z0g}c&^Zrt;>ei}$5G_ble?@(_0-q8zR)3fJ zUJ;G$h>Jk4QKK~BTRf9)^pk$oe@?E&zMqa)#h?E)fEFZRKa$4bRr=@7l?T1$BG3!=KWQxe{H&UfmZR%qED0e2afLME zZ?9HF*Qd(32=s#3MZ|L(auo6U^b#%ty&$?$tNvT4-eX~Ho|J`AG=v1iVA8l@uAaf= z_3O9@^ny4~#P>57sreW){XE9@5PHE$M6KFz|Fw#!U+{MTEl9w5MH=so(7#`DO-?yH zqeAEfXE153J*pi$`=pFaFEoQKNRKcT3=1#7&?D3I1DTrhV@|L}wJ&Z#3vP2k<83 zc!74pO`rwq1wA4z>Df|gRPL1-M*_WI+&lzYkl?@0=6>k!ADl5GpfqOhm>ov~y0I=yk>Wn>Bdt zB7t6zosk9-XhDMC?!g**fAIch4c>!DpciDBq=5ulkl^>Fu!i2}TsLbli3EBa0x>XhDMCS;HE> z=lRYF8eNb;FVGIT3A7*qdPG3avynhA7()+%79?QYh=4iIMgqNHEqDmDAOZ7F1gza` zB+v`iw1+?o60nYmfE|^M1bV^V47&-mAOZW42#5?866ggn#zUY535Y91K!mf9Kre`u z9s(^$Kzt+uBDIACdO^(h5NJUH;ye*>Mp;Op7o1%l0xd|uc|`=AwH6ZS1!u5_K#P}9 z``p)06OuE~TTfD-%F=0{I?uz9OLz#hAOZOU5s=APNT3(wL>>YyNI)J$1kHIi$6ea* z782+Mxt)hV3lfme5kYHLY0!SRkU%fUQ9T4&kbu0D2-<^6gZ8_H1bRWP?IF;D1mxF5 zaNRsstc3)6!JR=zpA>->B;cN)Bb*|5%#c7Yxchhrv>*ZZ9U^$HxgR|DNT3(o;XDLd zkbrv|5p+f=4PL`YpcmXlJp@{ifcqyA{M~?;Kir?cg-?Aqpq%u06L!D(i-}qOyVdvh zp#_O_jR)7K6X?Zde%qUV*Cc<_U*`UY;G6!m1qtpG6Z&0~NT9__aQ`&H-}KjO{G;$q zf4VLlE1nzH(C;us0xe#GH8io3zUl9St&gkk?Lz|RoYxp@P%cXI!NlU6*6>Y#+TtZx zLlgW>f7j3L4Bzyp30%9pS6G8`YTAQL{9Gxl2()+!*3blh)8DIIu7Pj*({(W|UcBd7 zgYE{T!Nj?$trdY5FTu1X_?!Md+0_!h=}*^%v4mq6Yv^~eGSP3~O!%fhZSfMUp$Yz` zzpeM(2jBFk352LCNgA{=lFTom`;BVO+@bi^1-it`!8KqCuLcTkb1`~U;>L>y&UV=4J#P;OmzoM*x z1fI2gwmbdc7?Sf+U8R8*FX8lqzx6bDOBvO3Brs>-9L1RrB+%j|ocZAQc<1*0D$2VT z3Cw*s*J6#-Dv5WxVzwgC;w4xkwG!=?H@si4l6Ef=n8R_-$Qr5DZr2aNy-48QfbSx#k&2=z0xe#GHByn<{^ib$0PkKT@Q%ZGD%MDy z1}Oq9UV=4JCyqTTIWNHb9SOXv@!gO$Qm2~T@<<#0cKK|ycnQ|f1noV0z}o&n-n~fR zozwlkS0vElC0Ik>wwXB9=5E%Y@A`G#D(<~In|>rz&S1|feJa2Nw2J#p4w}w zUh#sxnbgF>f14`;EwDclupf!wy6JQdvKA8P1u@1Dy>FeO2()+!ZXv}hB6y6x_~Y&% zj~NmWeOzw{)&yk$ihwAZ^b)K=ahEiB=IC?|^4ucR2soXSkV|NdEEstB}r38x<%+1^eZ4)9nZ0a=FY{mVM{DgNAN zih#^ZwM6QLJcwFFGnifR`;7sfb0p9U@d9DbwcnQ|i>x$1NI?pqB?IHnLpZVrq zb)J(35|Hnz_eD#+ke3p{CuZ``xdprjkwCARPTuYz(BdUnkIr)naIo}}r*KWgi&Nve21-Dc~v=3HM zXB1kz1ncQf&pDTF^ia19-n~e`EtO7D=Q|tt?+w&@w)w5V7Q7=`-cQYM6_@u@(>~|# zICK-KZ*6fA@ZNJG%y+R^|BkL1L=7k>;eFviG|H%r-!~!ey{49=-UQAqq?HJ*vY{?| zi?w=Fwj!Wa9s(^$nD=3G&lQnlO)dLdbWHbt0ppdVmPo6(jC#}${vFHt-~AI^e|EeO z+>(nCq`_k~{LlaCZ`*|Tg1hycQP;$`hq@xc?L`eKD{b|SI??fU{7at01u1O#hHOSpwn zW}?Tn=cBAc{h)V9k1%yI@s$x@qd1LqwGpy|4*_oYIb?JKb#tl5W zG+vIL^PDw=SUn7hd>7%+OnfzeeEi#&CtDkz$;n)rSB&cKtTdc@`TKxqrpnmVw>~sF9x1%9t-t&$|(S+6z!fCB(l}&HPkJ7HqbjJ^=7vsvs2^~vB!`-T- zdCS*-`ULOs9Qy7vC(59gJ2E`jbNTufueCRX6EnPov(HC9vwZ!YUmZd$NVt1`VD9qu zE51%A(96BgpIfqg{X+*dffgj(yY|V6%h&%?@TEF&^FA?#tJ|eq~XFtVG#e zvTI)-w0!;ie|4*zXn<=M_X=xVcjxl;SwE%|xQld65=++JzkL0U(z;ddw#(Xe>+v33 zo=I~~J2r>Dbz0^ePXN8HWW`MAOLLw{bDko^;;an!$uOZW&3Puxd69&kf82w))N`8i zOqz2=IQ?+f>&z?@H0PN#=V=6bIWx-y&3Puxc^ZLU&YUwrbDl|aZU~v@T-Ryf%q$Z$ z=b1F;X#{#Xv&jU_c_z)dBGBR@)ET9t_JqDP=b1F;X&O9k618y*C-jxPgw79)C1IFB zD$82P4?B4YX8>q%6RG`A1g|H~OLV*vORmx|a}Ii}!35_el*y2W5cz3@i5NscUb3DE zsTbxPXx1p2$PXjol$nq$gYps@;Z!aXhE)PI5|oz!k?$fLnhD8EKL2OxddHF*hB*fs ziAXF5hc`=1HOOI!qcIXjIB$V)7=xQNsl#RTLfE)8ep<2q&n@)Dcp z7FUL|j^&idB?9siA{>jeGTf(+D=$%moF7OyGs_x~m$(S@a%PhW$V+UrAmPj=6OfnK zXhFi6StcMa@enfq66e)@mk7v9Y-iRu8UT@syQ~3uiHmUNUo`Z|;L1y==dwR^#G#Q+ z(rwbEr!#;G!}0@n+&W`TG2b7d@OK^QTk7(Yrc8fLtjkODhEh2&*I3N(K! z(wM!(;w64OHaI-#--U*_e(tKk@fS}t@)F|3&nx~mAv|a26NVVxe`O%M=N{E6v9K4l zBD{IZ6xBk})~#w2Ul!>6!K}1aAz{j4O&okfS}HCAR!lot|aW{t)j-SPt` z{#k=P7lP+sG^m_wh-wYj2Bx&?EQGR{R;7p&HF_lXR(j45iw;Es?fPz%u}Tr*#q^)W z1|;noiw!aB;9>d{$LB)}m#I(57C$~+M60+T-?Sgp(0GNZy-6XYENfcN`Jy_7f#2(X zuKFPsFJW4k)WpL*?+6U~p;ZBUiN#Bpei&l^hC**Y(pqKuM8wj(JpOFS;(B1CxmBzh}A!R@W5&SxF=l9ge~sTq{#Zi0I&mLdp6tFf}j zUb!w>cG4T`-rF-KLGL0;l-!;l=JFLan19<;w69Iy>b#O##TjzhQ8#L(>57m_3;(aUN7V;LM-fs1idpV zvF^=c?dBR{_tmSS z*7Ra(K9CSErY|h)le~V}5<^sJy*k=H+fsyB*b51I*HUuOxS597^h16$chu!+gm^Js zxy${@{ln)NqQce{(fi{!D?%*ng#^75Ct0WaU50q}^X1WHeRQjk5HF^G-0@g)&mEHu zv2lKW^y;a(N<%E{g#^9NDf#y4UWS-K8e>}Kq!Hr9^zAbiB?mq+$PhnocrIF{%qxx1 z!eu1r{XxlN6Pp;~$Je6KyiFNOL+WBeyttfCZwdWwLn}i(dSxuyZ~H<;h{a3LJEM}H zSY@PD9ck_Mo2ym{65_@5yR$YVPxUEhh1 zCd7-&iL);yj}N@b5Px3S7~NTStm=nYyac_MDmgN~($f7HxN=!^-e-AA0}1hBy5Esk zl8vV}H^j;D`4p{vKD2Nd2~)PU#-PvgqW#Z|R6UovfUvpzd-qq84PPpr(8Psa&qm)| z-A%PhEMCHlf*}q)wjw(I(QMUoB*cs9-!9pf+?co65FJ(&M0bz*NUajFuon_$HVv_6 z$(m@bkr&izM?$=qKHPV6^3*Fw3{hcHUbOj@bycgx!d^(2HI~#pzjEQT(dTOwsGcJs zUQFLnw;;Lb>MIPffB5QXy-K^(=!%8CkTAQ;5brLGMqfJ`R~kr&7t<%6eJ*+5_-=;S zK5uRGowlV_Kg7abNDTjGezN~pqYcsc>bcQSzmAF!iDH&}}t)At7G; zd~jAya$?Cx46(Ptv(d_ntEw3k3wt49qMadf$37LkcKQ(2b0oxz>3jR!mi#dEv?1G1ACq7Q}JF~?Qjjqj)ess?SMTo^qm~6lhRSx7vW7p15twKV)nEt!vtVHXYFBu~D z?)>PO0Y583EbN7Z$!ZMo`Wpq&#=k93Bg9L!aP(%o$MdfkBJfN>^xuD$DdI6>VJ{@U z>rjcaK10-vEs1uvi>cL)gm@VZ%h4FrVoCJQ;yxjig}sm$bLX`Cx4YRJ&2=QWqR%keF?KVaW*2`sD$6?C)jE31CX@qz&K|3w% z?7_uVR!5&2*Il(rELbm>X+MT3>oXeHPg)!;R-#uLAzn;S#0WdFWMqwH(O)jxstB=Q zyn zzFMJ9H6+A~35v&IC$^t|KQDUljqg;e#Dev5nNEfXG+VY!?gG%Vj#d!p=FE_wBl9&spbHKg8lC=u8Y#o@iQC?z)Z9f0F%G zKadbFrs)h0JLmb5+*tI1pHC@5EbN5@o$X=D6Wuw3>IV|y#Wdv-;k3L&^+PP|g#_g& zVagMY#@mCV(T$C+NF&6HY08PhPJXre=(6a_<<-=Dh=sk7pd2ntd7?XqQ$0sQyqKok zE_~5EQCZjv2~#$iW&5V9qCLLmx`jWS5(NIH~Zah2vIsJ6opEXYf=kkBT46!%01h@ioH-ST`2o) z?RW3WEh;&5(dowNf;wH!DJkhU##rOK_gL%I?~naFh@S z9Pn_ICG;9g1jq4p@QfqJVF^SrP0v1w%I7HWmOSsw|Gv`5df2vv-jAwL^T=Y)X?&|( zC8&!DM6pfJaEZ$2!G;$t^uAp?UI=)igpMn!q0gL6Y+Y<4ifwv&O{6{73IR`)(D6|< z^w~L$KoryTOr1!3J{JNWjB{Y9fjlaF)c^i)Ik>jugqL`+)R9Thpub!)4>@}~mO9*&4$`YCf zsm3W?XL+qIX)XO>2}ChX@6OCywN*26ytOTZ{(y(0EP*$A!96(kmK^WuyYE~6!j9gh zUpOabJ+}C|a<-9?v3;z;X{%bdzP>yl9{MfcTeNVY5b#8a4@aG5GRw8i3Xe-5N@;#G zsTvQq$noAgHE5M>iESbBxu8{TU(59#9X(rG1rOJ2iCbqql=bt!dZ@;PF3Y?_E%MR` zL@|wgF3?EL%JrJ=Yb^vk9A$}Pucxv)HNQeN+Eg#_ivQX*jX)IB$mar$s+*U4CsrvI z0v?XC#M|9}$?ExWGu8NhK%w_s`zO)}L`e%nS>HP^FZNnrTSW+DdK_g5WM@IEZay{F zbNk&Z1UylqXaCv>`a`SsKka?Aq(K^iD5jB}1sXTpy~L~k!XhEy;V4VcQ75RCnltRX za;bOQ6Mv)=8pSlSvq0mb?FHWab=|j zRp8A#I$sEQq6FRh3A$gjRd+61;w{L$xd}&E0#RI!JSfl@Iw8kv_0K(WFCebHEzf&)|2f6BF18V6$~C`wFfZTxdvc2$2QsfHp?X#5XCg|pg?2OSBt#H-@YaUJRD^S zWHkYCN?wuIXz8a#90gC5&}&Rv^-4*;w=a8yXjlSKOd}5pG>XnC@VdMbJZCH6SnK8-*W)5wDYjUmk!crU#Cs}S&TlqK|@PXxryqD5YZ?_NqLf)OXdG_sn2 zICik^@csR-u$Wa1f z?)&-Ps#XsQ0Z)|Bab85Q1KmXSj1kZtd-v=6zOs0ZB6w`D~o3ECUOh!B$WeJ|k`MwV{BAHADfhcKV=&NNU zlacS49Ayc*o6R@KNG2nmD8X3_k3d1I>h8|-ipI>59zw#SI+l+pz-zkBJc8F-VzPe z#RQ_*rdh&#gRIe=zSn+nD>51JLn=viSR@Tnw`xT#YiS2o+v^0UpbEyL8~+aXv9&di)}=)O}T{mqWJeumw0C`Un|D} zPn6&%qTSW&t_U;+x6buC?%ke7Aj)Xy+o%COa=o1GZ&)J5QI^mamIWG`k);ucVp@++ ziT{1K#9QvP6#^b}9A#{4-zafnm0Yjg#9?U!qL|QrQsVP7bG`R(87u@mwqCaNS||^W zBa+GRbtTW7Rzt5!)re#=6$GMKL$7Joh-5N+e~5-9^d7`Oa*}`J`T!Pc&t<+lF5jNqb#9g zyAs=KFY>;tS15fBPn6JcUWu*C^SrknjinKYVp``YB|bW#$QyDr7)#*cC`;&kr9>o? z;W9>%cZnt zS2WZv=kk)?^Anf6cN1waansl$=h<-+WDO)dhPDKqD<)Faa*sZfabD}( zYsaHP*fDDDb!V5Klea?7m9ACQv-@1vJm=(jzc=Q3;bGenWG9#o&Mp&cj_hxwQR0ab zRY&Z}8g$M&CARm^cV^c*H-n?#ISx@4Cb})`nnn;UQB0rId3x3bjddkQe9VKnPLJWY zF1H@lvqV{#nDO{WX#~|PQB1Ene|0>2jjrT~XRR-APW|c`X%#%GXNgoL!TpiBwWjTl z1QU9u#nv;Os64wXdd(36p5qXF)(vr1>I7+(CA8N>L(jSr+#jP>PhZCMS^`mAu4md1 zjW63SeGZRCaX*WO_JYs232FGyumqx1 zTfXl|t3m`nEAdl=tylGwST}q@2JctHd)L^yY!sLCvmod3zFY6pCqo20mS7v@zWdw< zhcbBI9o|vL)@7r(oS$hqkN4eEe*Zm0z+(xvQSQ69-Eo=2`v>vPK(;O$#pV2L&Uw7= zZav|`5CM-R*habUUe~aP!}}odo=CPX8^z`Pj)9*Kd^a_*b%=n+5^ST~cb}hqi^Kal z@!n3hE*mA~6<`DO7V_Uwk{jR<itLufdu`deY!sK%HKkun=DjvQM8IPSwo&f8=grHPUB7tGFk6?6;&QqJ^!rEt zBeOyTJeFV^<&+`seca*w4f$TTb=fE`r#n`^f9!N-hX{Bq!M2ol-$q|dvPV1t!nbwV zD5Fg|!%G{>j-!5=M`R)-`A2$V+WqHj2yj>=H4oe^H2l#}aI#+;>;?T8thP4R~x6 zYv@%%8s)q5LIgaPU>oJW`|YZExDr#gE*r(=bdU2FMbd~8@K}Ovl>2ViPiEqd5)F84 zlxXNz2jBIdnjI$8V+pYq(9tIm8hwO-$JWa>%0nYu8i6R*&{32$ z%qS`ZJhoo8Q63tp(+EVdhRz10Va9eL;IZ|xjdI`Z_I(a!oHPPatf8|VX_#3}2zYG0 zY@<9hbEXl9Vhwyl2+htyz+>xW`@u;^c|NCBnG7I}K$IRw8Q;;NECa0)kF8hrl%OLo z=JAmCPqcN}C@!b-re7N9?1l(YnX zgD3%yCD=x}?`~{R>~a3ad7Q1wMsYcf`TE^p=ZaM!0v=1SjdI^zSg_vXJe2cMTbGUE za=JJ4D*(;sAp#ytu#Iw=&t*Sy&Z})*Hj2yXj@7RKiEYb51U!~to6B$LT%Eofe1B>& z2+0{NfheP0Ci8iS(DuqRIS8Xi1kL9-@=RNojpA}WyF?tg`X3ct;gs~vW;??&oSeq5r|?9ns<3tBMmdF z2?39-mu-{>Z$EziF4tMwb)~!m(EkBXa8%+i+2vyz&lFqVcqam4`d{e%RkMN$g5RJ< ziPh6*m+x&qQi);h@|_NiCZ!RGV!CoR;5VtI-{d(jy?wV3@NiU!s2JOs7%^{&v*6$b z0bynXOMKNJr+i%1p4zGvwF;bAd2-W$9C3m&o6We=WiAQ9*(lahPBJe?`zmt zHS%ZYI@|hRm_{Iq>1s7rmv1@u*R0^|)|`~*eA2%#jX)F=I>sn5?bbZ!sXnxW zyIZ{%%kR!zp~RN)xlVE7AMys$5{P1=ayH;2f3Ymz+0yh0(SXO+%l4*C8_Ii^HdT#g zALlzifA(w|fhZ<0Y6nMN`_){h>E|hF6+E_Hw&}m_%h&jC1uN*{Oq_jo@aE1Eh%$6p zpi%aHo^xntZE2Myv{f>fU|tCbcU7KK@2dIsI3&svdfrr{L(^Pm{y+An5s2beVU`Fq z{!Pa*s9SJ$;o&GtX#cCm(|LK$zH0}Fh9wZibmjcPJ-G6^Jf}v>M}&Zfqb#9UWqHu5 zPY>id>&xy)BM`;3UinI#GBMvd?Y`^M2t+Y~c_q-;(x$+v-YY{0cx=6F>m95b_uiA^ zd{8I2KP-VL(Wsbl_{hIHXNfaq$CH7EnQ<(EZ+bzi5`*)d=|w}*2t=_4=8}M@+ArT3 zuxY3e@NkqRFf#_s>({@B(A>fG;bWHs1PWxkS(;~;Mc7e1iLP!+Tq%Gq~pfU2oJZDmm z5oncoRHK5R{?v$~4`Zl`F90 zZLD%U2^uRC z6XZP{9|!&4tn*T%;7c4lQ9_R?5uDvGA5J=_^a<{$;}8j^wN*NQoa{d4^tmfXjvOAN zA%q^E5?RFsPMxmz3IR`)&~vCn-SY~apC*s9XII`1qU}u67^CmV_{i_8n&WJ4AG8Xd zsD@q(dgPI@gs&fIyVcO^O^L`@A}xq&=ryfGWGs7cSgAy0EGaWbUP0)1 ztVCoiDdTG>s-a`P5|Oc_jIWd^LDzx4FX8KI%8ml(g4(CaC~D^=&BDtKT^^jPw&xXu z@^&7PIVws7D^k9G`e>8CJw44|lRZ^->#(beVe|h=RsMg}Pg_q75%BOc2MD&YcG!1` zSWX(9pHlNts^Yf?b;_`Wt`JJtdR0$}@|QnZw*Rwu=4I{!IF5>S$e>xHa#eBS z(pJTmfXCL$Hp+c>@WHvoliTNK-ZSxD(SXNBu}0;pVu}tC@K}Ovl>2V!A0HOeUuJ6Q zaM6IrMzKcas^SlR`Ea=<;IRbTDEHl+R}C)y@sd;GpEVgE8t~XC*3k8EbnQO$Mt#o` z@K}Ovl>6@CDV@9y%^SrBW_1${cx)7FVC}H)zPaQ3VoShd3AR!0yQ3y#cNz}s`unE0;AuZjjd zHi|W{+SqqbZ%KOr7y=$ku#Ixx9a_5FJM$+u{?v+W(SXNBu?AKf)3>4WtG(E7Q{n^r|3x(5u~Dpn^~t{b?uaKt1U!~t8|A*+q~~1P2Z^(pU@s(iY?RTU z^*$i(Jo5Ey>#>BfiMXJ_Y_ux#PYAi*^!VuME=s^->t!3|zS}=J6K7X6;IUDxt^GtA zLq;zP5%5@oZIt`&>}OZvDiIBMY!qwg^+t2lkst015%5@oZIt`&$&cKQt6enUu~Dp1 zxz>5k=x0I%JeFV^<@A=be-ZB5xUI`Zak<|AbR3!A%?lCmSb}Yo`|cUNXJYgb4R~x6 zYv?#e8WRiWh6s2p!8Xe24Sl<57bMw0}8;Axx zHi|WLULlQ|H?|HD@K}Ovl+)^j+y2U{hu%IRJByKOS4&r2zX6AgH5 z6l>76kQMA~RKME3CYFH55^STKR%~skmqFKVDdljY0gsJh4Z5avXQQ?sm4pa*EWtL) zefRZ@Lm8Bjr6`9J4R~x6YtX%^I~zUpMsA3J#}aI#oO8I649dt-l*5SzJT{6oXpBh& zI~!57V+nXH!8XdNKk_;`^p~O>PBh@LQLI5@rS5F>*6$rc1U!~t8|A(`{lxAL58Y1Aa1luV0-5EUwIF!SsD2J0d3LYE98Z>t$f_;h_j9wce z;IRbTD5uqJioJWd+hYZ4&`tu%Hc4d zOI{*F_uZ_Q7dVu|r6`9J4R~x6Yf#>$`xL!XwJb!yV+poV z?z>|?+93ZuU~)LA%SIUuTICJm&Lel7ZatPTHW4-IEJv$K|Adh1O^=V>Ep6DbEJVO# z>t!3|zUwu93TIa|;IUDxtvyH@x$9{*F_uVQVJcheAW$Ut0T(0*&Y2>`SDn!6z z3AR!0y92Z4WAqUXcx)7F=r~3iQ34)Iu#IxxZTkHE7)3<`9vj6PIv$fo^YM#A1U!~t z8|A*ct=%w3=MT|<$40S+&MTx*cEOks0golvM!D~P-S=8Y=Rwhc$40S+&X1&V)xZ-& z1U!~t8|A*c{em*g=b{0RjbaU*=SgF7`wJYM&xL@;5^ST~clUpmLSB+aAc{3KMm zy|0D{cx=6Fquh7fP1=(@x@^2ZD*unQ-DK0)1 z5b#(+ZT`OrYL#kqhDL;tDAvFpNwhkl*RI&evEO&Tr(<^9dThOHSN^}j)kF6rOD}Aj zdC5;f4u`sI6xW2En|wFJ*%d3_G$yn5_Y*|}9!s!||A?Tx{qjA@6|)v(-nwT(8i6R* zzz$Tt+wai3u@+UI&%Cgs~vW@>Yq5SIayOYD3SBYOTYET-1DAvG^V7|L($2DF&c5?g+Kgjyv zvGwx*#DVtR>OY?uJLNy8#oG<;CmJAZ6x)@*?4W(_bDwj)_Uf}&CH^nOceT$;xzCw^ zhuaQ0nNAd1WJ|1A}LUdnxLJ+@x9sb_WPdhPR4?(-;tC@#l;-Bk2> zDfhYc*m~Kfp4FY}wa-hr&!YsQxSaZfz9Hn(J*a)2;y$+?TQA$xPr7q`wJk*@YwP?q z$|3(vF9Z)JW|*>BhMA*m}9V@;5E+U*5Xpp@FqirylGh1U#1D z*78@G;D0T*{O?MqzEdaFwttwgQLIr(JTUg3$=}xwUJ|RFacgSum}8l?E*r(=SYPD3PY!!6`AYra zsfSzsO9*%@!8Z25r)=r|mtvXyMyCFlx-E@B6l-8blJ9;tE}1<1(D>BGBhLr{kFA$& z?14|j;pbxcx80W-^!c1L0#U4i6-mB((OoYlUzt8Rm364E5b)S~*`_@~bwB-chb@bJ zcJYI$e-*Y&BM`+JSdrwr1A47WW**H>9s6*7XX~-`vW-3PeYZzxPHf+tsi`NQ7?nmK zifh7(B;S4Xyu#$TeN$6=%YJ;-dThOHV-I}aoly0u*l(m!{KP0fN+8O#mfr8ayk~y$ ztjnjQy0olYYCX1Iwy_7k?-sUsIM%G`gQ+u$TBZ?*;+n7`iQW`F_-OK-AMQ^r{@)`) zz+>xW8++jU?uuu|#Lm9`zSPps=cEycVhyZF^4)72-k&@#HagXCRGAR)*m~K<9{6-e zZRi{OkgnYs)3&7%h+++_Ve;K?F1RVVx5bduhpV2iQG z(g;Mc239@Mf4KeBG5PJWKB?b3*G^fFt(R@=nos%e?X_Y*(pWO;Xx%gdQCt(g71QXm z?40C`eOILBY`;_pcx=6FW7m9oPkn5Er^)BWQcX&lrxA!^4SZ4d-8lmemh@=gq%Qj= zAp|_OUbeB%KD~ARBB#?2G`81j)Fq8T6l>_1U+%m6vTK$+@^J0clRNqd0gtWM%xXmZ zr+FL9Q6a)cnK_DxT4&#y>{_*ED*yT$Qnp^Uv46j%>AEVqEcrgowM$RBQFf-l?<++K z{2mj%t({b>;|B{)O8q$WW+C8-5}GqmtKQ$!-FY!}Lh6q-gM@&`64D>~n`qP@uMI5e zx&1)t<7Kx8XIDLzU>m;|;Ja(SY1Zkx%fBwYxal2f1fp0&vn6WPxv@)2CU<|KbmOmM zg@DJ_%QklZ_uby7{oJwsiO-il)^1!Hfhg9{tdBIR9XP!4=b7V5r@S{&2zYG0Y~%L= z=sQkoe#fd?#+2UiLpp&d*3cZ4G>Si7u(3_YAN?wAvPA{1ZZ=RD++}NJCrI8Lc7> z@z{Fx$oYS`E04UhIdbt>f^Gc5K*ib3#Mz~DRY4$%HS{TrG_(gZO%L*ash8V&*{=NU z0li8xah0Gh8^s#>6h<0)C1#o{QFcPG1lyIrJ)l>6Ca!kWWusU_pQA`a@2E_3Mc<`zMg0gtVh zZTyM>y#sh|W9;H2?|&&m9?LOYqow*~YIJ&|Ev{ zh1jx>$Hl+AYqe-t0#U4i9aiYgcGHq%zaQ?8_t&fs9$PQl_}v3~xAg4FSj{UY#YgTK zAsUuI6l-8l7FxHod0ldQ%PH}5k-Y}Hz?9i~*~YIJ`0iPY3SuW-lO5kM@Q`H4sLMvN zhVJM>>oRtpP@EjPZ)$vpX5sKyf^GbYf$vtmaDME@Kc>dd-2Ul>wk{iG%IUkot9utG zhab(3*WVjFO<+G6OR$Y!F`ze)J!ZwOpyN0&@Q^%BSOQVzT=7?czdfF;`_Sb0Q~Fed zeQ|8PY~yzie0S3M<71PlKX&dIk!kC)QCzP5L>fQtn4ElM#`ySozXnft@K}Ov{EC6^ zw)moN?21pu#jhW+S~M(yDAv&HEkSQmTiu)-bN=vntILC@RCsK?Y~xo9=)LHHma+YG zfBdy@zi3zjQLLf&4QZ_0-7fjY!~yXcD}twOcx=6F<983J&zn|{EnD9&-h0Gpaa)&- z;&Q$JN#ng2&PX@>MjB-~ z@08U4TdVlgHNo2tcx=6F<5vuPH+HO~q+z^O{75RDK$MvcNMp^Gg`Jwy{PEky?s4m} z^>TUT`^44buT0kJUoU?11HFWR#}aJg&7|-4dTN$8kLHi1&D)1G%$$)3A9<5GRUFN! Qg}}QoCNx_X0=Dn|ANIr_wEzGB literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_6_wrist.stl b/lerobot/common/envs/aloha/assets/vx300s_6_wrist.stl new file mode 100644 index 0000000000000000000000000000000000000000..ab8423e99da86cb9e13c197f8137b670f789ea2a GIT binary patch literal 70784 zcmb8237pN<|NlpclJyhWKZv<^#-6BT%pEDB6e6ueNJ!Cc9ec79QrWrp&M=7V%r&D) z8(JhwDk<42l0?Ptyw16=`+0vpcjo)}|2-b_@P3^4`+44HyXSL0XZf55JKc9@^%k94 zRllwNt@Rt$Z`9=G>Mb9*?}3iZ7cN|QrTYK>zj4Hho((y+RF!VK-BSIJAt$M!OJYabtcGBzkR`4Js<{;qtq?c6L3 zA6|kqtfse~pnc>`zbVJICN6tG``Go_XF;jSk7zcaY75(1kXBLW!%L8c)xLH^w2zV9 z?p8h)W&aaIs=jR!4oXda#NW-*l#g29o6_|Xq+vDY{chUF`EPnEA64$$r&G1#^U@)y z$&cu#NL3$K{_`PKUV=2N%A}-eA4_geS3Zh8^`p+mc&kuIYVsqtsS;3SHFSmc;U!4J zs*@@&w9qyOCMqAPSI^fzrVTkAl$!jAF{&nQYku=*v=1*q8djrKy~D@lO0$%Y8YMRB zvf4YbSV(H}BburfXByABzU=S_UGgQlXI4O|jK z*~rJydlo4lp=L$2kA#GTkksTy*s8B7m>>DyhkjF!_)4wNU+( zQy;Q)r6xbZ)Q7A=Nl=DWBh^pAhiO-`l}Jr~glSiAEqh(J60|ExP=?hC)lb2P`F(s< za+~h2(AuRYKf?SzeBM=65c821!tc)wimjf)CSQ$=*k5 z@*_-tC3`qYP=?hU)lb2P>33x>DmD2Lrr(u4wInFRDn<2E@L`@G@@XJ7`4Q&%F|Tv7 ze%9joAqmQ`I;;9A_%P4GZ-Pa2e}$)-)Z|B)=b(IYN`f-1l2kthALe;3pUzT~A7P&7 zas(g=%CPFE`YHH`A7w~QegsAwwxvcg8R+3Kl92>uSnX5&6ntQWV_WAx+7>)lxJf|$ zMLKNioL1*jk=$-|8s@Cpnc9Lf!t-Wct7`C8)x%wCxYDqVw)NGod*&U7KWup5|j<0`r8Qdfd5xaZY1&R!r|54Zl(4!%a9EN!(rMNljNfb%P=h|D!W%BKIyIGG6$0at_N&uhowc z)VPV>Q39y~q5c9p#wYvW9d+>Xx0li=BPE~_6T%(h!=ouasmYJXn=W#$N;e^b+_Ii! z+9e$;D@{m^BNu289{Gy;?4kZB}47aUED=vtYmDG3%=Fj9jB_+kD{(|v7OwJ{3h~=5Jby-P` zktM-=pxxqc>&DdJZ$%%|{Ri4;rvcq{ZvdI$v0s!XzM7g6BcPE43o&e7fHamZ`EOj*wPt`KA}mDzq-xEb`YSBJ2~ctN@D}L#5dQOfSKo=> z2mYnwiIX5Tl34elt%<&mz0smzLRzI>Ij2U*<8w#*XL<;!89Obgtv-5V?*C(|B#}_0 zo~Bpz#XAntpI<(t70d8^PBBl;rA89wU1WT&dB@rNTC(a#(j#+DT<4R7v|@c29}9mT zTMI-=rO`gAk;IZ$E2N>UOg^6e!l!-Ue@RFy{LY;kylq6gMELkQYm857B(bl}yV?gz z+P2CMU95?x8o%r!q}8;ICp2Md@X_zT(?ql1`}m~hi6s?vO3*T-Z}qnQLus9lV8bU} zJ|yw*k!G4ktF*1*xA)YuIIm^a^2@lS6~ob{b)BOZ)uSbr6-IsX_d&w+)T)WZ2&s{T z>?`%SL=$z7jM9BO%AI{XdsN0`Ql(O)iNRf(#RzC*yp*RtR#>$}63>2re3^_(S}~lz z+VsF5vuY;>?(LQct2&n&<-T|Hp#bEBgr{OMQ;4!k58Uwd0~t5})+L$oqSyBl$Jh4G z-M?>Wz!1;xT@d{7v%`KbK`Vr373-T@vDmsO(Pu_`zpq|H|JjE$ZZ3p7}K{=bZ)Ml@ zPkXhR_8|#cAtu!3nDOVM#2?RH$(m8UbpvS7mMU-fOQ!^K?WpV~&ONX=T&?XcT_4nt zCPCk(2GMq}f9VsQ4;e4oasGrFW%xGNZJtkkI0T-%PFc0Bu+5j&eS-Eu4N@h2e0Nua z+&*tG=Ob?{6dX|eS=|yPK`YS1PuI!aP=lpA+$yHt(GwE9@xq54Ei2L{=UH2?_Tf*) z1^K(Xl5=1E($qP98zQZHC1351^YrhW8ZR+!nqQ@g?aJD|(?21vimr1>(8{FNr&7qa zyLjukM2u*lkwl$K#){$ghG4XnoU8N+o(M4l8W}I;)3M*+iHc=>^Y>54mw*+0nD;^a z2Fo`3&|j}jN-Q57g(FoYkSDt*dxjxXs|VLi8yoXMf>!jwF?D(%`K1k^qm^EdwG#G; zl0e;5`mS)aFL~$T&ugi_r7|waw1SLQ()^?MqkUrY%ss)~jdOIWs4+x?+-`%1>RubA z?xgCS{rWP1_jTKPYdb3q-pNo_ zlv$fdl~W&&ojYwDpuv+2GM;42pPRU6(&AVR7DVuOuAk?4 zqYq#NfOs+T!t>m;p zMldC;1NPb`93y~esxXpq`QWI=y=ir+z`$ZF~rm>lVSull5m%<$_L(~Fvik8BtaReVq37S zy(@l?5mF=LMgAN@)q^f4)CXsZ&|Wz^gc_7F>H3HfQX>g>&QTYtT?I`(%*-9)mE|UB zGe@S{Rg5sX^%AmlqxsP73URT$$~QgfFP4ueVcx^hG9-cgVH|AUagY!E%@4d2d*@_X zdHuyk$eL((xn+!iMy8Om=@aRrf8NGKrbH63VmL?o>5+f3CTA4w@KiG5;)oS8N62m; zs?A0QH0zwSy~EkC)OZQ@s3@!Si0XHPTbd2hbC&F1LC^{^>M7Q@N0O75FCLvvFAbSaneGP%%N4b-u z;!?$UL9>@IgnBm!emlOn&N($+e|%>!L|?mQ^0$Ti)s}HVrWItqml&eX{uOGkOhSUx zcnQ#W_lXi0)`o^$JtWCX@I4CQOsye$l`0h8_IZLPsDYIv_}*rSpH}@Hs($$TID%H7 zU2l+);JbY?CSAKk_a)T83U9w`iS%uJbm%%Ws47s`2Q^;8_3j+``>oEwiEo%+l$XF8 zHfV%9JzU{;D`)QBuvWJ#YUqOm-_=d3T5SG4l(PJ(kcxU?9Xi7ct+(-YY`X52IxyNqcVFU{QjNZ zCu{IMx61yiAj0&C(WhEqLC!6)RWkNhj2BNe_%`!CB*u;Er=Nq=AcZ6-v%f++#~Nfp zI>)Dc$^11&t)+Z_~Eks}s~~^eAOn zx~vm2xWLe-#r`=yK&x(S&osmYIsm2NsIN$@=rDIqO$4hHX0&Tm_m zk2~keGJ;i6td7b$hm4*9D`Q4BYo4ZuQw~&XtnQbZ{0OtIrhc_P<7ew+xqd2XhI@&W zDN-W|%7#GvSP55uKG}cBbu|+%^PyJ5RX!F*38Tr6pbt|U@Fja6>5r+EtzFlLCh}%F zKG562%AG3ArbYLE$Y`b3tn^e(MfR)$bJQhe$U{Yi9HKR#ah3pT%6tnBAc zn0&wo^JH7qRO?WG_*F&N`p~M`D!sp8+xq89wGjS5u!YNC5oES@$hOt|*!TKZn-sb# zw(^6wyFEK!*6Twj{<}N2x@7v2ZtKpXB?h*X$&9ToK_iJTnvB=k}05K+ivQst#wo;Fp?NXXj|E0p-@}o`EYuwpF6}Nu8<}{09>8 zJEukxU%&aT4nJA0mCE_(i=}j`?s%b>i;z}@=VLGT_}reYi>dd)A^+6ZL}=KOrBXAg zu(5i6RiW+Dw{5lTx?Shv)bQi6(nVQG;`}FXYacKFJAJ#mZ^#!sHpR%oy8R29Ffk|vJ-Sv5&& zBynBV7)_gBRHN_PYXbjELRz8EN9me=*PoHDi6=W$_DhW<9&I~S6Zp;B)~rWIYU023 zM`Lq+h)Y_HnKnlgrZ1^p>p4vfSvSciH47h~r>)RON#C~h!d+#t>m|^tfh!ftuJ-rnaj-B;h+X zMALZg+Sa?vFX;Mc(s-qdkXH0z=6CEVj67edQc8GEOBW%n&n@&+a|Utxn=wdBLY$* z33(PoovwL#)V4XHJ3~JWb`#P{?yS;8^V>Si*M!taLhh5&scOztNsT1rDHxseROVa~ z(n{{E(xscq(v=!X$kRN!22)vsl8{z%UzTnqsca=uBMEsbNw>sQwnRxtE4h11xAs)F zcBzqsJYA)KQ33v917p6JYNnHIk60 z-E2$sZ~^vkl8{#NUBtG&crh(-{o`%7&e@q1kQzzIQ+q1sk9G)b-FZhGkM!f!8swAY9eD|@ffirsr?(E!m z>(*y~OqCi*$WxSR)$*6;0yRJHney%UH7-J0$u}h1I@n`S;Df`jZap|{SYUs_a4{d9m zEj5y0xtViCUr&B1aO}NQV|Vur zJltkhN~I>dU4*ofZd8-r8h9T109j!T!;l zAI$DlF%UekIOUcz_qhmZCEsyv>+hRO2EKVAb8D|Xogz{r3HI~m9AvKr|D>)ex-6yF zPhDMvw32Vdw)Iu-A5-@~wPNe@lX^v@MiP8pne&`Sp4*vBw8Rq(%~a?wWJL@01;ty7~7|$`cb`aS_r=zIm&2!kb&C9@w*TYn38H zB2ps>jvvhV+SKH$Q@3V>Q|jy+<|3q(d{?)vrYFZXKXC7=t?PP@h)9hjI1V!Bgo}3F z8Qk_uIHk-VZbDkgcXjP!8+}NPBsc<$hD$Ybp)o9#*x(n`)C=(d~9wktJ~;G0G4_mR!tha{wxoO95>!3ckY zQX>hzA;o^@5&q64A+6+$h3-ot>`SCZ5`5E(^;Z%0SCWuca$ZCCi4pdRQX>hT&W-iE z5%#;1kXCYDL-*|w_U%$537*c4JwGCRen>)E$(a!SjEe9XB{h=Z>D<_JFv91cB&3y` zN72vP2%oi5BMF|)jXlpJe4a}}TFKcKJ!Xh-%pf(A;CbHIxFo`Hi6o?zoS)HSp9sf3 zQX>iXIbk)vig0`-327x~ck~!8!ZDoGNP_;%>18!ejBuPN327zgfb>{2!m+5-NP^{N zPGPI@ZiM4qNk}U>Yoy225ss;)MiQ)lbDCU@+anyeOF~-7IVb&Y5aGLl)JTHu*qn-2 z?;jDqe@H@F$(bqrjuYWKj?_qkzsKlTRUYjS;d_)Mq?Med((h^!zN<-%B-pQ*uM|9- zo)9X3XlSI#m1?Q`?#XlQzu{gSgmaIMdYkYN)R+WbAxA+dq#e%e_Z>Z z285KkTS$HP5XsGsc?r$8B8u*|UWbR?It<8rg7D&(vF;TXy z%g>GWO)q{TyWiQTv=3@zypWw8TT9dH6iCntJ}9gAsHQu8^H0{up0IPM_Cbw|7qYX* z>-fbF3nXX-AC%R%kao8YsTtu&=g#HyjxFw*LcFrh8E#t>4wlnILPF^z#6?YhgxR0? ze9eT=;gYAfHMw_qgx+z^i)n|9@MCLx<(@s?SFI1WOH65Y`c#eVCOd~}f*MIcMv0hn zUXj)(HeW2gBKzhl1LFuAdF_?92K z-W4g?yjC1REBJUh`PtlW8kAP^?U#4fY?h;bQQPVt&z2e)FJ%0>%;~ckyO(TUbK#lD z(9ib75wt=~>qZaAt$Hd=`S|L=Eq4@AJ%j&BHBC?>KwXh?664Xh9%<& zTEPcptTd!YPX2Jk*SgEks$Csc8nb5;azes$YX9bUEsShVa2evJVV9ETU91(98ZWWz znE|;U@LW;k*7J`f?`v>XhL@lf!rQIupF2jKV=_LT=umQH|2{odLG$HbjdE+M{gjX| z+}j{GVd{A;Gqr|jyLz-g@%ODdRn&NiNJ8D*pHrh}up)O(=v%vOuUqQCN)og}cPewV)xRf)h7NA-tO=QRNmM`6D7Rc}zvw%k zo(WI7y?JeKs+balvu=!!%?DeCHjSAcEnTP9BvHI-wcH!B_C@niY)lE?xZy8GYtSKR z1s~70Meeyu+sG$;rrH*Y00-u4|bX0gacK@=MX&b5mAD zeLUTIZ(_aKPs95r-g`>p6rq%qN8n)8}HL#Mz(XRjHT-&gCl=$koH2=}= ztu;Z7m&i)}E2nnif+*4ON;}^tl~UpeT7iDSJ==@L=m z=-5Pm+Lf<0L5++Ta{Df8bH44J9wq+W`hz5Axhq~v) z5wrqvTgzoRvlp#bJsf(UI`cRAW_JHj6V%9fA)hXvp0i=6Ik%l2sgZZ5fA5~mID%Fn zzTUSW=i!!_Q6I}2zTkhQ%0f+0BjbhKX?Kg9?mHig=3`{hh5o`%yc$Q)3Pg#k-_7~q z_1RG$-M+2nKl%PPO;97_h1{@JkL@F`bcqrd2YupOI&g7F#wD#FKRxY@?Hx9iixO=L z_fOoobfoqnQ}W7@t8#v8^sw#|-99SRS`uneZnw`HuO!qizU`%+9UJxW%|nm--We3q zKBxgLi8edNZ*N-W(P&vUI$S8czGSaBf>xkUEL|4)r_ZdYkB^$R4R_vijV7ppl_Xkc zmT8>v?b}h}-x*H_vwVMRf*LQe?sPbNRoCv(RL#7pV))4xzr_)>0=?l-PG$yKu3-4K+cHm$>GMx6%p?yCX{6k=AHgVwIEn zSxb$V7}mO0>Y~2PN8vi%!hODLr+r9*R-h||N2g7^rwwzy{9WIeb9IuX2C^iAlYN0# zZl;f2gRjpRzv?Fa{9s%lXa%|K;Pz>+T-Q13;!Se&~g?T?&mbZci@FnvkK@(aR$ zPMog^Y7nm^o;x@z?Y0IdqwVVFZHGgXD$NSPN)og}c(dCl1}+zyA0ti?Q(v<|QKwq`8 zbz1ma_M(SMpIJKVoe?@!viD*C0pi*x-p;X)4UPI(`CskCroB3Af*M#!qT{5uw@)fR zU5%;HQjAFJQ0;Q##a9$mWBz)BKo@9p+e>I;&_ zN6F&#{4GCR5=YPqbcd~ra~@clk!pyGwg`)m!EmAH|>Fl=N|@j5vZ;pwI1G zopbEs=%|n8yQhVl{SwgxHL#LImDwNXbed8>>Z97dcZXjcw~*XLY1Hz4Zc z$J@7sSEOcZf*M#!V&DCjasr`pQ6E!ZI~smz)%$S-tw5K1u28Ojb;)SEntY>G`-XvU zYJwVAN#g4NZpcks{a3U;=H}M+jr4u0>q8Q>0)79>wR89Vx-m+;Ubl64R{w?Chb$ji zA2VNWm-AVt2c!8IXQgI*5_~`t)F56-;OYGRr2bJKPaUq5F}cE^ID%H7@eIyhJ2grK zNBYCRl-?Rg&~Z>+rAjC=Kv%@ zE6^CDytS`al-T%oa#F{fH+5N211m{jB(pEEN0g{N_Q_!1T_bewlQkwScWk$w+d;{N_LQ-i~{{1QyNB=Ragl)G>08_}o1ahuPlb1n&5 zfyR7^Gc)nT^KC+XUfQJzYG5UaVz>6lZQFBqbd>Sa8wZ15ylLLmBta|C^(G9+?fea9 z?l4*^d%UiH>4?jPr98Mzj>OYb4!q3KsBplg!$5m$me!dcvg!A_6#0!56S9^qqUkUDAo!)%daN~m- zX$6_@xVF{jM5mBLI2z=ZR*)H!Z7tv1K6L8t4yn7|8m!xuW0efEeg zm*vj|wwzg;DmCyyE6AJ=vaR=Tn^Pb`E5t-uor8R0!?Gn~h6lPA`?k5%$ao=hR>ZcB z-n+3tf>wx$vTYrk`)6YR$A$&A8fI$uT*>fB3%p0`Ih}6pqHJ5; zzW4cu4yzUj1n$v3sFCqPcIIS0&G8pV&T4BlU%0FYA0z<0kUNjMu^P1ru`ii?TX#IH;4qTkp-yFaM5p zXJ_^dK4^t-&bGx9)VPT}K~x#_pg$D8CbjdPVcLfz99hmf=cV4{BAi)gCtmntxNTi^ z*LD7~zwb!xHoCv|L5;LRKJeykX3tNqsOlo9aT6Fbkf_pHrB;Ktu~=-;^{9NC%oQ+si~o8lsz89^sr_+z-*op35QQPp=KGklHqL5;LB z^}+eX4|ja$BAgjPCtg!-Byx6qw+ueewq#t=3gMjhv#mC#a$N*9ZX!<*oxYnARBb9y zPPHu=7YK)TW{uPhM_XID2xmS?5~keD3}pJRn}e!Nq0R&FAqht|?aItXeRgcGi$Fa? zgH$<$seeN(`Rs-e;z!$p4@o$(`F)uAtAQ843`znm92)p=2-ETn@zAb9A=Rc*(YD}2 z5{@kAuhu{RPf!xhoRt$V{4rdeMLtq0lwtZ3?SmR=1>c;RQqS7P$u5E#H=#yOu^F#U z=aWN^n?6zba5RuPbK~~$`DIBs-n|5A+gki!tx&XY*ZH8vO_*ninOmB(yI?}jGf}p! ztJ5lmqR%MpgBtj7Wb-64GhSW-PcLZPgn8N-B7MX)q3E+#mz5;&+{N4*%8KE(wXJ<& zK{y)tkOXDhdTrINU~~ka^FfW9FyjX^JD50QZGi+v8L&dCDBISOt9u8dV;}uHrv^Tx zjB${ev;6Md$N~vk!3SmA>bP>pvgjC2`=ACsq|EtJ+xlzRi~R#;e#OPRb zo7BJutsrxzQ2Qv5pcP`Gtjg-tbH3=9I$LUFypS=zHZzddweDXaK`X>W*|x^6-QkPA z8$_f=#*1*gCzu&XFF}o)FmD!yI5n-1Kl+ZNeMmyec;7KIkX<7=zJdr^Ayt&sj^8yu z`=ak^+6OgAm6V+s$eC|e^cO_X3O*>S-G-(8{^&cW_CXDNNSU*rwuSL-K?JSfgR*Ts z*r~QZ`X;P>Py-*1Ea!LC+qO>$46za%hI zfEjG~a0oLWU}m<}%!EHWm!W+~Ldu*Y*K-+yF!L8!OF{Y23NmT+ZqTH*|I*E~w~c#X zg!bWBxoNJ}U`{3>K@!v;AChLcAs)Ez%(f2A%($Hz5K`vK*8e7Gg?vypMDq)^vi}KT zhpD514_ZOydfWddXoZ+48)ENE9kSca9;|&(Bjbh4^~nEC&}%-R{Nj^KBUYwg#S&@3S~vv5KEiy z%icDskM=YbDiN27`8dW74@AC-Cs9m4VM zC7jiar#`ns6&l?Y**OS%wpE$L;#Ij7GS@}acOWNx<|~Mx6=I@nTRTdP@~t`cOyu^8 zpX+f6HAt0|ot2-=+UtV_5wwC2%Ib`JjumP+dRS!q)7Z1^XyAiZ2zORYyaY9F0`EIq z^HR5%MNbd3S8GL%hO)EEJAcCQo*w~P&4ssY8A?1bH1b%(>S`=%e3*Fia^x;=q{H2E2N6DnhUR3d1e=Ytv$jx2W@dI@K@p(OIe{>02Z{|4uutrFQ1Xsdll!ja{!NiX5- zfpp?U3K?!&*A1T^yxg;EAsyBX@#=lj?H+28aJVOrPzMa#An+E#~m6JIdx`{ zenwFPLhesxxcVkwmDYlAyn6}Kwl%Ka!ey$yBf8#Ida3ae+(E1EiXSn{MNs1=^2Gk# z;FhXBRo@ZRJIX{7jx0|o)V-^*i*WV`JMqFF!)+_+&M$nbz9Xo2_@G8wA)Mza;t6Wp zM4lizwJhsb^_`7+mvMn`XnA5Jxl>aY;hY$eM4mWf@^<&OepTPusCUFG33&>J;kI?x zU3Uq>@eW!Nlx^$U@PmF;-`S{lN|jXhYxC`6~ejqC!V0jP2>q;z`1cgRo?;BJFFzZeMD{_gQ|=dgyS8wBq*yIobh!c z`gL9JD!tTr3GRAR-!D0o=_06c6Kd2S+jFOWwL$djsCT578W4``>?2fP<+_sOBAgwD zl2H4AqB{@O6Q}+MLG2Or zjY*Y>7qatqhtl0Xbwa&1rHaQ9v;x5|78oA~o6oFwe%c)?q(;UI*?H%LkHeGa)|+?u z&NzZrAaFw3oTCSEb9in&b@o;5%ycv|Udpi@rh&J5SE;`|^Q79v8c&#WuqNEOXVgEu zO8q0NSJfo}jf@vEPk@`8|B_?ZZ}8X}O;F<{ID=q_Vc(Xmzp&1jdNMA^w1VuMaYxQ; zHA<>~>(W`8pvFsZCdByop+=edAARsg96>A4Jdtk*-?=9BZ+pE$eW`&g3C`#kqD-Uf z>No4xHjbbbXntA15Lqer*WbD5Elp4ZD@kx(%Mg9O_^aM?f31ikXa$;INHD~YR~FQn zu)n6R4{Bf~3C^||B5zMt=2yFlslByMTsl?Jy~mKz$KYEHh8UWAds4?iTa%>5OK_&p z5V#X*bc@Zp?J_P9w1SNNqK=OWJFhG&wq#;Ebp7@$H4rf}J0`QKyP=fuI#+ z&chmF|0@@LFTaGd$c_fGoDpVBhM3;hB<4iz&5HC}?x6+@INJu1Aj`cHaRO%k*M%_p28ZfV&jc)9p?opYI6IrmQ5 z5OZdf$=vIosdG*Z;+2G41xOEEm~kZOtvlDo5wrsBeyTk=Y(vu754UN88dyn!s~jd( z$41_jR6LR!N6-p1-#-m;eTi8~i*vIzK@F@V!POc=q+Qw&e(6dmj-VB2zJD6x%{|-v z71o-ZQv)kWa6gM79(d%z(BJi5*YzO@T7l-fs3BSxDHi(e^4+>!Q3ESUa3_x;?zy#S zXl}XoaRjYEJMWz6cOQK?B{ZP_CY>s3U?mCeXEHvfsrlFKB`U`ev;xg{QA1=dSr@$c zXnCC~YG5S^?y@q(vQ2eEW7@1tlyO0(6=c4D8shTjErX5P)Y3kv@e(Mv*ctc0FCzoN zMj!j)2wH*WyQuN;$h@(^zWuM&1U0ad1ojujPTmL3mAoPJYSk}7GA_upg3P%r4o zlb5|b;~h;<<0UvVWr!yRzvnOXOmR(6<0ZJq&k&XW>>NDxcy1g)E6|*oGQ{=cmiv$I zo2LnCU?mCeTQtO&>h~sndUK69f>xlpgVGS^OQt4W=(0%v2Ia3vuGg~V8$z9fOjhS0 zH9-yHl?3;D86vW}W^$dEpV0(0UV{6*4AJMVq@+K;+o}m_yaZRR4e`<2SCU?7lNm?Q z3N-hA86wc<#@gfGc}}-0YG5S^uB98|{f9mYl}nwVM}3l@6=-Ky7=Gs$*1Y9EeR7K? zsDYIvxXZ@)_`c%rp{^re4$HV8(+V>8{upA*l46NJm0Pd#!94}A;@%j@^k<02TI@(_ zwdn`#gBma4?A}2>X4M{-G<8OL96>A4Ori0iP6H;Z(|{S?cx4K?XT}ifG+)X=>mH7AfuI#+_LYX%GP|9B)8hWx z2Q^*-Z8!F%kiemXA^+pWa1PRm3o@-BqvglG6cWfu_}c$Pkw@Zkj<5EoL{$HYG5S^)Mo6f5rO~CKb^63$!Y!jpvFs}&SPJV2xRO?^Y?z?^|*X6?V$1d zk9}1o@Zc}alP>nb*OMF#WJ#c3iGA@TQ2CLh#5XG));<^)2wFkLFF5walR%9d+a&GU zH&*+g#!KMW9Q)!)U~AJE!5@cK*JULMT7kwdIQGSpz$5jqN-pwEd0kf2z)BMMHOIbq z5*Xa=x8yGKL$zgGkZA=Ozxmh~PXd?fJ?uaG&6~P!r^ZX5XNZ0ABry0?I20^9TIXDj zWaNm0^WvtJd|C39(7@4InxFGBPKs$5c=o$K@+M(pxJ2XKJ ztR%tJOyfg+1uCSz0u@Kl3N+`)4UyhpYN%SG$vHK!l7zFCid5bIaplmuJ|AlzlAsl6 zt`!>}<%jkSR_<{;j-V9?&ZHY+^P{hXw)DrTUq>V3g)G;$(*u<|>n&Fcg882ksi*1PRJw6QwPCT9DC1{0k&chqxK;cMu_9JyQL5++TGH2Bd(ecL( z;i8k8>U>b+B{(l`i2wfE5dN?RzN_Y$|5o>SpN`J3@z!xeTwc8~eC+UqID%H%Uu^aq zE%DxQo5CGRAJK#}W1bhg%^U=7=&tl#^akR@7d)o|+mj!7n4))}8%&2ity^5*YM(UA=BVjhm3)f$ZCjl=nn4;G|sBsfcNvoaxg#rZBd%t*}}{*|tJs)`sdlP%Q9Izb@JbH8Nhv?7M91xAUtDBxnU6lx-{g z@zzkA=YLC`GqH#EL5++TGJ90DTSV1IK?JSfgEID0w_o=DD|4E)yMp~Cc{%+4CafIU zbz(iQ!SXeN;8}Jzaaf#j-`A;roi<~iZZ;?CLlTZGPu@>?Xw~u-g5a5a_;3j4yQAtP z>(eXiRH$6N+3u(hNjS2ZFE!sB=%T(LFtzEpW-mku%&|fP9}eMs4b}W=yNs(IN}qAk zUwgyB7M$^d%-JZ&oTW0v)Y)}HpO4$D32M9q=a~#KJd+`^+MNzA?(mWJAqiT6=KGZ)IDaKIkR`#HDMN7n%1h7+;oanyBLkeR zg+{hl*^W6&Wqfc(7z8ztCBd0uLvYsFOVA48oI5iFXSSsVvLrZ1ZV1kvdkI=0oHOZ$ z;0(RgK$ZmO`VH~5T3Pyi=(c1pK`VrFMZgd($NiX8^x|4gPy;JTaLvLH>l<2`1GdbJ zBWMMhD;tL3iiy-fmIPN)3^6G4OW&OBx9eXNHC}?FC_`*2Q_Vm9`@ej!k_4>~&XJlS z7L-r({q$zPI3KhE;a>B4GjmcXw6CA;8K{x*LUxZ{znk+}u=`6l#u2mv!8JCMs!uj{ z_RR==vs7wiypTC^HbjH*e=oab>Li^H#wD#FbFI)2og404dgjB1nxMu@ID5}ALRQ~f z@~iJH#Sydu?Oqve`{Lx#=99MWeW-zzB)DpAQZ@VLXM@E8Pih~MpcQDY#2R8p)%xM3 z$KMV~4P;4h4cZX%e|{%v>Gor~J{T7WT0!QDvLQOz?UvRowqCa@mOHHYz5|(gGKBhi zQlk2LlCD8&yoCE*O?@?cnfhwB&bcIL1)3u@pxz%?_%sW@~~PFTvRaL#VH2htyZI;|N-T=A45e)K{}Z>Z{qBpaxcw;Jk(*I9~!Q zYP@@aB}SGt z*y-vTjS~ugwnl2a1b2uTAB|IbG@d%~*jiXo<0ZIn%@CKjXEs)U@5723FTuTWhL}~h zT9ZKKch|v+8ZW{9cZL{#U#q06a~9~9$nhWuu8czFh|>@UDmPCab>ez{_;TB_7QmIPNC z4N<{=Uuf=QX?g^}xIoYf@}sdYY~XiZ?Vm~hbKi~91T|j5y#}eiDH~Sblnu+cAkzvm zSLjTtxRweH*Bv2qEfq3TXb7&QN{yG`Dybp3mg*&Fg>a_O5L`?3#w%0E^-n`^EfoYc zkR`!2PeX7m)l1L{;avYT#P3@c)$aboOUtDOvLv`l8co%O38CaGmvntFE)cYW>|RTK z{pZo46Hni$3Dy*>xRwf;Z6TVfDb>_k>L>acMU9u>Dybp*R4WMQbBO75VHGCxKhX2N&cg6 z>wHk-CAdmzQZ=debx9lVo~C_Bf>xm2Z}bN~o8{lU?N;rB8dyn!tE9#U*HUF%kZA>( ztBZ!nTi(q#Imyhh$eeR!6a-7b5EG|$PQGvQLm5&7SrS|^HAL6JqcTcVxu!O(sPPi+ zwbX69pZB*~+Al8WOgm_8lTatQbFV#M%ft4h<=4psyJI4nDMat>2k_4?lbH&sUpX@lBH12Y7{luXLR+8W< zsUa$NJ(zr3`MJ7uB|$6DTro8S*HWbhvLsw1Ep=~jSDl720va#j8udjQ zuk4>V?!Not2wH*WdzA4dpFWsT zYj}>XL0RWq1p>kPH^jzr^OskhF;_jK91Ubi@SVXByM7++Yp~&}Bv{FOFeM1*o1P(F zy|aP;(^)_2d{6@`N$@?<5Kq3++u!QQ2XO?gK=VD(5KC+I_rH4Q_Beu8Ao!+d2;RFS zH8NhveCsm=?_Kf|v_d%F4GqD2m!w9<3z_eUhTy$RUV>H#cfCPIc<++b$ao=hUflTL zy-Qw#RtU#fJGLh^!h4sz@jA2IULX74x*WRZ)Z9er9kL`aa(3=rdM)u0-;Q72*EL9u zm*5lC2UXLM3^6l$?~>F&mIR-6hTy$RUV>H# z=M&Bl{Tmj_d^K@>rqn=|gzL!}QBTg0+J&TM4V<_j(+aZt$vLM^dN{3chq(H1#&Aws zFsXXu+fX>C@nTJ|{UBaRxJG1=3bk$tANlepohnJt3N*)d#s}|Rk{Za8;CRjuymtv! z)OZPw?F_+tm%Ie65bhfFMR@NLH0+lkv;TnXT2YMf-X*E=5?oz0srqqFKmX}hX6x3@ zxIoYfvTJ2D()OXE{tKIT>$Xdcm*6U?@u5~<{c80!j-VB2uHzbl_by2dWJz$n%@DkI z$xF}*;ap=g#NY;X{QIZg8I~HzlHjaJ)W-+U`ZwG%SLcIqfuI#+uCWcd3D??Pr1(FN)|&Khj;;^J1%g(Px!z`cs5!E*nj_QoAm$WZ4E;s{!S#xvNtcS)T$2&?l3aRjYEa4yUE zSX22#c=4tcnxIC;3z_p;hTy$RGA?Na8PCM{dzYlfOStA4A|E~eVCZz?b-LeWTp(x# z8P8zn-leA>Td3et(+V=@{Y+W$-X*E=60X_7 zNM-e{?Hi7Mrh6Y}#U1bJ=2RXw< zfp+c8jNCioPv6!>*K0zi%2|DP{23q4?4YATyprHbydh5hFv54!d&Y-MJFP(TG_WBK zPk$qv-MNIWb828E39hRfqVlR;$&HT8(XCw)v;xg@(1uukU{B_V%3bu^HZ`!41lQFK zadcFpti;KevSeJ4X$6_*xeal{!?Uv9Epb>A)OZQk8hvEonpRnNzd0k0pcQD>iS@|R zZKJc+o_$;s)WAv-+!J6@_33-}X4QY9b{s(~&^%vnh{2`%XPvm_%N0@sSrXi-V2E9J zb;~;c(uZ*btw8fT0fv}o56F7CR1r;311m|mRxKkBWv*IYcE9qVu<{bIUB!{x-dR-#H;pqcXuJgI*a~mt{!y#y+&sCNekn~b`Xr`OeGB?(%A<~J@3adH1wb#EK;uqLR1l_a>* zXo%j2->>`D*!SZIT7hF zt2CXY^Fa-)B*9%zhFJCe;oysxhw8B?HC}@A*S6KQQ|H(XV6ej22j|kT3gF1jY>WHO zFc8i>j3nfWiM%t+OE|PM+hSW@!kLG0;zbG>uD^R8y8#S7sF7BXIX~mRGfZkg(@MtV zzB9~CnDtYfIFqz(6|LMMc4wH>fadHF!YSKUxxUT~U{d2IoD~||Qs1GE-5KU3ILn1_ z%C@DxrysikOlshRR*;=}xCYCs7f8?wF;RBk874I{UdWsSw5<;l&c^Nx^AfZ|IA!;p zVNxUGh0M83_nl#0f>sEp?7lNhYGk~SIm4=MWSg-zc4wHEpcTR?yKexK8W}IbIqw%w zP~#??^UwbZ#-5KU3XoYaf?mNSz20my7ne%?`JHxyLtq@Mx zeP@`|$ao<;^NGLqOpM(b<|Sx_aLVpG!(?2L<&398$UDPiTwa2-`_3>B)VPU*Vz#zh z`}>rw6RFA=*l41}}J z<-`kr3|C)Py|g2C1DKbf6~ZyYW>(4WDzVl@P$T1o%y8RUI=MpZ1~3_yv_d#%x!re$ zNsXIu&gQu94D%9<7vY?;^Cym$X7SXI0&IhDnW^kh{X5IMxmNtY30fg0%7);bVNxUG zh0L|||4q;eF;O-IZvc}T882k6rQ24;3kk71!@LBo5KdX$W`5Kg4_ZOy>e>G$XoZ+48)9kn&M>Kw z@j~Vrn{D-4S}JyDn3tdx!YRA&43ioeFT%OT=DssbYTSf8kt^>E^Ad~~;ap>L-x($~ z@Zk{hM6SFu%u6s{gmYESeP@`|z=uP~6S?xvFjz4zO+@eWk}=uV1B;wn#-zqea8=H> zUY)utb^{m)YTSf#p4WY6n3s?%ag^P6hJm04KBUYwHrq;GF(P)$n3tdx!YQj6;X-Q? zd1si^zz3}m&NVjoEn`ySCh#7W-wj}}qJ}cp)flcu8RC{PuMb#B!mQoNJHy=Z%2RtL zABOn8Vzt^Kd#-)yi&eELayCWR&94$QtZw!lPa#)As>$Htlc&5 zH@857R)~qRx+gB{wh+IhgY@!jD6Aa$U<;llwXKQo*Q>*?^?;zpP2|SHZR@?~8!YFy zcf5q8dBWAUR(^VR9lxZ5c(G>!-^Bq9*_=hrjh%^AZ(f6MuFEg!fM8s1!Z}52TP^Qc zS%=^E@e-0|3e{agMXSW_S3|tc$%lik(*q1QPc`1J1|QUbmgfy9Ya({P8VG8<1kWDC z6V$i~_o;a2el_@zgp_$&!F|6P;-v<(lu5hqS9252Nq9-CH~M;su^ZW>2DCiWKv})x zoJzZ!f{10Pc6NdntCeY9YLR)~qR@}UUc zmL@guK`Y2S7od8$=A8>9XoZ+4tFh?M55{gwlNuQ>WUk$+8|%PTa2sAChonxjWiR zID4I)c;S!X?%UGfgBodtaA%jdypc_6+=Tq{m%LvMR*Va>+=tF^HK*UXbL@UKuMbI3 zcHgfCf*P+6?v&T}F2(Lw13`_OkYE0ix21Urhjw=S+m@Gb&H^~`!XLxkx23@cHPQ;< z&WWm{6*t6gWRn^<;e4ONwoYy?6uT|WOE6x9J14{B{c2JJ9}eMsHN>{${c5mcT#)5y zH-@|KSM&Oi1ZDSaX&|Wa`rvuIc!C-?p=MR{y8K$otjcgBlQyoE!TBk^6o%5YAp4 zNjTpuvMqVP8se3N-220D+@t8+ujch33CiyK)j&`Ke~v77I;oo%WB03paP}=pLVjaQ z-j?Pi99oSAW8ZsKH!sHSR|7!}QsofxTVd)~8@pf4OE|Q%Z_Rxp8wh6~nG-MkG2FJ~ zZE0SDRtV?5wRnOW882jp+m^gvO==*^XRSk&DN`nPznb*!B}ijrnI7qv)2-gTZu8y) zfswbZN8xgOZRDyd+z_4KzdCD7l)yL|8qm&|+PoW7iV+=~jb8r6-Y-^peK@0jhqkRJ z20xp@@4X`JJP!<+r->00!)@#CoxWs;a5P?mv|5P^G|S)@Vi6ZLZsK6+*cDXa0-Ek!fe|>suEm6-3YqF;TXyU&?L|^9!+310S@4%v0aC zHRF#{{(=ZvAtuVIbh8G8`Mp=Ek?}(2yN?D)L1qxH8Nhv*lm3Ozxdkpwp)ug`=RSyk&?}8>D?ld zpcQ;@7rWZmcUQ+PD;hS5tlQsM6V%9fA!8?S#bWE!y<}$&)o*tFqEeBDCmxI=XayhK zjc;3%OFgsY=He%^OPqa56V%9fA!G0G{(VE0kL|5b+;Oq=itL-K42&aa1s^e*=OJY8x z#!Ha4tqBLqg%JPp%t}ed%G`cP8FvvPCho0w6H=2OVeUBWo7UKmyXbMlyve!w0=p@< z{JzG%X8Uz6g8Q2#0h!^p)n)V^U!jUU0|N&h*FLC`R*<>3+P2n>JCs-uK`W$|vTaSe zr$pkp!c79|FCsNEUdY@puJ*|!%w1LxK`X>W*|uKsZ(FAFkg8IqeNZFgHU1jpb{mY} zNBXZ@f&~#giDXhs;&i=j9mh@cf>qO5joRru7$ z8k8CtukpvP{Qov)dVvJnl1VLzUZ*Pi*%GBj#tWHkTFrQ!D43uXVxnwY4L5g-{i38s z#*1+7*|)9s&tByssF4I@hTB%wv01+PCu?L+*f}%+4SF)1+JG$2f-u~+S|4%`rXP*jyphgmqd0Iv7L#|!VR}euf#6;P)zP!SxSQ3g+EM zwZt;dg=--a50=z9V9tx=g;wX zceUjq`;N2fd5%ALr$!Pc=gGORetBBe`J{io+O+J}#{-ilUKK~6Z-*6P;y0w!%1^sT zo2{(SGf-8Pu++$SA)}|>P~({LF>B_*&Bsp;3j8^9Q5-=l#Kf;$sj<&>?V9b~KQxe} z+LqMFcp*E#!O{=kp@IZ+V4mS4^v_d##wK977h2XMlZV6;vM(H|bg_35u$x^qi z$4*`JJ+Zgs9hal`O|Zq8cufm8sbXvYB_T1ED*kHm>-7H4T{+*voP(f75|CMLx^(Yg z>3RuTA>37iTUdiqBjbh4`q!%4DzQ?_<5 zK`Xoo^Y>_5X;;nM#NWBp$asxE(<|xU`R)9jdkOyL5zgPE{+(~+?_6qRyhttkF5CM0 z*-v7>b4f@mggb=lMK`e*mGMHx_>;3n4srO*#C7aNWxQU3{i7OF&))n#dr=V7cnP*? z+v)Rmmuwo z8L$J5JpkgOj2dJwVe-M}IS8rAj{t33C3f%hAw?i$S$RvrsSgqz^J%>xa$)=BC=bi?+)KfEFL*geKh)YE!X_DSc~i?S!oQnt*QMkYNA?^M?z8~ ziAIBmY67%F-1lA4B&m_a@9*BIi9h{i6;c27)l-nFT0cDzmKsUiSG$f*p&?L4EGtP! ztGDJf2p}H=zp0>nNJ45PG45D;#363(T63!M5qWWY`7p|=&ZUyNtWXM+kwVDK`D>`b zNVOsdd{QF`lt?_W>iW7NNk}WC5QNEj>E)klAM=Jz@=J{*P$Ka}(=s!XBq6Pka}chw zilEG-MiMAPhxo7cET38(MalxQmB^gS_GVl6eKtW6Uu!~Yyaarph1%A#3RhCgpV;ny z?XM>yvOZ+F$(Rh$ztw3U3ASoUKt{N!!3!^~OfC0xV_(^o&qt(260!_!3&f!vCE^Ha z1sOg}4UVsIbL!c5W+vWHYiLAjBq2-Pwm>ZL{TcKU(h9QEcH7@JCy3ke&>E#i67Cvo ze_Q!b&1;&M^b*oa{%&-tvIixN)cKGaNyrvsh+BLAr1K#OX$9FSD^p8x)!Vvdo^=0fhgppp)s`B0@C+bYwtSL&gaAKuX_{k4G9 zNaBOeWi(-b52C~Io~iGg-gC!mV_yqMjU;X=eC_tUnPqclbgit2oXee4zx;Mb(uIcy zy9j9o8NWe8jBHUeb;k>1Qjh-hLNp&H?e~BBit0bg=DvHaog-BdzpZ+B zXh3QtasHzY5v1zXTWyu9C8Ov0_WW?PdGTk42c$+42WKU!-pBY;r&3Df4Gv4B%nD(BhExztGFRL4?jNEK>R*GD$%LlV+z*R+ee7d17g>O7lu zE;W+)yG#+~qhzjWC8}Lz54=1}w=1cUgpo@|Q>E%W`?HK(UFXsVQpkFisdYU$(`9aD zeMo=UC!>3wK)II}CP|GXWUI8TKkggl+gI#YJtC7Sk*&|2DiGC2{8k!I9I26nY;QUr z>FC|?RFh?5Qew(SmZ92#ebrI@to`cFKDDJr67sj{5FZx55R!znlBKTZWaj^&eViy< zI7w;C}7Av7WY literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_7_gripper.stl b/lerobot/common/envs/aloha/assets/vx300s_7_gripper.stl new file mode 100644 index 0000000000000000000000000000000000000000..043db9caeaa59dcb0a6bf570956b0904eb60ba63 GIT binary patch literal 450084 zcmb@v3%plT{{O#7C{%`AGldROqB=*XID40*8IfDAM~qyGRBpLVv~#H#Gj5SfXx!yG zzC))td!G|#P%dGj(jXDJIpHJsM^M5@4J$~l9e&_vuuJ^vI%X_W8 zKl|m}|G)pb>}>TVv6Parx1QVR+>FMR6Ax*;^Y>S1*||!T`{VB@2ZUpb(CP)6YYGU& zD7=>aqgKnCO&i%f;kYg)-X7jx>0#ep+8D%eY}x*Q=V3k+9d&E*mOw#(vi~ zPXtHBMDLB~_rtY%`Tl7oN5z)IkH1R2{y1=Y^Dz?k`gQl#N<7l;uI7p0sF;xJCPy=) z5m!36RtbB(fBGxk{C%F$SVkn$K(v*}*=k+5K62f(jH@f>*ASd}L9myclX~II%Ltdp zaC{_kgi7Gdn?EY{;uvK_5rZvENbAvaD%w?IXU<-HPU|8hj9jmhUL^I_$$#tUQ4+(+ ze@3tumrMF!CY1B%QK$FT_pUna!M@-4GW@iDCD_aNU>~E50Az$7dpeFV&o&7 zKPqm0ArW6c7^9nex9|2D&uS(8L$3mQfpg6fe0_Y`Dzx~mUjB;O9+D`T(nt6M_2 zCc;~o@MRm@-<(*XF&;R0K*nC>_rHX2O@y~F;mb3$cR6?HxV9Rj{YFDG_9}0cC4_4t zyoCv0o}r_JbAPyCRfKER?SSDKdzJT(62dhR-ok`0&&Wrg>wDL0jN$K(&e*HG2bU18 ziSQOCeAzO9d5u#v##c|CpRrf@xKcv6Cc;~o@Z}jgRysHT)C!Gp!9C+M_Tv7rPQo=2 zzAh$wd4~38=N6wltOoa^*Nh1ndzJU#62dhR-ok`0V^+g|5~E&XD8XJ5uOS>)nkT%4 z317COl53SB2F{$lte!}ZS;{bQDb0)V=oyWH3sIv|3>(_nDAvAMP+Q)7#OM9OU8MPfjQ&9 z5xy=aeA#9LnQ=4*<|y{^StjRj%@f|jgfFAtV0E|AfKwyfkK>YyvQI8v6Zh=(S>ycq z+ce&G>$d$+?$vASM*Q8mANB7Ak$_+?l;KrQpnm@^DItz6Vlb_~iTtnp2ZFth?RVR) z>&-=s|2LxPNI(N(|YtT?~ms3b;{7oQViH(e`b@=PDmo34*La$GY{XlO4%Zlub!;awaw0K; zy-Bo2w$Wpln3H6^Ck!?dESGF>)d?g1u0NS4fQh@Cc2u`k}TlTTnJ) z<@G}}#`ZN^ON^XIj9@R6;S~~_?=V1PZ2e3{%odc5c=P?i8e`bV?IcD{Bu20o%J2$_ zR-5gmG2UO?CuR%EMr{7>?=(j3{yRvFoJfpdFO=aG60<(vPGh9=2ghtd*@(YgGf-n( z@nT1bkrRm#?1eJCLgI)uEi{I!t&Q1&vJv;L?XNKgeX*m&$ce-V_Cgt6Au(;uLd_GG zA2l*&3(7{^zIUWC_I_k%iIEeD5$uIByh7soKi;D;PQLY=m@Oz9@#(<68l%0dkQh0U z7{OjB!z(0yyW{a1;vVU@w$$twKVsZiMr|)nyCHMr=K&LSy)QUP`bR%J2#aX(bv1t%NNo z8*%DOJ8BHyc1sENLK$8mA+23wptZ9FWh0Jn@mr1I`(P=-UMRyWB&65Ide5bwvjt@% zhMc>d#_(fFDZySS!z(0Y^wAg?eb|Ds5vz9IT4VSzv6Nshl;IT;GKy*pjG}Bo*@!(l zZmBW+*j`Go7s~Jo37HKv24(}cplrleV>Z_qevT?7*b8NNg@nv%8UwQ$TTnKlVVkxZ z!_T#)1bd+juaJ=0Sz};!W(&$jblYV!jp1{KQi8ouhF3^PmZ33_Wv~ThBleoUiN^4` zPbtA(D8nlxBwNxL$d=fGvJqn@wAL6thbtx63uSnPgk*gh16dziP&T6Po2@j4&qYfK z_Cgt6AtBkT#z6MU7L<*+?N%Q{`l^iWr38DS46k((Zg4iNo-HUFVX+54`9nif3?tYJ zWq5@|e&$ZDRmv7S4-j?@FS}%w#Gq@Xgw<dV) zKYwt>7A9=&`p=jKiIEeD5r~0$ZB~O#A@4rh7%Hfni4Ag5`AG|{1q0yRIx;H0Wnz4lm%TZe$ z`hOB5ClVtN1NB<=3a^lG#lIwD3lo-W`xrTpNCK+_V!&cqxRsGpdqR#%*9JH$u8Rp< zGx%$j6M7z{UUp6)Ay+rWk>P%@#nvCF*VaD%p63Lza3!o>TNS}8B&3yS474k@Fkx#r z-*$5XYc(Yh1NGYK4qhQ4tzBcFwX=l@TZ{TWm=oGRO1%&dULhg9Hq*N({hTeft_5Lh zYCo3b1lG<VovCIRqBO!@CpeTMKuOSQMTAV0|?vW z@MC*U=(t&fwkZeg~AirXZ?I)sM+spJhTuxxmQVFZqb~)h{5|Z_44CIMy zVZ!!geJ+|4*n3q1F;K7V*1{_!Y!4aPD_fZ0z2&AoWFrs*_42NBNJt+~s62J zqicY(uU{JU)XEEL^zVZPzuy4ACW3n{_pas%wlMMHwy}?K%7-N}*o%8t^8{O%XmxEr zjj{8aAD6^nFYaB<6Kr8(+8cg9@!CJHEQ!Hh+`F15*uunv@9(GQaom(IOJcAW_pas% zwlLA|=>Zz!`dQzU#9%M(UCk40Vd9WO_tzK?w82_U{w3BD*^7Hu^8{O%xcN~Z*aGR1C>}BI4_7j^W99x*MG5`3*ZA)UXmyPq-7j2esY+=IYu0g#wFNwikHeX?X zw^^c?2T>Ojd!~JKyqf%n-;~5)FUyv(Pu(ox*uuohCwps*I}XP)NWSOnWm!M=+nXgE zTbQ`&x+;zFbn7ikVz8I3Uhv$YS;Db}iE+bvX^aOamBwH%TZQ5IN3(=u3lqQV)I($Z z@_cCw_OjI^p4~J{IJPiR_g?ofMv{-B347V97%|ESxru(}9(~=!0cM5rZvEynIAwjZusxMGW?`-7kzKWkeB!Elj*JWhaeMjEO}I z_Oe|(jEQAL5rZvERDaw_V-#b15re&KHxgre8BxSw3ll$_)lp*uJvNEEG!4@WLtQ=IjmyxiSjgQzJEF+2- zY+=I2{IWfnguQH>$1Z0XQN&;i6E=5YKS-RV16m(sFPpEhzgtEC!kRN-3lla6e;X}n z5I>5+UN-My*SU-Uq%qjSgyj-19Jit3CoG5u6(-zA(~>a zm*qj&-!CHoX$-b7VY%JkzFF9S5KS@I%knuq%_t)PX$-b7VL58c^Gjo}m*u5+c2hr zf-Owg8m_GEI`*=48`^I31Y4M}wP;x%bnIp8PxQg&3AQj{tL?I}#IcvHqcN705olK# z{-^uG-u<21X6~r{w`jcn=_)Ndw`JqCU8;++_~}3Y{`u`Y?xL0c9IGM;j2y_}~6kEdyt?ZoK#I z9kjgqgiRW+KB1$QH@!69DN5{GvDa_vJUx2#rsaeL@>iGZVj_OMlg5~|cfM0p#9*(B zdV4RIwP`FPiWqER;-IlRX^iWh&v%N780_`KM?0$54ac`@EF+2-Y++)_-kp`ca_4-f zsEEN{SEoCx*U*q5kjJA47ZL8iT#gxylm@Iu^@ zn{(g#wZR{fod3aYfN*skTbST+41Prn_t_VI#A!41!-lD?eEEWpmNndWp&t`}NFFWk=xLv}684%t$)EZ3J3eh_mT+ugVpWBwzZ*qQ`!oi79X#6K z!H4I3(a|Fs*XL1^7!3-`SW+*Y6yw*|JqNzFsBY1wx53cUbxW{XzgW$VE(As!bG>vJzd^w*=x@S2k4QY*On1Q47Mc4n_XpYLN}b}l1| z7;Ir;;6XkHG6Qkef4(KQd(7w5E00>#(C<^9Q?EH^VZ%4q`0~x4(7IMf2KH+AocH?E zuyqg;#mC^fnCMsAORw&aU(=dXW3bnM{^-5#9`>(>GNOpV7ACmQ`_s;kDq*jxU;JqB z)0($}Q9_9#2G_+z^J58T_l+}rc8~Q(S*D-ZQL)$1{rl?mL7rGf6i3AtCMsUqN9po> zm%T3Nzpr{B-z_7G7;ItU@7L8RU7okISF7zJ^+MiWMiepF!o=J?W2MX2AM7>xMel|6 zM;TGXU<(sG=8Lo347(rf_2nQx17IChMgYI-EP)V349D%~ihud}3iA@rT>+7> z*Sz&SfwtQ$;n>1N!@b?~>X!FG_S)zQ?}a|tEaBL~M4NN{O1KzHaPoSsj+^Y~TI6b@ zzxQ_#Ib8eS_%d?4@XXn3=zZSnxZdj^iWpoM6R(f;Z8wYP?KT~K*lUAty;q+N-fJi$ ziWqERV$^-U5B8fvJE`{3oh-fbu&iWqERqFWwTn6 zx2uG`CT-yfWR_(_5rZvET=#^}mdZ0^_PXP2KfgwjA(s(F47M<_`C^~-m1p|w^?x_` zBSEHLMiepF!o&gd{Mc2#VqvdSF7ii$6-yaW#9#{(+?&OjS_yl7-^CvZR$gU95rZvE zaR1jB1;HcESNr-A2YE@^=#yA0VXua*Jb~P&S;Db}iB*UB{X}F@dQ?RW_G-P6_d@?@ zmT+ugqG6EVzbx~-Bv zN|%qj?6r1N?}c%dujQK_`L?s8J#=)km)ta(5kr2{k`IU9J7adZM~;t zNFDana`cCGjbHA%NB>F3ZZj9V+|G4%w?sR)u8OxG*f~B+S{z~=bxE7X7GLhB<=*?Y zZR8zj=UzIpL)4?XGJgEJ9zhJQ_qFL=l|Jzm?7e>W;3m;S7gWVlck2C-9|)*%6YVz)HUY1nBa4gukW3HQgr1} zRdL@Zy2k9a-JMlZKGi8^FW#*Ui7W4(6V-2A71wUFeQ*bvSUGPOy&pf`u$kPC{Rh=Y zhyJrN9y4vbn7w${IV9@ZFNqG^s48BuZM&E)OtctYp)uZ_faeC^PgokA_F`pRGrn!i zUc4_J603grF`=ch5qk}bKQ8YTv)6|w_UM1o$v#F%UCB`lHbjm)RUm5Sa@PUZEc>gjae)CPo?40%FT1|T>Vha;vHuEuj z9~`n^yKIph)p3tJ6R{VsutVYxS^I3{4pnjQ&F4jIVdAhhHF_R?EIIb__Su^<`gGoQ ze#Bn9q7R9RJz8fI)5`cy&#a8t!bHnY_R$!AO#Jq_*4gr3E92|_^hv~Cyyp-Sw;lhV z^y+6TU-wz$z`z`z_JyfplqHETV*^Bp1LgLtSmZbO2sf^z`s$I+$ zCV1p??&s>I=}YTZ#Xlb0HfAs00}6?K2Gys>$gFmn%xY|5g2zhvHseLzv(LY;jNf~{ ze`+mp`J~kiyb7~k@YOdzHaNHUF+H;L)>g(n7Hpof7q1ON;*vvqX73zb6+iXfr}b=M z;^l*VPpdd@t;G1_#=Wvv%w~W;uUKN@l$1X*u2Vk^-mq@*}}wWr}-E%>`0H= z?D@*9i=6r5S9hytFWwyviN0$qv+HE8eQj+A`37B6T})W)FJ4$rVtl!%GMn&2Wqi}> zHZ|$%hG zVdL0EyL>J&I(^?d+eq$Uhi;#w?8WQzkXUbR`)t5lmGLLT=cR06!p7rYx58Id{&8FT zY>1rsE1l-2?8Q3>A#v6Aow76DsEnU^?xB<|OxV0Ks4t##em$pS_S9FE@pq5TOxcTf zLPFxV$92hOOC~dK*GVZ`nBY;#xyygqHEZ`xW!ycQoU#}1=!8U@GrDL0k!!W#wEcq- zjtL&eWUl?ktojY*ejIjtuZ-80{A9y&BCJK78-Doq>5d;%#!J81D`PKy-VzcUHg2DO z^RcX>KHe)>*D_(b-GEcEle&E7fONdfoX7pXd&XY8zZViO>^&lFFZ0LZKX=X8!i43h zH%$IOVm#65^mMZH^Iqe-X6(iLi6L=C#VzT_($5Et>722J2_7-ztN4#kOJDe;GCpN| z=Zw90$1^0lA37%;zO*vFjPr~mH%P%_tDsxr&^uv5VM`<8Ly?+PSFuopi= z2#MZrA5nj_WJ~A%xiVu56Wn^7lY1W7J-78a?k(?^*^Wigt|Dt!?8SR>A<^!!={1LZ zB)xXa%8V^c@D*`x&pl_=ymn1heDp@WGWO!<6d_Ud_7OG5%9)=dXU-NT_!>GV<8EZ* zuB|ySzVg10t#^yDJ+iT#y?CD~BxL@GZ2n*i6Si(I=BUW#DE8w0vXB_uFeh3h{bSo6 z+h=TH!geMwKRUPakU7yQ(srMaw##0;?-vsHYMJ{E?8W<+A#w20BcfZR5B_pr*NiPpa0_+ro0g|XhsiykGO}yNUc3(*5;9&z zHeRuX32xJxi^i6V&Rx?{vu)&@{6@+j#&y!aBS&>k#`f68cJ|^oU_zopb(eVf>dN?U zn@&pE!o)p0_?-zqtDU$_mw1@)m$HQk+j;R>#OkEgs-8ISEdKV>g| zvnnM1wPEY{L7C4x{&8i>7ACki%NH-6Zymo_EhEFC6)Ai1o^D9&cfkhntCC;27r#&0 z!UXq!=S~>gKCY5AXT{I+BHmBpH`?rq_;u~%*SCv5l(zfN$DWDUi{FO}i6vimj4zX; z>Tt_L5nGtBJ6o*JV_ToI7r(I=60!#n+a3U0n6MUF>@&o+&%j>%=3z+4UPf$t8Ej#~ zdYWHN$l4&bwE=ta8msRn&8B&-ize^^NcQVGVon zo1h_aw(LGmSW_9#SkR${Elk{YtB)abxvYv7%liM~1(oq%wrE?!Ui?ODNPH%%#|>mZ z@%lG9$kz~?>SDrT`&DYPqB6ckGUQ#p+O3|w_|4pqcg4=>~-8!5Y z_niLO?3>%JQNp~Ei#_pr<5${ZutV=>&O4``iZgcuCoc=yRVjg*JTb_BdDv|v-#p{o z2W5C6r{cWJxtvIhU@w%B>4n5C`Bxnm%2(3Zg0d0Z#+*Cx>UQyn8%NE#_P`^QFt1jR zd*X)mK57VwXJ6P}&%Dj9gEO|25~#`NyO(v+?^C;XG-cNt=UjK|n2fzZBL;HZkU$KyE5u++DFNDN;c~6~ z7yjhxVkKOhhdfb68CN%4pFeYRJ0(Vpy+qgN=GE>eywTWm?wMzm5^Lp)i#I%b_Ur}n z#YL`*30@~UxBluU>*X|(!&^?sO1%&RE7OpGxBo8*)|~J%f>&hXTSBlGm(gqeO85%; z0w&jmvJu=uojd8fCu_RbK0o^iIS=;wswLi_^VcdQDFNEAg!dYISK6b; zXLBx+mRNcRaqRH=$Ln}&*0)OM&X#+=U#oxieL?Oy-w)mi35gr8nw>uL*3olrl9tF8 zCa}kW7=Gm?JqoQPL60i+!coC1Bu3=lnp`Dqmo2<^g53|q@NG9I5+kf$-XjT#EAwwn zE<3JPcWbRKCa}Ybzx$PNP9#Pk2BPymY)G7Zb-N6WYpRTiY+>SuLwyX4kIu=Mn9c8a zM;*pQwlIM`Ssaxg6J?}Ej07WfsTYnAULheFfF2cc2Db2CFZN^+!|(6rL}G;1%R9Fr zAvuG_K+eDxCayUEZyx&mK{J4Cmrd@N{itLBY+(YsxFGymO|lFgB!OkhrtMiF)R(+pN(YVXKRYG_uS zMz9ykSfzx-C%O92Cv%1cPi5d`1V0gSE+-Nr*b8N8*P>n2^bDzq7&B*BJzG#V!j8(X zKP-k3?1eJCLgKdk%%6C;B4vx62MBvsV;}81Usfz^VS-zXyyrDu~T42>sRy?LkZMnUMRyWBzouHV!crG z4cKBw1;VbnU(t7#Ghgp7qh|Nt@meLUUb_nE=PgQzN9BG<`*f$@F*4{;r37m7G1hGA z$K5YPX~V`VJd3w+7w<#acq&N!Mz6KV;n180KXoYMb|4mk`5b6#ZrL zv9s&vR0K!GgpH5>?Sxwv4b&J1p0`t6>VbH086|w{EsZ39Hve)NStCsDz+#H)y-1 z1ZwgzmgJetTcSi`*$dv9vaAMW%Q)~hrE@uv7=gOX3uSnP1Z6V88(Ws|fUwNKzt=~Z zj1pEayikT$NaR_DlPn{6XMzcC$Ig8jyJ-X&h^EIau z=4BcAjYs-6hJ3}pr8iCTc3j=tZXFY}#8Lt^dE$w&OKVQK`|R2C69X z-fLXyg(HMlNJ!3r`{9sfumxo!_|7_)6NwS*g);7cNXSU7F)&iI1!W_+EjYJKc2akJ z^^)0JiE@_hm|}*sT~5rkw!`W(fP-Zx7451^+ci^>u2uEsh5O9+-?_c|KXiVjUN`5Wj&by^5FKA!o!VH7JwzL8vELpN->;rp z)A`KWc-l4V>rN_;9ebfR_hFwpBu0KXHI2vC#<$m_IY%3Z5!Y!3ie zl-Hagv0ukHT`WZB7gtBT=HRR^Bv!sZHL8&_Kjwi&5zolsc+O}3?6|qn!E)xWRy?V{ zmBE=~UJA!SCf+>e=jhDgwei5oTLhzz-E)kI;Zgmq-}*7G)z%AVN`~1~m$evN1#Y3v z$<^AZzWlXE}pvpTw1&V25u0Xpu2z|3hQs-H8OVmtTmOBY8M3DLG< zs{XDB1ZFax2g4ZuTrn^D;1p>kqaTR)uJNoE5@WA^D#HD^@BS>}S)a3vkXUuwjA-`p zwefD}Er_@+F&z@0Z!<;DqpIh!i1RjXl_4RmJ+ju$78@Cmx7&!}*En5kJ4b&%u~y!! z`6=R@nhCDSxoe*oruXBTn^r|!7aw6rZ2#@lnoctMJR-k>V2h1DSVwV2?%dO7RoAp1 zQ5&~Dt%a_Na0jujVS;ONZtmJ;HE1QDt#F#@gTQ)#&nYC1JG;6bFMkVYJnHQ{c=gNiLPG9fYIl%FHKs#CM!3{Q zIJVf>jx~;r`F@QfZ8x>H%lmLla807A_r$Oi{o`I~CA<&AV{k}x-F8ZfGv8ENJ4a_a zBxKx`_u%}v%NCn)Y_AVj-LEF3pQqN(dGC!0uE{y+=XxIK=e+C4S0N-8EdMCoSVp*O zj-D8fiTN`RWcs`(r=w_UqbTnJ^R8ML$MsyBOKSo=M)k$iYkFoly`wSUP#Cs zmD(J|^DEOKA#;?@=a{2xK1WW)Gj&K<27oz=XMLta0vUj1OKh&y#lRv8xvfUbKlAxM32fw4bUeIAW)ax51dm-WYS8;3(=)w zs{Z~11fB_6i}6qR_&i2S|5z^b;H1$Hq}C^pw^_UL&mEb#PWs0s5@Y=RS!#U(Ph739 z_~)lg%$Bj_8JPzUJa0j2;|H=yro;2tMMeh1Xwh?7YNLTYcg8vSr_&rmGUU`UWUkA` zM`Xx068UHJyUHl~w9JER{`pgCBPZUCVS;ONZpP!o^r-4?T9tBLe1st(S$Mr=;cT(_ z!`>FbIr;Y)TAWc`zm3dMZBA>UZ*stb_b-^>nnY#u=VkS{=kKj>!5b-jP9cFg3dB1< zw+PUxPRLQ!*iqSxtXG%bTMCa#?nh+z!*UVa zHKs#CRxFXNSlD8@7TTC)PQJxRON^`~S{8=3%LLaX3dEB8;5_~+_uTRwv_#8;d|Tpc zwL)?@5PL}5<>*X@F=QPT**c0XmY3SwhG+}EcS)~}tk+t`ik`{@*CcOKN%m^J)-qPq z#aAIDV#(VvtKE3a#BhY8_xdcq_T!3-iII(owg$j>WtqNz_RrU9!wHKur+%^X)ZpDg zKBw@gWK2{7W1_7GFb;COkdWCxS6-M6Y>k6CgXxfv*+AD(mbgc-nAMShmy^RSf{ z*0sFyVmge0J}6s#8U7c_a!`{aVah{Oo? zvKU^2zJw@ZaC9d4XmLdN=Z^|XW;iOS&pBzzFIF7pz!r~#DG#0 z*AyNVd*NH|AO?x$%qhf-uNO)Ax1wg&f*TVPvty~r(u{+3K_!>V5C}))s>pUtZ z_=0MO%V~2Fhq-%^wweK@kJQ z|9%IV;42ay71UKwFZvx+P*6sHZ2qX&3z{Y%{`c0-1YeQxsGyI7dND>p#|CALUCkdA zdqI^3#Q#1rFu_+OI4V^JLcLHNf)WwR;_?4-RO|&^ArSxjD9Qw1k?^SO*rDxXSHUYZ zmyFa&-Un3~2uA`htJmu-mk<)jkJNnKnXn_o6$y{Z?lV+$ti^bZ?UES9QL&fZ1Fx7} zLag(snBXfC9+mY8Xk}RM@+#>iF^Z#NFKe$}^Sp#u=TR}iS0p?t8$Y0SVj~e$N%*QO zk=Pw%FYDW0wf=uODkk`f1Tj=A1+4@}WurDUUz$HE_OfwsorDA`Z&yt46$y{Z<|W)g zo8i`Z=80V^_Odx+omY3AN5zEAKDZ*`QP~`h)^6FrI$KF`RP1H*>pENFI**D8z9QjK zS-yjj!7`_H_Nd~h*voQ}b@tkI9u*UOMZ%-9+z?}iWtr<7eTt)EFU#B3Il`^;sF>g@ z;@rLR*8TS_{;%#td56U`c%YGKnm^Fw^g1?M$#XS);qQ(ek5A_x@JjWI@*MC5E9_3xgU(b$NABQz@eA&+Y)Q@WF zkNo1IK2v5-h`BC~fsp|*UYU;=@-I2=xW{Mz`s;+4y-a<|tHUxOF={LZ*Tux!zrk-o z>^$UJ)zrK+V>Yf8dzp$B?ng-6;o3ycd>Qw_wPFhspY4XPDck*+zT@#x_lwV%jeE{s zrUr&q5)%J8WK=ZlylK_D$vtNa6XDgBmKc4v;z@0Z>}9HEXq6$c`v><&Rr}mky=TjF zVzw~Bchh7%jR^InvFH>iOa%)H&ywBq3i$%9o&z?FWXeCUr3XZ%vAiujC z_1GUrlM7qf*4R`ZeXe#rY*HGAJ!celKM#a^bC z2j$j~_-daH@qcDtQ(ZOxz?dyeuqu&r@5viN15W>Q-NsA$#O!6Ne^71>iP|1L;*+XSU`-o&uTOqiJni3S)cslB#bGZ~#e{NeNPK(X znD`%EPpGcy@Jz%OCRm%tx!vR~q;_>D)Gd*>kl4%AJ)zth67T+ee*Bwv538OwV^YKx zCRk(0xd-L_lGZOAUU%%wiio{Tr4-7oA#vqvh zK;5Iy4y$1=R$C2;-j7X)=MC&r{rl?=s$mNgtoh{J3W>4y)V_5GKRc|Ry(}J-TSMaf z>nFqm?%JdJ%=x41*}?>CSNUu8*Wd4fYn8H>T{kGVhQtFGjgL>fRS`{dLL~ zCRq8%k0n!X{b81jB^i6!xB}(YkeEE_i1@Q(m-fE3XS<9oOt6BJ9}`!PSvpI`#EiXc ze1vjqNGz}4FFxqf=X!s*`z{$OX}fsmO|I*GP}_qtwlKk8 z?3Ul9%3NFb_;s_slwW7Em(9CSjSPt?kF}B~J6hupi>uaM9lV|Mx<)+~JN?W)%&UYfCm3DyPCoZ8*^w>O`{+Lpa6 zzebGa3AQl7x;cLRG5Gd{RX7j!vb6}VRY=^l)4*sF#EZh&aFu^)T+OE=WAGGX^cEw({(nH$~329epr{Vj|Lc3xM z6ReJ*{UaSPci-OVAMC|yt05u%BOO2MtXb$EY+-^`KD3`_Uk^C1H~Kkyu?}lUNI%cw z@l$7^pR{WR|jjGmTObiJbud?^LK0XWM6*+ty(|XA2XoJ)(I@_TtF4)yPZOtKHKB zGzM~?kdVA2+whzn>X4VPg$dSB(fle)-rb=Z`4xK|a_IgV136qsNPd-_dR*5!hMG$bTX%&LaGbCg^m~HfNQit^*TbN))M&Acp_L_)3 z7_pc2N35MgLe{m}+Tl~`u&!kb6Ra%h$C5XWoKlVTIeXc-f<1tcko9?X$DnKLus&xC z6RdFN$Hc8WU002L2KKV?5qlXS@p=3Gvq76ps~aZ!3~XV7mD*&lOvd(yE2dSyCBLX* zFB|8vCleAo_vn!wv+tdC7s-AJTbN+QIp-dbIjVL2oz*YPz7KoZe1*NGkdS?!?CaO= ztHZtzTbN+wJl(&_9&USoHTJLA%jR9|k%ffpUuE+?dZZ5fS8QQ|6##V~E6=)}B}lwy?$w*HjQfC4mwRE8nb> z5H!hmQvFet6Sfx)SN~rUDC)5O1MkU-FA?m;>JjTC00#TJOz^!4W3U(NTa*!sAqHE@ z3A*PA4haN%u}(+x_na+Eu#$)#kk*e9UlTq;-c=8XguQrwzl;zp!Ee11eqzE;Hn=8@ zQ4s9K&ncQETxe-}=D|m3G4Ox&el*UXf0jOXdi9@&24&H#$)86xG1> z60?N~oQKgGLypL|ME2ryDkBs_47M;KeY5f6`%BIoVPd`}GWs+=Hs5PJ3-%qmiLggjJJyAOX=EV@C@$a~0I#xI8W8mfj{DjIHCuHmL$`0c#BzpG{ZCW`xtYPhAM;g;nZ zZbb~PSKdk1zxyvCh=yA#8g5yx;a0RbzULt!8g8j*xMjJ9ThW%dC5D7(xTT`umgO35 zMRX?koK(Xt6%Ds6*KjM^F1P%U5Dm9fG~BXW!>zbJOoZ1;G~80raLaNHw_?N*bv7+S zds*Il)|&ix4Mf8&6%Ds6*KjMmL~BjU&|VG+(Qr#e!!64-+={xGkoTS99P%+|mA-!6%UTPhlES+3z$)GJzRT88#=NQj18CK_&8uHjbH z#e}?Dt$)YwBUQsK6Aia4*KjN9l`m*(8QRMsAsTL(Xt-s$hFeh=6Y^fT{@s7qKs4MU z(QwOh4L7ymPKn}>#=t$7-%#k^eJc?Sw@5VHvRuQh@Di;xEu&q9glM=$qT!b18g4~h zOvrCG^zZ(6kfPxhiH2L2Yq%Bl@?0AdqTv>ahFg|vxD|CVA-}rNzx$D4@&TiwsxK?E zGY(V@H;sWePk0;*iB@lJA8os!GTXyzxD|CVA-@dNzhmT+U#0BWG1@`e?sHzltr%Z< z+zkoQaH|mww=CCiE9zpx#$b%7s^L~68g5yx;a1E5JTrs@rUKD$%W@4jje)wD;89yO z-1Zd>w=CCiD`qmD;X*<*-0DTcEz33BiWp4rsI3}q`0ja@Yq%+a-%*RIk=~o=#SQUY zHT}E)m9c2J;oIt2uHjaAiPoByxA<=35+eV8dzNds6?HKozYNpA`!8mRh8w;SpXC~E zMZKc6rsWn0DXt-s$hFep;!+ea@Cv1Y> zC=wwWZn0>%Wx0l1VG(sUr9sHA#PsieEIIb__OWQVWx0l1;U!vYTEFWcYq%+a-^z%pk;Z^RxBPNa|L%X&l7AyU%Qf5z zFVR}lGE~4rLNwfB(QwOh4Y#5$CgfL?`gi{;O3`qOMZ+!2HQb7NMQcsV3p%gC?=G2; zukVY7Tb66M6&5Dsx1{=a8Fr)=(Qu1J!!64-+=_ZdYfZ~f&i}O`Bt*k477e#7*KjN9 zV#1Efe~m;m++xvi%W@63qF&Kj)AG%I*T>gFwI)x9hFdHeZdtD3R#=#@tBX-dHQZv+ zaLaNHx1wHAWYcoDDI4Iowpx=Xa-D`O*KjK=Oz>!@8g7wjxMjJ9n-chinIYg&eebV%eHJXx;crZG?#6V{{rH-1IK4LUzruHjbHD_Uz> zhK6)VmuHmLJP!|(6GWcK7iH2J&8g5yx;a1cuT5DRq;G<>uRjbzI3DIziMZ+!2 zHQWjd6E?#6U(Sk#TPzxGS+3z$)GJzRT81inNQj18EE;ZEuHmLJP!|(6Qv2WCiH2J& z8g5yx;a1cuT5DQ{x_n58hFdHeZdtD3rZG?#6E@@cUoVS>TPzxGS+3z$)GJzRT7G!W z7x=xi*5nD%aEnF5Ez33B3JVi9*ZN;Fi-ub)8g5yx;a1cuifmer+UReewI)yGIzL&i z;Z|6f;L%Ps+-gL_Ez33Bv|g+&MV(E{cMtm)zWA;+`CsIUh8wiDvRuQh@M`y*--m(b zeMsbbURkc;R@B9WWqtTftZKMH6Di9z+%yL26|FTbuQ_L7Lr92*TO=B8S+3!xF;Ev1 zmc9DlsEUSLBpPm6uHjbHD_Uz>etgl}_=U9AB#1KWcEZ1;T0y_nwET%C& zfA=kX9l!W{NU)bEvNc19hFgtjxMjJ9TTvGi;m$;^+o$*3R_?eTqGY8pa5v?PCt6d{ zuAmL5?TWobYfTBX#E=jTw|dcV%W@63qAn&ZL&g3iPoCNz^oP$qT!Z`hFg|vxaparE+%Ye!nbzOa7#tQEz33B zih4zBP0MKQAt4%Wsc5)mxrUp@KwV7Oo{aBl4t-7?+u2LB)|9|(5E7!{mWhU2mTR~bbul5o6W71{IZ8C#vRxKd zX1Ru2QLkvNX&JLxNQj18CK_&8uHjbH#f0sC_}N)B+%nN{%W@63qF&Kj(=uk~kPr>G zOf=lGT*FOcpe`nCPsV2%qT!Z_hFg|vxE1w^)|!@)WrT!ixMiZ@mgO358UuAP!M)i* z!z~jHw=CCiE9wTFuZ zn$xb8U)PF;TP7NAS+3z$c!}1Uma%pY3DI!NM8hr1HQe;5P!|(+&x`drG}d)}&R(Lm zrZKPw5E8kLyY2z7g$ZlB#XbYH;&q>ay+mtGV_;_@Byv4^-OFGL6V}s;wE^^y=`2|Fsk zN)-*aOf=lGT*IxXSG3l&j8$q#h=yAx8g5yx;ifTA7ZY}M{c2k@+%nN{%W@63qTWA0 z?_*%K9TK_5x~|XJ!UT_%k^!7|l73_2`m4W*_z53B`I``JrcdIQ9D%*QoJfqYr+V;0 z8D1e#d4MV+xL0~NL~LPV_M@9V+4|@Cu0?&ls;UR{wMNh%HQ9`%Wv3G4H4iq?VjWjIes)g)+QC zV#r@6XpE@q*)?oo;_tWm7#;UOYtMV+4|@Cu2OztDT0?7!{g zlr2oWd7W=p73m6zQA$|7@Io10Au*+5j9#mg7C)1+g^6Sv-#^@1byWc*( zKw^{oCGUAAvU#ug?j+HR>ast%hcF-i%m7hWjCDez3@UAULi5^hPUyKSMp7-kr`W<7?ka( zG46l7PGXc2Rxi9zhF3@&`L$OvyW+}oGPW>r%aauvW4#TYmKddk)eA3_;T00A=c?XB zvizruGPW?W!3(=-j9I<$Tm4eP>V+4|@Cu0&w)nSd>Ro@yr5Rh8s9Cv(#;DYfC9Ga}aT)K)_@ml=i+@9J!rdU}!F4h5bKkw`TIEDy zgw+c#lyR*>V%O)qPQwRsKiI;=$bqe{n;oJfqYdf|mKyh0*9#A^>6CgT-bn7Ht>-)Rg#Cgwz9gw+c#l;IT;GK%VX zVBBR36HC4t?9W5T_MFg>y3|YKiC0L-Y@jhPf3O8*BbNVlh{o`9R8AyDuouek3JICj zGzR8DwxDdpdEfi@@BCbw6NwS*g)+QCLS|=;f%%**C>xQiI9$)e=L|Wa89=EQ2+bJ+ zLb42vfxLw4LfMEt#tzjOKKIFq#0d668D1eF*^qwgPn&6yLr z9xU|&0k4pdRjS6oDwQoL8^Q0{>be$$u4_xZK;XTckifVuK!*R3FKK8S9ksuHxkJk! zculSDM&KRc!b{%3FX*xuiN#pbuq!cIgG(x@_Q_eap9jfEEyR%2G_*| zk4j+-_LAR~X^eaRutCWP$1%7rCU|rWW3ZR}K2Bpi(`EgVk(y(0T}<#S5yoII`JJD} znETeR4P}I2d5@ymiwU0Xf*6jyiCc`nfE+#mO3S+RB{0>%Qd^hULhB87he?Qp51ZRU` z4EB=W^J9=V1)?lHXTrj5b3* zEXnja2G_*|uQI|I>?OYw*BDv!e#wf3V{lze@MdR7suebnBY}k z7=yj!cl#RS(ds27D@cyPbuq!K*DwZq$@d2|#>%4>m8^t02G_*|ufoF^>?Pk(&=@y= z@^;CJo?~!bOz>_(7=yj!dk`Aq$FCQb>`ZVBu8RrY6$xS_>?Pl|&=_BhTi8%W2!oV`7V;iz}VhA!4@X?=|C8Rz2y5&8Uu4w^8{O% z;HMm64EB=mRA~&%wapW3VS=C5gfZAlzPF_@G-n8&6?w+5Shy}G_^DGEgT3UtVHyLu zPxAy@nBb>pVGQkty#jcg$aJzAI4xW`Cg;Oz?!pJ!m))3UWJD-*h{`UsWGs2E+Yi<^Eq3X z;5`Rbip8D}v}K_&qHl8Goiuxs2k(xdEV`Vk$K;$S#p*86z{$%}wlEf(3DLgIi$12x8D=k1iSg$Yrm(HLG2bf+B#WMBTibDtLSO(*u^cgI3P z6ruIZU;Uz6#ug?}#(DVn^mml+m*A$qEZ?SL3ln&cRPUf$(I9Vfln^*`)WvU`hQzZk z_@~Hib{(9tg$dCW(imPlRg}iF*&S=EMQL0K#K0S|{2ppZoP2dVJ@cst9+9zy36yaj z{=HYx4c9Z@sJ1p^3ln%J6@-6_wUoe7p)P)NH6-3#vrwNqFO;vOv4sh|lZqJrE!I*3 zF%X^KTn!0P8rK-2G@h}A2~mmC7*L5)1^aZ4yrC!x_DUcIqVxNyAt4I(h~Y%RK4S|L zDC0c*d-|7k@=vPYk?-8Gg$cZ~4Z^?WT}t4nP#3@19TLyn+)mGY#Mn!q+*{PeglKT- z-@S_O<)fF@e|YQOecqHW{IM6m*&PzYzk3o-!`;x96QJi+)WrnKI1m3Oxi}~OzXY0L zg@p;cb>BRJGe=$gZhlCtzxqjiwtcu96R9oH={(?=eC` zu5Kjf;c#`?!UW1qcTjq53V?sOYm)bt zu5O1I3Ho`d7wScS42dh{YoR!*W%3n4wxDc8_)CkNNQ_`Fl+hnUVuXAx6fsswKW7Wd zMufi@$%(`W_Cgu`F(hu6uZ1E8dM#T}HX{7x%S~6!j{0r1bKhw)GO(BE_9=nUAS5pA zbbNIG(KpX|MS3k;nBe>GT<@`WMHLVHt?v~wGO!nD92I(SNJu}|^T5c!mQn(=9~nr& z9x9buFR~2$iV9xHGQwX}<$Cl9vJCbT1xY1x%}LEy{QK>jbsrvgdo=Dd?u}JSpbx^r zMEJ|FJ3E}HEwObQ$ug*3c;Tp!4TMCse3Kk^aKOyA8C#eLf8mxBi4j&Wyii6i5)zU# zXbj{GY+)k&rJm#^@y7A!KFCYhOEfMu26B;*=p^3}PBy=N_Dhm8u!RZk^Ue)_Zr}K} z_x{-TCCN+J3pCCH`9nxZmZ9f?yo4>K1ZY2&{C3{BxX-|ueK+3m+Ok$+cT;ptH6B#$ zoI6pzPyMUAe9i*NUb+47Z|y?j;UO2r5BJ@&?}$4_rfgvXzcR&9`8SvMm2a!dEl-BZ zcOXl>a8&RLiQD8$>1ZWSJY12o#eTgC0>73;4F3jpP9#QHz4n`0c!k6#@)dK$7&B*B zJzJQ-uYM6j+~oh}L}CPDpkDrM@Hz?i$(&&|Y+=G;`#0h(h7pK?=yp`_3W@3YwYvP_ ziij;t*fsQT_UA-m1Y)3GySnfSiAUw0<6515$H<5+Ojuj++Vq{JC02jYqfh@GuZ`Hk zgpFhVHx0e>R&t?yIkMCXM+mQwpfNFGi?uNjHuCx3X5>U7Yc(aTUTgXA3WJS^LC2a!i0@uP||j8n2ftE5AEEi zeoloFh=F=-e8e{yLPFMR8bj7P2A*malBp6zWW?>M9dZ@EZ6d1bjb6>MDj$9 zq4!*l#IiGZg#_hrFOjzdR zzoe7riHYQidQ?`g<#X@~iE$l$Mz%t9e%Qi5nEm@Q1$+Q)x;XScJKVpWv9ESgBAUN}N{g#^6i zKlzu$Y_Sy*2wTJX7;yFfdBW?h~JbunQpOMm81j9ps)_7!{gnJ4GL zUbbSz)eQ-`x~UwM!_{RA6DVUo_jfSg%W$&$5!;Rj`iJd=plrJozDLpShZ3mEyikT$ z39(jpKio6Yqu7G75w=U=d(v2xzk8J)8qpLB0 zu$S%0Va^DN?gl-8*7AL7+Yv_2V0*pDMQrERXBh|k z9pR))TgglE-DUGaz3?g_{Eo2eELjFyP&UH$WPO%#aK49Z1bd+juaJro*?w%=_cL&mQt;e`y@ zeo^UjYRQnbT_HneFVPTJ0$FiL?EUch*_+EZ?t^@nElk++1fL;S%p0dMkW-g>;i%vh z5|Z!gc_80q3(7`t>nWaQXog(s1p;j>B=V;jnjy0VWh1z~6*2UQiFsk4!Qx?G!;ThZ z=ep%*-cHuF>}6LWS7>U@6%w-M z)T@g%CtH}X)>Euf^$r?=>w|jXg)+QCLe_&C18YvUFcJQGIVW_LTIz)uGL$v0lh9Qv zTTnK_Vi&7aJrAr>OT9qADAOO7d~tPZb078)ZT9gy|4e+pdTM>=Gi$SH*Q_7xo?HIlcg&d>`Qg+k9$TB; ze&3?hvT*FTTGsEM-7qnG+}vo$=-O;v#gnP6Sg_Y)>mC1`i-{rgTf~1nwlKIfHpNbJ`!jus2i`Nh={=k1(dhs4VFr=~S>=Epp+ zDB=u>=ctf)cHG?bU^(+wE1ryauH|tzB;Gvc=k(0swb{VQTj+R&v&E=p_uTI-@U{9| zzx6X*tF0H#l)SgeVl4)vGq*AMh4lOuN^E%F@_o7OG940ViFS4QNH_-5&TVw{=jl^t z)Mme)a(cuT9tUmY!-y(-`pZ8`H#)sGt3767#Pcf?T$B6?d!NZelNkNfV= zBF=sI{)fb>+h(M*kFU*kJ8wb6ZHeiS_;fm$yv#RUckEqRBpVlH+M=`-QIX8FhvU;?V&sI3isnJT1JM%e(#Bpa=*C0kK ziNO|LfATufIXRCSI}cvhGQl+=n|2OIwdCg(!J3oTh9M#6QDf)9>vN755^@J4yMsKc zF&z>z!bLX1vBk!A3(k9(z+@D2-)!6DIg+bI#w zd{b%d9G&Tqka0J%ahEMN;~+z}naJn6($6F7=e*a)1lJ@QBUeAA=Yf9Cb@5dQi3Q6) ziZ+%J?wX?~hGSy>+z4wC-pkZcG_p~Y_g;BdHH>ldrHl1ijg=9O>*8|?2^mF|z$nUl z$Q&;uWR8k#j^g>1>5z~)O6POTQ8u3=-{F}$BrF5K9L3KKm<|bK0G2JW#f}h}ti|*B z?mPK;Y(9AleJX>I0ogVaT$6K;=jXBi!kP74mmQVQae2mB|LV`9Suzj)bjs=HkV#~Kh zq?L>pqD#fp)LI6fB67Si#%Spu%Vi#%H2Q(m`ULVerbFU7=^vL!jPdtpsr3mwqqDx^ z-#p@@nk{3=Gcpezc;154#t&qZOouUck&yv0TJ&6&+Gv31@-|BNcYHX8WXO?a$Xu6= zkI0a1B=Ya#>?)(^(=rdP`R7lmjhy;M3OzsPn&b=Pj}OzMs=H}b%60J(hJ<9{HI{|5 z#pVxW;Wp0ur{OKmsIJ*Y=BPHOwFut*V1jFM?zNwn)!?4Lx5DWYceE1J#pe_fGDRgI z-ubyj@D7X3ef~`szPcx#UR{r)YAZ)&Gcu0dX0>ucj;h{{%4TGH-^Y$HJSw>#sof9D zMR3=c4hdPYq_$#Vi{)BqW0pDj79%Y&wU%gE7}_oqT$6K~OYVd7_^aG=%XjRJEu4pM zOMIL4{5s`o#`-!tfNv}N3q57QuIg5GJWroUYlC4wTu=0oC&VUIq9{j^;)ir zuR=(~lDA`4yYZNb;Rr|XZ(4rs-?Nl4F|{$#)&TmJ1rcG44JRztochJiQ&X;s&nYBi zOjH76qOAuo4syJZkl8?2UYHGRjbpnixP#@RsLTesj>2qU>m|$pwkq(k;(|gK(M8h2wGwhgS{@B)~&y3BB7>$ z2x6Fp3GM~Xz4z-h)hp^Yurr?5_Q#XB{8_4&v6kgt5b71l+^1goQ%fylZOGS9R6`G$ zUZ^O^EL?cWJg8+n?F)%UQQCO+w#sbS)0IKHVuG)_bF7KPb#Xi9qm>!wuzk{v`idsfQKE^o@uaSJ!dsj<6Oym!-~ArIo2Q?YULl%Ddp*%LW-lHkLV`7s z*uq43KL&^?LXrO62-DM2MnJYKl7C zN|=zGQ3=1U74?YJ)FaqS)FU)Tt~Wu%!=i~aRCHzD+qNCvH7G1hNG7X)_fO(#lBMYg z(M0MrzHQ82qJp6@a@`CfSQClsVnXt3CH%UUHIdj$)I2msuKz&zEL+k7y#TFPcb8y3dQaE+%9xqJ)2TcV64deeV*ro4-6&8H`ul zqj-$bVI(0%9jz;WE?<;G;;xS$u4yT%JHS9!cJ2dFoEjpEQ@3o|8Bg4cdL`f0GWvE%i1t}T+Gj;wOo*zP{vCbZInh3gNc*g) zSMqBuqi=_VXrD!-eOA=Pgs7V7-_hrtYY-)x22m2|Fr;nF7A8caObPU0=UDBAy(FjB zqrzwq60E4h7A8caOkSPO*gv`3kkhz}Kzi-H+~F;#TsV zZKztYm#jrJ2A)lX1S@B;g$elzwZ_2LtwVJ#_LB97#=w)GkYKeNwlE>zs@53zx^<|i z!xkpw%hO8WTh-37Y7cwK8b^-``+gz8%0O&kLcTn$G4QQw=U9D+y<|KxDvg?KwWJs{$6kC{( zFIsC1Xat0+R_tXh2J708V3ioQFd-TN8Uv~V&an~=TbPh9{wo2E0C@^PYB%gcIK(dMY{G(Tkv6Y|A> zjRB1S=X#3zP(M*!IC=Oy>`Z9uL%lY3VYekDzFplqhN8}&yM2|fZm96tZ>9$md{~VH6%opq)<^}3lpMBqA{Sy z;~XnBv6tng*iQ}#R)b;-6QakXF`(cRDo(M52~pQk0(w01G^5}2nk#c%WcIR*9J|gT zA*ww!rrN_6CPcMIV?ZCt=|56Y(z}-bIjI& zjpv^N$ki=0k=RSrxs=G&xrjJ5*F>7Lr6@w>dl{&U2|hySdh9u?e!gfT9k)@hjJ-t9 zNn_w1goLO;)sq@jaebHw&s?ntJi5w7%}9@==2{8O(gabg*+uN z;@Aq=6Re5E7A9=n?wDSv6tv;X^dRyPmjtIcZ(*HX#;XyOxXSd`oD9c=arhC z7ki1Gm&V8yz%+&@juB0yYSBch9NrnfGA%4j*v^Z8>TtAZBFzv@q-j@n&e%(I$uvf; zWTrKFf;Ex2E+)8zhMGw1CHiU_BUfb87--X~;g*_)8`s4Ix9Lz5NuIuHUC59`u})(k z-;rmY`ggxuFPTiCiNs!_cc(eUTNCQO^Y55B?Q}z=5L5-0s7HUnNI8Zc^x{4;!$^GZy zDRN<9!ggMeqsZGkq>02{qNAuWa^*#>$rG%J#C0*jy;)YmqKULnG?Bi3XGO|hq6eul zas^3^;h$iM=457?lUx@Q-2a{HHMV_LDVj+4{5&t>{Up)h)fl;Qug36uOQQ9gnbt3R zi8`hQjL+THS3vsf;Ex2E+(v}`M11f1zBh!v6twjYK&ZARbzO9HIcY3CglAIC9pO` zPTi!5#9pHNsxfkka>HHIfx6N&3$!mgozy2zSH>?L}_8Y5RA))<~(O(d?12_7rudg;GJ-i32c zzU8a+=HGSJGQR7~dw|{_&xuM2_L46ID~)dohlG5kxv=p5zI^Xl|Bl!Jk+2s(U1*kY zY++(uPy76N@UingW!ZTo`I#r|#k-DWgq)0z!4@XuTg-aq_+qo3c@cxXcsH_)C}OaM z3Hd^_#=zID!x-$vyOCu?5rZvE$QP|OM)3{o;yl=kcO%P)A_iNSkZ)6I415n;&!ZsZ zyUuFCH?Me{mv2gkL~&H?#dAp+QN&;i6Y`~NjZuE)?8Q${%7`KcTbPiqjcbhZJIG%A z6sU|SVz7k?`5wB)C~t}E#ZR-!h$04CnBe{|&eA!oN3j<_l`A6v>FC22CV0d^2>eqb zk+1LR8RDycy!$0z{?otXi-O+W2=?OLuQH;D!4@Xu3x*m4Uq%dLuov%sl@Ub@wlE=I zV$>M;!ebbNy?FPlj3{ETg$enhq{hIPDm8`?PQFjA7F=DPapc?B`geTiP>ICuAbar) z*F3=%CgdC68Ux=s3}dht&(zHmY+*vaRjx7cox>nT!d{$llo5jYw#ybK{vXQD1YWP{ z`uj%`GYQpHNHkFiF{K%vkU^f~CWclbh!`rgFVY$+rgBl#F{`4bQA4Y=MN3*#2NAi? z$$e1N7)p#qgpgA67{j}MYn^rWZ=dI0f4!f^-Mwpl_u6}(J*+*PedNw{wSjvMV;ii+ zo>L1^+F%J2a(BGiz&(et4c1~0u!SgXu!IS@17B_6p2OG%Yq2NWLXWbjh68|V=dk#Z6Qh|s@h)i#0Z9EsmN3D-9ZcZI2=;e)AFsvt$vjo8#k+DXL}`O1OvtU^TDlll zL|F{D4c6jaxfTKta-Ok-3Ax=|ZQ#~)(IXqI#k+DX1R%A+5+>x9cC~@q-(e!;gSB|S zu7v=kHdw-h+%~T^aEm=m1RJcy`*-4Y2) zn2@i0sEyWV&RV<|(k+p&gbDdtiP~tbyR5}~I^7ZpOPFBaE_#9)Yw_B23sKe*mN3EI zpxP)2u6?{e+)@)WuO+O-yS*($X@ez9$ag5TbWuY^Sq!)h*5cjX76OpAD3&lG-_uYV z_@;>{lMUA5{oxh@khNNhiwSOzu?^PZ{oxkEZ6qvVqWgBv65b8v9wSOs!dkqS+C9M% zCgjU5-IOkC@osOoM8Xm#xF3u1k+Bx<@U;+S>9T|g?)j4BjUK<3H;|HK-_MRpc^#ME zq2P7jlE|F!H!7foFjkslV(0Nss*PJ`AC$6$30`wbl7h&b@OYtxFxJ0gqVaR^Rd-{+v+S~g4b%~&0-@mCp=zgA&l8pOg#NbyV|(qs0X;QSi%IaSR_f6@OYtxFjj73;*BHpnP)fu=G+ELnBbKc=}Rhv#|tflvDOn4XPu?@ zcxAmlY&2NH1g{_^NtN(;p@lHktYYHwMf;=fWg)r6-V`53iM9s$wn{Ax4gbDUI~ZdloFz=~OeRUHgvSdlgfVxDiFxhz{g2tl9-Om;37(N9NtN(;p@lH! zfH5&-9lZfFd*}M2bCxi{UX+~duMi$Dv=D}O9}`zxI0L>U<;M5=GEMbDZ+9atG9xt>I#>_h=5WoG)a+WZ`{=Dc`2#*(99LD?{ z_L5}uQ%_F-_K@U*<6;%sfwO*+WCs+$%)ZLhn+O9UxK3IaV6TI@G?L%!i!CDBT4aS7D+7xAl zcFq!no!}KDZRa2|Cs+$%^d&JNy^q>Jf5j4no#2%)?XT2^6Rd?W`ox%!UQ}(M-(?BH zPVkDJ_Pc7s3D!aweS1vEXrMMQey{{#CwOI2#}BpP1ZyFTF)AixR8t!m2U&u!6TG{u zNuoJx7uYQTz zaDufEhVK&-;w`BS_*X1J*a=?0R{u(EIKf&7!-tCr@%q#T{6v-@>;$jFtDmSgoM0`4 z;fuzEc&};${w_-pc7pd4)ZbMbPOuij@Tp@$yl}MvFPtR^JHh)R>bI*6Cs+$%%nf2f zW)o@yvk8_U>;&)c==?)%IKf&7V~!IOGAmLWm=&=EVJCQ>O6O5(!wJ?x7<09lklCHu z!0e7C2s^?1Z8{%R8&0qm!kBZ$gv?Ua24<-&LD&i2H`IBp+Hiuk5XRg&CS} z3BpeB{-@5*)rJ$Sg)r6tV&ZRow^JLxmURY}AnXL6NK2A}$eds;gt3+p6EjAPP#cqE zy@VwQJHaRGlB6IqCs+$%tjWZLtm3E*tm3c)VJG;6psxF9SvkR42xDz2CS)~AZD2Ku zB?vpgCmnVDN^Lm7S_or}EGA@CO??Kes<8xNC-|(YuEVL%-~?+SjJ3X)nA79;YU5y8 zPh<(gPQ>?@6h!6(Yaxu2vM~XlM4SxGJ>T!bH{P7uIZak;+nZ1AjS-k$=f$B#MhHGJbJf#7qIP!$XH9h+^ocD7v9-Ql&NCt<3{YM#N#V|(3+3T^TAqE zzGuY1Efai`Rq671lr~tx#8I0Veea&diLH`g$w9|j`Rw-t{qAdQ!&8;9){fKcdEjZX zZHZogTAv3KEww}#tBG7oaZ`OdJ?C~3=uKM$73 z7mrm7Pq4*C=J{YP`3|!ZsC_L&m#Jbxz7(xAYJQw5mdH1&RSPYu#YUMb){-x2D{eb zS%0i1F8R$=m7tv;^Pb(~g`D@gb5s5MEnEL}K>-wf32SkQc2BT`iA!%DqBd6O^>?$8 zc`acrPJ6dRGGW=48dq)Czbv@D@5nOz$+)e$$;YkR)>VQs>A5OS&9ygCx}4fL=dAVQ z<#?N;y@@B-J;ABslypz9*1!~*; zTh3)P=$>E+6I|a)8@Yrs-ml~R!LIIAvu|ND!CJg47uiVomNfPmFlxIuphPAK(p0e) zdonEqvY-U-LGhj!r!caSaJ=l1wb&?A#aiqqwh*4Gge6R{C#$J)BIC64{$RKH$XJVa zEn5h;k+6h`mM54MrJHbi+0*CzX+E6DSc~T$Ekv0rmN0?w9JQqMGD;h)#q+2ZqO`#h zCNR#ck1GCyC`-1zUa=O>2U`e0sEO)XdR$DvGr-^BKR_?oU@e~4wh(~S21}TL{{S1M zf0cPYSc~W9EktR9B}~BkfQ`~GDQ&P8uQRj|r45!a0e=NH;MIt7D653Ec)g^B0HkHb z5+>l)z((YSE5Ta4?$bh)Hdw+0d?MH=y`{`k#ag_6)k2guSi%InDA<6nCCXG*ti|ha zEd(IVIZK#;uLT?MQDCC1y9sOYdSVL!NNuo$3HWfZ0iOsaf(_QS5p1v)ukW@HfYb&{n1IKrWhG-fOavRO#p~291R%A+5+>lIYCgmdf{9>*wRpX~ zg#e^BSi%H6S=fMg1{1*sYw^B83js)Nu!ISCnXplM$e9zY#rq#EL}`O1Ou&1EjmY2C zRIwKCzrD-{Yw=D~3sKr&2@~*YVFSLlD2L~fu@>*EwGeRc8WWtaxEp zhErP-nG>vqFv=$;YCG6>M(^KxL7gQCJHe%%Bn6Q9q)+S%H7@7k=+5`>-LR*)nGkvYLy2&3J_#MBGyY;Aq>qb9Hf zVJEmX%NGlc$eds;gwcP*#QT04_o~SqEJ4@_?v>36ZyS%wswb8H*By3 zVJEnEm75AH1ZyFT{yZiQe9g|*Znxgq4VED61dkH(9mNX4S_orYiivZE=(+H0|0i#2 zumoWzc(jwVQ5Ax<5cd5K^d&adc3hz6+q0=N|J&fW5O#t`?IfuZtc5V<biu=gQf&8`rvg)sb`nAr6k{aSN&+BQRSmLTi|dr@)=ZG~VhgfSEz9gvAVJCQXN9z@c%n8;)7)`Mq#!aUSPNma!I+R% zo1(1H&RK%66TI4{?Hokr1ZyFTIeAR{W|#hI;~?p;Sc0$;8k25Kh%a3tc5VfsF;vZO>JNt zWC_Af@M^S;&%)s9&NsoM0`4;rqmdcuQ&n{uN6Qc7k^~)W1?2POuij@Zn-Yygs!7KanK}JHfj( z>L;oVCs+$%_@Xf(-mBX9rue%oLD&i2by9y+I_c;qf=TTKH z5SXjQgv{>L24;6GLD&i2mDTy6=EDirLKt(-n2>p`+Q2N8B?vpgyURMSRU1yQ7Q&bb z$Hey*+PrqrX&v}RuHGYxyOsS$THJw*Fussz_aXm!_IGpi?c1NdSZ_CW2@~@5TP5)I z+ay_Y*a7(#e@e$5`|#`0eaL>ZE^aiAiC+)+4s0Z=^Y6IWuOp>o{Fe(4rU<20qrsJ46`1Wly=MTKLMa~i?5Jo=i2IURcwAsWzpB$UBgbCb-uFol1Dygax zNEPDZThn7={+%|P=)KA0oFz=i7k$+RzP2j2{J*+>e(S&)V;;ND2-v_q?R;x`OdNRb zTAK6OJMEscgb9R^54(;1%;olO-{O5{iWKyVa`%QiZtqp7oeGXt}-H_xhd( z>uu~F7ZbQa9e=mG)vE+-z&hWv9ut@R_|}G0_U!V@4$oP_gnYkPZQx6|N%G4Rf7h6o z-#upk%Z^q8Hej9aS&xafBd&yvGK9&S4`%JFjXXUTCrHB-wGfz1z3)j2Tg? zpydRAb)_USCs+$%w8xluWVyYg_?WbFmLTi|e|05E3L{xWUu{Ado&~~a zH>H=MwFF)UYh^z)0-i-oJiO%r>D9NUV|RPx_2_F*Oz;<+O6;4e5ONkL>zc)ZX;7~Vikh|i#91)qT>Oz?M}l0^KHbd_}0 zSokHZC0_xzlD6-LYw4QLFlf!;X}0z+Z@ou+29ApfZu3cU!0p?lmp^;rxO>DeVJ*^}W%=ICr9oBrWBnku9Ob(g=j z7893WWpkXH<_u}Dgb92N4mRw&00ogb0UNN+-;9fim#?(B+Tru|!?(%HxR}6K?O;QC z+s-5@h|CGtfOY=%U6(}i^1S^fu!IS>ZC`e98&1Fmtb3}U6%)TI%IfqvL+UJH!pqRU zH&GCo6R?4Jy>y`!6MvFtE~!Wkx#HkDOPKJw(0H|{l+|FViDOv!eKlJlLVPn`eGpT};}XL+3^On7f+-%435{jL;lw(cXZs|}$CcGcBFAx_*<^*gYUhf~F6%&_ApNMC^(=lI5S;B<(W4)hSO>(}U^t&tW zI(Tfyydg@!2IBSp5nou137M;@4VkN@EMdZXJNsJm@-?haeC^4xDNC4eFUr0lT@aZQ zNEPDp9u-Xy`uQGxq^x!n8$W)2m0R5gQiYVbKLr zXzSO;$jmEc2@~!);akr-yMup~iJusKN!k55XvM^_1I;5_+Vh7gOPFv^AK$D_l7h&b zKt2$!`*YBWiU0oGW)s;FC#Ni7!e<%(+z~cTSbp<_9k-o5HeKB`u022s`1c6xN~&B6EVZ5QbJvU@ZeV zM{Q>b!cO>_gS8Kt6*Y=kkrJ-u>l$dOF>%i(*NY0BuiD`t}?-N8j$Nb?DoD6%S!wVJk-i5IP!EwGc0~Vgl=M zuz{YMB?vp=>t(15Nh0G%e&0p2#$fzlEnkzvm=P22oNX(2bs0ZcQYB!|Yz&YU;eTJ3 zjvfE->vdl@hR@(@z3@eR<<`864qFk9_EIgT7;8iiz4T1$-I`eyc95(jfwG6x{F^}Wh~~LEMdY+-Dauu z1RGT?Y+BU(Lo|G`$w znK<}`+4b~@8Tl`-d7|N7IM!R;>$kldCT=~pS)V#l1i>&NJ_rm^d)4KPklEyWg#|N6-Fs zOe}kDc4LC%eDB{sQD+Z{$EcW?e{8d{v*i4NAvf1~tmS?;CLY=Qlg42O%*eMtdmZhs zkX!U>{>*J{fy?U8+xEy&R_i`?z4*OB;xz`nGuJWMalfyp5-VM^WE-x#OveOjqL(hG zgl#Y_-(EiV)yCfrosoYw^AMSbgj8`q=sh2LRQdk-k{27R95N$6Z?9A9Jiao)G0EwK z@$WW%C^>I_f0FjQC@aL}{iBT;!FH1T;zv&^am0|>bsjm{UTov8rS~?TpDDFu*6-{5 z)R>NmBhLL>1JC1{Yx6q$KK%S+;`Pg~YTUZ-jC|8$7S_2gF&z_|uXm2-V~vrE>+DB! zt&9n&?G3N(Eb*QJ{;u~J=7n!QV{qfI-WpBIVB$xJRdx-WrAaZH=QI%)l;AJjOLs?H;f6% z#{|y@&(GOjOvn?g`xE3|jp>+>9?+V7nD2||pP+RoOQjtS{^>)!9O#77)>$UYL8zboy$?(Lk{`k3ID zl0@2h-P<|G#ibAv2QGQBzOwXiGxk0;?h}iBBg{p3EmM2Zy7!{I_R6cOv5kNK=t(WB zKGMT+T%4zvkX}@u2YOLnLuPw1A!AhC$0#0OnT`n=qjWsS80F(R{2d;tW5PWEj8VLA zz;sN&18{GNC7wcf$ZpU4-N%c3tbO)6x+{a80p2zf98;3qSma~7$FA?-xI9(n1iK?K`LveGF}DslJV*$uB5*hOS}v5i^MK92Z(}+pekSeX zWJ%RY*X9jx6WF8kwqm=8oT^);FS$*|!JUp-*zo=X-Xznpjiu5voFq239J#pRy#e;+ zy_c}l0&GJ(jwNH6+#83&i&^-;rnPCb!A`{x`}lB_K~98&e0 zi(hYWT%5v~5HEa!d*Lkc@dIAC_w%+J{+&a{Oz0A!7<4lzn?6gfK)xZ zG|?S*)DpzSd5Q@cqB0PVf6_Deami1lfVPt^T)I6E9n*nS^_Eomh>Wx|9ovvpb$F_L zME3JOp2C=r=h5)z;l2o-8q+Z$GnR(WSXkn|7V4OLPF7>2CN{h#x)+AJ%LK=iBv;+I zUjwy$t~_)1cl^W_@?mv}%W7ls;Xw41y35v?j%~<1s^Rk}mbhPv_UK-wwJvG34R5vX zv7((b!7(L?v|3FSS}n)Lr4SQ;62E;_>96kC>(sc1qw|~YU)woL=@T2?C;A)!eV=>! zcH)!EDi^;UwPfg!*$s}1^Ax8_`b70b(I@(R0R14_iwPMGbmoQ8z~?x=s)8rj+Kb9) zpz|n<20mZH2;j3K8)Y~jKJ&u7mS8A(!Q;YSM6BE*|vqqoM0`tA$e*g5ItY+D;~#745T)kfy2Vl5lh+Hr=Z zm2eyKJCqd@Tq2^RKlTKzcW%cCs%>p7X-8kOEyrZ)WvcWfm}%LF(~h%ht%P8$WyJ)S zh}tL#>(ARU0&HtDAq#h(D%P@*tR17z7fclsTq1F*Y|d#px6#1LttC~SkBqf!p83C| ziU}@}N~(01#Ojju^H#^YPZev~Xz;&0K_<9F;#65LYVFQ?QEQLgr;4>~WcXidI}&sy3JdctY5U+C{x8+USDNrw3X;GRZMV+#HsTB zLsp~OyeE=9;Z_@Es#we0wyf5*5?!ZCcf;GUf8NF=qNyrvcwdWDd9N+!8Cq>Pk+GKd zgIy9`riuwJkvLU8F5wCKIM`**%T%$Jj~QK-ZkMTIf=eV$m5<@5?d}b9SxZ8y^yGUx zcG=r}eC@I(c9|+BxJ2Sqxxa&+!9AxgTU41U)^cB@%U0WEs+iysiBsjiA^HsWGP~@3 z%2ctI`)ytJa9yT~2`-T&xnEX_Mjk#R-Rx@JSL;lYk3c z*khus&uF;k+#VGh#rz{(;ac5SQ>_z^N+yc0u3^h9=lpKj`57%aA9S_utEtv)+kDz4 zYh)V!&8nZa#bvdyU)p$9i0Sv}zM5(++5dw!Sz*!e)_Z(VA)b|0=Sh~|l}0JZIH=)OH~38K6>FC1YFF#Nno6oA8WU2w zsh2LNgl)v7TdXIhvYv=FtKN;)Qb{6yCi)84kPrdnTG@L`*buNublkBJv#J+ZOxjI_V) ztEm?1l8nwJ9TOX_cTPQ%d@LWK`)aDSN9PCd88nPq852_5>t5Sg;ynXuyNuLIqZP=x za9K~h3y!U zeYLWdc<G#`YtX2A$m){rqGg(hu|DYM^>b9?@lII_Mzm195#xtKTo^Xn!>R-06 zR>mbhiiVM=n3!?Mm=4%j!}it6RLPp95=fQ!5*mi>B$0e{cs^tlRteI}L~KLaTY{SS zsO_tjafz2vhGRnV(c$@!QD3$6d62!BkSEyiC&;}T(=j1ET*G@fmU!QeS}9|@+O|3- zb+_SlS3C=qptdu?F(t{#vipj49JFBZ0F<`&DDAxA?Ogl>m7r%}f@4Y&Y3Eph)OOBsaVf;ax9#LW z`Yqd6E9;f)v8X-tiQ?gC*m|O31yXxa@eNdh-ja#f#;{YK)Kq2C!*N`krHJ4^Urh_GaJyiGAlt5hmJdmfD*iLH6u|oXR_SKXaabk~&USnV{CN`D!@r;av%WYpx z3HWVZuRzB{alRy#^Cj3q#QR5h$lepda~7XldeJ}2IJo-Vy04}-_I|tPL?$>U z`Fg+&`!$Y}RQ39W?yD(*xV*nY3S&aN@DBIFS>oddyl@{^;GHMQqx+2M=p$p)NZVIa z8-4oqn#csllqA=Fw73J$yywfhucidz^3ec!iV2KSM+)((?W>hGeC&h0m^fj^mq}QODeK zvKmvI7SWpMUKr{w6C6{LeDj9=>c>l24UlK<{tlkA`&3q!I3Fvne@-2>WVX~@w$5~H zL*`L+pGUF8XA@|T?qyo*l2%*yR_h)sS}GG9Q+ZlMTP?@Mr4SR(iQnE+`m2j=UoG@- zg{P1H%KdBWSENs@d!OiY0Q6Vx>9_W9AB*3PvU)@MD~^lv6sJo1M4T_tKGEj`=m*(e zOvq?Z_tC)TI2bdSjtLnJQXdU`zJw9LXGJ#3@H6+B7v{CH_Nwhe8rejqV;jY(;!Mu( zcGx(GFYhI77B2VLB&H*aJ+@YYwQP0R#w#a^6Tf)Nw80V!8(|~okvLD^mL#nNYqhIZ zOvpQGSgT#NVuDV@VA=0n~9#Tgd05wwi3QS?Z>ry(|43D#;?t(cHEK-Gr40g5;8)du3S zun{)y%2!Ht&AOFft#;LliQ;XJOy1_ed-Q4paaq_18>x@Pn--FfR)V$KRVyZncYg2& z58k|28;HxoM%dUc&qLR&TM5>()ySAA-ucOJiw8?AY=n6O^3`!&NpB@st6jBXLf+2Q z=TY3Sq4_{ure%bU?MLFhGAXN8g0=e%o{io?|exvX=?)B|V%|{?ut6jBXLf)M0K+fgONt_T;8;HxoMwpLsB;Ixu8?6LuwX0T4 zAb$Io;oOqiKwK6!!n_){(Mqruhn6XqAV*58)2T4KXZCpwjfx`o=r^fT`w%Luo315dEG4tt%xvO-nEo3rI3{p| z0LlvE2TLq$gn4H^MiqpPIIUVXmc)d-qo_9I9Yx$Ir}@AbWnm-C8}zZZAn;aWL9mvM zi7_E>XQ~Z(JG1aCEiThC!hA;e844l`1Zzp@iq8-e;$^6f;w?IR9;KEM=4HC?QxJH! z5AWRx!CK~{#6)o?M*{zfB^EZq{8IPf=oXKHU@h~tVnVz=%?JEMmRQ&b^JK}h1fiZ~ ztCsnUF(KZo+JL{y5(^t)p0oME;jWiJu$KA0T@s1BcZYZ4^m#}s+bnE^+qTmXMXGS0 zOhK@g+{G#<&tih^#ld^2Y9nYF;bmwi-RNGNf?zE>YZ4R1Z9R#+If?gD)du47l1A9; z0#4Q?3El5g5ak&btz*!N397qz&r59tEj#t%wcSp-QQa*F*0NJCF(G$m>NA%+Gx2_u z+CW@h^AYw|Yv=C@A`67Y>#Y`AF(Ef#stvg_6K_bXji6PYFVer`ykC+OL>36vvQtRj zD;YtzS>b)>GA{40pyhp~oxdxHOzyub2#eSIM`*gEbr387*!A!ua8&IiU}HP@gBX}2wHaX%*S9m z6-Z-kL9mvcJc|jrol<=Uxz7?eI;aiA<>NWR?n~HN#e&EJVez_`0j-!I-v{?IsEwdi zp7GPaPx|h2QdZ>q6a;J8NkI3ajG#N{aHB&RmwQgoa^KF*Di%a0x7HPe#p_-lv|{2D zxp6U(pNHiZ50)_DJ}ORACP_hLfv_`)?!7`QCM5by{>e{skP9WAS% zRi4b%zgrtD2;2i%5Ugcw#b>WZ6f@xjHyg3U=e5xC*|zm1G;RL-XOPKIA4(ra0P+;6AQxP^;J%2#RT0S>{R9U>d>KqfpuQk8@`2F^jaRlq0 zR|$pPP=x1dc)c<9_k}O(xf~<1K(N-_PH4r%7Ejpx6SW6ENsN&W3lFXRp;r?;Cx9zWPxCB2nDaZVBVN^cZv7qkT@YCySZl6o#l*UA@1Qom z+<(KAB^EYf)DB-#8*BdhE%{v#Ss++zZYQ*2;_Y6e)dqgE#KK0bzfE7YvED{+%I|{6 z0>N5yJE0X5NDb;0QpXYt8}a3n`>Bmb7rrjP3nB{yYt8M1R!r<7&jB{Jmgm9}3mcIn z1JuSlfBLWdE{H4;tTngOw3zsh)F;?jto4f}2ph5DZ3ETDHS=DR-vyBcg0<#$LMtYI zd*Ur>W0bTLmRQ(`IlsewzgKl$^3kjEyCAYau-07FiivklKSOQ2BJG_e7B=GJ8#YlJ zFB}0I1(5}UwdQt0D<=LtVvyQcSNbiMSlEc)EZkgetT6yK3L*;xYt8M1R!qG4E%diZ zGD><=mRQ&b>CM!J+;=9w3nB{yYt8L6EhdVSH95{9+Za{XbI5j1rrz{($i@9W(&rba zEOMMfHqWxQfnW#7Y9C9Fv6A(GhA)6mvZ({G?&NI}TehxVh#jbvibI3M>tT(ZH zZ+rChrk_I&M6rLK;~cWho$F2PliO~1z3JzW15xbP=Gd>bRh)VgJG{11q&GB4ZijaU zqBtp=;~cWB!_=EN-DEq;^`@WS4McG=Gsih(n?cGuoN@xw&Nj#`g2g%HKoqC+a-2gp z?^WJ$mJ^?LW~ScsbI5@x&co$6hiragy@_*gcDk+J^mE98kaNg5d-t&p#%Lvz$53A#+_~Iwp#fnK@2o z+KjH=#92hEDU6%NWgMQaXqVgOv-Z#*8ZtKR@Gcdt1={e*&?q@(d z=eW2OVxoA{BFCE+EV1)f*2CEvx%GTvBis&Ctk7F;$ppugB*mK+Io`D3xHwNSQM}EO zqZhTE1{-l~7r=Yx(1T0AYwybF7{%i&)3J@>T^Svtd_2ck#3OY~xCap4m9a63>6j?q z+EQ-s(j&sNym#50lA$vcTB*mG#+|MDq z#GfF}+<8gcIppG8UygHq{si?LvYzV`@2oh7>@g)tapo?^Ib@ED^AzW!IM9BdSC>Zym!ae4m;57~R7@*FbGz2-QF>^&z=$}+(*m1k0OoJr-lIE67$ zybY*cI7@u|fEVuLik-|YPWWPJjH|zQJI`W&T$Ue z$0gWcdofX*j?Qs9+DBxho#~h;PDg91d_>mL)$>I*7m11DT(~|D_eJp3n2w3!%}JfH zu*7{W)G_y*%5%tm<6?1!zTQOLWrAZW&z|Qvd+z=YYNGo=ehxX*#NrHnjx+RZo$1&{ z@jj={qgdj8DcYlZndLcTygi_;);(6Vb0#<@J%_A5HQpZJxZD>-Da1ta-b9Y~CRpO0 zKKd*7ugi1DcsE1)MEBeE9CG35xAt(wdlNa{o8Y)OPi$NJM7*1!eWK3?(6_U_m?+*# z(b2%?I2bdSj)~%}6detGzJw9LXGMMvIXv^??HZle+B&X{YD~vA)KN^b9KZR@gpD{y z>In!CIEO4Mvd&;XN@O+y*y$DrSD)_U9x`O zPce3vD%P^m;D337OmKOJ@^bAaJiD+3NVcPFn?`(Z-W%n)a6FndDl~vnOlqia|H$RzI$wz5} z`zyCs+=QVv?EMc>F9}aOc5=NGY{#`?BlCQ)mY1~cpH_&{2B(S%PoeFMB28|?pL6S; zdBsNNgx9Oq9qR6`eKV5)h`GgJHRFh&JOO{95w3YHiXZ-V3+2L8(SEEPm<^4?_Sdpg4Ra6?AF}%&ZSEH z_W50#gL-@pk%3^X6OY>U3)l$OYn@fXQd>>ch!dwZH$D3$P1T?crZsO_$x;|%B0^Ke zT65>_*8KWWpF?QQLtM2^CPImj4J8^gcWU?Rn+y&2KFF9HJ#vOoS4t zrfRKz)0_KT@T{f;;cJgV?Xw!%QWLeTSnD6FPj6na`}5rsEvaH6lt?vI$oUHIKdtdX z>);2T>Dq>*2tTz>)`E=#|M>5&2?L@W);gI8B~nclYDtejKdJGeMBn-DQ(fE0%t)=1 zweURV4z)aWSrauMK~n2vB9urqRcKM){P1y232NV>2rJym6J#QkNYw`V+Wt>is*sZV z?+f9mwwI}5E%b>@M?{yYVj`4CHC5l-acY^{r*E42`DG<3t97#0x4*heS<)?~+hwYl z2qjWY)res`mo?+TGj{&`dZnpit>+f+T-M4jmMSJfiBwZH=l@M9ThYW{PWk*csHtMD zRiB$uw%{+8DkegSR8uwXoyld7^M^I2e13nWsba0ShEFMbyDye1CPIl6slqc?8%UM+ z&TlTA+f@Pr>ob(8VlC7$_c*>-s+b5RQcV@wfqO`3AKm&_WvW;U?a{rnFP17MLWxvU#U3mA zl5Ty`GF7aFzRNw?FP17MLWv~$qw_(rGgC$yoSOTx{M)Vw!;A61BP>7Jyyku#&+9h= z&BuXXd;fjk7HL-=ITNgfFqc9IgLwYhA&vX=TZh5BuM(j|m|!i0gI0~gApY^uIgM5H zWPFfRiBN7#uol8W%f=OZHXyc__g>G?6aGO`C8Fn160C)A(5g`wHgJQ7-OUjsRU*`B zCRhvMpjD$Vh~He-C%;zTxCoLe5o$gYtc7sU5Vc0nOsj>MH`UT%0sS=@AVuH004q7z|gIId+sS=^@VuH004q7z| zgSc+SjC|ZjxXmL-ss#6mfnY6!gI0~gu(7M$H?Z!fc(W=uwCu^2L{ii%wc%P-0=3d+$gtrA zYatx8tcI3EQnU}X;aXJ!t;=Stu;B!2Asn=V=zLL-zJnU|cAgL1QwQU{^8+zB$8pBi8LO5ty z4_*?<$oWI^4F}*hk07ZM7;$WN4;xOf7Q#WxMxv5Pig8eFxK@?GC~B(-u;B!2Asn=9 zL@kM=7|+#)YgGw&12(&d4JTL&;h<%nK}jTqU!pc#t4hGDu{8(SaDufE4q7~?79uJ9 zE4ATTRRZ3bt#QDH6Rd@B&@xZ0B$C2UR2!~UC3t>bdX`$Rmc@=^G^YQwc) z!^5a=@O^D11o?1+wGa+k6(afV9s5mqR&NXmk}45aLSVxQ)FG z^<>y^g0&D1TD$@c8yoL+aC+QFxXmL-ssyi7Cz%thg>cZSQ5ZJFlS##=RvWHWCBj<2 z0Pua3U@e4$7Vi$ghWK!)_|$5{wW>te5r7RRSPS8x#d`>_afRG`G5TcO<`E=Sf_EB{ z%n8;)IB3-<3>%U#sZ-`tyH;0(?dh1N5v=85-}ymICE@wdxq(Zn1WLiy8DXQyM+a*m z9JH)NO2VHwd6NJdXxzAsn>qnU{puE4ATTRRZ7{y`N03wrj5xMN3L8$a7Q#WxMxv7NaZt<3wW>mi6#bLs=Dnyb_yrFT_ zEk`0BZN3UDscKtv#?c#<%2`nh;WT2xyu_a1^OqhyZqqN_-Pqxp@1vHK z@mB4H)nPH=bG66@2-iYP9@a$p3{q_bNlb**;TabV9)JD*E9RG+x{ne;5);QR+PQhx z2RPgE!Mm5=`W0EHeqL|X30g>%(@0ey?l|k*vD132o$vXNjoYb>Ac=`3+w9z&-Us=3c&j;M&kyU=6j!aySDj%a5U?_8yJ7js zXOCAKK@t;ATdI7W8gT_lOoSC^VR&UbB3uhGdDv`x_pTlD)7KfKsS1)>sRiPD^QJV{ zd~=E9{FS9&8uy~CY(Hcx+ocvt*Vn0I0#?2|bl3diUVYU@h$|+Xwp97bHsT7BmJ!~JC?&ALM0g%I-+ICLK6@T5ul!!4He3rth&Mc&B)Ra~)y93}rbF_L*IcOi@VJ;j zxXUMq*@TvEvFfZ(aF@EC-qI%D)Tv!t;O@!g&70IWh_(T}4e)8?IF)!j6CdUU$_76G1CHC(C)!qSS_K!3Kws zb9h91r7pe`97evqs&q;~oT4^8Gtawe!6LbQ!Kc}dtPLXr;?O2J27W&|~ zd+V9IvP3LZMNgfw7Q$X`T!xma?n>7Q&|Zc~a?(+A#*PRp^g424T^(8&6aV;zp1ISp zt6bC1ezN1R{D3pYYpPre1nmM)80qqT1Eklrs)Uz_<=hF@LO5uJGPIl*BWFwLIsrPA z^r0smGZucyHMZ8L{tj0Ap#`sI?8=sNcpv3XLk8bxuMeha&Rq*c&@vyTB$C3D(Nwt> z69{`5CP}Zn_qa)NI^k4XNmVZuYpl?M_j1D2{y zf6}+Uf7{8LbJs$=L90e#VSKKpsdB9<5%xluU@e4$R*k|)m+!Hl++C|m_>+Zxv?~)4 zL915Q1tpUA&gZuXt?xudzd9kEPxASlX~6j1wEsx^T|!r4JW&XkbIU zzEtLe>XEq?h@e%YFbLoIL8@GB@u zJ>lv5&QBZG+u^H2>&I{Iu0A|c>m_2TdVPI? zVgg|=Lpe)&;7a2zmwlX3wvW?Bdn|1O`%W)>^;%ol1wzin(@$mYtf_J>#2d7#M6sKp zsdB9<;U!`@cY?JL4q7z|BUP6k*PhnCf3DhaEhZ55GK_Mrb2Z<)ffn-Qs|LO!WT~3J z%PHvw{eOX-pHd6qpjD$VQYHVB8iJo7>52&RS|?b`!^Nqv@;Pb5S&=H8JM$Cdus^4$ zCN{jrVTT7cP(HqDfHEw1m%MZvtc7sUvgc6}m~&zeQf;_amGDxxd^o{c2nQ{zS7BeR zsEKOBwU|ISJWc9-l<<8gXrWCM>q*+W$~~{FXi=JT*8+joWm?t-OCl*+ZAa_`Ysu4xK@?$60zsu1ZyE2w5)e6 zcl(l}r*0`-CqR1{Mt+Ir93y9OnqU0~><@v!$Z6};NLMk|YR+8(Ev7?Q03Xkla0v*E zOSW!oW;u@7xwOC4LS8SWRDj%f|iYsCBgfHrB;>jx?s$5`o_pcH#<;OiS0bKm@G{!MlB>R+R`l ze|Unl+ZPc*%RJ7oqgZ&anh)244Gw$lv9j`=IOGsMHFkJFco={860zsu1ZyE2v?>Jl zqcEFjDP1Q(dl{Cg(zhTW@jWPn!yXjxN1?2WnXo<&*V0tU-1*o(`c5^`G~3oxbw^-M z6?PPhnU~tY3=8qXM$obuSxNYOP;IzYl?Z!<$cMkj!deIiEt^^Td)v{jWvNvqd^gjc zAnjU4M9{LibI6D9rJ^>t7HoK!Ymcn&ZoK8VO=N!l?Y5J(tXvBO=4bvqLLEc8irJl( zl}ngF*#EBikpH-s;co-2C~xt582hK&$v^Cv+PnItUy{XI!wao02(rO(1tPu)+|s3~ z%J`cG{0)WfQx$8iQltuZ4zO*qAwiZf;o&0Zo{x;v%QvORF+sg3-Hf&P{`MBaZOHGC zDkk`bc~R0IE2~&CKyz-lZ?b}`V@eTYHLNKo-LBa%oBf!$+Hdw-6E8zUa zsbVeuhC&O`WvZCquRO%5VhMk5qQyq$`Cu*n3PuajWvZCqIvuBK(U*ovJNruWmA`$t z^TNN6)-c}M`_HCZX!r+5eOZ3PfTxPJj{N3k-4lRPplriVLwrTfH^=s%7i_TBrmu}q z8`Tsl0Z46ds+jo7W23sxhmhNe#Cw@lx(K5M+mF{ooY(+?9>>GzyZD5M5LuBb`OR8v zuR;JqK7?RNAf)}PZTljEXv&WfQrlHx-{1&@)M@>@eg6aMPH@hp?y45PMAAaIjf8DT z8&tx+#}Vv_vi?}AVyyv66g`86%f4M0FI|o+5YopeVc*Rl8xr)VmQ0jBShegcIvf)b z8EZ+KP{O{6(+weTkT4;wOKJPs4cSOIz0!-SmVJ*S#AN#ZJXlM5Z6)mM8r=|4s+j1u zmL!~B=~vW-eMP4m8yRa!-=&0o6Q>&@N);1a$CBjP&n~HNwA$!&i|q&N_XqEvvL3$t z-H98a5SH&3cm8zf7_rx{Y3~o;v&Vq?h%vSF#-EMQ@Ag4UzMkEQo1YMtuUvP2>G6@B zXMM|wKkV|W3EA|~Y42-C>392F3pZvVEZ?lI5S^1woiP9MTDsrgYbnRY#B&RVcmC+R zZsR|HSiOGTaii1On~sQxKlB*g`9$5ca8H$|Hc8grZG3&@k7{Y-rC}*+J@D7jozq5j zMU30xp!%LtR;!$~d6aV|xZINDkwf;cpRwoYbofo1r>ynj{#$o`ytdhhiC=#C^!mde z*3!rB9;#nnM0)WIn24Xpq-C?~9lMQA7hgX(Wl85%_+n+h=8Jo*(~0}95EGuPd?)Ll z*Vd;>&PV-yP|8}gbCcY1sn3!d5LBGjve*A z@2aKWyJY>8wT^4sMr};LXYJ0InA7*E`t+4Yr_ZjpR>~44a3dIO$d{remI>K2^@HxN zrGrlDld{&T>(|xBMf${Pdyk6=+yaKb%a@`hmOs6^T6)7j zYw5xVU#_#(e|KzC8?)YBqcbMPKiW6#(Q|bA)UbQ&EMWrol)=WS$Dn6DrcZ7Dl~YHj z7yPZ3a?9ZswZT=xI`==&TaA=aGrz~OOs6`kV z+{Vz$4r;ve*IN4IW1H)DEj?b`JBTn^a7@hm+Qp5%)*PKqdu4FS5+>^3!FM9910^#@0&j?eaY|p-B)J`6IcIs1GVw) zx6xl+koV0G-e7ck!&>+1S9?5O-2I6#dV`oa`=Ryo7n0HGT{qlTX9*MI4l^4gR)meG z-W-^pCZ#*z((Cl=Lmn^g6h&CRF5ejwm;P>0{>pu|beqS1UuOvu3-^MT*{`|IJLs>r z9yT;zRZ{g}ue0=fMIJBiWkvXcZC31ziA9Z}`AQGe(#yu2QD+Ggy?@kSZPf2xNq+Y{ zdRTter?vEr`EC0BD32Gnw<0X}$acoWaf^rL8$Vb}dw;E7X9*K0KEJ-&*y5aC@_Wd? zM&?UCsHMMK`GpBAVPe_oM*L!24>#bTktbTTbB~0u*%i71Bd9Mla)qRHMx5}t??d zwe+1oUEg2{6Tdpk+WD`pctvdN+J8`f(!;fMhdZuou$K1>as%pun3#8Y-+bTKYiY-z z`x-1^VzouqC+>Coi(+Hs$9?l{rK}D-;9mV&0cs!O^&U=cR$UMiZ@;@*zLK=4^S5}p z!4f8BuWEh!aW5_w8_zzxYW~lfj0Rs@)?h8~spUr61u-%4xL)}KQWKNA-)pdhi9haR zHul*XHjZES!$u#;`Q|6~%vsAv9J%RsK}@Xts}CBlKUqtMF6^1Jgo%&W_?q@5V|zU- zHa@OB)i_%GlH-T1m9v(QoN_nrf|%H7{*#R@p01_u9ko`@5+?rhvW?ECk9t~cOkOar z@x*^>>3Spj=d9)4fZQp(ASRaWGOsc7nOb_&f&FuqF!9>U=4D)Q{}W=P?@gC9?tHnH z?s?MSoFz=Gw(?NT`HfF35@O+yOB+ihA6p$hIA<;QmgIKh1u=2cphFsGOFl-Ow0X`F zCKh}J>t+3#%a49cY}~okL5;rRmppm?<~eJ**C+QOFNldH*H3DkB%|{_-yD{+go!t{ zF&jVG4>nfn?B96nC7Ip5G(2Z5_g>{5=>;)yz_k924WF;2&%8A}X9*K4pMllEe$C(R z_o&#o^dGl$pndH2%TYN?n7DTZtTXm&ezg2wLgd^2s^iQ9N2lvvGD^Q|i8hFoxZf`K zQ!j{#(TjHP_?C>$N1tEIS;E8_kD85FpN0+j$*z5&mX6zaw0<84HW07RKM-yq5+_)~ z#7UcBHL_pRY)I+Wy>xx9kEgcQ?N~|e*TggMRSM)UNu+e^Ub?LH;fYwMv=WVp@80mM z3A?;lOXq#Lre6l~vSNZ$m?R^zg;k|{*<)ZPlor;S;B;`WuPaLuQl&FuYQ2^K37QZ z!&+Zncbw(}Jx)yQz5b>3G0SRc?SR2KOPKIA8T2bjve(>8>R0`{mR@q^;GDJI`(SIe zfj%lGcHZlt`lZsteR|F2IZK$}8k!_;t$0X%H+kmg9K3nXTHC&2br*e9Oi1rj_uhvk zOmLl6PbPIw2Dgf%?!rSlYn|;iAMkf@6FB}3uSUMrc<8XyJsH-z;wY>-_G{L~dx?nw zV}_;&yjx5EyvAAjoj8w+3EVJ_zr#mKlJE2znr{49E&XiT*$vkE%SDsa2K=3vSo_m~ z>B6^VMt}8n`VBXaiwR%-fG?3GdoLWAZojCOF1hpi25ZecVWQfAzY`NXz0fz^Ts*P^ z+wRpb%fSZXV!~Hm;G-nTPyf_6J?HUSdc?T<8m#r+P+P@;zY`OWuC!YE2l2=Tp14fE zEC(BiiwSPcG84XIwe+zuqtiDZU)o@;S?^gphrbgOr?vM=7m6qI^LyUY?+L>OdIl!A z{maRkBl@N_nL+;UlY8sDp0wY7R#up2dRf`p($t0Pr%y=T-RFH3lB zil2xlv&S<1S~JQDaWR4K1>oKCjH%yWzW#!|C3v1~G>-3qxTIXJ7HZaeOiT}u4u$QbxUHI^T4wf+C zwlOyphhb?gy;SBO8^5t>2Wy?*ZZ~0#z;S4?lk&=7L=i0^o-wGet8H3--pECD|}Q2zy^15`?j@%Hc1||F7l) z@p{@@cVa6<7UF%i&B9knoF0a~3L*A9C6IUuod8{vf7Mi-wb|t6m0y3V4aEO@V5jE) zTOIE~&g|UzIIfwUOzif%-HTdDHk1gGnVnniGQF(rEjBVymw&O=36D-M+e!-|0Dj_B zG4Y!bdlWUMNEOsG5L`>F_tA4}+BU8IQ$CbnE$**Ek5RP|B;FHQ?}OI-*vU^w9qZbL z_fesLY#|gyK7s@`0)f{2&t8wmHiVkl8Omg4=c)g1kFpK6lx~LPfnY6!y@zWd1i(-H zJeYuO>rtt!l;E_Z=8qcnsHELm+71UGTqRKZrY(F-wNQ^=dd-LsQ?+zi3vI>X<#Maq z2yxBqj0sO+l|awn@uFYpHdUG-r3iVJ9%ajJ`KU=CsaQ(Doa_yXEZpbk`OA3PIBIv;vN3(pE*mI;Jy1K z`TiqE)nQ|D^LRPiH?xguds`UWx6{AddAKUUS~mLNTrd;;-l?VcU-U>vK6q4$lh*z= zG3=dt=q}BJCq1fX-NT#3gM}FMvqw4>2*FwidryRz0E+h#Mh;qk(T z_rWNuKx`!^sa`zw{Koh>8>@{Vi3z`pAW1eA;_lPVZ>%Q-$BXcJx9!}VKk_ksf`NEh za^CsZ>l)9lVei)lNlf_d1#)Uni19+aEd(E~ z2$GlxHzE8`h&QgD-#F$}+^ib35cUxVWfh1MWKHzn!|!h#KdG~~=U2S;0 zu;HU6@)3xC%DJeMPk67f&SkySMv%mW-ykCGLx?qxd9QK!FMFvCj~6y}|K^nDokQ(S z|3JJWPjK}!dge(vD)x>VZ*&llvN=1ly#+lY_(3_|E`DC zMv%mW-}{mz2MMvO5L@2;u-fo=VdMU@CpQn5yIx=;5KE=3Mvd*CuXy)7wGkvS5$==e zA!W5_O#l2LAvj)ye>-k+^UXKx#+yJ4mM6IS3LEAdo@Vbm2T4r$ojgf0T8OF1hWTI4 zz}-7R3t{*Ak&i&s->juWb{&!*vH0hjk06N&zqv=wmk9Bp5Klh)bG6~|!p1$zcWPdp z*xT!YxJ~v3e|-Gr`Q)65{Mh!}5banxr;7UfB5L-kq9z4yfKCb)P)*PnHeOZ*2Bg8zHWk z@cW%)k6wsJh4|_n{nduY3mXs3*{S)rZS_kM<&98D@_RXx(I$JG%|UbZ9vjch9Tk8>~D%x+|h(ZFsyO zuKMLp&D{>wuWr!oVrxome?)dg#WzV{J;c>Y*u7yyh{qJPJbdHD&uJU<+w5dzTT*qK zr0U6)rtACXL1MHM;dZgBg}7CS5w+ z=-=RY5k?)m{)NR_R)P47)b>9~`xw5_c4{L?Vgl{P-gkdQh{L3PO#Wz++VFT`!`H8n zS|X&?{y?|E1z0Wm^ zf37xyBqq?0+1u+|Nq=>(5H~&hbG6~|!Up;-tau_Hffysb=!epa_CC#S_zRMlK!0p+ zdT%Vm3?VwtxJGSwys&}3y-%MP)kYvzlJ>Elj2|!FHBa*qBr$<;#ok{3k392bGJd># z_dK=X@xlhisEg#jPvj#IhsdaQi;QY3-u1BB2$Gn<_-OCc?=8f>LQJ^(VYT7$!Uo1f ztO&zKAa;?_c|RG?ADgvUZ3Ib7V4Sy`pf3^PUsKl1zj4T7wc+u?2FCU!pO}q643x5( zEPlxg8-J)af+Qy3uh`q<&r4bTPW+PhhkmFwJYLvn+VU-rt8 z!yt(X_+9pf`~yOa65=!=I9`O|Yhf)MF$Lm5@%oMxKk=m@tE-J5i3#|R_U3(4h?RvH zvhnI_!{dbw_>8MwW^Wk>V$WrALT|+Vjf*GQ9i~AN6YzuW27zORSXKPpuL!~MBJ8W@ z$VVWKm!4sn`0WRrw!Y>gNMZv1yuE*Zx)4jnZ$Io*d}SL1m;)v zrvGRma+yc<5rX4I*jMXOR)N@BW_M#{KA4Z+Ol<^7O!%AZNwSR)8=uhLxLOE~7h%i| z*V$&7mQ^4UX&+n3y!L?ehN+Dpi3xv`U2cJrvReCzw#HpTaJ&d(?!4)FW+M>K%WV60 znV+xty%B07NMgd@eV21GGNYd>^YfQxj!+vOFKqZe1SGO;CKd<0^EJi)*3vsV2V-?e8R zBry@*yf4;d>ar%IHauR~*kaS&%6b)uVojzlYciUTAc+aT55mgo%0+GU>x#PT@xsPI zx9(Q9k3dY97Pa>A?RB&$tykrp_AwFenHVR;qbIf3cPrYU#|s<2H-(r2F!q1W8PUJ3x91@yu!G*GCq8iN^~Y$80yP?5_fGyVR>K|9)Nl4@I9CBr)MPdX#H2 zby<_q=i%|f#$WE9R`$DrI9Gb=b$>Cx{>quww+Bf~gquS46r%4n^XnHCeY?jC8@>~V zvI@k`GUEJwpr<}@O#gJdf0|DnBr)N4FD1!xA@&ktwh$aI!r#7gdg-?ZqF9qj zWlcu&5hO7Y?sQ7znV;Qb!}RTwY;NH3!iMh&qpSk)p3HGJ-EBy^gUncBNlf_dSxGWh z<~X%ohosxetcc@9cucQ7%6U{ER+3XloyTpSK7O9f)q*4@!mV7znoKHdGHS!)g$>`k zMQQ_azw`{p$!&=JJ11#Af+QyVF0>^1P>63#8kTNY%sD+?*yvf?qny_UqK}N6^Op@z z+l#q#ki>-Fg_a~=6JoXyFWzo*XO9;)MoizMoSz5cKQg2L^zu>Z$;BE#ki^8m@|L{C zLiG9NsPwR64Z!1t4d1m!Sq0)%S(%uAo~%_*v9*jKi3!|bXX_=ig;@FgTDr<-yX!iG z#|scH<9;0iZz)aX(jAlJtjC_5Bs_gVlv_!N!2ZqkKK2+wWT02 z8%`j9cJKLfLd+N9#!q+GwI!q-T3%Mz)%UV8;(00Em8EpgF4o9GTvk?2;5pe>T$dHZ z%wmm<_Wt#m`#M}8hDa^BR%*$C#adsG*fVzm_04XWUt5T)g?RgRTkFF!hZgdII_B$% zf%r^n`;O8+UR*G#jvNL_OrYJ^z4yhMOe$+Kb&eNd-%Iy4Xv96T!m?c2`Ox!i?KQ*| z6KMbTrP$Ae*!cL((@ToASC1Dq(B^%8HxQGg_jy5jpOs}r7}kR%CeXv#o%Ekc4|k{# zN6M-*$BXa@#W?`P6o}>Gi++8D4bvTpweTQ`3G~NyQ~p5dcMp?(chO0<7XJS!I}bQ3 zisX-vEO??sF`$B=fQO!_BniTMyah7?0-`4d)HNMu1qIWnC+4i@=@~#pPd#%2bl>bg z&xnek=!tkDW<)U&1i^p(s;B1tdS;);e?N!Yw^iS+?w+3R>YnKu%NI5<2HSpnnfO)i zkJDu~==-|c(=SVW0`rRd8tsol94W+|LU6uFV~(=t24y1NlgZ1TjJ8!-;uDx3UEKS4 zPbM#WGHS!}g$;XC0c}+#4wm`+Wtq?W{>43GDNB3;^Sq0ud$bU1g}5qy#$x%x2Ih8q zj#DPSmYTN_FXN~9Sy5Ty6Yy7Dbo`%$=qAKeAvj;8;rrP0s50@LT*3V(t;ntVyL;wU zmiPqxE*FhI-jm76o{WrgWi6!by$rNfnRr#azI((^d{Umo`4XRi|L7vue=EeC|9qKi z96!6Wd|?AVqdgxi6Bmp3I!XN9Mb+*ZWLe@9@Pl1!{ZT?J6MuJV{0!3ag$;YB1f?w# z!(}WPEq?npQ{1!EvcxCg&%21$@t#ah_GGlJEMM4w4{y(F%fwo_f~%f+FgGE7CR~>I z1lA=kp8o4X)I9xQZmZ_*nXu&x8(53jbLTR#k*tcg53k9+89&=DOMC+BD;M!U-jm76 zo{ZMR@`Vk1vkGlhCgMGrob1WyH7`qi0xL)t_Z-jYXP-SW_l6LhFVa{W+Is+H0wcp- z3k$i^;&%}`=U(L!dNPn6$n!4CbSvhTAnwqg0g2EX-ECLV6|KoP#x3BR2lzacbE-z3MIJa4>l znx^ON*tI?g#+AkoL1c=U2#sJZq@m>#2kfyxZOpv+_&iIHHsT-KA;QME(y-x(&J`1( z5v+wYw0xp?W|Ii@m_6~(JWG%^;=|oLtBp%LwU*y85gNf-NJGmfzTcyr+UWhpetDK4 zZN$)1w^tk2{~PhcVj?txwUCCEPmJx3U8o=!{O`VbmLP3J{_T!xW6JI=Wxug0vA6 z9zv9Yaix35HJ0Bo5gNf-NJGmfE}esKO$Nce+i#a+3DQQa9PVs9-?fq0h>6e$)j8$?;`p|OoT?T7Sho2iHSF;jqs#5POfDM(nd@h?QGm| z$QrScCRht;X!*ngleDeE{J}dGS%S0?&p+jC3|@lB6lsFBkcO5|e1EE5^YF=OR~A`< zv=OHbcl~P1TX8xwO|TZy(DI2XQ%=V92pj)WEV2Y?BbIe>_s7rUzY`m2g0+x_mQURN z{!waU@|HgoS%S0?vwFGveAt8~Vk1qk7Sho2iOZ&pQX9ARXce&pX(Ohe%S555z{A zU@fGf@%&uISL6Y@`X+;xuaRN_ESJ3uQMg2;P!gJvM^#GWw_uj8`l{+K9JLMI?-II@;-Y1wu!-v=#`Ai9R8tsM^4|%MzrG*nCr* z+aIT+wvM}M!wA+w8e_Xp$ZViCFn_QFX(JB3Y>?V;b5u-(Mz9vr(DDhH)zk*&L6#tG z#9p%z<3QF?I@iWTXas8^4K1IL*;#F1K4%HiMzmf~tu~y`5EG#htc5hRd_ueowE@3` zB}f}_{o{xxFiyQ1^-DmgCzI9!0pG_b#9LAu@UK{cv=Ms_9ildz4;K^ak)^djK+7k@ z>r)%>6Ip_^5l24kY&c&uCe*V`Yk`24Pl)%bHsJ5F1Zg8mZ#Wyyr;Z8rkkeWqpydyNY+2x$3) ztcuhIRz)m9+K7XSu3x#eT1@CVDy;KY6GiOmLP4!Uq5m8xm!EOgsyATS|Fh16SCS?8(3|#1Zg8CPIKdx+XILRU7x45 zKtRhUmTo>oZ5%H93@ky~h|;cZ+;w{yF%cTUT1Z37CpvYKd|8^sc&jX3td zZa#N=WHF)pS7|K}(DDh{Ra2h!+K64=bAE~2>x&89hf8aLfR;~u-{=9gahU8U zvIJ=(+&M_M&nW9!M}$VO7Sf1D;S)bK?j7Np%WrA38X3b8v%;M@FP}xnSc1RfWME8$ zMz9v0A0*<-yWN<0zzc^D?A3Fd0_GwyS&g(SRZ#txk?!wZ7OfL`OoT?T7Sho2iAVL@ zxUy&YV3!LxZyj? zax6jGh!eVPt2S!xT`j+3A~b@vkcO5|T%q5N#`S2KX9?0qtURrQ+Ia2hU*va8$n|gp zYatCSpIFmwu-@n0<$I-_eU{EAA8`D=Wm)|iF8o^pfL(3m7{QZLVZS6msW>mBjhJwFPqpFNO6s9I zEJm;v($Mk=Y26}hpmkY-v=LWa-&<|CYaSDNJ2}_VRV#$+z)Q0Q3 zF`@k`tpx&FJ|VqbZJ@Wa1Zg97E%s9z?jDQ@y+6`gAfV+Fa@Xp7j=Pp6NE^}nUwfzx zH+J}g1nh+bz8R2yzgjET?))XrWtGwE9V|z@5Mz9vr(DDhH4b%o^1C}6dMAPdAsSP(r#e~iuX)O@Y@(G#M)COiX zmLP4!t@8?M!_BoZq4Qu`3k0-$LS|>Rf!UcQNE`9bMb&D<`3y0k^Lbhe1hjlYybQGg zFM}mW8`0|7!D_?#J~5$wNm>g8w0uImCA9%>i6uxIF?_@jwc&iYm{9*Jtpx&FJ|SLT zd_B74Sc0?>e|yB)aK30vsGpeD0s$?b5bsrOzj}u z3D`is=FdUPC&;smSi*$)sDrx0Mw);PzP7WGCSU^+^TI8S z(Z><7rw^Yx;=Gu!HG^xbn84aV3A16V326C*w63jjB9<^=Yae&bV*)<464q9>DuR|z zNH0+v=vORZ!q#xE@5V%E1Z*H*Tirp+C#1Kl4e_ZXmM~#!QFjl<1bk{GU<3KuDivBj zA$M(Fu3{iQb;J@TY)$RPl9+%`tpsc!Ut4WM%O_|LAYuswIM!rktMdD2*UOr8v3YuI&|_(R)Gej>)amhUJwe%I8%VPwpNqXf-Ey$5U;!9+oc%I%`{B zCKmSU9sRc5l3bT}nkr#hAm~&p5nt}yE4t>`4fD5bv|RR0Y7$ABD4z^Ha?_sCf9E#N zzkAmjoH$JKMVd~vQoP@;r}mE8ztS>4>DC2Gm=*{+KT5==(|bm@w%R7&`VVzlDzly@ zaNfv8)1Er8S9H=#+vFFW`Mlb&d_mCpQH_A=h-3HZ9nERhIX~s~Ta_>^5Oh+Lh!aof z8GW$NPWdyxzeG!A*3(4!MCIs4y`!tH`BVPrKF6yK%NGQlqNKRIo1fDwS~aOh{@gR0 zs13_2O_Wa}Zgzf;=)rzH^D|y=uQn`S5Oj)?BKb}~rgt>=Z$0zR?tcg3EhSn=(|JWA zE}7Re8rOSw-0SjFjtblm;UWYx!CIDfCmCH%j-XN@VwRQ!T1eB$KrNLcW}V$LYI$bQ z{PW#5%vq`8bBP{NK3!KE^@?_A-aY@~B8@JVXu$@Z45XO3*T2;(>btIMey{H@RvVUA znkb)qyJmj(=!A=R$xrGzKF3-})2Th}S1uMW^+Y913k02yBjUfC$QSZvZJqCTN2H}P z>uI8V#_W+XJ);LMZAD&`C5R=H1vc`fdJ(`CI2N z*HW4FG*Ldy)$-(C(f%J)<&S+$qah~wf}oRVIx4vc!9U9g_saH5a!<@_nrAJf>C6`q zeUFu~r2WF&+}hUCf87X&ywXJZY}Tdidq?lKoSl0*(z9eqz98s4mX7T%Vsn!NdqpdL zo0i++;qBFi<&`GvtW*%(^jeSThx;GSb^2sGt%v0cg3e><92LirF3)O8m=*{+`9#EV zvwB9g*Y2IW`Czb1wkjDC?58@gL_9a{`2*~ zb4T=0!n8op86zSlogyB<%Toqk{I+` z_j&c{dy4-Y*GWrd*3*Q=ew7uy_&&$2ez17WFpXQA(g zhUJwe%JEZYiSM&v>p8_2o@%T0uzW#K>{tE1g&P^Zmyuyq=OxAFHZn+rFPtU?K~YwT z*r;2tsNJy}Mt^GR#w)X)Cd!dY&llh4#JP>5v+iD_W1{5?f}*TaWd1?o`|SI2%V^YX z3zRS|5ERdph}idu#P`ur)U2n8a!k+_;`_Yw(l*h6)1OxxmM;j3XG-5UxLtgojhc0q zFYDf_glU1G$e~2+FTT%i`|cEtTy}|;%B-h}a)i$|;`_WRUqpPm&+%%*@&!RrJ?Tp; zbI+D9<4x`n{p-voYQyqM6XnR5bI$7#E$P=Y`tkMlYQypcK~X*H%f$8K`?R{XXLND? z4)roj3k1c_BqH`?BJ+JLuZ9TsO%o5#zXp^hEC!)GF>$_6QGB0>wUDOxfI7CjuLQ-uPf>gywPAUs35(qq1n-FN zbK>-ei+g^uo!YQ`K~Q`^ouk~hglJY%!n8n8Bt9Zy-=`?PkCw`;rwNOaC-3_>-=`?P zkJ_+&K~N+zkQc94FHPEL}^vx!DRyf4HF5)qNL?2BxT z*QJR+OB{fABqqR?$F?eRUQF1x-R}7WHl_&ig%CZ*wJNgK$hNLj-FDod+9w{8=mc-e ziTG6u3PqMMVc!hwG#t-s9}@y+=&OWatO; zKHJZI(R0UhVdD`Ywh-dH$rFpL)w8p+anw&6RQtpw5-nm2i8Zmi#Q$Uo6ZU<@88cvG zun@n>SNOh>_@AtG+3k1>zHRBOA&shiVv)qjcuHzM?V0iyJ&_j^_65m~?eR>wwZzFl zY|gO~$CR};yBKf5w=F&WYNKkOm>}OyI7Z&x-Qb=Vk}rB9FD9=2VW9S_tGdF*y+Rx- z#E}xgm9^{}m$mOVs`iO75{2X#iAZw2#Fb?U6ZQ?z?&rcr4l{HYuPtI54^Xk+9&$l z-8jEmV#+)>enpWbOxSlu-<}H_mq{F%SB2O^;{3AK*^lP+dOY%MRkcsFkuM=gY|(sY ziC4@LChR-ID?8xX_5z8AgE(75g^1R#ti3Z)NPn(D(OxU-Ki#4!;_(Xpe zVywiEX06U0253EcoFmWfdbv_LqS5SGxlg6$BPFUeOPH{48IQReHVP7F2{C0J5`wkb zZQEaM9Pv`)YM;1z;`H2?67^)?#@i*|MMhps95cL+w$=3y!^S7)PtR>F*SuS!?IPBy zpNbO$ZA+8pH?H=Ht0an5JBficM52tdgbDjza*H{z@q|Rm`cPtE?RsFBh_#+uhZ6&B zOMMzQsrHF=^6i9MBr?}M5-pu2O#F0SFRjPrKfuORiTL%25dS&*PZ4X`mz1Z;GiaY! zy8V#ck1{fxE^*>n!i0U3`H-Jr<2(6U^DROQl5fSc)~Hw9_noVHHL3QAP~xfGBUf;z zZ+44V!i0UB{N+vXKEv!+x5*(I^yDSGMXYt}1vtIhw$y!elWL!sDskanlZbB}ByK-T zm^kW^?%GxzHiwNy9cBzH3DHdm*0OJtUo@^swNL!K;pl;N61i@kd`*BQOxRb>TegLb zFV>D4_^c3L3c*@O{HeRvzFBG#(g!r8z* z=o1^tw-bJlyLOD+=PY5O>bo7a9&Rl8`I-}pcMGwF5UjQD1~}30#uA@+MWTexlhNmL z8LwEv#GQ|KRU2+hyhI|AwviETjS#GrI}(uz+?ePSkDooghzNYes_i0{Fmam12EezM z-Pqpfg6YK-GEyHP<1TA`_DL7DfwA2uiW0RIzUX-}8?c0lC9`)>8*av#D1^k=&R-z} zYkjn+liI)>gX<759c#HBLqBvwnDJh?v0%d_zXU=oqP%56{-2o;$^Uei8Whx zRvXUunIrLo=L)fx5Uh2@fgQCT@O^yZsJk0S^>WRdoV23I5+?rqNhh`8e7GTZG>*O& zV(=L&imY{WQ)dG{oKMV`Zzp^qUf&_&C$fZz$9~veZ8%@_Mv3QKD?}^#-WF>ueG`#X z+Lqvp`o!%LWqO2oug%5ZWeF2!ws1C_Pd!Wsc*qY5!CLp-(_U@Br}l|6j2cnsdAm9fVkO-ozqneR!F(fitBlJW~kVA1#Dntw+DyTI+$evri0>sQ6#WYI{RjpRk{RcS{C*K43Scq}5 z&%j!9r#Ktfned6NKJ67@EP4FPcC{>F;`ZB|4e?0ChQ!8=5Z&)@U$?7et>ce#HlXDb zn+oxk5F@^5H;^SvnC+(Re=EqhAcXk05O;muZXj!!y*BgL6?{T=SfY2O=Iw5JXCOv=?$LVZz4zC6B_!UuA4RPKYM*9R=31asJW~s|!AHh0Hj| z%8c`~M2Tey6E=6<)f6_y3NccM7rMWhV=bGn=1%;j;1jYZ6UBQnIhHVCbMUK^a87s+ zd~HGI+Q%h6E^FDmd&JCD1)nI$mk{QN2k^Xn6@ev8m@jekVX!e&e1`uDG4hNRIo2}& z;r<&}6?~#re4k}<1^;zPRh}hGm`}86-7jK8_GF6jo=l##%ny3y-zy6~arF4b#UbL6 z9WPOoS;B<*c5j{q8*PNh3306utY!Y(^rKc5d_wkQit(OIo+V6}kNVf$VdF9JMMsD) zdfV=8@~mZk=|5VoEcnDNugxlA2Xd}NwPpzu=4&5RkMqvA3xPXoju5P6{`HUvD+)fb zw|qNcwRrlwNjz_sFkx$kkN*i9ZDnonkr2m7Ja5*rbwZ1SRup`q=& z5+-cz^Vw0b(Op(WKMFBL2-dRo&h;yo7kpy0tks^DmDlwWEuAGy*c$HpcCgX+iW7@( z2{BX%*0Ob5@s8yMpIEtSaB-fD3{&K*2rOa3)}jY)1sjdt9$b7%l4VjRzC5%?2+Niq5DYdvV;lSJ9F2(gY1#v+m;|$%l6A~&3$68 zm$u2lr+!6x2}_u;JwVrYAAfn9+-xCU5`wjC-w%D)C;I<5IQOXZ_Rd3g$+LtB+skzK z;Ma2o=Ux-ybh$rR%l0pE5BkJR*?XNWckQWi*Rq5O+mm%;$w60~n42NQQ9`hm?ZaX$ z@rjj-Zpz`iFR#kz!xAQJZ`qBBgJsuwp%AwV!CJPTj4{zCnq4$Kw?IbG`()f@2@|$^ z?#A|}7fjE6C&XwOcUjB!#WA+~#LCxZ=@pD*Hed-8w%70Gs1ZWo`QS%Fu$JxbV~+BP zq4I3vaGBMb_Gy!62^03r!p*gZ%Cm_&e_Phl?gHQY-&x-I(ui4_4u!ISFhU9#oN90)%R`k8(I|{62&yC>w z_(X4cg0)DzrRm~dv4jbG7Uq1obA(tZLQ%btJ1hx3UK<=Ndw;`JT#!IwFfFk#R1 zoG&^-p5475#Gl1aWG#D+2Vc}DY6fqfhxdA~c&{vB!k$e!pZbqN93@0Y`SJp5+4D&F z)IK45GWujx_GEG_VZxriy0yXd`049WLa>%SSH;@EC$^R+yomJQPgWBwVZxpwyERS= zA>J3_5FuF0o)2S<;}hG+lj<#HRn%VAQ7mD?o_V{qnykF?ZG>1L-=kwKd(MrunooQz zPuw?`)!p&39%Km<_UzuRIhzgGDc?+pk0(ydv6elr$C}e8@a6z!gSGNi1eP#i?;yCf z^K>EbZRCAqUCUbb-T~ImK5<_B2E-S#K4%FN_AZ6n1GroWtmu0S!CLnI1oi-YV!3mM~%Ogt)zo=JM_bc5%*?eFoOD_du|h;S<}+vk#0VV`aaDB}^Q5oO{0n zyDdSmPP8%Z4*IU$K-RkbHuvraw0vR%v4Jm||3mhDSi*$ac6&>$guwIK5#P0|Wi7LZ zy(OQ3wyZT@|D+pHfxG5TOy+VKFW28X^7dOB-YfF=X{9TW5kx>z4|vZRGpn(x$q% zfb>OYZIrc>n;uH3J%nlLS_kdWST*H-IUDkiu^{8GWQM80Src*{tm-71zU zWG(pc|G!c(!7Y+1)t&t{--Xhb;LpJZ`dH;su@<~c5bJ*hncx=jONH4P`QpBV$AL8N z$I7K*E%;g>*1xwi0dEjATEs6E<|s%oMqy4w8e>=GQn41i0nK;4M+PRiMYL4%A06RB zjN!-^V=ZO|q(%5UrD83k*MAgcf?LEdm6d(({yz?~R`_hn@=U8LO1)ka=Es$>pbQ3uLoI=nY6>wtc}oGm$mE~{I^8MX7Am{%ii@L7bCQw^Ff|je`vmf@Rx^32qU! zkq|a7;R<3m68GTm);we_n==}0-NXjhkO^)Pzf?Adqqmzk@VmVvWG$Ot8|;YF(jl0P>j_AKj<#!FG@%O3m-=XUMfnY79O)EtJkazUu8NzK%>wEP4M)C@(`@iGT z&o#wc*SjTuhaP?$vD+P+sN{zK{!%#Q!i_b3)W>VYR*DFXU@fz8<5E1SOc99ogxw&EMbCM1SP_c zE7hu5v+As)wW6;-gH@(NNjManBW#ciSXk})qArZns3#+OAE8V z>6WB9C#P-%Yu)wQj!In9{M+>`6%*VdY9lGtKX%V)zG$DX_w27}v|FZBMue<&^zOU= zKTE{~w}@Y=)(iL1e9@PlxOz`bqmNZC6>Hu1Ye9+izk*C~i}*fH)JiN*MAgcf?LEdm6iRQKQykkR(P%z-ZxK;iD7&XhOA}z z4sV4M94SH!x%-?YOjrrs?BmL%L}=G}%iA}swjQ(h97K^z*+@#oT6PWo@DttzPZ154 ziV1EJS0<~u-4i3v-Kg5`uI+yOL)J!8D%P_8y5)fl5Dk`!32qU;R5pI}pVYM4MxrKz zn*L6ySj+D1=HG0TB^oRh6Wk(Ns?e^vjkPG1joQE6@_VIXEgJ_LBpNIg6Wk(xscc@t z6|@}wi9+jQqn!-G_RoOreFh`Jv?#rwp51mcw~N!GgtvTsV&^!{UA;uDHR!RgPPruE2IKkA(_wWnEl zTiGY3O1!=UMx5R6>5FQWKzWfb6K;p4N6EcUeZ}g3lW*l>F8&IeY`_}iE>ypycb}oSbG-_xpCvkdM*{Mh!%yG5pM5Q#$7#^8WW)rtc5hRe4^9c ztx&39>r>CybE&XlT1K>5jnkk#No1kbbpOEWO z{9<9ZnYbP-VZ!Zf+clT#A#r_z5Z5EEW!J_hq?dpQ&`Vg7zJpN@cP@3eQ|~Sw-}jqY zlhE7gKIi+JwZ1>b_lbm5l8yLD~qnzi;zLOoT?T7Sfm* zd_v}^2-gF16ibjcqUmFJ&%x$FnWLf>e_Z_><|x*(H}EkJ`h?82QM2nu_rqMv5+>YJ z4x7&>x9W&eh40E-o7O_9FjM=4cmP@tcmOOx+6ecg!Tge#P@f^K1p*$2Pl)fMHsJfP z1ZgAAnu(LMJxb2M65l6kI;c}$_&%&Z!6Y~?rhtpEQ zhf8arRPYmh;^0*ywRJ~|X9edWVHbg zIjseI@O^#afObb}J-W7Bqo*^`il${mI2mv9n5Tc7d}CzT^z&zaEq*)lGA%s2K^m(G zpODpr+Q4dpB}}*{Kel2S|J-TOch4Q)e-Bv|*%>UXgz&5gHn85gtxZQQm0PR*W!R)> z+Rj5}-65+xmN4O-Q`rjg#OdRsJ=-+dM3nfI_ zdg!#KIL|428Bx5K;hoO3o`|<&eS&&ohJXzaOzU2T_7d64@J?si9gMepePWc{A8SrH zyI&vqo)=4)u#v&NhrIH>@oMAWZC>?GXWHEbEuXmSW;gomdD&t;Yl*fpEz|>P8SpmIg$>&U&HGli%%}X9*KF&%5&m=U=vmUh|%Ex+bj!d(iTU>zg~jWSo4rk0s^} zfG~f>otub>&JlJL)JLnSxZ~*;B1#q$gV+g-_HhM*C5XlCTtz$PM&wPYjN6glC!VNpVYmKkx~!N%k~_QukDJsw!-em zZ7sU=lid&RtflRjpsjpDu1BuTm~Jz1Jy^no?fbZEj$ItoTy_n-vzE}ZYvU8rOO!w_ zVF?qqf93jaOaw+)zP5h_EuZ+{8r>rcW=U^nE!!`{9pw|)hkI^|fqF-=gbCZ9b9ZeZ zdwnBX=w6?9a?*AOai9Byj0~u`jtnee!gf+Y%h%Y~=x%NJu8dbKVZ!!z-6$&KRqp$} zPV4uMj908>d#@N1ed5wJRr!(o-8}P?L&xf=M)Wx3#f0rsyV;;)vn9D%lke>RUm15< z3;E*Ofc6R4KrdMw+h8rEk*`n49Hj*2D3%~?gzdw-c@X>UW7@95UWRva(st-E5Bdb2 z8w`6}_cHP+IQBkcK(^RLAB$$xNJ=f3cLSj(R2z`ybdJdcX^GV&~8!k$w(KM~KPaLr{e zBcIknsi5T(c&-LQo~z|qV$Zxl*poPSMiI}|F5C3`zVcj63Cq`>vBBT<33}R>Piuij zzCKYa&md8%+ncY^Q;oPkOv?y+2I)NgcDo#%pI&?Z%su8U^Uguq^GIDA#Lqb$A*%`4 z2(X&qyqG{5wm}DhtZ|g+D{CCqvZuOONBP9^`^M)l8ZfWli?YUH!k+MA9mTZw6xllm z2`$tdHhcolw$WA}cf3wdHKM$xWrRK3b}L9c+wRk~_e|ND@XkTnb8f6TeS)62=UBpo zJ);LL(H0i!Q~dxdVb-$u0I=Hj3A{OAt8JDrVQ&<;JpftJYt6BuPivv((DDh{HBbWk z3@ky~2zQdi_A=50YauNyucsQ(>PYMEhxQWeesEq$8)3HHsYcl^(NY<~T1Z37CuA2# zZD1FNB~}j*)*>$Qmy|93!P{r$2;+FSx*VUprts#_bEO`=q}P{!K-5UtO;S@|CWcTt zO}O{8k(a%*jr0)d9eDdYwh;;?|I~&^@MgCWrj;UMGpNMeo{Bt2^z4pnUnN@pXa$$zOYly9QgxwcSiw zphjx$&cXT-=3_#xcM!-|heflkeNR}^_~xj^R6zVpr|;?z1oF*V)r!ABo1`sD38KX+ z5gH+1pjEAl?_6Fm8flI>;uG?HUnTGrSBr#!sHgI6Vg0-N?yE3nBV;X$Yk_#k6^Vc) zOvpEq)rR}-E8Ac#i)(?n&KUxbwk}JU$h5B2Bj8rF_CbqUySZ=ua;aF$BCH^qZbibo zf=tL4kG1CR>%eS-wJgF4A}CiR0+ukrS5_?06=W@ou!3m183K^DE=!o;zMwV|!mjxf zV^$PQ3z1tar|GMg7d#^ASI{yWh$mB-U-ry`N`66D2%^*2Ny@@xd$t1Vs%V&n1{qeK{A!H~5q`UxW4RwTUfiV68byY^l8 zm1D7z*kCP-eu7B16^Vc)Ovsn!)rR}ZvDPH+iSpfOm0(=5=vf%A|M)R77Gh^ZH7o}u!IR4!Ly?eYgsHTj6NA6vB451c;pjh z{c$yyFJ@~EF(O-xHH^F5>Q3GI6>C|Acf*pE0 zm)0*8Ygs%x%&!?DDHThY;QINc;=9vY6nCn%dNMMERu9&)>w%FWLnNhQ2@}?Pk`c~q zgsf#f1|wXCNNli#3A+n2BXwYNZS9;D1sgvOt65pFF$NK#BzygF*SyuUgY^o2_Q!zUx56!oB%)2r7s&PR$;c2|Ph>5N35gik8A1%X zQn7>y`QEzP$c}KVWicT!!exlW21}UWKCLxR>cLtT6A~kJhDdC%gbBV2)JBHDRkNOt zt7$zSal?F~>2-s&OFoiJoaPO{d(DiZNzGZy=05no86qha zOPH`36~4A8OVe6!XDyp+5!*0B08-zFB~0)r0TX2#tYxz$VjE@%vk|g{3GO{=!w88r zIzW3L`jYv+7^8S5@`#YNY(0olRV2JwjR{`K_%>L}R;*~<$^=W8;1!Z@SYMQ+?dD`CTx^IL_x1q0nghU$BpNCj|f?dqsvt$Si;0V z7gcMEYp|^)DVS-y-^vDKlakRe-0Z8vCmN3EBNo^zqk2vOW zAaZ18^a;%dYndN}tCk@W8!TbM{H~;5CBzBcw$*kY_GqJOi%*X4W*CvoA6BZ6wJh2= zzUGl35*sXG!b*r4PL%b>weAy-ZKI`vH+fC`)dfWO`^!l8_b!XDdoDkrwH0geHv%#Q zAiaVtVWL-0XG0WI`*5tq-#W+;i4B%8VYa`$E@dNREwhJseHkLL!4f8{4KcTia=EQS z*0OfPH!U(mVuK}2RQ4In%fQ-zze8X-;mUfY3RuhX#R?)rWJ-m+n6MI}$Eb~juvH4$ z#3DSR=6`#{tzNR%gS9w*Vnrfg2@`L;;cQ4@QrCmEI9_9Af+b9t?aciVvXh zuOzctX!T$%%NLP{Gely8B}`ap;i+k<5*w^#^+4p|43XGi2@}@pS>K1XtfdioI71{h zSi*$$9*oCcJwn#99)rlk86vU45+YTSj)U+j3pT& zX)Bg6!DD3*{3P-EVM%_==zyo8cv@V3GV0Pp;=kj0bWDV0!aYm%pPx2B#5T&3G*Nz* zu61|MYeUrI_~X{qV|+z48l(}?0d0u1cRf%Sjag$_i0^_l;#y<~C@aAdCeRl^d;LlY z)5 z5+<fcBozYpGZZv3H<_m^B$9vB451@Qf9- z_gqbFu-4am_E#-LxycZT4VEy0XRNT{Jy%m3tc3_Y&_Z;e43XGi2@`nw3fgHV|&0_h_R$L zWNfcYu!ISC&Y&}MRKQw@=>#pzQI!dnFaggQbY`v%SPN07poO`%GQkoi;5mcN_zVGS zA@UQn;4@SvSi%H6XVBhyQ2Q=xA<`7I;K@`bSi%JMOF(-oVYR_ph=m0$M9iv8u!ITh zIf3@}OVkEyAwrkdqv-~^f7LL-c`<>#GZ1oP`*Ur;T8Ij3T9pZwFk!a6{Swqe_Djn7 znmt5Z%n(r4nzMunYeR3pL~XE^wHqQ;W{AWFOPH{}kgV>E2wBUnKO$gOBm$N&VSPGT zr6x95%la{5W>zEumM~%WX0qB&Y_OKykBBu|kqB7AgpD!Du0djhwQO8L4AY84z!D~G ztn{8J>NRIA8y^w%v?39(gb5q-lP9A|Jy^@ec|?n?NCYfl!sf2z32$P9wQRmZ6xxbJ zz!D~G4#t}blD+;oFPyb(-bLKnibTK?Cd`*eo~4QvXM?rOe?Yw7ibTK?Cd?=D-mKAU z&RXUNA&ziGB47y<=G!H22qpDkE%WCP54j?d_=(7i3G-2tH=Pn2tYv;FA~shf5`PzY zF=4)TVk5Nc!CK~D!$yX%Qt5k^m;sO%6SihZ+A6WZTDDF=TV;sE21}T*wNG-*6C12$ z>m6M443XGi2@|%4OZskNgSBkkhQ6C25*sXG!q%e6J($>FEn9!$9?TGl4VExrYwBby zNo=r|t)nrPWQfEDOPH{|fn-cfY_OK?2VhLh5QzLT0TNvX)(ctkp6^VxvdjmeS_ti}0OBm$N&(e2dHYOhQ2%Q|Pk>cLtcUVe~jUHaOxx(p$htH<7v`;OlI zkIkrCw*t>LCzfvM@j~6&{_ZPk&-HoQ*+_^kE%8iZVyX9mv+LR&(OT0#JvR4u2-do~ zsk=58-~ON9Azpr~spk8iCadb6mbD@5b?6rSPV2JPb^me1>@kfi6JF~w!BVe z&)9pUy9T)C-0Dh%c0E|@_zCWMpvPngvk|a_iPQf$Mq2@O@@=qWsEj4nR-BVhuvY)> zjzCLihz3i=1ottukq~FCaQ7Xq^E=nO`vd)z`?OE6R+qEg-G#nenP3SM+IUG%C^;p{3lx~Cc?IEOiaeB#0G2eU0aa|xP}XE#}`&*l(@L=ck01f zRZa0uq8okIuO3Wr8~Qcpdc3%K54F*2#8Y(xm$>gwBJC3_Y5dZTN?;u1oP2_{{{E!< z9w@G0Wr8J4@ObRo;L&-9W4BIPmviz7*1Bx7EtNp;t4y$j2_Ex(8(R<9ynr*#TXp)O zu-W--H9ddsvcmooaL-SzzvLr2$D%W*Jlj?Y&Q$;U=pQxx>8bYJt*P?=@oZauLhJ3U z_3*uj#W}V9*3}IVfXqh0PF^$7(r7~z3O`vw>LF5Bb7>JxyLN**5t^6#lG$#QF1I@JXQHe% zZSJ3xXx2_!H>Tt30m$l+NSNU3q&5++#7oCwP`)ts`*_%idL%TMue>O z@V)S_rq*AX`#DR%j9o#Ix?atMf1RjQA!~g(7IOyZ72Z8B`ugK+a9&JQ9vMWUrNWr8 z%X0W|Q|sTG`wP*Ez4S4@9X+-F{P)*n3Bg>c*oKr!3DkpgafKetYShxrk&asdY4_vWit8b*t2A1d zTUzx)yB@5yRbNNU{c3HN5X{-&yqJ)*mI}0QgSE=_2&ywgV#AkM&9xQcny1(2oUh+L z)>bhQJURU2{F068Bzhgj*Cc*LlE&Y?x2ZxS{4cz79F7!$dPLd=al{k%wHuDAF(i)3 z5nsVDCgeA3aZHXBK{i<85pf)rlno(S%cbM*@%ThyL!M1YySpeJ@(e-Kc)vi-E@?U& z#Y6VIRf0E9WN$i2%lTnVXQOzS7WS!)Mq17fE0M$lkT!CyD^CGbf;Tqg%$KHdDqfyI zXxe+r0@ovCEjhuZTJgEfD@e|gw_QQjl5<{4<1~4O0HnQyB}`;m*K7pb ziq<}8QENBveIKnkYsqP8EmeGuUeg%@&n6NH6Y|7F|L(nuqc&JeP6n!091oyj0?$|y z2@`x}rJ1O8Sxe3mDjml)&~)jkQWoyhRJiB#0G0wyTzyC)kc=!yqK`Q zkUWn{Y_OJH|M+yj+Q<+|zk-Ab>!HbgZZ`1LQuD&o7aNK2ltfO^>ff^`@8uc2O0efG z?*wQ%J_V!c?8$q13ZN3ar6X@+YdStztZDBJA?@v~CFhb=D?YvK6G=VfX+|PpLY}1P z-@P}T)COzGX=&ApV~hAiVuSNyg8Q*3(;dZHa&BAmjbo%}I(f${vB7yUQThJhYinZ{ zt}~DMUa6814q6f&MoSXMlhJgxUvXYc$g@c$lHMN1BSXkq62C^Z;)ih>jYpZ0WPHN6t60=B&I6{-A6C$y}c`;$v zDLY58mR-R((v;drh{Oix#f0^@%*+|Gmi4hXVwT!Sh{Oix#f04}iMNyxe6Pu=Z_O88 z7|&gzO!ql!$r)}X;^<1dEs$H z2Q6*#?uRhG-wp{A>;yRhs(Hcll5=pH#yL3l)cks|mYkwf zB0hJg>EwNeq*R<26Y@5t65d-DT65NtbAC?Cogegx#0KZZ1h=}@BeeU2wdA~_<{O`b z)O7NGiP^xLnTdo6zD{Z*A>_%r5_lFb&+9cEpU%~EHfD|aySRepmtwRtuQq!H`ChZx z2jd6dn_8;S?hn>7KQWFWq@~J^SDY6U=G7*nsM!cv%RJdQ7LwXXh@`DJFDAGZyn2MJ zWga=^j|`F6U!oc7L#z`44f-8nuxbcSFvL3GSh417>iaBXW!8 zh5JCxaB3Ro&-uPlBD7MmmYe`pB0e*!>Ex{!!JG}wiwSuzO9}7XgpNL}C1+GsD?a<` z6NwGZiwSwZOo`@WL&pjNcxxmX#2meul`D3VAVMEt2@6 zR`Y;{O8M5~WYuRcdjzFU} zGDNcefP@KK`(!;C*0S|Z97#uQWC)yaOC(J2sN|Z~+KRPo-3E^=LnLj*5+-;YQyU=i zNbT|-;{T5;jUUpc{)T6JYZ~t)U)Qy7lCDg!*0KNXr^K+~cpt?5I2)`b-m7YTeo&kG z3=zhq3R!FPkp4PQ8_h0g=4>RyKepRJCAhY-qoZkD!FfA&)iipKDC>{b1N%OS*6Hv6QPb#G z6^Vc)Oq{mwP6_SV2+rGfTb1lNb>n)u=QX|jh)wFRJfef9lX`@9Jy>hg8IC@Ad9y4b zhTQewyqL(p-BE31uLo;Q>f^L!o-KW zcUC%kf3Vh-MZD2Cu7vv|LnJm>!UXpoQI@8)>%m(8dLHkjjw|6l&k%t0{$L3c+}~gV zKaP0*sckgh!An-ui5I5nMJ-p=O&jh0e#0Sa>YTa}taZi}j+ond&F>JL7ZW*+967F3 zdiS@K4c3})oU`%d8^6_6CRoD6%Hgga&v$Jkb(5bku1CmPOD=IX{?@-yeTD#}t;-T7 zCOqV9+&ivu$_8tl`-!u$^W}}}Gely8B}_bAz`LsBO6Od)Vaf(;wYb2QB=_ou^%)|u z!4f9kZR19X7w_39WrMZm9_&ie=I4#-Gely8B~0+BB+7I>SgZd@t|Z-?Y*L>g5*sXG zg2yq>M)1wIZp3LZ`qMh`&a_3({(N!W^mE*pxVrd7ok!qVQKGf+`)*7;_{GmF69MPN z#H?P99yVb~$_8uQF~!yVjyu1ut4IVaVPaVqNB=zjyOa&qI^bk?1s|UEZCynoU$8~4N(Kh{+w0+ukrqmp+$0@j+m)ZI}hUA3aFGQkoicpOt3@*j7f zpR;Hez2@Ifc(3k?4&9UVc{{oE(uME(H4j>x>1N@-ef55wJc&_a%^C02Ej!S8087Sv z;1hV?C(+vY4^Hc`58kg#1e_NWb$dHs;*q`|rfjg*w_myWEMel7L)|<$ z=yLh)8-BvLtwPrN<|{W3Uea@6T}2{b2@|_r@80x4~NfI@I0shxS=qmmyFvoefyR1dkYMBOwmGY>-}aj54yi*EB|-%{O&vj7my` z*1D`Udb-m>sWODw2wB3!+oujxd)d}yt;Rn&EwpZiNNli#iSg6-P#f7^!djbeIY710 zOEN@agC$H1n&DPR+1}1tn{C-&ZJ@Vjh{Og3VHdw+$>jl+nBRjUU)>AjSl3;Al5QzMxT%+Obi;^Q%kt& zhxh74k8H5kFXuX~dk&vpmmvVD4VEy$bE0p9wdB1eEy?ON?|QSS5@sXdyqL($wF$v% z^6&O`y#%Y&%=$dEda#!4Uuvna63!5b4VEzR*H4^1tf@trT9>t6y2;sq_nILR8!TaB z=cSI$df}|K>p$In4lg`IBsN&W#6d+zXIB%f_2WhHcqOZe43XGi2@_Wx4C}|w}23DydYh8Jpvw>A=hA4;JHhbsqeCuJmJ&(1A71&!fXUAVS;Bn&ql!a z^IzvX{~CTY``SLiTJm0aGL}>(Si(fzeLE|i9TQpW4}W!97!xZJ0ZW+R6@XWdkhQ)a z;Jki}?HM9zU6wGxYlb9tbR0u^NWn#$#@U`Bg#*qXSPBB9YvRA-8@Uv1TE=%@%Ms9G z;&b;6>EN;A;R7YYU*U~6PLq6tYNT<}8)=Ekr+-I;l^}?T&LZb4i4Me;Nf|v-6U@fGf z#?{+&{>v6z4%W^D1+6altr#29Q zCd0OoT?T7Sho2iKfkWQyYsG^vkmZX(J>mpR*y6t%4vXLL*p9)1u`Q z&n?|rZ4}?wKhF}RjgY8(Y6B6vf*>YBBUlS*X!*n+*Ho#EZN`qxvjk})Br2cUK%}uC zh>6e$)7$KCPE`v3u$QiMBk2wsf~qIlk+S=+6altr#2A5E(l^GG=jB|hL%q} zf6_+-(N^zWctM^eNE;zh`P2p?@dZIlghsFy($Mk=$v%V)c(5!%+6altM>e49{yBoR zIE@iJDOIfyS`W?(X(J>mAGMX#1BBKitpx&YdAq5UeY1p-<=A-!E~ptrLGX(J>mpW1NuU`*)! zk=6nMEuWCPHbPtBu4M_*Mo3gXwc*B+n9%z?tpx&FJ|Uxz+Q8_;5~PigsC;Sz(f)M2 z0-@toS_=fUd_qQ1wSiHTB}f|~QTdz=9ou6<$KAA+5~Af3G8?E3%myq$+6altr#9Ri z6%#stq_sdm%O_-3QyZAoSc0?>5|vMFxVbhabRJA=fq<4z$n2~(FgvpZX(J>mpW1Lf zLrmy=p4I{ZEuRoCLv6szUNYOfVadFq>Yd$aB9Q( za516&Ray%Kw0uImKD7a_k0nSOAu;dNhVw;ZLjAa~Hl!69j2OZAiX0UqQb1=S$5d>)hHjuB)yU_B9Ue0F-*NizKVhI!GOW?~M600ahzy|U){{dP) zL7q&+5+=+i!WT-^r-mm3-$x19K)&V&LCYtqwpSl6e6ebB#1baVx5JlKf*?)62J$t3 z4q84zo@K-mCd^00S83FzHeXZ;*g(GKmqN=YP;2)uj99{i`P$A#nt%;R%nP?Pd}>F~ z+92Y*n6Nd2Yb#nCC}B2iH32Q3kk-vf$pTytmM~#!A9u}TLa$(2%dU-2#4E1=y@VyU zjzYe+hI4&4CbVCrwO|8UJ|Vqb>w)`&CAJ;}VQW!$55|PvQE4sMfR<0lU7JT+;XY@H zt!qKpn%a#eF`*+vS_?Ly1sl-v37MVM2Ig~?*!~p=+dFeULrka#kk*0?X!%6Ea~HtNV2SO+ zfv`P5=ljG2d}<{uU)vpomQTbxkl3>3_p?+doOYMm->J#F<>h*xX%M#n)MZUbZtp2Xn!wAclcb$C#_qh8B^IuI~ z6ZPo%P5m2hw5`AWwm;Wd8h;OhRr+_;4duV`FU+$R(zoBXK?!t&1R%9xd8G&`c_kZ` zuMmSQEjF@**+?X5!s;Z7T8E?_NxmRV3pOmR1R%*9KQ;QSAdW{CKR1B?$xjE$+8}z# zDrH3J%{Shc-@OW#UOT+B%?B=xzX!o0`Fl)+NI|R9@B>Sa_y3O)_k1#tqo>-vi%B5nhIdeyr)@@ROXs}dFlv^ZSszZJn zRXX9VkF+E$=8P(BuyW!5C>3jsxqDP;M%M~NgQa4k+#+$Q5~5Yx(WU!OM~~}OK>E;Y zKmH%3Vy%}q8C^Q&U;k~GNNkkby;p&Wa*L!(g_{4i(Wja(wEo_Gal{3 zj(TpxFSR7-eLG(E#s4T3YoYH}{p{*gww<<7mh>txQErhmfzhX9qp!3ixKl^Gfv!ile?(;A44nOgGs4atLdVl$sN3YrDCGoBI#1~|9Ssp#QA5l zp_Rw0q*Sc+<8DKf(Qf@p#YDM9s8k_(2})(7^ABI{zaC>dYawkj!}^tqiE@jiONH{< zOon>=?|G25&~7%1u3xE`D7Q$uRJgV_>*JdLZ=Zp+(8tWPAuj2k=xkS9*Dq#?`G>ch~e!t+AWU#8>a#oa=w; z*l56`9~76&-a)mBHC5G3A9Lxqj!fIw@0?O@-;>8iTXcG|xMs`FO1wR{QT16fJ88OV z2A(dkjbU$8<<&-nntZi~5=S4lx^VSg12p~1 zb*odvM~AE}o_zG!=%XoZa#OE#*LmhqYYTSGv-NmlP^0KPX{+bvKP2xQl&xEjK`Xp| zfa^U?+y5r^q;(^-?#B0hHsHA9oFv_%J|V3eS?h91*aq7Uf<{*^Ek5^`vC-<96J-al zT&nO=JPps4ChYcW;qb*SedD#i%HQ7j?DOKrCytG-IQXL6Db1av?xi&aCOD@c_-K#i zMbu-vlLqHFFK#!V`0|1U#S4V^r1QO;9lty(%XyH+gV~G1A4oS7`O|9p!3+y#pjM38?AU{b*}p{ zSkdQ72X3{hzy#+M1kD~lym*n6>V{jEE_x$%IGuo>PE8HQ0^r*`fRgs zWx+W%%vHzO`E)KQ`LrxT^fnPw}ONTtlCEqvMMeU(fPq*7Ou^j|bkAYT?mk+`FH@OnZ%LL~ncboj6C(d76 zmFK*;PCg;^7-;pFbH|_5hF%Y{=M!=Tb9M!JRAbsFWQ5Dv2*(l|+cCn~n2(V!2&C`k ztnXGGjW?)VZ)bvY3WD<=KRk!NJ4t%UX$N*y0)3aqV4qmr_VOHR-nqx(99w5PMVwX2 z*|^IRn{hDi+DwG;I0)oE&)I$c*bm!lsW37y!8yqYchxgFyU#f;?$Hd8ayUmS>H~r|+82NM*&Dkh=Z+j=fXc-dW+t}s81zM_5MmWxk>*NzMisoz- z9XG+vmY8waUWzzmZO-N>o?n^v37MnvHb>cfj=6|uYM(F<0CN=2`b_(TcuRTnmRMpX zgtuh&;6(+&5~;_DGS_}SrA^Vw-f8#-)l6_sLGZNHW3u$b7v?`y%XwL;;G_7&=2tAu zJuUO#S0|iUWQkqDm%rSg+FE+X47|y4y7ZC_q?gnja#7K)V8`~2s+r)NY zRDb`=;3DV6b@GWJ(n}@?ab4$|i`Fx`pWCRK?fJxxa({dz^Wd73A1K;A0l$rDpE&i( zXS82UzdtJ4J+ZPwRkhtK@Bn>cnT#bfWggt|thq%SKj2L=?GvwTb$M>0)T6fh;-ZZP zWA3i1wow9psZWT9oHGxZB{n|7L$;9!o^ufNkWusrnFlv{b#>83&O?5xs%C<73WAxB z9-cc}O4ayp%Zi*Am(VA~3m<4+I7@8)fERA_3cT|mn15*Bfh}c@>Tz6EWb;SMwvDTq z;GBZs{?&^I;+j`|6-1mD*U2YjiV9B?V(Hqd$mS*3V0%6>X>8wGlxjCAmCeW~JJUWP zrK+`3*^I2MOKTCIkn2&j>tVhKt{T%mAuE=mtyoxMz83nJc}}j!NKY(UPc$zKeU}N& zDG2s`^zh<2(pK%{nw!6ao@joM>q})1CkUEseR&bRJJKE}d8Lv1mu9Hv5m{_zi(bfYP+u5E^$ZSxw*}&E~ zm@}C637HKdn+#QLoOGDmt>2gkKg0+tN>A=#~n>rgAB7`y2gSC#Id0?r{ zfC_{F_;Jr`WrUHtsHVWg&O07h+VSd!>QR=|6dJD^QJQsU1skClkbl0`*|&^{+lOtZ zYhJElO@RsQk-3&m6Ru~t>-_e^`<0#<^j~f1wX^ptjcJD`jcMY}_M=Omt;O>p{zg?z zq1*7$rJXLu-(w;~BCXZqoYAElTRJ*J2;hjTpFg01>s(W~tJ$#lYNl;)&2QUlSaJm$ zB*aWjfo%-!b3oF^$~mQNu-4$N2b3P&<$v|Wa$YqBCQf*MXsPLKcy2^Cv{ZaYA${Oq zKGv2lU#Er$(+cn2uk=Mwfq*gjvHRRzb0*5yKepijA@1qFf9Z$s@jP3u`DOc;PWk?W zxKx!!2DH_R;(MxvmVTj!OP9yWv<=)7dmTML&NmrRwI81_7=NdlhprxFE%fl7Jspjn z?-5Bo9(i_D>7}lCTcDyPFVdyz+xVc;VZY&ttKZwFbw8*y^=CX$ zPM4~jS52X+*FmL+K803IAwwt%3EP-7e{|`nw?9kSOWRyPCqU8w_8M*?_g)d2d)e z%dGEgz(jd`OqZ%WF4YtsJ8Woj1NUib1<*g|&am?cV|Btda zf!Axg{{N2*h#?7zASx+QQ$s3|n{b~;gr+S@32lX%qG-%R3^hE4im`?mT2oM|npKf| zL!Rg6qD71`6GaTESq(A7@L!*`&u8DyKIcB)pMPGzZ|&b*>%G@L`|Pv#+H0TZtbAP& z8%~_I-q!J%cyQ6rM7@_m|+}pP9 zeCGHjb9*fy6UV3)?iy#&=6+(AWa1blaR0-6Tx=D_>$8W4`5Ys^yfVl=_bXQ|JY8W0 zK#y>hDB9?fOdOLETuX`s{KPlk3$22e`Tt(kbj8s*81vXey|5A$ZD2LHHk;>TNeRsP z(>BB#X>#Q?+;i2!+|HG{L;$saVa1^htV??=4Np&ND%wyjtZKnG?1l&?lDfh=NMhLd zopLX;c;#J^iDORMW2flJbX{MuRjRf7#GRtIR3f@%f{pEvzM<{SI%Kc0&|eg}Nq=Nr}Q!TMJ041)q9{C;nfar9S6Mbor>o zD_4&dI|x4WT{RW2T(z*izJG6+B}#-`Ij?Zy7$v%9zGAC%#(`%+|GK#i)q-F0|F5r< zfKL?eX0cUWlHkMf{x@$`*W9P`$9J8nyPoYpy!!CKbR^nHN$UmC75xagrEwdI@e)b` zO`>^(MRyR`%W~!HYN3o0Zvc=<-+cUoU6&YYu!v zX!gFp`vy;q{Whb|Z2T$#W&16N|NVuvd)fbAe(&srYM~6Rl(-@PZTN=a8$z)zXpyjA ztN7omW0o`Mb;{Z=&_`VEMp76@pi zME-kc{O%6l5Q=r7Ou~MH=YOBDzUr>){(hu`Xzl zuwQNZ-#58wO|y{`H4>_YGPF|S{QO%ldxvib#k!zH!hU_~e_t^hVm5N3MnbhvhE_^^ ze{lF_&12ykLa{Drk+5IU`rqGt9X4{JMnbhvhE_^ka*%&XCwnY>Lnzh-EfV&dVgLJA zzgio86^I%M)j}CsDG^p0th4?_pja2QNZ4^JppBaGc5p;{5n)j}CsDPdlQ+kls$5|l~UH(A_9@O_GeYM~6R zlrV3}ZNOVn3Cbkw+cIt=_;5u+wNQpuN|@K@HsJNC1Z5KTjU2ZTe9t2WCV1$_dp%8Cofk-@(l8Ilc(wHmF5{V`1E}3(SVxb0<^_ zWoV_uKKXY!Uk+acavRhl!7)9(<7Kmv6Eza5g)+2KB7dSXdj|0hA-6#-5`1bO+4niK zAo*-`hKjhv{FP%V_9l@izH-{g2W zd_%}>P>TfDt}hPiFdI2hBcWO-Ln|fnl`}IB8Q&0c8`L7fHTbY0_m~Y?Yn@Onl%bUp z59HrSc`kfI$Zb%I1bvCA*R`3AoT!mdEtH{^61gXnneT%y0=W%pk)TiX%(r)%4e@=P zP%V_9l@hr}mYENSZwR>!YLTGVxA7)-m<{paoKP*4p_LNX9~i#N`Q(Ww;EO#%|Qp%U&tP%n2y;hyINyl^L2FLy=IN(mb!ZUf^= zB}#C27shT*V6Wx`Y@lB5?x2+tHrm|=M!QOs;4U>hgE`^PM^Ov*pp_E#)Hcvpc+OSA zeJu#?w!>VK6Y#>FV7=UJLn|e0_Hi4SeN>_ZV*_DM%n6^bidwJ-t(34?)NNoERSDw^ zAQxW7hF9E?=O<1FH0^j9yg7q>!1Fe*>Rn2W+9aM=D zj5&q1HYf01PA6ak^)k)`t(36U*==AwSBVmgodusEC-7ZPCtw5hGF}F)lrS&DZNSS= zi4u$s2Hz(q+%G9=dB2(OlM?1FxefSNDq%bk^)kvCe7KxI%+d+g%P1$bQo_7Gw*fy< zB}y<_8+_56KK7(<5lsuCqMw%ip%CIK6$SEJ4;u^|8U=eGCk)@oV6 z&FdauXE)gvDCaS2WHa}_hb-VZQ6r&RC_^hHZpr&<&h^D$YL6Eza5g)+2KLgx0WN>C>8 z$mu_D8*`V34Vl}WP%V_9l@e>d7uKi)?Ay^QL7BuuJFew6cAbddbLK>igleG-t(5re z%dpnASe#lVD3f?%4C0{!I%hq$&}`&Hjf85U46T&t{3`eiS6UoSB`A|vY1?(&#y@t3 zjhv{FP%V_9l@co+8+@O?T0BuDD3dtq;Pu?b^e;a(8#z%Up;{NZZk0yc7@MnbhvhE__r zZ-tnp#i><-GKrrK8YVW1glcISqa?POBX`@_ZG^tE>qrRILK#{qVZB?i zmU-{01Z5IuoHxR4gnM2jR10NjrG$+Vw}DZj5|l~2eLJ$64d@JGw@9cK%Fs#)8|`ib zqg^E^li096%58*aut=yD%Fs#)duprbD?GI-L7Bven>KYDVJ;~Ws)aJNQsTW31E^hO z^OZ_aCNcb|R<{x6#3G?uC_^hHei>pJwae{%P$ejncwm*P+X!=ekx(s^p_LN08hBq} zHBbr4B>J4Yx!VY9RFP0El%bUpwyL=etZFJjnZzY?$GDBK))ooXLK#{qVXL#-!0N0L zlu7*kl`Y&x@EMAPYM~6RlrS&DZNSS=3Cbk;-!;~41mCAfs20l5N(u9p+y=ZQm7q*w zyY07h8^MPw5~_tVv{J&nzWja+si*{H5*ObbYy@AlNT?Rd&`JsOUfl+~SCybl;$hEy z7X08WD-x=OvOUpTqy+OvJu+*zSt>!91Z}@}E`DFl{81!S3uS1fM1JL&dB}B@@H#-S z57+-betjr?J+G@o366!n*TaU~b0=T}^>UOzD|e>xPuwakec3D`ir&_WqnDe=er+qjdT`k<~7CHQRq;uhG*i5dyk%cmAvDe+kT zjo*p3+g6DZoMSE@f?r|hM2!S&pkB^C&`OCb!)Ku8Wi5dymK)swr zp_LN(Or6=>-cX4WobxYP2pclDI{_Q0m#YD^QX*e*GFzh>Dp7)K*W7LK+i+QON>`vfBQ^!+-tE+x2U2z`|k*c&v8TD+!|u->hsWw;+I;r;{la_^Yra zz1*cjD<$lyZJ@94oU23$?y19Ek`wU4oq!G0%iT7#QbJ+?4V5Ut*g%*QB?jOGY@l97 z4WN}063b|)LY;gn1cm z173zo7>5JF7+~;ya>D(Rq84mGD<#ZZavSikRKj>72*xsl50?{&SvtXb8RdjlN|@K@ zHsB|!LpAjT4<#N^GCsZRf!TBTkgsqMFKWZuST7_C76>n`q2{E z#uxbg?=dGUuADhp`G$yVAugWhWECRMABDUC$jKTdjJJbetUu)Ql8jSMuwI@5Kr1CQ zXP8Qq;F(3t$?DgEEMrA2*voUWdTWzRX2{b}(Ykp40WF@r#GI^dg9Pj4c}t#?)ommh z+3@ZMa{{V7f;FZ zoUC3`k|7W8ejq1nlqkV7y_l2LZIFNs)Wy@jJSVHy6o~HLr=}KYlzBE8@(*_RJ~g$R z2sv4U4b51X)0BM^E1DCT61 z5+(R9MUwrLIa%EX>f-woc}`ZZDG>0j>|f3PUsdZ;f^Um-PoS?L;d>w~W6lqRWP_?| zT}trXmU!hJr$%nsq898yDK zHHstAZIDncl%bUpnt@m)D3jpZRPl*&8+jJjL<a;0KeS$Gfq+&@$QzBw$?7(!MS|}}#+B1;U>($Y zp#=h3DIsrWA}6ccpcVxC8wXr+W?gNpA{Q;P)OVvU}R+kju9_44g# zXr)A+KZ+Sv{W_=x8z}Rg+u*|$3DrUwS}7sfpyK<~)FQ!mhl4L#BvcD!Xr%-r!g)?s zzYc1Vkhh~PUQ#4f3uSvgk(1SHLOH%2jo&CDCu@|*`_#y=>VFS;u;iU>Cs;4EP=;1Y z-XQ=?vJ!3MNaLUV?xLK5^>SQ6D3Tp9BAX->VO7HmK(CGuascy2(Ia7G2eIX~ndl;6rAC#&BB zYPpS&lhsFilCdz$bFxMW*AHlMRSS6(HOFC53pSvY5}K<~B`A~N8XWRLYOcnj76@pi zgyx)73DB2J-aQEJCZLrP*1OoTFej@&AJk$maPJfD zc}_4VtB-IH+!aA9C2W+q4fBxW`_$Be4V1Zu3u8AYn3L6QPzwaKQo=^N+sJdW`gKr? z1oyS!8O#ahWOW-LxJ!jrO4w7|KwrHPaNcoFf-$GC*5(9rvbqfrj7C8# zC2Vze8+lGvw?Qq~K$)?#;4|a|bF#V(YJq@ON|=}7Hu4OsZi8AR7y}HxPfjo=tJ?s< z=peLG!n`H7k!M(S8`Odglo`tmK3q;PC#&0_76@pign4~#BhSg|HmF5{G1=gY<^*%H zx(yJF)

+Hgr>qo{?*1^}%qZ;2qh z#dx}!fEFaKKhO>K*tts9<@;i|BCQ|@AtZwCr@cRo|7WBtk*7X}(OvXWIv^W9PMZ$=(uc*(rN#inH`eA{2zZwZ%ky zMt^R0UVFIgEwPr}3204mzo3!`1<|ISFu^wpLO5)Wo!4%(--tSE+1&f@o7unBW^XA?&o8o!551zgL~L z?Cwu%ihD$rL@0@CDExW_in&LiGB@qguO+8_PZ$QZni0t%r zt7kv$U@g0g)tcg7S0xb&qD?(vf^Tw#uu^vV`uo;d9js+{%4Ek=-X*FeLP4~tCrt2- zv=G+KPU5=FIlF_k>~36ZihFjIL@0^3nJPyUnabE?G|hH%<%-9S<9b4?$a)aXiJe76W&Vf zHf}F#yWy9uvzl4U+cEA1FNkPMkrxx*+U-{HUDgM~bI*R-%v#Mpnn=goHOOY27K8o6H^+RlI z4;Q@LRAVh4=W%a-K}1`MyqNIWz;4}Va};Kr8f*D{h5P>tBHB{q#e~ml_Vz$F*J9?Z zv6j!fc#mO0L|clynDE)z-h#+t21Ecg*7EoP?_(^8XiJe76CP#Q+ZvS{?`C zy^;kHZ7K3%!lNa7E9JxNy!Ij4TVgGb=kR{af{3;hc`@NppS@kP~?u2{?7U2D}A zQ%Pt`WC;`e=35AN{HW)($qjM`lC|s|yjE@bl|(2AYr9PF8+;m5>kbS0IcwRwgss|x zD+wJLSi%IqiKsEP+Q4|lTJ}z4tBypKgpP15VS?YN3_-?SwSjS$wd~!_Rvl3*2_30f z!UVq=sxh_N!2H2l_Ks?+&J2}=&NwV#g5Pk}m|AUM9%LxJp82PL?piZ|cf7 z`!})Q;K6*(TK3LxtIpJwghl`?VS?W{mRm1&UYj5;VJ&<2xm6>MNQ66UYneAd#`5JvUkxfvaBRRL0AmO1i#6y@vfEw z@h)rGJM|V*R}vZ_vxEtLBR{e+i?!Sy)&`Y?#_cR&!fo4|NK{uHtmXBFHBKdgy2=P! z8!+LuYi}Y+OzqFSgSGtmW35(6=sJoeOn6(cH<4sLs5Y>=V=ZsTSaVhqx*lW+6W*rn zO(a>@stv4CSufwSm<(Yx%f>J%CC=*XJx@!p9hU6G>uf zwSip&*7ETYdl{94?lZ822_Gx%O(fYbQ5)F(U@af#u_seW=za-HnD8;*-b9j^T5Vt# zhqZjZ!roFPq5D28VZ!GwdlN}wYPEsgDAw|M7kgxtgzjIlgbAO6?M)<#8S1R%@dNhy zDhb348DV>5On8)GZz56bQ)exYgRo~=N$7qeOPKJO$lgSHZcV*&mpm)`qO9fd9Ns0W zBtk*ho+T3=_1T+9Pmi=%^i|p4Wi5|Ou?t*Dgo3cWS0+4qwLRn|pRqTQzL#BR*5V!L zm_Yn}ak}n|x$~T`J!B?43O5@d>>s|^Tbu&m?3Pai`~*UE6Zv2HZz6l)g_fn`a|%0~ zz?mI5Im3$xK5t>#&IO%dEu_tpi#lTh+VBYfYbQ$B$H#e{pIVpC?yL+(u$HIoES=8> z?OT2LmR@XwPq3V}Q<<)WpNv6^)8?)Gj{DRP??L`%qsYt3VZ@|xiJT~Q$Qj$MdMaaQ zoG87W*V##opR4)#ho7XNyfG1|H}y0LRv1EWlyj;!BWR+@NQB#ZxEjI5yMXJ{Pcx3O~3v7(>wj|k3Dgel^n_- zf=fVn8d@uEXgPs~9{w5e=xXO{zJ1O+t#i(krghXer$w~sXGFqU4~{e9qXDtKh{(Ny zCrmWprI*|%nU7bjwe1Ka+QNLw5qZS~*GOEBKTf_t>*|1wPwssG zFiU^G*QxXIinW&8)QIl8k8eywUNONn5_@&wCzkKUUmx4K$4i#}pJKD!pQYYb5sSk;~83eupPmd&kn1CC|NLttGa!GF8@YrB_UFjl^DkIr|*-3ax#w zp5|3$E6KfLtuuaWL}g2?^oj|tk=UyVJDOJ*8IEhQbY+jqy<)A^uQsBx*H(JP1lLIH z)j~hBd@*L6w2Y-IN1xm)*1B&4BPvI@O0SsU8d0yDNZbZy9QUwtq|UvHwalye&IZxg zJ}DH0=TsU+6Mr6ojD_~nBW?T>&n|MA{l?ql@UPh6>E7bnQxR4 zdBp_RNbHsOb3}dKCn}?*+$+}d9yQ;HEb@v8u94U)9}^L!`uI^9S>|4`mXAL3jb0$%@-ecAKgp5m@5q zUs%OA_R3F2iyJ$3Lx^*Vz4CL;;vSLRTWUx|Uik@Tans3eRz)_l@B8rG7`uzp&_?1X z)y0h+yCKw&h`jPM=;BV1-C>Ho^4kf;Efl-;($GfYcMXcWF?JWHArX1yw+M>cJ60pH zS9~vn?}0S5A-4_BPO;|XyC2w_Zb(F4xxM0^jNQwLy>j1+n-zANQL>SEkMg=I?t9qT zM2QeXaUVoE{Mi&YQtZ?r_R61gafiXqqe?b%ue@CqH!JLPsYFzI#dkEgMq;nLPZYNW z>_o9-BlpVtU~z}R&Ie0GrB~kPi(3|U@)vvM<418WZ)d_K8@X3LUKO_m?1Z;ORC?v( zV{xCs&TiGK+=lN!!Yd!CapGRG;Y7k(J`PqAm0mHyH4=N}d&qc#zSoO#H1>+MeCHPR zRw63BVuEWV_R3EI(As^s9?!gFBguMH!dkxfjy6^zD!pQYYb5r{&v7s^_<0L%B$aIB zUa^*+o}fRLh)S=R;2Md&@{>5+d-D@Bj3p%-xmT>^=U*7RN<^hsOmK~;S572uqc{_^ z`-vqRxmR9};-u2X`4ZtaqOrZ|%+qcHnqNBZCjLB%)3*k*TJDvXus9Q3z|0wW<#kn@ zT2{ZA+-mZ%C!HU^A@qS*MC^d+da<9DS6z5zEh{z(Z zybl&9aTSqFJ|-4tHw_}o+$$etiW8*;M6Z!oK3)}PUKLTFzPsdm_qN|&?C<*<7yeEH5T3-Ijuu-*(ErD7Ts1nP4s7buLa%x)7ltOu~ev+fvX{ zj_jR=R=NAZTE3f&eVwLDxvL~XL0Dc)Sh_6*oxg98;0*=V zDxc|eA@pt(=f#Aj+fwWl>K8WjjB~^3LkF;y+bd3*8WSdA!fo4rVpdluc{6Kyy0y+OxX{``xRCh2Jn2$L}3Z2@%NcF_`>SiBV3KO ze0(fU<=WClgh`n2Q519tw=bsetA!2!-Be>OALnuYu^^%?MP5w!YyeuG`N#U5)Nq2_ z5oRr)uZmN-wzLsp5+;1^0xfq}=IHlc!05emX2Ojz2=7lOPetnVAhTfa5d@>2jjgGvJL31@`m z#e}8(3DUj38f*FK0@_j~p)HXmOjz1mqP+8?<-j{XtmP*(#c6LBLf;bNyqK`G^&9Qy zxI>nppR<;q5;`)lgb7Rg$ROjD+Q4|lT7Eu+F{+Z#5soEHSlUN8y7yXREk9!` z&Y-&xxc8b7CSk(THXiHzq2<8*!CHP2hdHB?&>4p%Ojz1yoLlW1bjh-}_N=j%pYUPs zt0Y1}SYAw6+GkFQskI!K&sob)NsE*5E`&w^oEH<8ws~H@4?o-Pg>N=-Rx@k)St??Y zN+J}5<;8@hJ(8jO?ai#^XS9f^DhZ9qSi*#*JtC7hQR@nEB5U#KbS0sYB}gU3IXQ*IRLm zz}E&Dq3aLMiwUnoTjS6(?_e!|{#b2Q61t9J2@~EHY^_FZw}Z939b?s4Nucd!gstM3 z@YZf?PU?dltmXZ&xZB{X)Qr$|E$79A_f1b_csaf#XQsZ(?0*|CB8Q6-?PNmZLyP%`vE0F zzHC%{MUKDa&EF1>Yy|d%zbel;MMT0{{H^RZif$WBxl0 z_@=D?o`QW-mdn8se+Ky8t9#{NFw4(z0&Dpb#MfI(1l4Zwehd@ddhF}1Q1|D-->~Fw zX8LpTuZtCgw-V&#eZ{=8{!tQX5Vrti|8cZ%E{=1fDR#qeNsQf9CiOwYM02FS?)%|qy6Q4gCs}LH zejCuff$c33HO(!?eDeOm5+=M&+c(Ln90`wP{xw~Et)6pI{oE_o@^9nf8~P(AfmTWkYKXYh#i$Uuv5$=_YCB;ZqMdT4cZiBV>E9Rb4PPh%}A4MBw z!gI3kw~M+H2|rsOwegD)oRg_%PcUIE|Bf(zZ=yuFjmRq|O5<)$@XX>-jXm>XCW^eu zV;^Yw{A%s05y7Jj6Woqt8?5E?IoffF$jiYJCK~q-e;yd4ybq#xdF___2WxqsN53l( zxmPSyJd9 z2X+p!x0mfL+=B2g#M)P(&4NEcKh?tyMCWY0aoCoAvC!%Hxti@77^BZ4VXbS%8S#fJ zCp9L5pV1*NCj2DMb`97DYyE6BvoU#*GrHX5AR=&HO!!Hh?HUk~u-3|VBIr zm-as=KZz?5f%9Ub;fg+CtzT?sHV&P9PJR+s-UHygnBd(6Ek)upCu_}}g|`9QQrIXF zg4qbi5+>pu7O1-o*1E6BY@n`6L~es6OvL*>Y=gBPxexCTwxxLHB_g-M5+-<;N|dP_ ztaWFT*+APZ5xEVPFu}WRu?^Px*}~&lP){-a4Rc$;JldN(*aZWx?-)JZZaDuel#vWiL3ESYjnBdbI)z59P*0Fn>4^SUJSTD+ zoEH;5#@Jmow!vCHuH13qKKXc+6S)n}iwPeq?RFd6U@adXk3M{_eB8~6+y>{xgpc`l zSB-73mXGr-XYY~EA32fR;Jlddxy$aVu?^Pp`D*Y&yXEs>PUJQ?FD85rw%cuNgSC9# zJ^l5a^Z7g{avPi%6CO+0T{X7BS{^_AVa=WLxFjcX8=Myt9uwJJHMYT89tTZ(V#hqb z%8A?t=f#A_c6PgsZLpTdb8o*lIFA!^BDcYLG2t<4e!DI4@rt!PE`4&$;5^>ViQER~ z#e~P&Ig#67Esw8ZqahJk!i29G@{;E^Sj*Q5sH=uVzWzX7O!(R-e}cIU*7EfZo_Rwe zUq>M?CVUN-w?wxQSj*RKXuFLGmN4OK(Y#0HHdxEopXh^)36?P7YwCPt$ZfEeucI-R zG$vTWgzpXHBV2BSwR}GSV`5{1B~17pM?O;LHdxE|H88d}CRoCR@73fpPHuy>e18UW zRAYiAOvE?ILlKt*)*7|?MH*9Mu5C=Pgo*fmJKJEbjv;0PF+*d5B}~LO``HF-%{|X- zAogiYu!M>D4F$HrT9@8sHW0%#CRoBm{N4oHV6D|2F&l_Q8xt&HB7S3pZLrp!Pnr#j zsclcr-Z5c<^J2nn+wC?Y64r8iSR0fGKsdV#EMday&~CS}4c78{!y2bV#6!>wSCsUZd-^P~v=P2q!Y-ctdPIp}t=1G;G4W*f?(530 zG}TyQX(N2qhh4l7$^>h*rqGHB`ITe6FCoADUSo-+jquegda(4t62V%ndb$)7@@vg% zLw@|J5=$H5y9pRkLnsrh)tW*pCXUR0 z&+GBiXEn3L(nk2M2xf*5$^>h*rqGHB`4w<22Yv;dC6+eAcXu$ug-|9~OWLt$#f1Et zx!RCles5-prH$}iD$LX&lnK_7-(eQ5nDF28!mqNk#L`CaZd>uTY(cPAtG@3V6Y}fw zD2M(YJxeTYgxf~sl)o*jzeiuzYE7XP6IscF)Kv#dyc{6B4iN!Hb(Im8uh%ZLVj_Ej zL7sUBOPKJsfJioa<{8nNB42MM(29wyB?f7`9V}tO+cYBbsO@G%Yl?imwL>c=vK|$r z4|cGG3GbU&Swwv>BU)4B>%A6QF_Dc7LB^6gOPKI61}mg!EXfG@R+QxHqYt!VA{*g? zjEQxYFyUh*R(jExm=Uch^7T;^S}~E0)IrAfI!l=FF&`_|Xl&1j))e{rYyhp8$Yz`% zb5xxrO!(Y|m3K5pWkhR=e0^4fR!p?mTpK<+a7djcO!yp(9fS}vA}NU06#4q>46T^B z%wmS{j(jhJB}{lMft`>LG9oF6))e`AlmV@nxY#0@aF~4egC$IOOoSaBxp$t$J_RB3 zpycb(60~CC(>3hf*Ei&zK1-PJ*bX~WA!I~S5b}jD$=9PkXvM@&E%tj}Psu%fmN4Nl zDt6f9twtk~f@n>VuSc)YiU}Qa^?#B&OPKH|+-zh-B0+LSw5E`F3}2+%^zZ5w-hB=5 zit}QEciVD8%Td;{GR4HCwe;QB@VGn=miSr(wZOY=@+EmAl7g^&P0OB5Oh_xid#T#4 zSi%JFwrRW4H(AlH%39XOVnSNG+CXb(iKUI;-8StXYNH@n%lb-8NUyD<9O$(yv9uAq z+ot^-g!c2Ymi76V7;nFo5<42^KSCL{bo}WpjH>NL-?Ig}8(zmNvq7 zMJ)Eoh@>D`%VLz6koZb%AiiRWrH%029gE>IA}I*gvREr7Bu-Qth!a_2X(N1>%3{%s zND6|rEM|-eiFegTm_BqCODt^!@3s|h%N7J{S%e%D*}Ja+Q8-I1ZG_vlwSm7aTM(>e zF?>u=T{W}B%Yl5o4sDG?b(Im8uh%ZLVuGG|GfSB8wqR>Ddgd8nYaDMS(25CayUi?N z!rQd1IjQYtgss)QwL>c=s1G)?gbDAPwsxjIm=U(-^j-_Cn4qzw#u6rcjIlic8cQ<5 z*3LfqKr1F_Osuhl2_GwMFN4O!jIccbA4Q=R6EwEhSi*#l`L-vM5ear!%38K}5)(8> z)mY;52lDl~%l4LNj>-tj*Jm|o#f0oeX+OvQ6-$`#IoS5dG9oDm+gtK^7g{kPyJ{LU zU>}YpOn59|dwm&^6om8-$=9O{XvKu=4yq08C$fYIkBMy0G9!|Lu)RKygP;`?Bi6PU zZkFtevV;kb?QHKgBa(u!Jxh=JpcND4eQLY8%7n+Lwuk)fLcMFxTs^6Ilj}E--(8w4 zzsNL2ev#=u{lzJ~v3l6BYvfljE*-Si`q!r+{6(Vh9zW|{dsc`wGJ>^cJ^`05;;wrok+2r8Ya0^5cM32L`idUol@oY2sMGw$R$wh(pJVhX z5r9x~y{8XwkjU!_c`@P7$)Z>G%1ekofwt>4?d8a8H}P_?#7mAR z$T_J6Clc23nno)r5rSD=v4jbKvNk)bm8^ewEP|NRV+O>yo>N}CxmT>^5db3Z5>fIB zc`@N$m1~!G3V3It;S)?)i}yXd_`Q-sNmaL|!q$`>?TB zEThV)5f?d2)Yxi;_tmXM)Pp(AdAu6Fh=PHiD02=m$Q+p+|Y`VwQ-AgtdG`MXxOpxmPS< z!bfmhr9$0%6iawr%Q?kfu@ahJ8+9`+gBMo#1xPvUQYN$({#~$Uaj;i^~^z6CcO+39z$=?(k4@~`V+QOL)uSF)f z*0WM%Z!epcKLfn`Y-#^{URPRbu=a*@Oh79pmI$Xz6J@19ptRl8cYD7YX%JouA#^2B zi>`&V{{nGAd@rkQc=U zdrr^~Vf(dbG{1IgOZKbNzWagk!*)No4i!k4U@cC2t%vZ2cyr^UCpCXG?^jW4M++Z) z4}Le=eg(XEf*-?wA>Pag)`AUulOb*;*(j~<;TiBgjIB9sPsZ2OP_(rm5>*7+F8=N< zrc8KV#WSA|p|i8+)s^rz1{+0Og8F%K*Hd+8!qf2T;cvI=#NRjHa&c+>M93FUjDVJ; z2SKZn0Hl3{^Xftjth6EhyvWznm}MlV5~0r3L`%z&c_kj%*VmlJ-=T?;Tj@ct7N@;T zAq;!wSlzQ6nVwWfIiQ6)aXRyg>WT^0LK^v&iOeINaYSnndBPrQI+|;p$R%Ao%ySY8 zR%#FlYoSJ|OfdmvCD^Mf!oAYxod~8+kjkO?LJK(+wJZ78U=oPda#+dbnS)5OR>EH8`NjnNhYkD_N&W;q z?d=#|nGGUPS4yxJr=39VJ_2p8p2%D$&*E@R@37=zd75jtF=1NUcfu>n2?jD7^8c2v zX&s(vq2F~O*elA52}_%YqMrRjogJ>V>o&ZN#kNH~vHvO|9{9HyBO6)^Uh=#p3TQUG zeu!4Wy~+u(6?sMZa!pId^3R|9;p$apgFM_mOXE2~JtO4*jmSzqu<)u20Vr!*EMX6~ z&*&~Tgk&vCn}=Np(ZoO00NY@#F3&uHdPb0SZj~|NWe_edxz>-@o3%t6+jBzfSY5Fe zr>zc0J!@n8F6l{94koxv+!8Y)F@m+&_b!Bv3>iTsk88K+QDTD#*5bCr^@bYCo_W%C zW=-m6bo#4RzUds$bD*X#nEOrVeQU0*=_7ahTK?buS$*wv@eV4v?(Dgp^NzRlv}r%h zhv@$|v+>Nt?&&Xo8ld#Z_qwMIZ6vI9?V8&tamAn>jfpUL)at4={Gx8@8^2r4Y%JET zOe9&!18co>;;KqqKQWXEDZG`O{beE?xu(*nL#-*dk+9YtZ~RiVP`f3~ ziTA(ywsGwytabTmh&V>4yUqQsF%h^NOuT*=TIlHX+GXd+|Jy$+IX{Dgf7xHPcD`sn z&m&>2qv!Tj;t&6v4-t9A#DIr-D?M#q51B*QE0&yj@|LQ#+L{YBeu4>W^j%e9TP0s^qF3& zRrv&SuUPBjr`AzozI`xZub4Rc^R<*lpO3v_$#0vj7h#m(oRn~{0&8{5upYI@5*37C zr;P&0uRbu89Uv=*I@z!~| zVL1}kdhRJ36EW5{B%+qc1drhA6&%BSo^XF2xrmL_@V#UsCs^w@M;n2XHzXpjnBZ9= z@+$D0@zC;SW7Mnj8rw)%YwC$MM*Z(2H50d9W#i*WnHgfQ{{Am}w(#VW1wqVXddOvbf}b@8?W#^pQE0J&y~&JWQVHh!nkc ziD3)p>4(4lwWe3O{6AfuIcs@(<;y>peTFWCm%hd$gAt=k_S`Frcguu%$RkEfxF;wF zm#LBvG^w$K2}_%YA#@Kx;@l8km^!r1T3p&nA_2i#mL8p=Mq|QCf^|WN#zfY-@be~l z4x`g&dwf+q4<%SDveA`5_F5L!y7ZS80c`WnFFIcxVe!LtpL}69a$?pB8>sas&-t?R zsKGWnFR{s&*)z8?St&9b3Fo!OUoCo>Kfzl6e959E*kf-a8-XQEG_ETy2h%^!?G@K< zUUDw&oo8AkgZg1wy-K{~to8NN79pW_OGIviB~0+MQ5!koy$Joz(`fmelM;!0#ai6E zNXgez4@Xop+yr*Z*IHgd06 zt9dA9%dzR^J-;s#m0mHyH4=Mu{Y!{H$ENrE`K!(!e?T-jHhtruugf-auUKpMoe)`$ zO&{3sn=(=96%$+|u~)}!hS6Yby4+@8cJ}-pk@wj2mJ7Yt(lgJ!Vy(aa3;k|vdhin7 zc8RF;iV3a}^(wcq&N>*?#->B0-;H6I>&)R~LSX$lKb|2PSZF?8v6lDk?VqkFN2OOxaE(M>1s`kSm5Nm$F{w#pH%(kmvoMnd>u-nWtR-h`Y6H9SF>#yx2I#`mzwI|zeyy1$ zOvo&%HZY>fuYe!1YW=9Kf13Wx=v`{8CFe$J1Lp=YaiP3RU4SQAE zz1XqVako!jed7@|){^rmwSjY$m{|757dj?=a&Eszz@m?iH)9yn*)enaFvNR}`m(TCc=EE>YQ?;X^!*VBWizx>_F zHP({zFSUVFvY5C*egpKa!5{X0LEeL82@?_ls0~CPA?&yHYqM_J{GRm+SMofXkH77czIYz2 zC1-bP1J67rc3$(K=AZT1dHO5zJXpen#6fDqp83a%+}QlVj@$P;OWGA{$;qGEK--N8 zX;;nZiswv6yJ86w5~-;TYrDryd$IYkH!kS+3+W%MC1-_d1AQN#~f`Ugvx zkZ4J5SRa&rUb}4Nd;6iEvzDAFstt@KF>%M79<>X9dVTs~($87KghXd*!^V>Jj##y} z)LyUj`%cCy){^r`wSh4)CJy>&mD)pBF4W%R$z5tJVM5|ZwP9nTjJvgkH}BqrahJ8^ z1XFEbY>x>UcWdKktk8~emnBR{45v11Y=8RN?P{0ov2xQLGJmj^oO7xT%uz8R^GEI0 zZ#Qbk{J|0?BxY0_Hb*UY*xt2^|Fuce_c9N%mYkoe4a~JMaoF3xt6lu>f$iO89%M;G zoB&#O6LhYfeZ!%({#y)c!hFtJaz{gLAZCy_n25JGIkfiLnftac`|PL9EMY<-OC>C3 zkhrAw&(8gt5SOr)oMx#F#6B@0aY^mob4Rr!E@25163MC!#J(Xs{=?YXaXTE{^!S}; zHnWzT%Bc;+a4{kARc+MUNju^zmM|f)w%O1aZlUML)h2(LG#zpIn$4^w=aFgyv1m+8 zmGAY99@^H9IFThx$O=GhSS%{>ZtcZ+ZB2-GSxe3%)dnKun0QCNrPp)SOWP-R3?0A{ zCS=!HZCFg*eD1_r+p?E64Q@GM7Hi3gyV}6Hb4!6#2|U*dycuUeKq->3`>~swt&-t5YAoy=-T#I-q-ZOQx9~omYm(H z4V+HL#6Hq?d+w07Z#ZdI2TPdnHjUkSsjHoTUpuPzgH0!_^JNEX$qBF8z?pDNOqD+P z!WmDtKltpY9V}tO`zFp1XwW$M3#=owel7mD<29EgzMP_)5maJGXkLy{~+4DUuN3 zVdLiMul=lPwT*VGvzDAksSTWY#l#Sqqk8`^r@i}=yVP02gwI_#Ns(_fZq&Ut`@C

mev-9LM@Y2(F?th1J! zN2(2+bH>Cn5;I(R@Kx=P$oI%t!i2{XIByBzkmaT{|KInQH*FG*ud|k%V5$wAzQzP% zpV~@8+9md>vxEtciEzFX!jR|pZ$9CZeVg9c{FFLt$(g6xz{zM#>?ASVXG?Z#ml&?j z5+*#h!+A>xyDa_kfHBL?>(|mYq0U-zGO9LkmKqZ+^7Xxzz8g+|TE26~5+*!G#feZJ zQ}>gYy3Sg1;+oqi5s0akU%e1^Y>y|^l z?e~n7gC$J(n!)Pop6B=PIQG#mrvF=>2W!b$y4t`qj|r@C7F~DeCRyXuS;B;`ee9X9 zvD}o7TVL6+y`Quz){+xY@6rXF7!zaS0@(xDd+-xYugLfMSi*$w4cM3{ z<8FQMv?tn6l5v-{G(BZa!g}F8+ zPLRE&J8!?c>Ax}$vV;lWbF#Ts=JWdHPfl&ee9l^O<5#^x%n%cA$oKlbo^(soYBHa* zgbCj}vzS5RlKNX8-O`S@gtg@6q1r&~6B81b)R#SLN)zG|mN4OafEN2md{sZ?{Oj8h zU$K_lRa6^@;bLMt*|VH8>WU`BS1e(|_cASplQ^+HcG4B?h!a^$ZZxV5#G)}Fabo?s zVHY(aPGkuaz9(z3sKmSV<6gO_9q}$}@qThl{3yRUfbshKi+|n!lS3C4PwXbxe}8Z3 zKVS8Er~Tb;Y%#%FmL8p!iFv((+Iaiwq4o1V{k7UyUT$ewdUT33=M+LlBn81*W+Ntg zOtU@x2Ok?+w>L(t9F{iU*|vPmszk7s*^3FC*Rnfayx;CMigk^g0!aC)?lW*J;ip+5 zlI#pJu$J4vb1o6$n4VPQWHh(V1bb_xaDw|e_eai2iQFsJ;@(vvD!pQYYb5rHM`|8X zOEz+^Sc}KU5>e?D6I>&)S3KA9oLI7vd&OEj!@( ziKz6739gaYD~@+LE-l$`uM*bcD6>RVdc_3SNbD7_Sa@YovXOhmTD(pu5tUvs!8Hu!8Kw&W#ve`PhcnBdslV?BDRrx#aiB8vs)H1 zQRx*ETqChpK7QaV#Ydv-wn%Iv_lmW=Z)Z1BVxrP3Cb&i-uY!-Y@XAN+>}E}DBln86 zd>pJKD!pQYYb5r{=OsKrpW)_P@`SZ~&Zw;2O0SsU8i~E~IUKFsqk;Lhl7zKou$c98<>%3o9A`-7%*5X~f5+SbH9K{kQxO{Orcx}lmNZu({BKL~5*j|aq zyO68UxuXjZ| z`-f*zu#Si<*mI44v0a(~CRmH_Ni`-|!UWeyWFz5wGJG$G zbBYPp;@d(EiNF#j_{qjLEb1FkaUM}bQA#AsKsd-~VL7(>EM2v6E^2r44+Ov-arJ z52vygz9_fcpY~77#5eYZO+CxuyqNIxNf$h4<&eVI+Tg!mOnLxu?W}7b>0DyF<2C)C zA0NxVijbGQn#jJL0IiSyexA~2b$c+cE3>hB$5GqDM(g{JckZ&rtpBVWg9mT@07|>@?w5BiJ!el%ud(`-`SZZ@ zH+{FkPwlODhA6Rb&nI&te}aheR%1_X}N?7Z${eM#8>S@oFiQFr0iA->N6J`BpwafnQy!fi>`xVn( zESEg-lC#!R?N`h1U5-c}`>BEuE9EE11bb^PWkkYSzqtK9`O@5o^vCC4{2xos1lM|G zBdovdliMO+v}*SR>D@2*lm5Nm!0BC{AZvLVExbgCAuBmcn3%fh#bY-#wvn*b zSsz@a#2RZg3_P=(it0iu|N+tVUesAZQuU(<(d9&Md8~NBCyd0d@ zFMesnaj)H$6Xll3T6^wn_KsZsuEs=Ejw&MeD)F&|wPvmRCoRXIeW&I&aw0E>w{}P( zf@(yR^`EtNuAfgHyz~LIv76`KU$&8WU9nc{VUv}3v*!b4LadZWQ6}Qp=Z8Ho%Y<;p z&HHxn=z}z3IE-pM^2xieMkG$KmPdUtvG{evq#ww=(dO5hxkn-G1oxW|G9qz;wU9<1 zjEOtWIzVl#_1(fXmLTl}_bw^15s4G5g*19?OdLIDC$;g&&a2m0g0vHHug!?W3D!ay zV{l9?+^e73nEk@$HI^Xl1dqodWJKZwYaxxXJthv=dR?`V9I}0lB}hBLqjm@xkvPFx zNMkmLiC4!isWuL|d+!=ckai-T4KgBeg0+xFlo=DBUifhDS4Q5^vEp5$YY)BlT5Z|? z9*{0E@p+AwdcS;NifD;f8FC|j@=sg-dej{qiwJ>e$+g~D^P1YRHxEhANV^hfx62E$ zgb-W2(@lNH%4EjZ+jYV#q?iBK2lb~;KOnuO_wzC)CWrj_?#(hAti`LXm>B*1SH1rr z#5Z@2uCas(#EeVtb)ZI>@@pP@d~we#Dfw#R6>Gh;{@>~&wi=SYb<7K$F@bV;$$5n( zWzv3*a>RAD>q2RtWyHodR`Og6abo+^`=^L3W8%;!|8mb5DaQ{|4wf*%&q;opW6n8! z9y;=lj-AB@qOgnB9;$I$|AlXCo>Uu}e)GYLU2GiF@0LC-LL49jYdtq<+vW@Q8k(lx zbtOJLarnLCj=H1cAL12j?RMy418yHOG(C7;R|0j_U&^tt*x+(7!L=^mtX}e_-ggM` zx!7PW#HFtvI8@`^nAqq~ci#IuDaXNLgSED3-M3@iJ%^?}zJ0OFihhf$_q}%se;%YY zru&^8c!3n`}M6Y@{fbk^DpgMSD$?GZJ)TL|G7j~(BqMZ9`S2=*5%i-}(ylw$qC>iw`h!Bxd8*20>j_pS%&N{`!{ys^Ghk9+nP8$k$` zFu~6$gi}_Wc<;($qrVXB?``8I*0z87`q}N{C0(R)JD4b5p`a_^17CD3gNL`?pETn?~kdob@qzs5dO2qpPN^Be$31_ zzdu$9pFen1i-~bxb*PPF&N^Dlfk+P{XIH{U)DR9jW6kCt{(JR|8SK0MzcBttZyIYWaK>6FvX9jMnbz zL&w)yg0vG{>mmH#jV}!tcHL()&$wWM60XH#VodCE{KCz9AJH;%tG|zro*)z4dO|q( z_CL>hXvaU#_-LJpbsj}|HsHOQ5FXv;@L7jVA2;)FS4^z47SB;Ju|xOsW^KQ1x0&Y+ zn^BcGFFsR<@UMAsE8$s`+d>E%-f}<(h`rZ4 zrOx|TJYMn0C%=($TdiZUUtclf`jbzsvxG-f&MAbiKk3ymd4=IKTdp2gXDyyTVxn{U z<{dLTzMirB>f<7>nBY1L;ihqmq8!OpcZ{!h)$(~TCieK{tFqq~!h6Yt=y^cP32qA^ zJbQhjHr{&dMD@yN0QNl|+xKrjzhlt5J!h^o?}VrvyvrFA7u-;B^k0(YMD@ zb(S!}D}WGQfB88r$GXprsI!C#q%lWfKUu!%w9*$!%$WT9I%{>^fo@E=gbAeaciY*1 zc)(J+@_K*5@9M18buYXz;Swg0#^15`F46JRz0}64i)~kDt**QEjR}`9fi(V(69M@m z&>2l?Uz@Dm~aUbNaOD~rwZZ3 z2?wf;O^5%i&RV<=Gk?PKVghOW-A=GL_TdqcfGKmMoY-cPnVF! z=~5*ToIsE2O7N*u2#d{FLv4J$pd^RP~QrJpuEWb#f zI&0z73N~<#S4jjXU;~~o5ubVW9ynNS{Qc{->a2y6KiI(eU?mZpfDJ!Ubb`+fL-=CH zebvTSOD|sMd~rSq0w;=I6DH!*jEnX?QEhy(WNQa&@t$QR5uAVx zc)|qle#$Rk{)F9rS=o2rr^dTZNTVEn=7}`UJR1`@*>EjB?$=O3_v6O&3JH~|~*gb6-93E}RucT^iU z{(j9GYvG&%HgK*|NdzZg1D-I!ryQ~~@yxzzW2M?+HP*t(25jK`qml?tzy>^Fg3m?d z+aj+WrZ%qH`~7Ct!ubbm;KZbo2u{ETJYj-QPeRz}!WOmBuioCwS~v@V4V^Fg3n&$mq|yBQyX_&vtcu9;q(MH za4J(t1Senvo-n~@FCkod{6w|!*xWM)uoli(U<0Qzl|*m?HsA>pd_oh#nCHyK+Pf@2 zi?wi?1sgccsw9FFu%YKeMDSUd{ND2U^Fg3qQx_-upWYUBLw|L$Ndj&~}F-~?>I6DBxv3gNGlHmYH4zkBiK+F}=eKJfab zcSzqH^iU_#xE+u5WhZ^1>6@2-SjP571ZyFE@yH!gBbL}?Mc7ErynOc>Yn?RqOU?JF ze?F`>NR&df4up)8f#5{ z>KnC@?)_+IB@vwPyqG}xqZxx!(9%B+|GnCnKKKkI6m$ryb>4wpgJjN96KkyX*zG^4jqbNR+F3~i zCp<4EkpBIHJEovRxO|5iR>H~T38&Ur>&3TzR2#Kp9__3of)kz>6G+#;+A#$!^SRtM z{BQP)<||xrv3&WiCB1d_#hoi$f!~=On~s)W?)AS1{Uv20l32?KXvGA6&0NY6hxSNd*Nht|XA^-hmm{gO^6kly>t z*#nQhpm)0L>to_&_C2Pk&Zt2@@}#{LH|6Z|j}j zbOnfH>d@MWk1X4CsSFaVwbCZ$)eq}k-We0;et(GCXxa0t4wf*1^vW}Or=UZa(Q~*G zhadIt4wf+S%6m@_ob_1mwAXYHTfBB;ZS4(~YdWg-v=XQ*b>4(4J7eOdF(;^vPmj8|gC$HL{m9Syq@ZP&_GA2RZ3ykZIHrRo zOblD=>4D#`-Y5NRm8*pKX80+!#lK#zY0v-ctpvP6UMntSUM<^xRcB26<=#`(#>H3m z?_dcNNUz_oPYODOxtC7>ku0_B3$s}3)VKaQ5cXdE?oVp3LX!UWR4KCX|_D6`(& zNs#EO1skLKU(;Dh01Yg0+KB;E`zS5n#mUMsa+wzfu$Gsp&nefcjS>-@a0wGgUp}W# z3fi6r${^39nYH{0-aqX+t*a6doNx&fNT0l8-xRd9MA(p)*vwkqcF%ivN@pbzobbGu zK>8O~^i4sBu(b3+*a+J`-OO6vYj<1x2JMd}A~@j^CXhbtlfEfvi9u!bfsJkDSL|5J zN1{j8zOl2C2u^rjOdx&P;C?A+xu-AVE^NrSTZ^=^+2DiqZqhNhLX;$yoKLf>&+ zzZ7YkabRQRT{o(+md{a`)$sQc5u9)d6G;0kD!JoX=zo(s-yP#SWq#u(zdINaSQ|j% zH};T@35iP(Cu)=-(L|?56G)>EW^sw8^GK$Wkmx1XLfYdMjj!xPQQ|Asl9);fL}8VL z##bz10%?!CG)~lWHAH=^C9$E}Kr~rNXq?CrCXn{{QR7{W6A`_#mc+Pf15t4$q46$D zm_XX&V2#@~PDB*WS`w?P4Mg{qgvRYGVFGE7=XL#|Hn5stEm?D@4Xjcs30;4%gbAd5 zU83tKwSiR;YsuP4ZD6%kN$5I?B}^dg>nmLk*3mz(x??R_1F8+I8Y>B153+;_q0CXn`( zehAx*I=6Y;J15jmz3|KdmpydSz}?0VNbh=Lk#ycerw+o}VD|C%bk6?V{@(Y8MP$8@ zj5OkhtIiz2T1Px>#HG)4CBB#S$5qR(()$yM_)lH@(Danu4v>7d>Rj*bQ|13#(tU3~ zzjKi+#1=xZ){d(l zrCO7(xDD$lB2a3n;~M^Vi7}6LKKVp*+H=j*I%n@WQ`4{Qd0OZGGalFUFLpXjypn%O zMkK5?@sfWmn22mFwAJ60Xn8J)?8P=%Yw{{ay!b=~0mo2|$SWrP@x%2P`R+03bhS|; zf)g%b0_hK4Jv;>+!e&byto5`+{ihDrx@)f47R_!cYooM&?m45ivyuo-cwS5(z25mpq@d*n_Up&1jY%`E>R_!Yqs_+tGtcO( zB!Uy37ZXSy_WBVi=nx*7srU4gt8Uo6gSC#j*lgVO{h6JWL~z3MVgl*MHy)OPmfLxc z*&65jr5>HdTK%S&jb9HqyR(uAPIz8SAU$!+uoSf1_nE6-3r()>yVy3Y_2RW=W2@88 z>8vDz6P_0nNKd_ISPEM1u>8)-k+#1-fVFlx-)yY@@VT9pL~z3MVgl*gJ{^{VmK*WU zoUG6M=sW(e`5#AGzPofkuM_Eq)*7B7&2$J~{pO_Fz{S7pf64fhm2j;a$B#-o79F16 zba-1A;)dS3N=;taXoqIbt1D4>HG2FAcolBi`-SHFdz)8V_Bp?E+UM4z4jp=drZ+lj zc#3ogy{;puf(TTNrM zLru$XhFv~JZTx1n%cAGemGD{*VYx?lRbuNYE7vgA`uNJ@?g`h}-_IU%q1gECEx)N< z@5S;4pE}E zR*xD>kamKfW(c<&xPR^GF=6Y&URp#6*ZTOek?Ha$4^Myfp*?ey&z||bf&ZsAzCU}8 zK696JCA=+2UCroI`^Vq9Z+-GETbAZ1ueZKW9hp9R$?)`~VHZnXtv`HgvoUPbsCJx{J(@dp!pm=|}6={&LUh{m1klsD$U+_B*q2$JUcO zW8&P-wbjPbSME?_2@^=~bJ6e=bO_royOI*Se7akWB}{Cv%#rCA=L}B={t3kJ$;;H{ zY;=16)!+WD67ULn?f%pVE%_r~PwtF~J-=OCZS3>6eQGRW0_hD-8=iueJ>)TZ@)O>A z`Jft0nAqg(5$W6$hNp9P{DTlv*8R5muWu&(kKFPQCEykE`o3mf-8%UXoiXu?EkD$C z?YoB^R$~bhNS`udcnUg%%buRC#O$4qtg(cNcfTH<{(1l5>7SklardE*G(UXLg#N?A zQA)roQ7i5T@>tC2NhJXJ-?K>1l?gak8O=+lWpxstAkp zq3$+V%hS+uuZ+0+jN`QA$K7{QjrU8qw7hpB&zuO>;<}0n@+xe6|GwHXV7Tu~ z@qi8AVL{r?)ubHq&z?EAK8{N{4mN!!xEFChk7rI8$cThvAC9%yw%W)E*5U{-CN`bE z!Bp5-e9$-3cyEdKvbaX%R@gdImH7F&A5LQ}e$Fwm#Z8Ca0~=dj@|USBVS=AcTn^Ua zc2yz-v**DQCgNuf^^8bZi|eOEan@@an=PkL=6)C0uX3 z6B5}7tR?%cSv$T2rQ|cx_o% z;`Nqw?qRKk&iqR98?84IVq%F|=PB{t%vGX3$OP}U#pU2QilYpUyP~>ESc_xE5|P&x z_f(D<8uwb(VtXYbx4{x7;wT*I*%OS)!L`ts;L(TeaSIg-WP`PM^->}LX}e+x6FiPZ zHUf`Pyej6LA|hceUaOagO0SsUQ9FdyyA9TsIHBLN_i&5j{p7gq{_xkiTcYF_oU!;l zti`+BF|pYarztV;(1oMc&IIqnYsvF+$mxsrXPno_$(W|IQ&LUaIj1r9Jh(r5I=e-X z=cM|Hx2q~GJ>e(YX2G91d*$iuPJr65Q+@VIPOx%`oQ!E2C*w}rd6W?DRbVYS$5R65 z=OqG=wnUaN!S!Z7IU(nqnlEZm&Q&#yGhxn2iQFsJ@-)tCOGKqt5s}r1o%TUJ^9rZP z>Iw374{=88b(j;m4c79~;>5K?k8+mB_g-M5+?jP*~zG==Y;I(4#bWyc7bKD zH&4rsu%;__gmW#~Pu4W{lN%C2c4buyyRx!do2S{Hx#Z8BwPbf#iEIy9)9_Y_yd0bt z6YQa^1g6ZI^^fN#)SC96em|d0@OcFOK61i<^qaXjo8UeDFX#QCv)`6`$zQkXM7rnC zSJ!mB>kQ(WZBE}DrvR*lo%D?#*;s2jCirZEB}^dg&j}^hFCivKtiSn$K{y|PSDwCq z%E&D3Ck<5uYjGMm!G@id;KXFqQvX!zc!CoziPKZwYECzqg8g>;XZ>8FKJm)d0}{_^ z8tXF|cL(C{i02~$QD3elQKo9)Ot>L|_$tqf35kRC?{oz5@x@%0Zgb9AKk&T44B!*WTIAbXhd0nxD z35hb4ww(#6d+oB8ME9zNlb8~b+h7S3vQALi&R9e}C%DDQx=o(}R;HzAo_H%^Er~3Y zz`C|XVBKL|VOmKfRpQ_5izDvZZ<*;)cDn}xbzDly)K}};%PNGar+vyS!h-B1v zzj=gyj=5ImdHp*g4%JWGEADqP*Q!<)`)In<2NTwEds%!H6JjWjmU2l%$SovzSdQVi z zJtuOnSQ3>fn+@z%G1R?wBQ0u6{`Z{7ZE#=XKFH5Wl=Yvs-GsGdMXyf{r|b=hz!D}( zZ8!09cpvn8kEkm|;oj5iwxKwc6W&UoYC;VTij4VEw=dl^dOJW_s}eCdtq zf`ns_Z`PYNeouyP*$g>)Op0f7&u_;UMB)UZSKPlbtrpdaiC^BoyxKVP#yx5*VWRyD zvoUP;1hJ73NkLe?rqz-{D<-xcGPeWecDaU(;$yp%oJ=&%Io2e6ZV?8cUei=^nFj z?B}qN5lKNy*C`TL%z<+x&Vtkp6iDG1Bgv|3VV#l*L5 z_u>v@SoensHI^{(yE$g#{oP?BBa(u!d`+t*g;q>VT5qzx^E3JDi8YomG2@z(v>c1+ z-Ka8Q`I=Ts3ayxUqIsU)NnNbp*eDa0uW7ZU(29w(j@e#q9P+DmYb;^n(Vxu5-91hg8)d@s zHLaEuS}}3j%X_PhH~TMHV+j*$A2?p?>iIXuij6X1`I=Ts3aywJ_2Qvwqu(AMH?xF^ z{cbiJi(ffLY?KMh*R)zvXvIXYCi_0aQ)6c~vxJHB-ZC5A`y3}W%7o=>S}iHGVq)qW zW3?P_op4q&OPE-E$q8Cl_s={=Y?KMh*R)zvXvM^Dr;Sq^vmafjnI%jduz}e~wm4dB zlnKk%v|3VV#l(+O?5^6Fy@m{62@|rHW#y2)tPskCCy*-UoQF z0y2ZrO_u^5pn!lU-nW43Eg;Jm5m{0F%dQ^%fAi=N&t$wASy@?`kx^AqSb_w`gIL%4 z>@0D7Ph)!du|AGK+F0L!b=QdpFd!I_;b$1ubiOg*=Opxb2A1(z3S-VAV$`ea77rp~ z#j_)`*H^X=p8kHHfO4j0Cu~jzEzYbPxI`ao!)F_)#WLHA6Mcy|)S}&s{N3(~*g#15sD-^yBVjc1&!bOU$g=*O$Fa0ZZ5Y&2ncv}# z5!^88VJty{W^FkRyBe^%9tUdC`XO4p;?zhO@+?G)eG&2iL}s4>Ya$C^1GQ*97lJ*2 z8VQ41v^opH>v@fYk6N_W3c;&$jNpbzUttLn*b8zT5rLzG_Jd-BcaS(1gz&X@QHyqW zLhybtMnpES1PR)=32pa-VkJBdETNs3Xz^YRYjRtKTC|T6f_GjqqF}3#pdFIXcIUzQXg48Ryi1AMh+2hOv^Nlf zcM~-eSb_wOH)>O^uYA;^y@A-^-9(IFC^mMHz-v=%gui?bpIlTAfM*|FYgu*)@;?Hd zk@3mHnu#l~`+51U*UuxWWp>6M|6Ts-PAjVq=h*Q1SZKbAY*@KWXgYHG*UE0I)~w#J zoZj9SEwWc!yXB=KlfB}iJ*^xOVuRXS!oEm&v?ctsDa-mcm(wajeUFd!l6Bogi`J#+ z-8Jk5u|f6Q5sz9d7wR`5!e7>gY9Uducgc<~Z_z1%{Z^3RhIv?m1dfHMRbs={%AJFP zgxJ9Iyy~UzmOs??eCfB?Ij8z4i{P{^4uz z_7WY{)YFk18;R5++bYzuvh`kLL}*B^bE?;la3t_52$kg@xdw@__0mX;X(~6M3TqiJot6 zT>jQ3ONYu~?{4_;H=6V8k+ZCOHJ7(OlvaNB{fYlK<_U(s>a3 z=aN->rF5HHbC2 ztwOCPBMwdJH5enJR-yG9o~f78c{fJTQQIR&t@>vioYHwWMnpES1PMI8P+9)*y$(;}Ti>8}(^^@TaUOFC)S_!J+oGGLYbLM+32LnqnaGVR)S_!UtDa1Zz$1_9LW1U) zY|Qr|%J=9=x$N@pN64t=di8lY8ZlWNWA2f^wa4~iopGq&iXXVg&OZFioz~xq{W2JM7a705&jb2C(=R!=M|SgEt(S}x@H1L_{B#YmeMr? z$D7#j={NoFd#KfXbEvfYtHP$Xx+8GZ;Xg+US4+L3Vnk@jJq{#z-PLP8RJNwXlhHn5udh(QSyjvV z9(%~zDr^b+!FqfV;pg`i`@7m#F~XXl^MN*a7gpnuQ~mtod#FX%{Bk{7Y@yY)zumq< z0%zBV@Yx2=GIXA^x(?#3Bm`;O(T-X?tEuM{BLrg`Sb_x4kB)!EgwF(CgDmTu$md*V zzOZ^AA}yE)YbLM+XHHsIQaYoG4Qi2X6>8zU8zaJ|i4PauT_Eo)r5-EJcCHQ7Vp-?i z7~$AZEhK85MNtdKQq2UGAVG5Eox8_@T66}ZH8Dm+$AKmJgzjEKWoycr6WK?3`uX_$ z7`2K7-$O0-gYIi&XEkiCYXeJ=!1>W7aHZ#KMduGZrl?guw+glRdepfjMudjs`iOcI z32I?hk11-E*q~WItDYsTC0X#{B9Fr*@am*%C9BsRUd=*K{o(ZiTI`+aRTLvaL+;Fg z1kYDWhsyGg@8Jr`Yx`-ZTohXqt*Yg$2cTN)Ka^J2K!k?eSriFeMMGt4%EMKLqZEHV z5>bmIA$rzuyty{81PNSyTmnY}jr^>(DmJcs;^=?5J|Zn1CAxCPh|rKb5|QBXrfYDh zEdTf(wYOOPS{xa4OvTQwh*}iQyOD>CBO^wHh9tHW)rAD^6K!+U25RxjsiQqcL^iMl z35>9Y%HeU~k&~ZL{MTzOYVppy#Oz8gA=;OSF4fOJzQ_A;^=ql8i*P(;(*Q>ryj1Y_oEJ1=>sJ>RHEdTf( zM+$Ui;Am8hGXu4Vf5>|UEslPvPmR~6)wRFfxdaK0wiUiU@XDbXC#yDM*Pzc$;#Q#+ z%~x4Hju>GZMFf^0K{IMrdn8nre`FSoN@xzw>es znsndh+Q5~JXE=yuxT_kq$o3U#@%*SW4!27E$H)dl(pOr71bWU9;p>rWd$~tpmm00w zE`eHnJ|Kz{C!$uVSCmg^YsCh&$R0Ur@rZ%g(*NPekw9NUY=pmPW`I2zd&PR4*L;1T z7GCo;6Ig--Ud_@VpMKN-?p%U1QH&6b2zgFMpN+|TW+tV750$Nr{3mNt`YaC7E6Xx<=vzr~oU zt5?dCHG?V34ZdT7@0GBe%cS%0!|T&a*Z$FVQ#Z+^6O~ZLn-a~QgEi5&o!3>%vp8X1 z97juY;kd-ses@T#_P1GXBs#?JrLmS0?$bN18$OUe^84S~wmwBN=|ozT@uozx=ePvr z#St5v7Y9r734PXxo@ktLi1h9WHhYq^irr*T9?&+r8)1OI( zrbvr2DV1neCYPXmOJalbEn!JMksBp-em^bq>Fs;8`>^^f&SvF|MBcG-zwuisxvX5P zwwxqKK8iAC;TXktS6t$x>eg~T=5#)jb8JO*AwgLyOEhaG<$5V?mpSG2@oj&i%wMR5 z@5;CYWxy00VFt{oE+kmid~5W)=p+9S;+0*Ji7hHYg7U4EXjV4LDY~k2X3ys1+qSmZ z-sBAOdp`Jvic3)LHn9=rZj0(df@RIOM)`Ly>Mq2sUrHvns00bhu~wp4*^Ie&bC1l* zqsO&vXS2OYtN49Ke5b`FD0iFK;M{Fkf&|OC+-)z-=p)4HX_DbDDnWws_?2k3KbrM! z>X-S)jxlZLQWinf!Z&JMf^q_ijW8!*R2LE~YaTyij!2aY@y=_K;V&vdf^zqjXtqCN z?jJuSQ?g}L+s-zNp!5~L+k@}?xCG?{6dRlq5KE9?IhPagf@1lKlG%ITQJh6EDnWv> zFP3P&Mq@5sH!^eIQ`ficYx6)#tHRumBJ=xEE-l$ zXbBQ5YkpzLZY(x9A2Mp?zf)f`p(RMLteKVB-?P3h3wVzXpD)4ZdRZ?=pq9$~tZR&5 z$YT^skg(6$+UJv5FR~G4*s#xn+b35k2OYiB5F;288(4ybefpDXl6N!2N=RUdeO|O& z-v7XwMBfi>_^4%{Pc4_XQes5GRv}@Zhb@=)W^9}EIPBAZtfhAW3KFDk zTZUR}gX32<5)APS6j?_CTT43j$7h0~QF4!->!lcp+?TJ>h7hPl5f-^eUyx8UPOFf> z9toAhBiB1sTrb71+`_qa6v2u!XeLZwbEp!gsB>gzs$dUCV+td^W%~P>b(u@SV|u1RJ0q zw^c~+oek{~t17>VptyQ5$JM!Bx+_=Acd!cD@Yw*{KrOl}SIl?G3KG^tUaOG69uZ}# zpMT^|LovtIxn8=5P|Okff;N0sX9Bh8zCkhH1t>@mz&~zZA%Q(&b?tAtD^sjBRA~fW-3JGqZ_DHBK|H!lF#e8>x>*W!{_sZ50x{`e={1t>QIY&n)4}FCM_K4dm^jO); z{L|S-T7_Edx9QyVe`^&I*dz2!i_hhoFQ!+o-f4XE0iVFH*mq0uPp@_hGQSsPjd^0n zNUwFQlYB zvM$l}h*92_N$uPIJnzahY90LA+r^!?Ule@(Mc+IkQ+t$m=1mVIS|8UljddZ>>(x!g z*W7{__)W#-mtGXCdw4*ejn{t}>5ZM)FHv+%uQY1S zTfVV)QR9n(Z^sYJBgStV>FxUaw8Wba^>SK;#F`g37T^9!mmo8FAhqgTvN8F+X^DO( z_e!HyQOU;QZ(ivdod3X}tV>+<+eq*GH4_r^YWGTG2@==-v7xxB-!*u%J?EJiRBM!X zRkM=Bn9g+Mn>G|rT6tk`=N*HysHNV(=qH)*ejMqo{@ts(^q;-bsCE528;XZ{U4w?V z4W_)N)_<_XlXXUUbuKASoU^ruW25eG8;Z}JbYZajAFe%W)$WnriUtD`ua);qJ6dfw z7H@2SVesy=gPaypl=J72-mT9*k~q??fK7td}vQ+ zv?FoNluwFJ-*8DV?b)u>yQAo;z3}#4&riO*cN(wG8(;mdI71%tGm{fewhj6=;MXI) zeOs1P4X)oijask&@2ld=Zt4~cJh&u}*hM4p+vmnrpE{?PGczEe&okL99)F|W-FoyM z)q5p-rBQ3ZS)Ug-IKErZbozPGdtR2PMQ8Az$MmV{IihD8>q4UcQ=5zbQ`I>*Y}gfa z!m)G@7qZam$OPsyeC~rsIbkV#zJ=0i%#I-v=C?3A4b8uOm9%N(xeMWh6 z`kbCPdP9#iYT@~CiLZ99N)CTypx5G)&S&BIz*$uHANGx^`hRRnuDYzB*LdIK+h_@| zeYj)6^JL7eXVmt(zSYCqe(aG;umlP0bz|1)Z@J?&;52OmLP#E z5#=Linll8ne&*|G1wQ%p`5>K3dwKrh>_sK<9cYgu3aOdR`TZi=Un!i=s>-PEI z+F=P2xZ2ToU)K%x7EV}}Y*Y8irMMr&^$Kaq(6hVT+iSs7$u$>uZiia94!XoyoBMl@ zby%CM)Az!qSb~Jxs=FQ-?bVy#Bw2seT}yEnhr2smC5#z=#29b+aogKh&%M7Lmf#wN zH5v2Ke{b~edZ1PE@*blTsD*2yOLUz-+^hP1a&pXbtE;gD3G7448&zwhw_)+%t+Zy%rRHSbfL;r*)i6?-fyv)`r>9qY*e;TO{4Im#tMpFwP3iONi9WXjqA z!Y`y1C+^-++q2{6boBBJ|&0KzY%6(?F>zqx(YSb65h zU|lLRq0ujE0|>v6R-E85OA#D74y;RMCNw^0ZLoSs_=U9M#6H(=URG_7!^gT*Wjq%1mgaux0|aP__ikJ{j8M$Z=p@Dl?(6%$f<* zLfH~e9nd_}kybVCE38XpCN!Q{Gl5ztTjH0aI%JAyRbv}im�N{IX^OwNSRi8J}H} z=}fB{+rYY1WU*%p03kD+ zJ}sbHapJYQ%`*)te#OV3T5LmQCU~CL_jxG>kRxQK*5?aUD^7%Kl-N)$wxKc;yk6;h z;u5*zRgDQ*arC(i)ru2e@2s79jN*xW9IC}ORAz$LU447q7$E#YT5%%u8N>$Gr7{!j zKWOF+V}KA3K%Wp%tvC_-K4L?)_&8K%g8iV}8=ydlC!^1is8*aH51D;9v7uUQLuDq| zpVN0#DNA#X5RZ(lqZZ0slQD0VZeI4)*fC-Q>r$Bs_Dl7RI)@O?lC7f_%GL&-YZ@S8 z1M5 zwxKc;cn5;s;Q7~g$zLzO#@o6zXp35S55Xnq{!&ZM>CE|^G4J_nH*ZWm@oV#-{&OSv zJLOT95*{JOr@ZPO=U7KA%uM1Etj!n`q!s1pV_7qkP)%92XS14 z1b@fIB@Wrk+Sq7Y71f0V%gugoF1fL}J^JH&_+88VZ*}U|Bt_e&-}Jxlp%%-J?f!f8 zbhF$M_sWW+jZp=@o?uE+~_MeNB$b*an* zc^pxO6=Q&4PeusTLfP6Nzr+i7cLwWHnF;bZqW9g!lTm^_8L^I9C|et}OZCECDtj_f zT`Ds{9!Ky*c2gL@~r7{!baYVU(#FNo@B6~7o9ko!lHYi5cK8&gvtV?Ak z$m58z0~rGZdop4jwNSP;xR0n~#6;MZES3qk~wN%1qGxbI71vh(IlrtqpqCAVbd@NOTbEQke;QqF}lD!NwFK zPzz>F;x>RO@`z;q81i~+*6(=sDb6y=r z2eB@dnc(xEiw*+e7t)Fo5bHBom=2rV2PETk1D!YfLmgIJf!Oz`!Xiw*+e7t)Fo z>u4^yDvSM7ZL}abR64Gr{Xs;pku?tvIocqJ#XjA@>#5r7{z|?&hL{K=2)R zv5s0O+v^-+eFp1NnF;m`auF6F!~@XiplZd5(36qlP%XBuG860v%mha)a&tQn5@*mmCaM)D!kCO4hib76m6_nk zOKyz}(;0RJ~tp!5jK6(dBwcD^b=VjC(m!I8}(&`2@= zUG9c+)LH!9LRxXc&eZgq=69_NTf#CGO8h#MSy_I3k9$;~3*{r%XL+gEC441Ni(3fq z)VhQP?5Y!$Ac3t7mE|AFwh%=*dF;a5fKg3W)pGJSV5G$(G50)e-f@J6WG#&9LIQgv zRJNv~eEQsrJp1SqtyCP>9eNU9v z4|vP8hE|~#uLk;#>i?}(Nbo!lZ-Yh+v)_EtcWT)KP&sD9w~)_oX#nc&FCw-O!Lbu8_dkVyG`jRj7qK?-)UU;2*bDNMMgxT~=oTcXzm(r1BbC zg<81BjS=(*{&8D{1ontkmET0*ZVPvJR9-`?Pz(2*F~XY2YZVgMBckkEB=@BazM^m+ zMddZL3bk-|7bC2RyjCHBJtE4!MRH$V;8x*|h01Ga6>8x=Dn?ind96YMcY31iTO^lN zo?C@`11hhfRj7qKmKb48&=l@tNS?gY3y_D`9SlXD4Ll1cVV0z|f z6A`F2xkEO)$Bik;vgi`rB(*W)$XBAec1&HB^*>Jr<@fp7nhDhUeAmkC;@wHfndlOa zcYLH(Rqa+@vpTIjEJ0#^>B?-&W4&PC6ZptyU3JFuztVC1KopiFH?GJ&)zJ(1%hp(v z^i^~msI_0G71>(lUa+}tKGCdRm)4D`pH`6_tP6=7mc5)k{60_ePSX2><7PkqIB9!C zVac~eFK1s_;|1BfZu*l}q1H>)FJ*tORV=wJ(YAZeu>=Vm3&sptwzBndYSBs5GCa=> z=P%DLu3I8`Ik6^Vjz9Iy)@dS6Ap*4)ov}Py^=OIY{&b1zy&hWp4H3KOe=I@5{X)gx ziqC9w1Jz$n1ZpjOKa)N8><*HJ)FqxisPU39q}`t=)H>qvOm_B{9VF|iOZ-r;PMh9* z)I^~ced{3m>eRCX&c*5y+`l^7u>=X0^&1h!=u>)pozwLk@RNBx&-Jq`YaUs;{^jq{ zT;l0mf?72DMBmbbf9w-Vd@l!*|3hciz z;&9K=TC+~-U3uIi*@A>oLhJe%36k&bSQIdA%ySES@p1UYlwbw5jyT=gxS;OCS^j&B zFiL0%5-eY{txdo*y~F!qf3abT*CtWx!g*`uIBxm!!E8Z-9`Lh-)`bMi`^|0>Fimer zj~FU87PYxQiCRB&v^HK`^gy;CVU*CikYIUar#1o8#{60;Z#4Q{zvz}kt-tMQZL}UW zH(QV}N@!h3usmx=>wsxvcF(d|%m*B@sXc1l`01O{R|DJLpDjojCA2OiSZ=?tb-*-_ zc3Cxj7V@=t>~8-3-fTgFQG+E)EAjUst%auVP1xfw2i4!S47K!_>Q~<*Hfkoc1PPW; zDry}tO?ji9mmKl_?Q`0uu>^^}$F9w8Z`3;Y?~zRK8Laoqp$R%4Lh#XYU3xZe88avA z65Y1iT=&)cU7N-dBv@X#SL=XjW8N8dy^O@~2i=~=5+oiNwl@3V_pO5NpU)N zADW<%C(X)jV&~aem*{%Yb!@{d`f^?xOORlB&ikzbrj5C8!XRnYms?*-V+j)P zf3-Hd?A2C5ld4%noIzJ@lamik4D!|r!L8!D^a|d2;;gJoEUi~6t@`(%57JnI1j`MU zwhEZ091z?8C9Nv!`g0mfka&CKy6p2$wF(}ceK!$4%~vB=)=$hdCWBf!cTG6x?yO79 z>3F5IYJ9L)21}4&`N0QU1xy>$c*n)ks;b=wWv~Q^-%nnj{cu*R;J3<|MEpoIb^5{j z37U6>;J)Izbk^=&cV^ZlhBT13Kh3DO8)mQs36^h|(JEk?Y&=;attu`#F@q&Ybo*(2 zcJQ=TLH!wb5y2}?yPNALj_BM}2yPYErE66GMt5ahqSJHozNmS>P4f(vAi?sATUrH7 z(-}OtsmCMnx}izWW@#>yC*Lt+v(33&7A(H#rX1nt2%D!JGc&uy(Jvk*HYPrDp@$_% z*c{JgVSeh6@Nt$i)`jGH*gw4Q?nb}=p!ih6D!;P8o%UBOfkgz%8%fcM-A>ro;n>Qab$-BhruNE6c7j8{r2@>`j8fCJ(r|+v-!p{-*`v&->4VP$=C=(lR z41XbsB}mw>e3VH%fZn6Fgr6hqH$U)OATF`+=YG?UAzZt0W=e=Lq{H z68u7mOI);QwAfg`>i8sU}8QaL?9}t(Ft<@IFFBS}UF%nZ3TU zeem@6`vfk*?RuPuW5@=6rx?GB8zX!mqHp9fp)H9K(Q#l25_o)+FCo>v&7>}ay=M-T zR$;xV_P4hWe%-ZC;1YZs_D9}ol(^`JUB_kVoybV0HypG2hNI~E^qc;dHzy-4CiLA$ zm!KKWV~%GyitnZPoFBAebe7_KDUJ2A%zy9o$0!;TCtZ8C5bJ4%LoJH+rZgh_=Y-aU z1k3#Q=W3568?D~&CN?%C4&)eeR4>IAQyN45b3*Gvf@S{u#*c@Sjn_9_EjI4CXloL+ zC>oj4nB|`nS{D*5^WW>v8AdkxCCbFcP1nDWL@kO&rZmd==Y-aU1k3#QJz5VT8((}p zTx^UOHYtf(6u(Sql=IICtqTd3`S12iO@}TTEjBW1j!&W%MLbg)7yWZW>q3HM{yTq5 z%9w*58Y?!=XxpPbYVlWNHIn-0gw}-w%VJyR#FDy=ychRvm#9l#21U=Mq_X>%EXBoB z8a>CWfU>vtJ&s%DKk@lFUcQz_&s`$CqQqyw5|)*~>&BS$lsevVixY`GS6|`LeFJF~ z-(8@)04cq1fUTw3`Qp0Ls{b{*%*)r(dj&4>$(?@_;@_RSI7iM}O5pJsbJX?^k~3!( zB^r@uNq0%4Rdq`JEZqx9>0J_RExo~0@(u5C{BfUM!*@&^Exlvn63;zhq*X^<+{-y~ z)=~nGkG@8G)eN>_rgXjD+q2~>5@{~m;AiQ+k;r@pi~r8&od0f2(=iVuTMpgbrcQ&Q z9%|8jqm!ecsM*sDU+ zYYc?!aq_jeM_J1y>J{ylJ?F8sSHlvPmFT|oHLtPAYO1MXUwm0LftF|7Om_~htTHJ3;eA8td-KW65!rsLaB(T?wp}jNjQf2RqS_{rw zBQ|EY7?&+b7~XAT2@)*tys&u~1E4rVdiX6Xia5?tbn6>Z?{z=;*}ALV6uH@L_I``r zdokvPSD#69t3JKI+(RvvQ%^US7zy63i3r04mgEyWuIxSGPw$+YKH;V@iBfNm&by?m{0zmq5{{=YR3#*H4G#hQ#c?i>65?v`IlynL+_ ze{L=@U6%-6I80jgDn)Ctgk>f0Y?23XR>RDlpH53$HvN1dRO`Gs>r;KVH4n~cV9z7#P=BI@w&#aUE?c`{T%s{O!LgE_``{zO5+qc%HZE=0T(mE>=RC?y!+C1B-*}YJna%3?mvQCYa$vp0 zku(V+aCue z!f};r$sy}S=8@qNG)lwf?1Lppu$-HH_`bpUAGb(^>$%j+>p86eS$$>#X=AeY%uPP< z#gw8>$)UV*Mq0E|XLZ$g3Gx8ARq6pmZOF&kv1Ii#`&G|ARaUjA z1PNNNvbw?=WP2eZ1)i+U}X-vi?DDK0A;kXZ$u&e|gANlQd?R~W{;uZB3w~)sb$9l1~w2!iP$uxcyX;I8d zWR3zCBs7K`9XS##Ydl$E$a3Ui3^}ToV!9%86u2N^l+e16U|A#35BBVU*CikYHIO&=Nxy8(|DNs+VHAB6AeDAYqiyx{zR5BhV5<78_v3NIoK$_m6P?S7#n_wJMtiIa3AJ74rT>wQJvWZd+;QBP>OQj?CsFH_cdd!Z<#(@261unr^p#C^_du4j69kiC;_9C}T+OzVxUs<&@B&_k{C(xb)3J_qa(xWqM-NvG8j$0zofSI@%| zhgiY%@Zgby_8=Q;=XS_U9e7;zGmV>gsC7}YvDjEQmTWi#XU+cU(}NO}q0++=B)Xi- z^zdNmc((D)EzL8-2iL0}cvZqft-(JWD>epvwMXC*oF%PJ)o(?Vq0++=B>vdR^zdNb zH*Dj?J`FQ}EB;^A@8#!vsI~QtjYBgKeL~NWly>{Rd{7s9!tDh~R43!?1Ao1k8Ob-tR+|D+J zEP6YA@gGlD?RQ!~54Dc|@g%Wv$D6eSm*BiO6Shq);%^XQ2@>_TGd(;wdoA18y3Zr& z&(D}xHEG-s54A3AdaBr1w7YiT5}X%jbd%yD&U%6+NDOJt^zh&yvnSd3@~fWdb>9T`<75|o#Cg6jiVax8Mp-J#kumF@7i##Z7f0J?<1KW9<(Rgn9JLJxa`puTb9(h zX^e+jm%rXjZ1iuwXW$b21(*3V4sAmjDm^SgqTgz!hX;d*Wp4Gt-$#;tjyb1j zG>t3N8oaBG*x<425}X$&_}i2!9#>d`#OPm{*0Fo+qPLU#e>APA5nUgs)%)nSVuPkd z2@>BP&a}=YSN3V>)xPZgqIEQ1q1Ms=YcDo9X`S2eo!h}XqjQ7AR$4z$>y4Hv zvB7JUOK@JCM@KZR=Jf+hka+hLrge=v=bCO_t$xiC3uqlgt#c|$#0IamF2OmMn++_f zrcBKqmLT!oNTzkIUH|aa-c$Fd61<+H*8F=qhz<4`T%umHtG(XiE~_3y-vPxEBrcf2 zwE7I>mw0bxFHf*vf?5l2I9qJ6@8c4j1N-@@1FP9D!4f3Cy_RY9eV*Mp-1{s!I5B;} z#3X9HeAqc+gMB!c;IAScbBABe{uP!Wal}DPlMV6V4%;}|yZPL4i4`*&CsAwnP-}yI zQI}XqnRLo~RaUc~h$Tq;Qf_TnUzGe^@9o`{3HEnU>)hL|4fc>-;zP>DK7Gi{>UJx7 zwZ{@9{w1{f)XAx1y`IZwCOVc~zYMkhG1%I8vF9IImtY&Er##3umSG7JYMcFe+GY0| z?fvoEgNfh1XqrZ?0sB}R(_8M0j>8g9P+yJP_o?c0D4QqNg@pED_MDw$V^Qnj-nAz@ zoj9@eEos#H=o&k&=GNa4oexWt&^hlqY)SP|l$8|gLPE#F`Av3^jj1OM_RgNOB=PMV z%hRYeYn;74F4*;ZG_EXhDUIEF=LFTKPFR-4x{%N@-J;%h?yK{z@&>hfDRKSrKc!Kt z|K{i4vM%uvWqhBpVNLZ>^bIL2K|-(1g>`->8>g(i*qgEU8;MruADlt0_Vw(1 zHEq|gS(g|_bIIg4->Lrk$$A+qK|<%4Zx8&9Yz%lQV`z>}> zzfa#-!xAKP?OOc!&s0nQrh9lpul_AD@!Fml)Vl45gxGki_Rm?DXh>P>R+qe1-I%@= zhb2hp8r=H;w(-I@ZzaFpx+-zx{{1tk_2xU)FIh9?r>sjHLO#R2?e3{wNjcoH1PS#e z=H2!a**NCV2a|goHak&dhGtOfm?y1&b-?LAWnF@OAMc1B)%@)~EI~qjqC=arjl~pW`qcW(qxu5kDAK3O|)+N}7%hsz^O+H)(OOR0CuKN2Q$;S5wz1P0up}UK& ztsIj)DBR|G|Cb5`)V&FMIo+zZI>eOmbkAV> zs>jCe={HvVSoJZT57Zje(e9)8oV&!iw8!b&FP;zouk&-dz>IP_!)7RIFGW>&b@3yVo$ox zu>=X-Q`@D->p2)tBOORiZsXyt#1p6gef`rBZttUhNRc6$!4^^{& zg<8jc#gWbOfPFZZ=s+>c9Rp`4*uTOOBs7+3Ju>nWGs7p$u4X?GwK|NqHrN++3Gx#& z8~RR9u%Cz}NN7yfdY0txW`?{!y_)@9)WUeOOK|jqBOg3xmm^S1 zWsaW52!_N4mLP%Ada1?}bE{Ab z?SY85`Wg3rugO+xs3_ewj21f(l8O3|7E`eG|$BsNY4%EWCeK8_B4lF?e zd);Z3kL|^~)@a)$Pz&$y*GM>hg#=!kkqy2ZXY?sOey;C~&ucB$XZ)@`c^{GAID?<6 zqaUCC69P+4-0wuudaA|x=&3-i$sv5yy79mgA=E}I!zN{WU(ZlLW zV95a;hKkk~f4myEp@ffGU;j8kh-GtE#tAkPYZVe(Ub#i+Nwr?Gt%?!+q-4jA?L_Oe zF0-;9PCZ=YkK5jrN9=d>Y$+M?;ZxbgkKQHnm(@>3t>T)fdN^{_n)K~-A&yz_*q;zf z_8y<+^UQVW`DZy;c|eB$e(~cKu8rvFPuBWmkAb2!?20LIB06$x$syaPN~_Lz^rGj>f}h-(F%&SulV7?Ihd3vnQKRpq7O^=fk&m0=9R$}){&ghl-|bu2Y#=0j)FPis2!4`0Mlj^q z2tDtJAP+}m`{pF6M+DYOKAdRrv*$GuK5CKACS86pV$-qs8!^7O9?+UN4}xR z{B#@Ia|zTU&r%3}R;^|Nwa7OVf}cE#5oE|72bLgF^O4g&O6uh&aLJn#nV*!c`N&a= zd{H6zS=Sg5wF*m+z+QLz3R{IV9-m8~7WwefDt>A*MntW`5+v}<%9}6ZBk~(CIG3<| z`tc<)6XEqQnIkjb{kLdg_n!n1a#hJ#2h3uerIDoao45wV4cHbkHn&F!MabGu74S^ef>9#?xkJ#i6b)gY}X zUxvs$4^sB5fU|Y+jB3op=T-^vYq$9eDMv=6rSB{8jOr5251A^&sfSE$g(XO=yQxfU zT(P1L*;x7V7$NvHqL#|MGPs0{6FQFRFFw!;OOUv+?$y#-yQ-bI#}=_sKJ(|rl&3~Y zcm|++G9vT1!q(DLNGE3FvV+j(J_eE%%J7Hw@ zav?S^+VnhSWs;KpX&$8PNh0$Vj5Se~n*$#b;`br*pGPgqg(L)D=PvR6%$J0CV9wO% zu>=XqawN2UzWvfCKNDizsb!0?y_8Qzw0MTYnvA(*+h!r2ex%uA)S~P#Lhuad5*>=) z7GiztEsL-O2^^u6MQ~Vq@w(hdXBw2^`b(ihqU#^2!n!DHo!DSc2K&&R zcTtOS&Y^~UcjsxqpGpfyIRI?4#ve$&o zu@oaB8(4yby}C3Dlx>&wGO)y6!8RWi)+G8qk1Li?%gz!uOIC~^T}xmI5_W#nJYHP4 z5?EsAV4G14YqIJ}pq9NRY@V|i5!t{JBw}aK4{i9UWv@Y-uPsJIHc-o6^EQiIj8Gc} zwd}lNbKAv;$Oe`mVdr_xzQ^j?SN6KIIVJ7&SSIf{V@;$F1Zvq?!e-Wt5e&&F!4f2R zR^qGKdKqFRB(S}9g|pcSu_n>?)dp(W+1chyj1dJ}g#=#Bt_{4l?QCarSjKEbtwJq3 ztJ%z&F`{6rkihfAt+EkLmgrjvfqq?qWsW)UY^Q(cFEB)ePZEE1!O>zO{7!?^WQo+A z1?dYiy}kOyizM@x=I%nj)b%V&i0Dkj;Y9qj`;KhAy&FkOIF_-z`w=2z_AFyMgv4Q? z4b@^o?YYDtBCa4C^Swpsq6Y^CV~6z({@#9a_U*X?gN2Lx1}(==$-2EegNSR1IEo0= zI{(&z!BgM&4H~VOnn!#(dqKJh5v@{-(r0=DgA;G<6D+>DBKu(Zz~GvX`UKryxH*s5 zLB#1q{7lDzT7zyM7`%2`-(bP^iFw3SYE>x_9jR5=UL^4NjOlXUg7k;!-d-Cbn(RFw z`0mcq;MyOjXWP8dKX~h|(qKg2d{2K8wQ3pJxHq{defh8**=MG93f_BpRd#h^JEZ~Z z6!@7{S?pA<{TLnj>vSBb#drAhEnJsqN;b|W8yAs{Nf!(VJ{te;VDEP0vKyWn5PZA&-@%0? zxgMs8xAM|KQT;rNJ}pW;lM3G4I{GApI-#)tN-# z)rrK(hx8AAoKhO3?wvt1!+B)mT(WT_^%WjR|7!;XYb#5GqqpCdXQKrj`AI~4LN-uq z>sbSWJ8v%yri_@LM;v#z9f^E>V5^Y8F-;?pj$HW56-9ZJMOb$`j;)W22m(wBX+ zw4={H@oV#-{&OQFyLB!j7vhm9-^PWf(H-u1D8h)&CCrf$0^jat{=KOlHyLTNC0*ll^lPc)YdA{$j_yCV?^ z9B;<-4$sH$bR4|bA9cYMvdZ9>HgHTEb1o4)!||$yTKHuTmuO5x2@(B>z!D^Ijxpvy z8oLJ(F`8P1*IJi1`UNMCD-Blul7H2vX=YeV#5fx5sCD|}e!;HmOM_jV?#R2MrjU(& zh&YXG;1z|$cCTMBs$Xd^f5shjo$pP@u{RNql8rSN4Gf-XQyM&Q-!0h}TMY~bonIQ9 z+4|PJ^RbSI?}!+2)}l0OJ$2Z?U|Y}9;O^J+iRMH!AmTW(fqjJpjvixpHMoq3AL%%7 zT^dsB_iV6Nr=ZrH{58rDF^q`mM4;A;H-61-S=uoOy5$oSi8z6XnREv6I!EH_M}Emp z8Q3ux`(J*`e>$Cy&xm-H2)qvXIS|d(g4c~P57F4|OT^!aKrPI@;u0UwdcK@SyGO@? zB}nj77P&kuhtqL%AscPT2A7i0sy$wzJ)7^L?t4Ice>W!@FV^A(@LZDa$rUhh9Jc=_1U z;QT#q$s@j`-u;3`$sn3{@rptMuV%^!L^l3GHd;`t@J!u&U}>BTbNaZ%H*|fx zLFeN~x<0T33H)+}F`bC`oQPwnRj7q|cwAyQwQ3!;sy(#|OOW6vxpLWh*vnW!Hr^lt zXRY}d`|F5$;)|Xkayec z`>>~vT0D;R`(b!yjafqHd^8dNq2s_3Byi3*W;}VXl|=AboBzEc{YDY?2xWnyGuV&L zU_Cm6_`M?hu8>P4A6k$;p8D#4?cLr*0>_&%Tc}lIsa2)aD%>^VZql`}Cms2XL|jD# zYVqDczX0VDgC1RwzJFP7Z%AINkiZ_{n2h}%U3f<^tM?sopHS`X9q8X#f7BxSa-B!t zxAag8_aZKV-_GO`eaZs0+MUR6!Z7>Zvdc~uLeA5rFdie;rBmIVY|Q4xV!6xT>;j(FDw#jlbYzoKYV ziN>rb)>ERfEL!KKwS1R@-Z&(plv>4+BGjTtQ3=GBfS_npQln8=7ZMbuD$!V$c;V7l zVN51!J4IDenh~F_f|N#dBqo#8m<($1Qym(UaS6HxlX?we2@-TgLB?K+Wh6D0LHno@ zjag7EqXeQK(U~=d;w4Fqm!KBKPD&uc0tCfmk{Xl2QGx`;YDzT1MxO*E8$7N!27u=o zkI6mf-x6^c5x$*EqF!V|zl!G)6q!guWFi`INYK2J(zu2(6thff%o5KnMW9MFeu-m& zuD*K~BsG48S`@!3fruB3EAq&a8Y9EHkf7LEiALCrX+Xp@I`ZFXRipVTr7;q^=2IFw z;U^<3rsIO3quI-dYRa}DNB}s^vM0FuSQIROWEZs%EdqGm;C8$NwkCets zT!QwTN!@eOt}&(iOxk~@V3!)5CwoQdz81A;kDG$nD-aZ|O=`3jM*|Y%@1``0D-q$O zMuc&UQY5WJqr*6+DU&B1Iosek9BNSjBO3rBrbOe3EtM(9xs=MR^lcw$oHi8vZ4wpaoY$Y}IP%rdDlOVpwW zREfqf(Y7%Zze+;N8C$A-f?>pm}LIQUH#{7du zB1ejjCjzez9N`oLioSI~xh9EtlZb8PU!fL75K{UbR+pgIQc`0}Sb_vU@tun;QKTrT zks^xqq%=B2QKJ;ZmSB`nG%BglDAc0JR7zv)I2Py$Q?daO`lv1>(C?C%OcG);(N&9A zDjpL>CddZFWTLB+qAJlhEnI?PGD(QZL_Lax+gB7rmQ^i`AxEh={yQj-u#jq0K( zUPR!PCQ-GdM%A#r6i-U&*TwPp=qpN(E=X!L3boirf%p}SD~fm}HR6SJA%S~b@?@U7 zE=hi}>GJZ33?HGsiM0L)8&zquQ@$n`y_H1Iq^`a$dEb{~s}=+!GN?uGO3}<|-<9H; z^gSlZA+*lg7(fI)w@~%OY|Y)oaMF8 zWCBZ&a9dSoTjeu>TKLUDmk6Iz^SQtD9VJ6gX{pRln6g}S=EVX3o%Q7DIiH1mEzO|o z5*!s|jw6H^jbd5r#fXJ5OspR;sl~4$p<1u6UYgQxD7XZ_oxnEuUo6Qda=GqRn+eq7 zcQZ8eG{5Dc-*cm&1`78*0_sxw;uN;ZC=FQD)nE|9rA`Z`<9HjqFq_ls3Dx4a-86%?OFVs0 z<2GYRyFXD_f&})u?JJ#6aE8NJxW3QH?-&W;hXg%CpL;h{=U|?r^zU&3wN&Prx@H1P zkigbPt>SwJ{M>7_0;tTb!ui-C__w$>&hdtx|YOjMD;4cM@}`l zL}Y`qI23CZ2ezm3*2#_J@29WhuLZGs*eV~jCN^#>T8~Uwn~f0+$$ge{8;ldJBOhFq zZIm7)a>X~VNnfcwHj%S|TDusQjanDJV{Np#tY4}iVRD46 z3kfS%1WePn$th&nSsJw_Ra+Y^xAaLBButL5bs=HpihyZj7EsPiwy}Y7Y@ybj zGpvp49=Ik|kT5yI)`f(XD*~pCIr#HS#71q(6^2^hTw`sl9eGu%AYpQZtqTb&R|HHO zv!YQ4vC&~^lMHGd+RWNmHRhkGf`rKtwk{;BToEvB%*Xr7H{ARk?-wdjXiWh8c5 z+$&X(Fge23g@lzW0;Y|5pK@mM`FNOeW}?=(XRVEAkL#H#NSGX9>q5fH6#>(q5fH6#>)6JVQA%gm2Lc+=w0n_wFw(`yVHCq1_$~B2ve>>IMsJ(CZR6)Yz2wN8t zR;~z`rrN1~`AusfYJI<{Qu>Ou{)(`5Az@{;(Ufv#vJKAtiCP^htPMWezang1NLX3> z>bqlmrrE~JbUsk)fHSQPK5KtP*t(FgvYvAqS7L)l32J$tPnEvn(f3z`tqTb&>)5?! z$0o7S^zwcg)LJ>q+Tg3`uLxTg5?0o0kgoF#_Z45YsCDy2)&|c8e?{23kg&4OB{W}& z4W4~a>*9LW2G44LMcBHKu(HmH|Dv3kd>qp#XC`X>w0?@551yU>im-JdVP&1$Y5foz zyc(cZqx-B4USCLc+?r*3x<|Hh6VL ztudXf4PN#Cim-JdVP*9hnynu!HnxpfmPV~5CtDlrz5Eqn>q5fH>ih6_e)ycTw}e_F z4zV`a3;Qd=)`f(X)rTWLQEaf+hgy5?Wo@u$`B#Lk3kfT$FG}94*kJD!wI&#AgFV^5 zB5YkqSlRl);vusQpKP>8Ewy*Ve3LdTg9~a)MA7BDv4U!Z?BwueRLcS z!9I0JR0Ldtg!V4e;!}$aI_F8$()0h?lQ%@?!y$N-ghWNaB}nKfVcM8u?b!93k6o5T zEgi?J>yL`Yl|z^uQ4w$n5<1$MHs(Eh4f-wV+fJyZ*W>N~935RB4q`-=T&zH$imsY9Y7 z;1VQs7G>I))9u{ur{7C>sHO9KuO{Q7dDkIKj;IK@1PNUYm=>Q}j)T@H54Ci?dUD&i zX#H>q_NhanBH$7vbX8+od}^^lYpsV`y6&DdXMD5{Is~uIAyE-<2@<+GGi^-hGx+2) zc&MfR!@4FDqV?P%Opd4sxC9CHGME;hn*9>?sXf$EKWOji6C%IFA=sx5iHd+rkWg=l zX}a5Yy!deb0{WH^YNSRULVuOwCyLpsQ=~IF&=8EUpjW@gvd{H z2$Lf!0xm&9y;r7rbrPT2r++-uQvaH@3K9&4L`A?_NT?TXZLA$&_XeBkI8aOX3EaYh zgvk-s1`@iPut&b3vEAdmMdt&xbic#rpdev#gzYONbXR20AnesV)Y5$$kC=jlj4Lcb zLU(s|B*LE4LoMBZ^2jep@SZay?AS#@cd7P@g1xhcTDp(sE4Uyb*EyCTp}TE6Ge8W$ zLoJO5@Jv*YkogKrkkF`so#CDiV;QG@knm7T;~G4p79>oLuyZ038vU>{HN<2*)YAA2 zuM7nVSwFA@360{|6$fHV9%^ZviC4IS1jm*_!md$BXf(>MoV1>Me97|aj9MBmj4}Q#`>!ukwIXmrqeG7z&&qL#)l*>fsLh<}A8 zNNAMPdSnoLO`?{@Vc7#LNQj?^B}iD=`j1gWSo~eoveDs6hz{ow;_qTzNMLN)u@Od{ zv0fW>c8PDpIJK$j)qcsDlW1pZeQGOP`rEel?Df-S{p&Slx&2ApCeGKGGHy2D7KMp(~7%LE7iIpvJ z&u7-gS7&luG$i~Sfm)RTYq`X(PbIQ#=Fperu*Axi=-6zsjD;@)j>Cn7pCeGKGGHy2 zIM_zE&EMz?d01j)OZ2a>HXgbAQnC>eevUw`%7C?8VryNAY@40rg=2}8Em7+WYva)u zE+!ix;pYg{stj1mCA_T?**2GxPmLv3w#3#hyeqBtB{c6h-=wn za)}9HWcxKbA6Q~#OBA2WcTXzhY#I|1evUvbdv08UMu|k7d6Zy@l`V1EDr>`z-H?!R z71y$3%q3{Fiwz#_SYl;M98t`7nM9a+Rlj~;pYg{vU8V9&@3v)!LulqSlJTy zkG3}K+#V7#@5Z(49PARb8i);E4Y0(@mdLKRHtZS|60&~8wd`8r5+Bglp!j@rC7&8g ztZa#aji$>vw`*-k_&EZ#?3(Bj}6nyl`XOB7Hh-$J|Q7~NnFeNC@w+XlGtEx2}`VOiJ1$m4eP^&g!or+E$eH!1bKa8 zgS|d1v9cwOT4`-qUo<4dPmF6>pV1}Adleh(y<&-#Ezxz2wZTzt@pqXJe>bjWeP5Rd zqv!r=ik@SMl`WyR-#>8}*@zRURT;3BOTdw*u|!+Qg!W-^Y6RJc6SiLMH`a2Av+Ozd zyU`cGumlMm3!6(gz8fbh1Fl!kKWn)JjKnmSAfaRW?Rp%0jT4mt*Q?{0wOj(Os5F)! zq1WaCUvgYDPE-b5uU@sRO9X{E^(7xqx^5_?kkoc zp=(#k=aa}roFE%iudZsWkkB>wkzXg1jW|&maJ{V1sL}kGBs@KO_F7aNujcoI?A6SBf`l!2`R+5c4Q5kT( z>X)*XOUNv3J>(3QAfdjtwGk&O11?c7JSSJk-=$TuH{j#Ix{%O4gY7Fi4kqL|nYflc zCYRVZ+~aJe^MNJ0|KNIc?_yq zW6ULJw2KYCKCndhgIurfMeQ{h5^_bwwd}Rx5_Hvid>nk8V~Or-xnA8<+qonpWM+tK z*=yb<`h+onwlrU1iSEz2UX2adIWZ*s9AWF#r~zxa1kIvy96ax02@)FPuycDz$V?sA zvU9LY&}twy$fwR=iN;H~UX9h*H7X?7rw$2QuSRiL%OxPTl)(}tH0EU2T8J%$gk7UF z8pT>J0Wq>PmLQ?AGwU-zj4UMVTB}ht)^Z8*GNiA_r%q!D5*h=vzE4Q7PaP80XVB;% zYqVe8ds z?f+x!Jm9P<&Ne=Zy`b2lVmH{(1cL~o?A^OjP_ZR3_7W9Yimq6qh?FC4Y-=ni3L3k{ z#BM;v!rtY?nt%~|G?v(6?-k2_?=$at=R9-Hz54C%!_0T*`OiE3%$ateiV556jPWk} zFu`-n`8;(_=vb6zonr!RTsqMj{>v*PJPzWu7wG(435bMMJgO-X5PKW!!$iEg#5P#P zqnZ*CY_Ja#ycQ;6N(ZZWR8t~?4fbJz*Ysi=tm08ki3m2>hlzOAlGDK|9@UhHV1s>_ z;5F7b9jxL}O^FCL*oTRD6`9k)DjwC8h+u<#n21-y*#@h4R8t~?4fbK8-m1QyF<}*t zY8n!beVB;%GjKXs#iN>rgkv8j;(ZxxgH=4LX-GKsVItmN!ZujNqnd_rgkv8j;(dK=gH=4LX-GKsVItn2$TnETqnd__!IY^P_**aoX? zJcrfk#svE?VPn*AmQ2iO563DSmtu{+F~L4e*jPK*NX!PSY3(t*kB(fY_Do~)&?7_vQ;@e zYfD71!9GmbF4iz+2sT({tBV*jl!#!1eVDMls$uLCY_Q5!Nip^*5y1xgFkyRDOJg|4 zDqHQv7_LMF8|=e`?Nu#}MIEbb)f!{b5)o{$4-@e&R>-q{*RhIM-%CWW!9GlwZ9N%A zHWF5uJq$k zJgKLuOJp(9+j?LF))5o9*IVLz@5W6!Ay!8Cl(P!%rTX@-PaqNDMj*DqL`X-;hN)oV zj0d*F?LgtCAcU;nF=ZQ8228-MHg7%f_*0v)4OVIE(p9;}1p6?dJw}H=eHzExyA(hFriPP4u7gSw!tcW`sk`$V}gB{&?ljZE#pjSYH|5ih>PRS^t>76?J6y zEwK#_iwW!V!`of3!7A(L^S8T>?7k(o!C^6>ZP4&VH$l5@E5*R*^LwYpB7zO} zVM1qEsqO|FtkPLkt-B>6*kB(fbf%cvV6ed|ogLOTSR#TA_F+P2ys0kfwS7R_ScLo-rvA!3O&6qYN>>;4j7f_!Q<+sk5I$@Qr_NuBxn2m&em@wPXjF%tpvdZjX#;ZgG8|=e`W;EmFZLrGP zBWAoxM6kg=OjsWi&3Jhmtg?OuGhQVk*kB(ftgqA?HXye#1FNim#6IK_5p1vz6V~VJ zO(AT9Ro2gA2X=`FHrR&=dv@uKCv1aN_PoNr@DdShun!aV4Az@l*aoZYxr_bnB_h~h zA0})pp*PU54OZFs0sHhzM6kg=OxT!6Z_;5Ktg>+sPAHU!V1s>_u(6%q2*fs6W#c)V zn%2Kz8!qgTE?NypTzvT-R+jFgCAgMFB=QFz$~t89D?8x4stZbw*5*gHcxuUKX8 z3COF4M0o!|SWMWvPr1xlW$!yE^M*utk3v{X*gIUQ?q;jVdJ@Ur+fa8K6YRr;y^EIG zpktN2f1(XGCfJ7wd#5h-C5~109*w@FF~L4e*xW#=PjsxZ`2h5ZB|_>h{*qd|o7OUN z}ZTDQ`%K4Xtqqs~(~2IEX)Dq<>bgHt?%tS_bOoluyck*@acf5_MEk}&JGyT5%<*w<+PYZ68`4J=Ukl(ND z@<3t)tJJNk5+Ru8Fj9`Nx-P$<*@&;ZuWU8~ZncpSzRZnam4)=+1O4L!dyQY!`LE?Bkxhr?s51+g<*5ih-;Sz%B>$|{e%HNpRdZop`d#<> znOk#2V`W6F(tiH`LvZezjXV$4##3+K)^zBYanhpDBVXWGT;XmVd3EaC93LzDy-cu* z-4P*JUU&1STHas5p8c*ixL&~ry_%`mZM{#Rd^%7|y1TEGxa$)DZhP9P+v~-M{GTV# zN12M<7E-2HGljfDPn72ydInpgNBCxgRoZt!g&5|<=d<3uQ+n$fdTgsD&fV5vw?_n9y42*=+11b*WG@bR49=OKj|^mc;ePR9dgJ#vmm8 zWvw>UL_7^NcdZ_4&xhYVki-P5*nOXWuE-s9d0!$n^02Hl(LSv9U}T^+{wH;+J9|du z<$?BbSvqm%J-%FO&|o2%44VdO*7&rb`#tBs6Ej9?YJ5kpVFhA$J% zQRE4FPAz|H!P;uG@<=km+sNCqj#26ou;E7<8Y_&7H}LgUM>0AtQ8&gbkY_}e4jo75 zqnbK|%gUn`ryS{+o(}21s-#Kt3b_CiE@6UI>_)B!0#KG$+SlgK4DCNO-}K3#HZnre zp+w#@G$1?%N(qa5oDQ^kq{(df{PHQ!)KPk=Gx4^C}W}3g92?ASQW>%4-J3 zq9aFMnSRmxsje{6j|kKTQ+@WA%%CyMM;w}O zb9`+NDbLcu{Z%|7vvElv5)GGC+y>QNNCzCj2EsBrZ^8O(uSdl54Egv9gx1}V@(?Rl zS&On(P|t>jWqD;p-U^B(h0`ph|9;y`V6&^_e3^2iwK`r=2IlDIbTk1v@9nI0)hlyW z*}JUSF4d9{E9*;QqR^reiBzI7iQj(h{nK(Cu@CJdv!P)bofBF%WdboV71CtypU7#9 zCCY^PSY8={+Fl~EbmZYe)sXPU5Uzz~?wp{fGg6PfJ>;&Hxy8^%9QYl&^0-9fYok}B z*4!Xu99lX3;qgt+c5g249~ZYg)B75E&-jac8Rp`aad+Y!=lpD3qN8)?ddQbm4-sO1 zMzAVxU3gv@VQE105bhbf{Y~1$O3@4ye&<&rxJ{Bvuzw2Jf$IxO6T_6$*%T%yu z?h*mi$LffYx1#T5zrW8>sMwA24@3f&<&Whk@@?Mb3!CwKDR)66@L?6(D-kf^ZI};e zCak_e7v~kLkPgHhbX~&R;4hj&c!J|@8@t%DpUcLJAzrl$7pC5%=|6#pPxtAys)?ejs#oU*`Ei;_Hufn`2VrA`| z$JF>8Em-HNnP3&%YVYN)m_UDZ>{tJ}Q)bn?4GSwK@;P$3pL)q(RW@H@Vds@gFKprw zJ=^2h%FU5Ntg+O>&h8~+f>kzasI#2^6++aVi!HUViB)i09g7LXYOAFec3!rG+0f@8 z6Nn+6T{>Hvy&L$kJNwilFjE}f4M6x>VlgoSwbDXT;vC^yOXy3AZhIdDqJ*jP(Y?){YDjwK2l67J z?*{oyDtaQ=3q-KNK1eN8psg2$Tg3iPN0;?fb_UDnh>-t>t(S9wXFqHNTUH@|I7ea| z>|<^vG)-k2^;C5UF=XYDhh@0{!tx5wk|zi_B;n|V?(ZE&N0C% zxbZZ=%yvxRDKKoWRqy(eo(6dhH$tBVT6c>!tZX$+I;U?b*C!`d6eqpA`)pY&@^ecz z#zjnQWDyhfRumBy6L72T!t>mp)PoOl)Kt7`i4mYLk3>q)KW|xOZm29)N>HqPe+3&h z(zCIM5n6(@mg)&pX?f@yYfMn?`W1KBKv+y@PTTC@XOgQQbayu`G=K z;@8!Ngkv8jhW9+%$8hDT_-;7cVAZ16)JEHxdsZ6~j(wPzyqDTI>BH<>*kVTCC|LF8 z?wZ=6OYB~4NI3RkqIQYem^5SGLONLWR!wb8eRO9U z$zbi<*@ubyPf>u@~T7x8|=fxr}LE#Wgcv>YP+5P=u?X_FA>28`!F%D zx6+~R1{mgO4?v{vPgMFCTu2t#K27?V&^{Slf(}6ZvB7zO}VPe9qY9sU|!3L{V zxkGKBFDVhh2Kz8^%SUP>^ohX+tGd@d&!+=@Vu=Vg*oTP~x6&AfzCGAr)g`B>4fO3L zBG_ObCSE&SZG>l3u)(T(7pe_Bqe?`u!9Gm<@dCAh=c9fLFW6w!-3O?R-nSf7EfK*6`!KP~vudMzqazD8SoLLx+Iau0-&IRQ zu)#h|ocX@mSo}JC8xV5KD^{I%o7(8;7*Q<|fP7xD4-?-mQX9!OV+uA{wfci<Q)<%&OfSPgH^lCR~t~32(uwKY~*1vVYXK}@|c1RR++u)J{=d*5r|-e z!(zhn@chq@E!bd{<=Zkne;>*t5WxnA#e~&`3s1!NaUi!cXO)%zpI16L)T=-M@*_(Q ziwUdK7r%01!3L|W9-s8y#Lzwh5o~Z+Ojz68f6J2#Hdtlt@wnZR(9Q!9Y;agiSReEC zuTLr1V3qYNpDZyo^jCohHaILMtgl>rk4Xg^tg`;`!b{~_*jY~FE_MD;(R@wL=+2PDEE(t`i!C^6BW1^$JDB56^jf0MP z^UN^53PiBMVKHH2yZ44nE#wueY&`eeerJVoVjzMI4vPsJqrP@n(FUt*TzdGlv%+{c z5WxnA#e|Ku1Cdw>vdYHSu+fkR<939_guOF_lm{EEviAh!RYM}Ye;_O-?A<4nV6ed| zd*4BsHzdM)6vAS{-r+(`G#idp_TGlN+n8VKu(hY6dj2~V70 zgH<*^gJ)D@f_<2kta17n}Y1p6>Cu9w;fBeGzFRb%#48yLeiCfJ9G?|P_>FtQ9bSoQjL zY6D}@#svE?F{xW;*h*t+$Ew?Zp*D0(-H70@m@wPrcLP?LJ-i!~2$ww#9Q!a~d02kO zVU^_@-f>Dqu)#h|SX~J3YDOfivhv5fT0_FI4-;0W!#iiN!78iAc;{?LIQC(}+Gcon z4mMb2?Gf+J^$3Avg=tdvsVVjv=)C%fdF;+-&!N>nC2a5M#O@1Hb0egPNQ{V8)5V^i zmTXM0kE~!2F+H`@hgpRD|6uK4#5}Ve)0{pLC(2nmu)5$^VnVo}^IT9h{u}2NVr4M_ zft8f7HsR$;-K4=X1?=fBI1i}+%p!yS!?34C~$>5{ASk-Mgt-s5@_nb(~MzI93qt!x+ z2pID=P*S3jnF6hS?3Nv^&CrE(WU=!5ESo`OJ1D)|LJC9zw5ZBAi{x~dk$Ap|*=n`4> zZVpFTF1DvxN&nRk01x zX1iWAf6x!w6CfvYdm6Ux-Z8?$Wg8Juuz?;9BLLJTZK*t7L5%$Tm5ea7CKgqAE|my~ zLHP1OsoB#KZi`{=hB7De=ea%Gj~IEb^b8k-@>hL5B39+20X2{j39GnXp_~w_x;wUl z4-?2Y5U9uXV5B*$^RYr1n95ozXs+#XnJb~?!DVA5i;z8$z=5z>#W`IffcjXO4`?Q`J?YKR#Wq-# z?T2dyT_S*b8|DL5k&wOaUC_lgSOvG7=IAmT5#dqxF&jpdayNmoqRL7Qzn6$$!+fA( zLd!|VS8+O6#r28_AAAM>)gDeq^ybEB8NCFL+x@r%grq~?0a(RuIji3+I{C{^tY^Kb zj?cA+)3gw<=Yhzrsp}(sQCRoL83rPw2 zZzBKaZD@b4@6M*u80vd;nP3&WEhOhoxpv+D%Bc+KH=yrxg6%A}9|XS>)-^c?KJCT;=;+m&hpv zB5XDSDt2S!4B{`d-W`w=d01QqHkRn_zDaFZy~>`o`J1rSaI0e&Ir(HHSxxi=tJrOC zVbQZzYDqrE(QtXBucI2ZVfTKpO4~;R0w*+ahmhFN{3*WoD@``UknbIw&dRo@Sg+C9 z+V&KyGP=Igoi%h+0&z!7APRqiwJu;n;@>-OoflL$JXr z-NU4PNkhW14->jCi+Z?VgH^g0OZ&uzgkv8jbblH3)WHU;bWfS~?F|XXK1}F7IeOv* z8?4g3ar%sENI3RkLihXW^U>ii*kG0J@zW<~L&C8S6S{A)J&pD=_`ZZyx>vD1&G$go zAsmOrgzmqToaVip-Uh35&t-d>@8zsRI1Y;m-ACGnwej?T$ue^aO{+gymthpCL*I!nJ(M_iRh6wO!u928YFj)rDw3gSWvdEB}1&d3#zW zI4mZtPDlG0ybV@aJStd9w2 z8iY}TRo1WMXByhmGQnXnVSQydn-OfV%KFFrY=*Q!KB?zZ&S5cOeSSD&5^S)_`uY5f zNqbr*I4maY*%i*p1RJcf=T&}IM*2rSspr$dVKHIP;Be+A*kF}Cck?qp?P;0du$Zv1 zL^!(?Y_Q745Bb@p_OwiJSWMWMD4f9xHdtljp!^J0ds-$qEGBGh7tWFe8?3VNTz;0U zJuMR)785o`4QJwl4OZE>G(Qv9o|Xv?iwPTR2O_aH$SNCO=V$xs*vR$>s}B?Q&Ja=_ zY_Q7S6Y?{Pb@D3PBdk75*t<_C!C-?`_P&#!wX9R-*&bo_VZz?wLQOOq*&gBc6ye%? zTYhG=PTkGUjH(Y4_AVM)RItG+d;iSOzSe1j+1Xe1VZz?2L(dRwu*%+}^E144`jYGn zulg`ya|5A=3pQ9~^8xu;x`+hJ;EBU?&Y;HHTDP-5o~Z+OqlKR zy8){#R{36MdN&9*I4mYC56ka3tg?K|_iWQUPO!mYF=2I~{I13-EB}1&IlZd|8yprB z);`MboUF2XobREhcg|pg!(zhPd2|-QkH}bM?J++KQ0HyiuSeM~y>pM7CM$fpqY*RS zaLfHy%@QI1r(>1eo?Fs>DrC1L21gd<1=253PfT=cJG|uJBC=r#Jg8csUT|4-hJ>~ z?isWNclh^ZYt8!Zyx7$fK_pLJ-KUdP+8#Un+izXM<%ITqOjv8ycjuqpbfUMh*rGE# zS*7iFbK%k6#$oMqJ6Xkh_UjTZC-hmwgtcaUcYbiI!@Z66 zCqL|D74PP+OSqiSCnpouGw2AQ*XzIWHhTPZr5da3j1k5nbqSXfIyPV;9?9&o&M&=< z#qaM^W0jqi!kDTq;c`MpGEBrHvfr)P&)Ycn`R!_~vNK;88`dRUPUwh?iFjoB!h36b z8`sVsUSpM=UBei+F5z-QN0v;)BjoQF_3$?OA9!GmRdxmsWA(a(%LyGJGZByUZ~gX} zCbYq8_Zd}Vm7OKTJ4ao@<%Ev(nTX$5j+}6!sUd%K{8SA zO<1hR^Mh6T9^K*Juz!ruH(@6DE!??Bj(%}2EIc9UV3p1XboiNqA0yNT6Fi&X+>z@a zI{eJdj}cntOz`ZEbJ9M% z4b*m4={%Es-&xw=j}cmTnc!I}`3}~i9yOE)S}m(|zO2K~r2QD7ZIB6`ZF5fgD{lk6 z536+Eufxv>{urTs2@^bP=$!Ps-UfP6R_Xj@ho9N}F+%%9CV2MKIeC6~8+aP9O6Ora z{0!}n5!$yi!Lzu|$#c-#z*CJ?I-jifxcwNR&nPB%HrhFPo_ia3I21ZM)(sc?Q!~GbcV;?4XmBYC+ zuA1m=oOMf|PFCr9i;gURjL@k3jL`RRCajj|+jbwVyUBX(bDLOY^%(EVbqSXf`X0`N)pmW`&e~uiZLo<|)*kV` zT$jL@IwSNwoC#~S`nLVaYrZc@`u%mK3ahMN!M?7#gv$wi4`;%9AKev}^@)k}i4|5^ z|A>8EbqS2AGeTGInXq0|cZFT3eS31q^V?NeW&J$%b=4(YPDmS+m@r{a1KkytJ);tN zMpam4&nxWfs!L!@oe{d5f(d)7>8`MyzVXl6WZ44`tgyzlDy*_`5cYM|C0tJEE*&Op zw4}SjzF60f;gWBAOsKHR#&g)$RhMu%p}UQkuu-4x3Y$01k42M5rcAD|%EqPG*HxEr zIib6zn6S|+?+VlXwXCx7HB@y88IvUy_F=+C;cBCAo4y+?lytDl-V>18x`fLK-C@Rr zy-jFdP251=ah{X%V3ob^pw#LTE+;gvn6S4ZE%SR$)_1kPNxfo~y|7BE}DtrG#E2>NQ_Q5_(*juW$L22g|6dzhGtL!}*y+K{Vw{!Mk!rr#EFQGYr z3ae~B0KHmW!uMC~!-UNmXrCzku1^PgQC8W!271)GgztCRhY6eg(7v7KWGbw(`58QA z>Jt9>!9GmbERH^-cmfu|a)Y@P{E%esVr4zdpuHXEhSTACwkVwKI8;i+Gj@XvGh zVZvtBbj%>*5}yu?GFWBvei*&fCH%OAeVDM>K^^K(8R*GQk(2{VIUX(DSUktu)9NLz+cT1gmUy0jd(=F+4wXhTcv~>KR3x z3&8JoCQ@y{4hWsc&k4JwphN)k1p8=A^u_{j-Ue_~8rtnZvjkDL2+vX8oz;8j59$^@%A{65Q=*g@Z&lfAz_vy*+) ztpu+EI#(uG)#3Mx#>D9CJ?bA*=XSD>x|QHnKp~r)#1;|#6+)k{oGRW zll%JA*hk$;*zOCQf{~e`62Ynte^w?Y=4S6v17wbjeblXl?IOV`80X3at2+EynV6WQ zbA8D>GS|mG>Q=&b!{8K*oH#2Htm^P*Wn!Y5y+i05-%s%Q?!uDd}6pV9af>j;< ztV~QiwSm4zJt=eH?4xcaY_}Lr!8lhYSk>Xr%EZLRI;WpJEpz(pqi!W^*Beg3I9DcE z)#1;|#00u&{g>3(N8L);?me|pCRoL8JvZZHg*6t3bZ}VeR>F26YFX&s9R zsqNkd+6VinTM66Us%9NIbis9Oo!rK^2OMkG1GDsA&IA-#{c zf&Pkp)UAZ=Hr75dBYY26R%zcA6AM=G?@?~87q+XhkGhqxUDMjPXGD?{tkOO>Cgf@0 z(}Cv)`>0z9+x@N2sEqJWoU%%vB{A_IeUEZ`$=U?_s9Oo!#g3gk@`b$Y%_}EZrO(8e z7^iy;+yhU2*vUTXR>F4UV>IAgMkG1GDt)%cgp4wLUSV9qKI&G&P8DEhl^>UYNOFQz zI!1{J87+Am7+pv*w|v51z|D>Q;hJt2mbtNlvgz$G$P~cxGeK(+3Y>A9X8Xwz2cj zxr|71f>j-Ue_~8fUNy0grK5NXCd#Xf&~PnxvCqjHDTK@=D zOijHD+S354n4o7=g?*T?XBT#^`!Tgohdk9Xq9aAP_Pl~B zCfc%R?MDY3SYaO~>=}$5_|9cSk`o;%!nLO}R55W$HfDHTRvOrc2^&k`B!P1ok>o^2 zig0cG098y}kd1wgkU3=bVZz2lIJqDa#k>OUhoQux>?Ja@PI-+iq7ejmh&!(zhT88ojX9UzjNP#g9(0aZ+V znCazgXU-in}#38^K1FAi!6`!Heea9VdW!q=;^O6yomNNx8v zP}|wZ-Ukt`y^Cra%n08;$|`LuF(IwCCb{d-YT3u$YZ0!!Q)^$65x$+5RodobB738E z=zZA7-p>)P%?)Uum=PFLXM~1pvj$MbL^dmyr?LC)(@>R56jw zusA#o*oO(5tI=mvMqo^x5!$!gEDlsLkR56jw zcsZFPYhoWJZ0=0Q3^YfU5&EpPSv9C)BAdB$GD2=*A0})LP{%$r*Ow7GX0X{osA3|U zf%M}m_F=;2GQ)@rwcU@e$|@ae#Y8rf>SXSl_m=E%~e3{qn8tz2xiJxYNn*Ji~0got3b8cwK3b zZdwk1xjrzvGrP zO$QUKf?L-Oa9?AQ$nLZBHY_YA>~<)-aZyqtPiFj=Q>(X`>21pSDG01=$X}8Xe*MGl z3d>bj`n<|>!886pwpOHfsp(osey=ODhszvWTls-CBJbZOi+N1xrRhjiFIht7Q<#1f+JkrAx2T!@M6hFD*B%?9rNGdJuR@kQ^a zn!}y4Af)c*u`-q2pJ+ER$_Pec^{IRlc{%waGzhCpM#COx#87X#eMN|#l7s4NN^P8Dt!tURF zSMJ}MnBk?V4r$~_Qw`0xfOUotjcemwUCtf zuaw|_FF&oR<(kd1x@)&OBIS8r*}bFAy)VRTLTr-}tg@Vj?VNy(u37KSUdrDiY%#eh zORe5JXtC9MYhM!r^%h?o*ZAhQ6WXngbqW8Ca`pkuL>?oRsThKo-ZTM^5vIW7!j;ud(OQo#BxG>yyU_rR;l}r z6ng?<08^VtSmoUotDJap{}saBpRx5gR=Mp0VW%a1%At~0 z9T9?QevKT7HQzPTy-rw0@=4uWRhRVk@cWW(1M$~Ct?l(x z7Q?!PvveRVbAv#xM?_-nqn@fRArZ53A5qZ5MZb%_Lo#m@#?WH zQ%)F}c0F@eb(7bSrndC0q2~#4lo0z1agz|NdiKh(Ewk<%nLgONqd-g(;us;;5rV^F zV)!4&w%q*T$n@4j&Ji0^ueiNwR_7s=SDI!w^;vpM%exn~ri-03tvc|r(JfC-Z%vnX z7Z!5&jG4DL%@rGe5@O#I7FBOOdssU5kVmWYxBI$U9X>4Wwg00&cdeY9OC?rggjh;q zb^CW?S{564Wct+S?bZI3u`QeY@yK-8`llDt@v7M9BgBB}>?T%SJ#K8v5icK^zO(lk z1!9p9TM6-*lpv>^3C?xrc9d8R7h;VYuxR?rWuU!>+o$>3AuR!zFiF_0t~ntKY5G zFP-q#)M`xpZTjs^Z;Or7B(J#CcAYl5Ww?~)>qi$$@Fj`WAR%6s@?cfRZ$`KL_Wahg z`RO9@{GV=b`a)vWUkGk%Ol-Ew=$22;YE7RQaFNuj4a7!^*cc@#fBu!xEpKizB7OhW zQ>$m}KBnd6sUy-EPfab9U|%726yjGxukK2Q@mubAML=G;z_yH`r?9xEld=Z%k7mzy~-T`#$|`ti`mt0xZ|nC`L1HH8*+ z>Wtf){wuM1Pg2gRpDgisb;hD?(}!2RxEM@+I5NLzT2*Ij*dp%YC z*;oD2eHTnF5O+#CE)Zg<5Ukqo(kH8s^4ERrscZRq?Yu&pg_DReaY5hJoK2g%aZEcUoMzw5qYHPahc^4IG;#|qAi-p)w>J_WDI&)OZcfW5< z&--tY=nxxA39)sdoip)uWmLZh3T zT2qK!#m25euxjC?-?ePqbH8-rSN*Cn@e3h-CB$+nP~-W40;cbMJ8s+(6I+w#Fdt?A}R zo>w6H39*(C8%geRI+)mp_`BHPcCgkz&kkyBY57HK`jZz?+lPpaKMS$15U-s5MD^CI2Bj0b{#<=!!NTe#LkFe% z-hX|eJdTwT+(C$KBv!0ibE}2bBR&|IzI^?41>!$q17o=PVuO2XCip4g+;(CE}l{h5B`s1aA{Vh3GHo zVAZp)ep{`5HY{DZ%%cUOMF_kbtSJOP&zazIa&A>2&_3>xSh4ESTfV6t_V;1wg}*Ge z^D~9mK!_W}28YE2kF}lKSyKK}A^syaxaCYc^zrIawSMX5?-twOaB1iN7Gj9xE~{2} z_+QoPE&bBkW>X98{1#~+i=@>K7aRQKWMc16pQs*v?tt{VzL!WX87A%gbs^Rlf>p=& z{a1CHnf=n$51Cqxi81nwx?N)Rv80@Rm>BfO$EqJp?Uydmfx6pQQvRUWcudm4J=qec ze^xzu&7tYjOBegZEhKmMgAIultHz)BX?1+MQ~Ld=hYM}+Txo-d)zdP*;_`@y@t;&L z7_(D4@V18}R%>4%&srG)+#*jLw9ZRk7?AGq=B3pa{`Yuw?xO?JIlsEJ&<5wqNdE}* ziDH9QXyH2H_sgS$9W{2RVO@Nz52re>D!YoD-gS0BRzwZ;9^pOoV!eLeRJ-3iPbcT)oBtderx2n zNe;=m$x?#7g;*#lXBFNJHXXEWdi}32FT`pEiPicNs~romVuEwTxqs|BckX|lnOwPH z$vHc4?(!VauupV$XZ$0}%2@7FAzlz-__A|$U=`0Z#Y8@LX9ym~fF z<=lQ=1v)42tUW}^{O!u@PLv1cuMif;1i$Aqp6d#M8L#(*U=@cO6ZYhknLBU8!eZjn z?hC6cExm54^RURHEG>@b_r^Z1bA5-8y}P=`%;{1)PRzbpPDH{gS&s;+hJ<6EdPF%^ ztTH!L7LpPNjy=0+;_JV!eDKH9=W;r@=5uW2-5?{bKmYW(tl}CT6G-{zvP%82{M-NK zoh7wi4m-V8>*OCXK$US{^Nr2P3!}=5hssO8~1eHBsMZ4F@jZaLlqN0UG`X?j=>Xe zZeky}ji_FtHg>u56S0vIi4m-V8>*P-9NX$`eDK!uP3!}=5wo9F8&{3(U2`rY5+hgz zH&iik<3$I08@pfDqryIL8}W-iTE~9XxxLuPh{On1!3|YRtZ?P--p1ditXW|nxQ+O3 zvf5at#{ps^BN8K61vgYNal@@cyp8ML?OS0VxQ!U}y4u+I!{3XIj7W@N72Ht8#9F)c z70xA(G&R*$-l4y5A1&Yiqzi5ka8G~W7ykD}JND{wu1K&7Zm42n$jNJX8`t#Sv&KGf z8`0jPHaSOqs!G4XD9x70_Myg2LN8vDR)#IU=!_UV|r&r)KeNU#cSsA6Jz z<#BIg^Or`~*avPSM*dW79NWCO*eDXLf*Y!sSY_Z9-o~lpkFT*0+(u09=;zb1{P6E3 zUyB5*;D#zD+Wxn+kOpSpX-XAyz|#a!3b<1-B75 zuBbLNuOuBH5+hgzH&ihpx!VLAC=d35+lbb2TTz*3L}CQ1;6|Cpgwzsm1NDl1;5K6N zvs-!_T6Z%dF@jZaLlqNJ+r1665B7oEh%0tf8`=glA~Awha6=Un(rUd8v~%`>+la&N z>Fd*>eMv_6o}s7$0aZ*$?^8i}pub`txQ*CzpxV$rF(VQqSOqs!F(JLEw}F0_ec(3Y z>Dm@P9q5C7zYD_m)I}8tsAA&mUTWjmm|TVvwGKiuW}#BINsTw@<~EAg8}Y6Gji&SgZB6Rc|UYr-*c+9uQP zM;n~>`IH*_s9TA9uNd#s@uyc|BO{WWU{zZRRZPrp>c%t5Ew$L>8vCeQiI=J;dmC5X z0~;BUmu^6%$9Fy;Kc(HS?eQ*VsqhN^Eht+Ia3k^j8^?R1M?Al`x6yO^o;CJSw-Os2 zFv;iD*Q-tt8yS)01gqLosA3{{R&NDk^CuakY$t;9L6s*OIQaVkC|lAK^wTMAW7-295(3cT8hXLPcUx|LX==VYH( zuY7Qv*vN<^Cs@^%LKPEx&(>RkFM4?6PWDl^68mqaHm*H#oY=^SBqvzamO>R1-(Ib^ z0-x~f1Lv}jx|P^;Yqjz6Q%8%9j7V~VRc$F$F(GA$@<{MceOT3&?z7MA<{u|mwa-4+ zl?dlnlbz8|$S&zMW?mrquHmjRbDA%MoY3DTE)tuZD5}Outjq=xE}Orq*$k8f(rhzR zaNGRV9aFlS)rJwQve_@FN(3TS0sGi3uM#H+gz3xHtWFk$3O+;8ycgZUn2$-SeZ%yGn%FaBQ8453W~x4=hiHN8;(nj=~9^+k@9Kb24x!-tAtgSCbSjK5s8rh(^|qlOjtSfd3keldMej3e-#?UFRItIS+ZNM4c+wK5mWg14+XoZegNxYzX{>fw{9zxH z$r~Keway^yY8sa=e(#}O8!k29yRZG|z%G?r%31ZyNsoHfW``YICInL(92OH@bN}J# z`Rg1M+i)B!rb~TdQqRVAyD#wJZvEmxKhU>xSWFB*?=er;UOq%)71F^ze}3d&UN!cU z!^$>7tXOr==Z|}0@CqY;fZ$j$!Ot#Ho|7oPu+Y?v5^sp5v+n6s+f34XXxEqvktDX58OuBO!{scuPQb&A~Awh za6=Un*?hZ``NRtQz-@%hq`MVY5*su_?+I4H4OL8J^X*RNMJwzBw-GjzzWOK2iw&Bg z_XMlphAJkq`F6|*SJ($`BWxzU^1`xWgJ$SG!78|+iivE#9W&b%_JP|7n@K^qyc9 z+)%{?&9_(B2W}&5CSA+CNU#cSsA7WV+biq?w-Gjzu64IaunKOdVuI$|E9?We5jIDz zZLmnN3T~)kLRzi#h0eEH_JP|7n@QKcq)4y|Zm42HdLO(I`QC?p;5NeM$hA)_60Cw7 zs+h=T=rP}3VIR1Szw!ftOMxU!>Zc*Mpi$uOpX4%7E_D|$*?mD}Q-KIWAWf$xAoAmH$ zT6^X&`Az;3`9ELotim2x5ZEbOA^`b!XZB$NJN`lAWDiW>PYImbf)CDi;S3JkIP=A{ z>WyF(PVj)hnV*J4!YZ5?0)cZy4GG6SOq9}*Sgf!+8sTDRH+KKQjUC_E6$rPUd_l5} zz|Ma7;2a$G?81%naa>M5<$+)ocKm|C9^n!JGrm07hY2p(*v1mFI~L($cPw_z`WVXo ze-6nL!3Gno!X8-A*fkpy*ryL4oD9Kv6S#3I1!wT!#;Lt1Rtc+cmJBMKJ}VI+R_wzB zPQHQ0dBr$Z*c}NU?8e2OOSrK!6MGfm#_q-_R?d8IipmI_!D?LQ^=bxom^LI5^MMNc zQxOyFVzuAP^@@FBB5(h3I#`8Wv#^2P%3PXpUa=1or7};fCURZE857vRsT2+=juoqL zrUe8}zLW^T%C(&dZfQ|E67GGt&2#OEVwJE8=RXiDoERw)Ay(|e1h;}HR*vf^P6NUQ z&JS`(ajaN{lVP5avt%WrZmgKVNhHuX#}>zmeQ@##Dx8lh*+{bTNLYol86a?)qeNJ& z682#NCrLo-S!9iumbvx2ILCth?NDJyJoYEUjnlbaA7aHSZu2F=V&&MU9)a_`u?<#P zFM}M1*v(4-=M$cy@Ukf#7_{*>L12PLp#vMX_?M z!dY|>II&(Lf(`az0;jM++?in{T09C@VokX#dkF$5?1k>UWpJxzI`NYgWq>Jq$pMitN87uM3@c7K1}d? ziMJ659!K5y^Z~w{G5+N7V?-pZ8g|ESo;Yvml^PR{!(!r!U3&#Ow!tc%18PV(_F*D^ z|4=Jh9<1UypoWBFA13&1DNYBgxNI5{j(wQmx4zg0tGJvS5{~OD(+%54RNHx;sYFQB z^l898OmN%Ow>zXp-qk8t|5){ByQQd0m`~p2+C$UPM^0_FbrJj?hy(~7QnRhG;fzU%NQ_{W&3|ur%xPu9Y&Z)Gd(|wp z{!DeYf{7T4*#Bv)Y~5hO8!HC_`D4Fdu=da6J~1&H$RAF*+0)z=6N#mxo(i!l5rF(V z4*QrJM8jA)&Rv^nzUTduqMY{0HX8}6Y@Yg&=Zs?UXIpb*!_Cgt9kJ`7 z_f5Krh+P)Ae*n)x-8-m^rkumF+4|jY9@{up39D=spzE)r8xv7Fn6Pzu zx%Szr%mZW2DA&Y5u*z0}ZkyXtCM5Bia;{fQ*s9Yr2b^Ds75mtF?QYvlFWU&QVwJ5A zw{3rEnW!5pCb<2JSQ26BXnI=L;<1i>j^gJ~MN( zs;!t_SlzIYa#q<2=74QCDHFj4hsA`gv2HqVW3^Et#&@n)HPvfP>oo3t5>}awXC7Uv zG2yr;W5Uw6?Z}@LV#Pj|Z?o54y|ImiRko^|zQ0OiB8pW#0#Av!1i8*!3EUuno)bI9xfjJbar~~kykWp%#VVX} zh6?+%OGJnj+rT{vAaDZ-hoo_`bg&AypMb#L{Kf?PFu^$z+u%I;`#ri>4LfB^L`XTS zPMWJbwy=Mw_ zm>lUSs&IB5v1&|kF2-fRxh^&m{Z}q?%d5DYvRDC_zpwh;Tj#B5l&am~onm+2LXQqDx<@?aI$#JYr7!JYki zZD1mUpilWW`k8WM+#Mm2sYS<37ap~Q>G#h1gmV0)K1=`oC1+ptXO4pp*Z{6*arJB zVY8}wh8I!FY&iC@`F5NW=8#066A7zqejlfoO9UWa=Iq0SttaRyY_j3l$JQfox|>5n zq(V9pR@v-uT>?-kR!rD@vYtg|8?3S!VdQ9u2sT*7w9O&wx$Qm_hg zjP|=THePNP`Yn4JKxO^PjMjI$VnV*nQEBbjciW}qq!6crRUBLGcYo8q#B9WhRcs?B z5Swx5eKZT{VIL-}Ki2a&xDN-J^@aRzQH7L46%#V1_O%dWYWA_d9R!aC{V3eqFv7y+ zXKhT}cgo>3beAGL{%jKHlbo?sQ+P{oAY_2O;FT`x8Ef!m0!f4Yf(CO&`p9!Q50xE;n5 ztb!Y=n2;tzE zM_r;eX7pNCY-B`Y1gqeNDkkI(A#dZ{1>-x}2W}%)xL<92yVRqy?=vG3BUlADR52lU zA$c49n%C%LAGnR!;t92};FF1BBO?+cSOqs!F|pzudaCg+-|ak?ec(3Y{C}$r+z91d zMkGeC3T~)kqVnXiO|zc5ZT9Zz_zK^1#rI$F&2P?~`|h#WDeIo>8efUOF%W;PApa%- z6ByCkHw|obZ{Ih_iJ=m!J@%W~AF+z9>*yW?$5w8Y7h<__mkj{H;o6A2hkU6gCUy`4 z>DZ%?awg!;?>sx}(~2+i^$*{?#y5%c4dc9XNKRqz+vJHy`t_~wEzP`M&-)=86Rd*U z?sAuUb?~0Bk!-Qv8WmO*cWIUgXN37M0k_@$?%ZK3AL4Bs(fNH7tBQL^ON2ARe3*dS zzDXe8uN^kV+ZcDmWBzLe=&9{%1#sJr))L{2FdyE9#$PdzI}=_$-rG3s-pl;=4J=&V zGgFsvM%Z@~n1I{9j^Nw__f7CNF1vP*CRXwOo4SNE!op%A{)WOWk52YBzFzs^A*?Fy z_pxtXIF}L52=ieAZu=sJ+#~ay_CA*nT>gGm6?Y^xCd`Kkxa}Jn(ue%Ur^BW9ygipy z#eGtZ3G-nB?)*y|`!75hdF772_0Ue<1IM=;Gc6;soyXUzD||Y5`lORRVYeppZOSom z?SNCfjc5Aq)X6?YB9GO$NuxY*{oc=X^1eRa6&T-Q-skcoYa{x6H+Z8FuXeHz-+Rs> zId@#sSYJz4|LoDuqRMV#kBRH29_M4V*W%Yjv4YA7&O^Bad-%B8ZufpQc;yRk_k^kV zzUY`(IO7CwV@&T$qVgybmh18r@P~Hu#LTPLs&W6y{Vwmhlp7gu+_`r2-xu3{(iiJ_ z!oC>6H~YuL4iD_*^XjwBSF06O_9cOsc=kmdk-fb^j~e^HZ3LI5+*N$wezm2JcH95$ z*=0OoD*kdoOmtTd^(p`Q%tgM;(O(t6h`@Ehxu@^lwl?O5#kZfmYyZ+S3N-e;^4Ch_ zHr>|keabHx`Lif@dDm=Atnu}ho>=9c9ct{u1b^Q|zE<$wrnTd5oI3dF!BtNnCfG5~ zJIQ0>?0Fmcl=r%HryBb(0k?fOMMeOtuIXbn{KMUA?85|qzrnfIX{*#0^_@C+-PeBQ z3B(G!;CXj^OzidL3O-i9z2mnv_F)2U`!0lYtDm@-kJZ5E52~>b6a1A2=l<2_%gzZO zB!k!J|2t10R@lwY`%41@=5vTiD^&(~lnQdU z&vU;Sf}JNXuX>PZqf+c!`e6b#5ECYN50kX>g%iDv zP2S$1iB(+3ewcs_#Ds}>Z`2RfUC^knF@c=5*+E;igv#9ci8`fKo)JksRb3+3u$2+m zFgFOBLDKaPZ$;-U6H{T;isyao_pmaWSgcsZb4w+n6f1XO+g6MSDZ-%rhV3QJt_bU0ICR>f${;#eMryaMD)hVP)`yW;rHs>nvd z*3BO7*)G{gEU#FFd%e*HF(*?ZLaf+_2@6T*mLRuu*nQEM-?Mw2&yo2=4oUPmk+90r zgjvoK0mzp*`_v;!wcYV8o1CLu{ytV_!?B9*^lD774-*aRRTL|}qmym>SS6NnR`HFS zC8BORnBcoKBO8u=_%_UvjSwqV@!ggsqHe61;9DzwtOCJz>2bJxkDn(J%PUs#je;d2 z*sz+2o6D^p(4fbJzbK2Vo1eYM+TF4=JBC%MpitivS5y1xgFu}JA#x}Ujxty(E!42~< z!79GxzeI#su@4jWWYF&$K%S-CnGc>BMqs6Zd%ieUtg;xsBI_R|BE*V)n6R3!>o^i4 zq+eo&f4HHCZ|l*ohv@J2Mc;aaeRbIOd(|bxgxRpL@;zQQtB!G(7iy`%NqdUSjT!nM zwt-z!rs5R=tODrQkF#`m3vpQS8Ukn~Zu`Uh`w#0rV28Wkm{P-D=Vd=WEXDm$yLA4u ziuI43Up>&@GzGWbP1Wb7b?`)U`<=LJ&EC~;J0aX(e0YriN{sC)#!Ylt*oO(*#jLjoj$C=k%7@ig z?m1xA0X0?)eCNSx?-^s$(|*}nxCLs-?f=uX&RQ>QH>r1Pjl*KX_F3b$E}7qb;`t^? zc+%t8)>=`u@~F`%R55Yp)qe%yu0Q+O8vDR)gzf&uEnv>I_xWqnpU#~>=kTkPFjfEN zN2(jWH!>Y?!=cf=Va|=-a!k{E?>;za?|~=RI4mY?A3E+0lUbbqwKgr9J9W;`{ZFp3 z>K~IIt$x}zBCYOwa92#c^whUQ*8g_upj(%lTw@<5Y^S{5F1Fa@MgF#)Pgb2=E2^xH z#l(VJ&yuev$qMNgS`#tSLs(oZZU4U3#EeLcuyCQW`Wh1t9zJI-Z2bH4$u;(2!p<1s zHZ$ikA~C|kg$iz{Vq)0YJNx;P&z3u-#y(8gDJZ@3EF%&lEL^DIhAJi|?l#lgIJtU4 zjeVG~vst(?&AE(7jIeN_f*Y!sSnb03-o|fk8B=2)ChS}p?pTwZxJo2OSh!HZ4OL7W zaN2j?#<($Z<2&8g#)O@G!!4rDWkh0xg$otjP{qXF53TO|-OVrGv&KG5*m*qMPAa$Q zDv=mr;X(yBR59_$>i+90?wVtoYV5;=ooQe-zVVm> zK|O;f&}tDD6V_wk+)UK_R9Iy_(F4aH)f^Ml!&TUa3G4avbPe^Q6;@fli_r@_wF;~33HSH?PHv6~ zdU96ShY5S4>Y1Ov%hUPF!Droj;)Go*tg`1hPW{Hj>e&e3h!c0Mun!Y9G63z|#TU-M zf9Ns??lAj}DKfvSBa3HljccOy!FryP`u3f3#7M~gyOOjsX`6Q@z%9<>ka zwV{d$>f0;q!-Vz0I0q}=8P%r&`gTvC%n`2j+EB#=_3ah*VZ!=gJ;O_VyC+}+;aaZ^ zRZP4)P5btPZW&WyA1161#wla@ijoqE5wL-9t=EPsCZ=S4`^Yi!)!Xa|U@FjXTOW+G z&vM#DiNpw2!3|YR?3nfK11{gQ!ai^tVSO-8vdfxR*0&qMD!8GFiTTn~JNbL(!W}E@ z1Gf>@2g~44Y&<1Tg9G}1yxsI;nml1D>$PzfJtjtFefwr-ZC_y@Cg8Ta0T3VAyCk~- z|1JBedHsXioqqdJzu~9^b~9op`Lwkk@#l(gmT1x04_A}do6^MxPObiP{=MOMPhj7< zCs>8kRd;qb`E$ZCal_E-?wr$OK;>sk4XCjX6F0R!RNZF7N_yE`+{AYBU#k7h2Cq%< zT1cFZ=T7Z8;5vy_i|jpT6|d05#HcmjnKfMU>M}_=`!K%x* zZpIsKz(Og()ujYk#cNYBao&IaH)}~L!T%O&2@_mHott!H|GSAyD-6Kj9*#~sDojM_SMj_AMHGMrm%s6%+Q=Q0&HKAGnR^I9zS$9%1`xs1dA!8>*O)UBwl&L+mPMAGnR^ z{fOGoz0Mio_aPTmAfSo~`f6w=`@n6)V!P-aYdY6QUk&vHtKfzzCU(od8v3^E@@5~n zjrjgGwV`{@Ga@m9Rd7QU6ZF;48vDR)#6_3r7)AHc(^o@1!78|+iiw`L=~qMh%RYVf zf!heXb?jEZmYNZX5v+n6s+gd!>dxi0H2%VFysk!H)%66zMJs{|ZnTe>;P$~jOz_-t z{#9MHkD>}T&^}^<+Xwr=Z3NFo`~B^x?S6lIQ3V3+BPQ&tx`U*Bun*iu@SJu2Rb3-k z1vloxW8(hotGb`b=>hhE+lY8BJR=e#SOquQM@-z5wU1q;eXtMQM%W4jR!N=9h{On1 z!3|YRESG&%_f9#@!9H*sVJi^YJ~ARPf>m%s6%%qQ#rIb@mBK!78)54Sy84*3+n! zu?<$;vaZ@d|5ze|4eqaOT)LO+9I^U_zALuDDz3*RBG_ObCai|8u+vU{%_r3MgjH4( z(Iy%aj_at=7|B?DEBCvsvNU1bULry|*oO(rLmihuZneaoIA^Z+WwZ4L*IxZ~v(<(6 zEk0`&eNKd@8dTPo{Nv_t$^;)1X|ZBO8uYe73Vh1RLzb1fSaUHtG^~?h^a@ ztaah}7{w}Km4%BvB_$%*U>_zdhWA)68VGB(7St%#AbE@qVxEn)JN$oZb3HH$mGy!hE~2-e=i}u-g}* zf_uhY!&4<5@2%&ZzaPIwg;jRrqTRAtBAgNC!vx%?Z!I@0^16mED&I%Dt#U8^jHvbqS!3eT+6@ z+LgmR?c7_M4mWVEXXdiX(uDhP@q1&!e3*dy=I)`X-lm(C2XeQQRaQ2*vG<1w3yTT3 zM;|^k1?}9iTCd!Mfmd|0%IX;I5&mJq!eRpMQy<+a1s&Q4YI`TEtgYC+#f=H`VFK=} zw%sY!yI4P*<=eTtS-$efDr@t&@AZcX3yTT3N8Gey3R=#RX@7;@r^YJlyKu|<4-*y^ z6L9}}^Bq&YBmT&&-#ufuzBN`^ziaomHzv%73A+swv|q8Toxk=U{2fAe|ItxDUB7BK zCgCgK{B>}h<3roPZE1Yt1>c0h-=WZ3-UhvY-z+2E++>9R#u?j-39P{VbJQ-guo}lc zOxRs$dOJQ=;3jPO0PfPOu!`eeCQg0&VNb9R6LuGxep63oQhi?n8$}gnQlW~8-}dh3 ziQg{R&hLl&*;oDiU3#`>0{80ecj=SW(O>pUufJ`Il*hZh`qs|rxzcuPAKw&q&_T6Y zwvz+*+sDL4Z}))>_ul6%HTGcw?oB@Hm)(xP{E*&0Ru`Q&yv9CE?0V@F)sY|cOSkxQ zBC$&ETfMgTw>`Ie^twGgfu8gK8aop(D~hY{7qTjgAc!FDh#MxL%yvnbJ9k_lFE2VM zfgr}X5Lv`g*}@{w%8LefF(Tj_g}4*N$TEn)G_(s~6hU8+h@wGpOGH5kAi{j-Uv*E< zzxv+c`Q~|um0Ramr%qLMcXijPQ?@1)vDYUWo!rvaYU@Lnhn&L^dyzixi>@}_uj~Mw z*}&GS^57LA=P>caw2hhRTe?Pj2EZ@l7lRH~fBaU9)YdUqSpu~}>|l;5>=WgKcG~y) z;Pq=l&S3)SKdkR+;}#op+UCt5g4SOR2|0&}8Nb_*X%u#i&i)r_)p+1r)yrqKNbOxV z+!Cl2Vjy#DWS&5dhYh=B|S?=g)D`Lz4NxY=)FF%eBAut5(6X37`e2)`+1Sw!j+?Op*T)@urbvJMJ@a%;m+0niT)b$N!taO> zjo*!7g3DqZKGCJ{m>wTa9G&{*CZ|KoVgj+M@jGHw%QNbX8Sv8&W=O4)Qn(%=_P#y4~z61aF9 zIwDX4I-s2+f%`<4Yi3v-(<{b=oWlfr)*18Z-j7O8{hyN5&>h!XuQ2GqNgM1_#<9wc zx%-X{&=Fj*ewgQZ#vXJ&QT^-rwpKfa-x6{T6I?@M)^~on^o;LcPhI+Pr6tstkA3`n zqVwdrr3IsEiW{{bWi5vtXhkM`%d4k1O1GPlN;PKe>%+&{ zTFvi$Ntl#U&pe;_siGMO^S6`wdzP~|9ouKj@@6MmV!=88z1^{zrIM%Xs2^cW7$r1^3HA__h@^k9(P4t~yAN8)Qt;BlI7Tdkyo6Cg zeG-{KT0IYI{rX0H-^=smORk^e&BCpDsb8NGs0qFf@@f{+wFLPsS&u)>VFD{y_}#5} zkzZfzBM9xh&gB#2w`4v3v@9mDVus({Dl+-?#Xf@2&g*JEp?*utVzJ


<34N!sL?C*sEm+4vn_wLn zG0>5o-s+?>tOy|;`!mD@OCjz#q;5OA-C+nWiwUdY>hZIgI;H$tXP&-%(5%EDFhJFqqm}@J}VM0e@d|E+F zaQt>2$MEHZzSu)3&|0ySdV(UVMh+3{;6A`gHOj^OLEA022U$vKte@u)u@25*g6~8k zEJmmuETtm`>-9MVAUhH{hY1~_@f|KEbcADE>BvWm@^};B+FBWw((4h=s~jTM!8uIu zIJP=s0w+eG4{)z#TE{f*c9saVtyqe$i5w!9h}32_D8PQ zi#{{(oX}?pr}12|wNf4S6b!T#r1aXx=@Clj5Z*J22~FqR8SE+G(1CKbZ*ay$orFEj z0|d%qLR&pP1tYdY+X{C89mlwr)Ttw2DSejUepM&o)rtwNA;z2Ex-6y75F~L&0rvcBtx(UulZdZ#jA|x$ELa_Z_PLHY`Tu1)4?~&C~~dKIZSZh_?EMj zj&RKM>m&^4FyZ%kb`=?WWzv{s;7u5F5uS0VSE$>~0pf~x=Pbf|Crk0HCYOLU(7`!L z0{d~Cj`rf)1!8S!sof2vIqGc+DfJzNSGh5L#kXn1_@bW-Z6;eD;Qy00T!s{pm)9Hf;%4YjtielEUUOK!X?_3@(L zrq#b0{^kP*Hz+@KTSatTlU?549Ai#d-O$!*RL?8YNvTfF`bMyc?K9@4daW$6Yu{y_ z<&aW>?K9?v^oG*UdrwcDzjatzJy+o?Kl_IUUirt=gmI(N>O+eiH4CRVET8tf3JGid zpH*C2snyqZ9Vd9B;+Aw$>dFZf5p42_2X?$_Yc*l&2+wjzDZ%y`Q~71T(qQ(Tsm((s zq}3-CyJ%`oZ&dzOVMWww_}*1qTVu{^c9Ydn`t7)MQffi3iU>COMEhY6T4LCkF`ng+ zQiAO>X819idJH-5&eWkt0sDuLrMv@57(-Rs#n&E+5dQB6@!8zExaX zi4Zb&lU*6T>+2~p+I^{!Z7U+sKJlv;=VE0v*k3rsvm8=Nuzj|zR%%_#;&au#;!?7>DcuNxjt;I zaD8wN(n_#>_I_2Z_bc_;#vP~K`$xw2EA_K>dw%3Px3$7`o|Mw-+$ZE-Vrzwa3FjcK z1lwot?bVy_b@z7NZ-Be=z`;kw_jazWG2iytZEIEX~1k$xn=cYC1 zlwwYD{uf=+HLp#SxzE^WaPy@ZJyjXL=RG@&kl!n#j@=f(%OXphCj?9BS4Z1JceM1Iu;ndF-qGl|`bDvxS{Q-h=nDFN%(y*8_*gy5Ohi^X8$up## z2Y!|a1PPK-dU~0b0)t*L+^BQsTBA*DYKB73Q z5vSDZ>Cndfx$Sd>Z;Nz$p;$^iS8x2XbAoufO^aoqc)^b0|xls?LaF%cy(OXzbBUm9ip--Ue zI*T1Egy0+|G%l7KSN+FayR^MXzbzEo!FA_nyD_at+)=euh^|7gwfrPwT4FlQn^|<3 zNIxtTOYw8iCw_PA-flG_{iXcl947o{)ZP_GSN)$zA0v9;{|(RnMKjy3hW|Ep613{p zX0`v_XYsh_mwq5|qgqOoCZ0#}{EBtUsa8*w6rCgGuM|Bj#q%AXxNghT;+<$G(Ze}R z_^rFO|J%jyOO09y!4~qRn$$S7YW6!%Pk7ee(ZHv)wI2g_D|+CE`(<^#x7qu>eJqB;hBkR@S08a zinIq=N`3QRy1r9_n0r=zOSG1n@m0%&?geOBzoXRZ)MF17?2{VF+2r0+jh_r`lQE-~ z&0hM6^hIOo6PDs5d zVp+|ug7o&bvi?l-E1sA5#PZ<}7q*jjS}(QY9463D*gf?4D@RLPZEpXk)S7mM=@WJq z*tw6+cX(#u6Q`YgUuDdbd4LGP`MEy3e5kJ6qBj63<0^Vp?glrQ=0MrRd-sCb(zi)VJ!J zQ$3FJkRMe=djgn-NDM5U`v&^0bjoA`k=S*-L8gp*@g+<+^{1=2^DWtLQs^8rm z5>JDTRZmvEB+^Afaam0Gceo4hXtHF#5V)7{?1jIo@Kf8E6YptT)K<#hAOuVCHyNLp z{(G}zuSm;Y6K@8G@k*cd5T;e(WVP{O0F zPQn|BOw?&dz*6c7idC{4Lh9vOmvfllR?nJ|CAdvg3jV2Fl25Rd>VUUt-2~?_q4qg1 zRv3}A1E-xZt>ev|H$gd^{1z6O;Dc(2U670ctjM7&Q&glpR>U@6{9ltZWv!#a5143}heC=sv}?<=X3Fr32# z$IQ*@kof{)J9C@~jsCo-)r3_VQx@?jB+CD;W{b12qvLZ%A*HdSCpEY&LF}K>MB`Ii z-&(9eqAVsfZuQUs(?rMkXIGz(IU@dXjz$~4fA{o+j-6LFTbzwmoMtJFRorm>eF@^D zoA(rKl=3AWvR5l6G*0pv?>{89!XMs(@g+wi=;Gu>q}k(F({iRoX6-_?gUiyGyK8=& zm8jJTLw9S$-ZV?GKEFRo{&7V?Hjc1oM=s&~lZ~nW#z{-Q6&rp`*ukF5?Ds4ubSGkR zeDKl*5x&-8j*H$z8Z%C$@lCF7f~Ango^eOyi^+i;ynmuxe67n%#4$OvEGCe~-goz{ zFJDX!M&(6X378hiLb$1w*2jj*BR;{6k8eErBv#4$OvEGCdfECSGR z?1VsKC&V#1kc0O&=)gCUyab{xSVGHUg5Ub&r15M_j%O$)2g=2}6LjExFfU=0KzxQI z!S9LrV{)KeysJS6-XQZ5aZC=xnMe}+o``Fh_gftn-+SMR%6S2;YPWijD@nUF7>b|p@pQ#J;Ko|eQ?8bQLH zqQnGCu@0a3siobWX?lHD5+-LE7+07-@Qfoq%{-9P%Zl15JYR`VGY{l6^JXN)j$VkNO=jP z1kP1QO_<<0QGA+tAg7sEvlQk*(1F=fUcxAWbJbB3CU_Pl-(H_}do4R{zI-K1VYUPv zn9t=Uj1r%;9${<31kbhXV?+MOy`}PK=Xsm{p7TZ@u#~1X5*un56FEANlaFw*+wLe& zTknLICr=DN*!EK<+}$(U*koM>X_Slfx)!^HL~75t7AsDb(y?`Q9{dN0_mt>&j_?J%dWYm z6kYiF%i}|qnz8;rR>!Y*tj**lj1pQF6G;F2m5U?LvZDC&C#;SEPmc^)>e?swSRJkI zTARsB7$vkUCXk+f!^IJ3*{i?%J*(rBa@dfN@!V3ApPL*iz3j*JU7+)y#@=Lm4+vxObKEO!Bqn$Adu0?zd?&80Un`b!C(T#dI8}8MEH&uH(Y6&3Z>vtia1Ikqei&tG z#1Qjq#nuiyYqFJk;`cY_S{`Uyv6MRzywaZ3RA*Zm&SAox8(wM8lJaZiPGYaLQEuFs z?v*xL58G#nxK=FX&W*3Mv59gB!Q8lFseAkX!CKz=@3+_8x&cf5YROnjG`RaPgx4QT z@aXX^=QeR?tXJC8xws8|%UQ~u>0W71OUohDa<4y_aA(L@+SA$mTDcSKD{VxeUAIoK zmd`SIEDyAGS?aTYj<*Ej@YLBKURyE2W5KT#*LT3fw^|*yb(wsavCC2oPId&M(ft3l z6%#pj#Fn$vIe&KdF2obcA;cK>Eu3?h;8yoMGeh-sL5y&uao5g`7cP4|1NZx7M>mwY9k8qfjf(Hz2V*6r0WFvmap5^LUlWYZvu~qb#^$UMQ zVzR2wwvAk!^+@{T)SnVDuvR@}tEus1?sTBN+U=!OXUxdH2KHFx%)DfQL>bI0^ z1?NM5-aNZEBUJx(MB`TPwi`DbEc0q>o@;J>&x13+9Tz60;EM&DeB#=n*1z3M8#BhU zT)pO!t>E?>)Rfu18KLe4Kpb-Q@q1$Sp)#(mG39@?e)>WBok?L*3O;_Y$tM;(YWD(| zN2?}!maFezvK8F@YFm4|HzR~EC$10FO1(6H_~=j>*Vafs*gXxwonKFp(eCzUs1)`z zfcA+F&)Izw=E$Ncp5^MxnQR5Ok44)`cb}l{>Ys|X;@TP`I_#SlbR?y;Rz4wi;C;}* z4$eVZ3AWFUt5O|Tx>E=JtiGHWS6o|Tq(9s{j`T-TN_)^Jq|ZSZ^f~7stpwX=uR*&% z3fG|SYQi<4URw6*%AVk3N2QUmYiotEo0QVg&i2XsM{~P($>93n9QA=swt~H1mFoRU zcYxvkppUr?cLtx3dx>o;+)FqIX(iY`Z{J-A-zbcB+-ud-3HNrc ztueG;O-8%hou^WI7xjtko;ZX1F6SVv1lwoKj@LV+$2M)+{qr+=hw4X$XOwz~;W@~) z_4f9KNhy8e_(XR9pppH9p5^KxmTU#La}pyFPiHO*HPojl*VfJe?Atb;wJfFk4KM@9 zOW3C~=P;q3@}P~uiY00#>#3ppX5~&lMH;b}8k$oQr|QB(?@+f#3S{Nd5-Npt?sMNb z*T(zw*R~&*m0jrQB?RX%!K>u)yK{gyNPNx4IwvAm>z8e$-<>0M#`uBe_e$UK(=ajQ? z(>Nm+dUPKP-pO_T$?2oNe_@p|@WgE;I@T3$TcT3PQGNI>$|V^C=}k^Y;7f50YxkQZ ziP{{colWj{x5wn5l>d$VJNDe$3Vf*tr4=e8ykTpt9I@fWIR#liORopHrCT=JlbJNE zF#4+faOuH`zxY{kD7Ks_{lQOXeyZsji#t8yo$rqBmTh7C9L)EW@resZnnhV#yk{*x zqkN)sqdirV#PVTsE;8pZ;Xgn6{$Ix>SkcGz!S@or9(A?GMKNExWPR1ELUa@zEX7x< zPb}$s-s0?D0Nc9Q+k>*0z}T%lmHqy|?Y4VmaGkRhdujRv#%$KVJzkH(`S47rH>JGU zlt~QiYmY0;`tQaObC848H;sGm_xTr1IxhW8EUzz?vlLodquBdIul+3wF|NK7J2;04 zzGE2k=Bg)_jur3go8>ffo=x(+lzY~gdwza!={(v0aZ%$!Z}!TwKA-r0K%e5zW$Ydy zwc;EmcuY&A+tJ&q?hre!7R!13@VtaeGUgxqE-S7U9cRIEn!WHm$S0nk5Ea3{{eeWS znBWgst4KGAr| zD^-6JqF4ydVS>kk?0;PR+R_)K2fIrTa(#I&;#+?EJNFfD7Ry_RkY zNv&R!T5%2&{wxF6M|M|AsJl-RP1OZcCeK0g25ccCt8ncXRj#S zOE`xKes7oO$*{G>zn1+557saA-st&Fm`gI|!((nq^_HC$bM_Y4cW0gN@SC?!9GW%1 z>N#nv9*G`gLOloE*)@m0Iasnlc8ru9D)8Ru`Ayg-Uin#DyDLSWZgyPh*)>e4=YTtd z=lJezm$j7rKJPa#v~SxwH{^G9pFj`F(;wb#A?Glmo&)YIp>6FZr9L~hFkNqVf%gr7 z-<^G;X!G-h$H_>P9SZgir)LQmzHd!Hznc|>YU zi^6o%0|nmLWrFW~66tp3{Z&iE^79j|t3D+-4ao2FZYR#s{c0ggsizCh_VJ0!&N;m* zyDP;TyG*DrjytvI-l;F?9+QxBkk+$ud>v)`->7;<>`03pECn5U@{Ld2zu@Ddp3)zW zC$1?kB_yA@~l!?;n1D%zR^cRh86A_H)`d79ENFzT*@7cAQ!Dfe^AQ z*Xuzh{29RW7oJ-@T52^?YQ<9g{^1iHj&E6nk@$`foWlgqSKL`Ia*1FTZlh3QPK~HM z8u<(9$NsC8od>&_4DN^BPxu69NPBTBxet5-`*5~3>0x&^at;%iuR!n#`A8LvBvN~qUe-YgV1iq+3>aPb%qLD8?Bjq|Nq(8muT}#}$>gmG} zEQR!fxh0V!evmi-q9Rx?=M{NUZ*R2a4p{M&)saIOB{b(#CM5mH#U&AFDO_UiK*vn^ zNWoI=e&%$1^3;X6gYs#$91#ZJd1m;5D@m%#aIme8`8Kze-7;s~_7ZA)|;*io^) zUo}e|*TCsm(|TSeFJY9>vY0@6){jLIXk!jatQzQO*?QATmYTTj9otq1-+MfhmoQ3b zSxg|^V^L8AT1wBZsUeY+!c}zhjK?y03802^lvbk4$RbM{QU9^?`uE;q|Tz~3@%>EOLqT3h$uMpo#502T{Cbe^WzfzXc z-aNV8|7LumpTu8*j%7#PRLVI_ApJ(eq6oAx`$mtkMB5P$mU0dgb4PE;%=@k|`g+o% zLLipY%3*C%i0#BuI*u>-Vot^{7D&-s|kZ%7< zVFcQk?GpD2#3`5VF6A61J{Z3-Q}ujdRMZW`Lb+cZ`A+LpnS2yxDZO_cJAYQjClG%H zI%Hic%{fdUJ#SuN1X^nI<7Jk3xu#{BbC}q7*1MUlvkIf>oj~l8JN1frty6N}wFKG< zW$9h}`==hs_{7Ney{(Q3A9P4_4iiZKVMbvDT68>DZi%w;Gt!*HM86;2&D?ljVf18Y z5I4y)>iGv+rzT3AIF{096rO`Vao0;JtK%;vUDKSy1k(CUGzK#Ow61*5@ScP0O`|lP zi7^p?U@7*+@ri}gMplc8VC2$qp3mL17DLM4>M$gFwed{P|4v2;5iEr?`X-lv4cYsm zQ9l`+sW<8-_~KMV^}{CK`Fc)V@1!jCY?pqPz$tv{Cxf&{81>|EUkBZHIHdJ=d|UJh z|9he%AmtPD7xW0h&66nq9CwhT7ILIxW3oh`1lk9&4Izaz_Hg>dQIGerI+jdnm*yNM z{0PcfB2Yrhg%r|=Vd@j}|1`+z=<{g(ILf<9DZx>X#STXVO0X2th{fs?)i(^WI(EqE z5uAgx5*!=Zm@E+}!BR*gLaa~7DHv7<&a~hhq?PbvE@z2A36??{5ovuw&gQT>?tOb) zDd!-qgvQ)PTvlVUM4$vqAq^>?kTXWCjxJ?wOF0K=B{V9yJ3Tu~1WK?J(vb3r<}XdL zI-Wh)s|V*GtprCm7jHvH1WK?J((vW=iL>VXt+ZcwRk}&p;%dFl;ajIy@TYe-wElPM zi)T!CA^Hl@PzaXVIO*#0jxBy;cWtrvo;;X@I9-S>LU0Zf6PsOIKB3RR$X(~Z8Z<8a z#}(u3`W<|lae_7cjR(K?T4vSjH%71iX1wf0cE3B%2kbfWo%|YFNdBmDb%b~-f=HK2_roZP9hI5$E^yE{n6CJ%o#}}@31IZyple#$2@TG>GUSN;Vd zOY!P!l5l=%V0lMHa;HV@{#q#;tt&cAkd#t8@OxfDpuw5zuU{V3)ZpFHr4QAdY|}%o ze&P#aOGwf7549VdsV!^pYD$yt_Xgh6t-k41;B5sW_4P9;D8`x}7 zeY3Wk5c1^l>TZb|&kod3{sQ;U5-gRi72A;|0AyQO?XXgLh{t0cF~L%v<+ZKg>Mv^S y-(as+WI2_TB?1BDpChvE!#X^|jlwLEp+2|zxOH9sJ4xL)>g#Z{Yb&H3@&5pgFc6pk literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_dependencies.xml b/lerobot/common/envs/aloha/assets/vx300s_dependencies.xml new file mode 100644 index 000000000..93037ab71 --- /dev/null +++ b/lerobot/common/envs/aloha/assets/vx300s_dependencies.xml @@ -0,0 +1,17 @@ + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/assets/vx300s_left.xml b/lerobot/common/envs/aloha/assets/vx300s_left.xml new file mode 100644 index 000000000..3af6c2350 --- /dev/null +++ b/lerobot/common/envs/aloha/assets/vx300s_left.xml @@ -0,0 +1,59 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/assets/vx300s_right.xml b/lerobot/common/envs/aloha/assets/vx300s_right.xml new file mode 100644 index 000000000..495df4780 --- /dev/null +++ b/lerobot/common/envs/aloha/assets/vx300s_right.xml @@ -0,0 +1,59 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/lerobot/common/envs/aloha/constants.py b/lerobot/common/envs/aloha/constants.py new file mode 100644 index 000000000..e582e5f30 --- /dev/null +++ b/lerobot/common/envs/aloha/constants.py @@ -0,0 +1,163 @@ +from pathlib import Path + +### Simulation envs fixed constants +DT = 0.02 # 0.02 ms -> 1/0.2 = 50 hz +FPS = 50 + + +JOINTS = [ + # absolute joint position + "left_arm_waist", + "left_arm_shoulder", + "left_arm_elbow", + "left_arm_forearm_roll", + "left_arm_wrist_angle", + "left_arm_wrist_rotate", + # normalized gripper position 0: close, 1: open + "left_arm_gripper", + # absolute joint position + "right_arm_waist", + "right_arm_shoulder", + "right_arm_elbow", + "right_arm_forearm_roll", + "right_arm_wrist_angle", + "right_arm_wrist_rotate", + # normalized gripper position 0: close, 1: open + "right_arm_gripper", +] + +ACTIONS = [ + # position and quaternion for end effector + "left_arm_waist", + "left_arm_shoulder", + "left_arm_elbow", + "left_arm_forearm_roll", + "left_arm_wrist_angle", + "left_arm_wrist_rotate", + # normalized gripper position (0: close, 1: open) + "left_arm_gripper", + "right_arm_waist", + "right_arm_shoulder", + "right_arm_elbow", + "right_arm_forearm_roll", + "right_arm_wrist_angle", + "right_arm_wrist_rotate", + # normalized gripper position (0: close, 1: open) + "right_arm_gripper", +] + + +START_ARM_POSE = [ + 0, + -0.96, + 1.16, + 0, + -0.3, + 0, + 0.02239, + -0.02239, + 0, + -0.96, + 1.16, + 0, + -0.3, + 0, + 0.02239, + -0.02239, +] + +ASSETS_DIR = Path(__file__).parent.resolve() / "assets" # note: absolute path + +# Left finger position limits (qpos[7]), right_finger = -1 * left_finger +MASTER_GRIPPER_POSITION_OPEN = 0.02417 +MASTER_GRIPPER_POSITION_CLOSE = 0.01244 +PUPPET_GRIPPER_POSITION_OPEN = 0.05800 +PUPPET_GRIPPER_POSITION_CLOSE = 0.01844 + +# Gripper joint limits (qpos[6]) +MASTER_GRIPPER_JOINT_OPEN = 0.3083 +MASTER_GRIPPER_JOINT_CLOSE = -0.6842 +PUPPET_GRIPPER_JOINT_OPEN = 1.4910 +PUPPET_GRIPPER_JOINT_CLOSE = -0.6213 + +MASTER_GRIPPER_JOINT_MID = (MASTER_GRIPPER_JOINT_OPEN + MASTER_GRIPPER_JOINT_CLOSE) / 2 + +############################ Helper functions ############################ + + +def normalize_master_gripper_position(x): + return (x - MASTER_GRIPPER_POSITION_CLOSE) / ( + MASTER_GRIPPER_POSITION_OPEN - MASTER_GRIPPER_POSITION_CLOSE + ) + + +def normalize_puppet_gripper_position(x): + return (x - PUPPET_GRIPPER_POSITION_CLOSE) / ( + PUPPET_GRIPPER_POSITION_OPEN - PUPPET_GRIPPER_POSITION_CLOSE + ) + + +def unnormalize_master_gripper_position(x): + return x * (MASTER_GRIPPER_POSITION_OPEN - MASTER_GRIPPER_POSITION_CLOSE) + MASTER_GRIPPER_POSITION_CLOSE + + +def unnormalize_puppet_gripper_position(x): + return x * (PUPPET_GRIPPER_POSITION_OPEN - PUPPET_GRIPPER_POSITION_CLOSE) + PUPPET_GRIPPER_POSITION_CLOSE + + +def convert_position_from_master_to_puppet(x): + return unnormalize_puppet_gripper_position(normalize_master_gripper_position(x)) + + +def normalizer_master_gripper_joint(x): + return (x - MASTER_GRIPPER_JOINT_CLOSE) / (MASTER_GRIPPER_JOINT_OPEN - MASTER_GRIPPER_JOINT_CLOSE) + + +def normalize_puppet_gripper_joint(x): + return (x - PUPPET_GRIPPER_JOINT_CLOSE) / (PUPPET_GRIPPER_JOINT_OPEN - PUPPET_GRIPPER_JOINT_CLOSE) + + +def unnormalize_master_gripper_joint(x): + return x * (MASTER_GRIPPER_JOINT_OPEN - MASTER_GRIPPER_JOINT_CLOSE) + MASTER_GRIPPER_JOINT_CLOSE + + +def unnormalize_puppet_gripper_joint(x): + return x * (PUPPET_GRIPPER_JOINT_OPEN - PUPPET_GRIPPER_JOINT_CLOSE) + PUPPET_GRIPPER_JOINT_CLOSE + + +def convert_join_from_master_to_puppet(x): + return unnormalize_puppet_gripper_joint(normalizer_master_gripper_joint(x)) + + +def normalize_master_gripper_velocity(x): + return x / (MASTER_GRIPPER_POSITION_OPEN - MASTER_GRIPPER_POSITION_CLOSE) + + +def normalize_puppet_gripper_velocity(x): + return x / (PUPPET_GRIPPER_POSITION_OPEN - PUPPET_GRIPPER_POSITION_CLOSE) + + +def convert_master_from_position_to_joint(x): + return ( + normalize_master_gripper_position(x) * (MASTER_GRIPPER_JOINT_OPEN - MASTER_GRIPPER_JOINT_CLOSE) + + MASTER_GRIPPER_JOINT_CLOSE + ) + + +def convert_master_from_joint_to_position(x): + return unnormalize_master_gripper_position( + (x - MASTER_GRIPPER_JOINT_CLOSE) / (MASTER_GRIPPER_JOINT_OPEN - MASTER_GRIPPER_JOINT_CLOSE) + ) + + +def convert_puppet_from_position_to_join(x): + return ( + normalize_puppet_gripper_position(x) * (PUPPET_GRIPPER_JOINT_OPEN - PUPPET_GRIPPER_JOINT_CLOSE) + + PUPPET_GRIPPER_JOINT_CLOSE + ) + + +def convert_puppet_from_joint_to_position(x): + return unnormalize_puppet_gripper_position( + (x - PUPPET_GRIPPER_JOINT_CLOSE) / (PUPPET_GRIPPER_JOINT_OPEN - PUPPET_GRIPPER_JOINT_CLOSE) + ) diff --git a/lerobot/common/envs/aloha/env.py b/lerobot/common/envs/aloha/env.py new file mode 100644 index 000000000..1211a37a8 --- /dev/null +++ b/lerobot/common/envs/aloha/env.py @@ -0,0 +1,311 @@ +import importlib +import logging +from collections import deque +from typing import Optional + +import einops +import numpy as np +import torch +from dm_control import mujoco +from dm_control.rl import control +from tensordict import TensorDict +from torchrl.data.tensor_specs import ( + BoundedTensorSpec, + CompositeSpec, + DiscreteTensorSpec, + UnboundedContinuousTensorSpec, +) + +from lerobot.common.envs.abstract import AbstractEnv +from lerobot.common.envs.aloha.constants import ( + ACTIONS, + ASSETS_DIR, + DT, + JOINTS, +) +from lerobot.common.envs.aloha.tasks.sim import BOX_POSE, InsertionTask, TransferCubeTask +from lerobot.common.envs.aloha.tasks.sim_end_effector import ( + InsertionEndEffectorTask, + TransferCubeEndEffectorTask, +) +from lerobot.common.envs.aloha.utils import sample_box_pose, sample_insertion_pose +from lerobot.common.utils import set_seed + +_has_gym = importlib.util.find_spec("gym") is not None + + +class AlohaEnv(AbstractEnv): + def __init__( + self, + task, + frame_skip: int = 1, + from_pixels: bool = False, + pixels_only: bool = False, + image_size=None, + seed=1337, + device="cpu", + num_prev_obs=1, + num_prev_action=0, + ): + super().__init__( + task=task, + frame_skip=frame_skip, + from_pixels=from_pixels, + pixels_only=pixels_only, + image_size=image_size, + seed=seed, + device=device, + num_prev_obs=num_prev_obs, + num_prev_action=num_prev_action, + ) + + def _make_env(self): + if not _has_gym: + raise ImportError("Cannot import gym.") + + if not self.from_pixels: + raise NotImplementedError() + + self._env = self._make_env_task(self.task) + + def render(self, mode="rgb_array", width=640, height=480): + # TODO(rcadene): render and visualizer several cameras (e.g. angle, front_close) + image = self._env.physics.render(height=height, width=width, camera_id="top") + return image + + def _make_env_task(self, task_name): + # time limit is controlled by StepCounter in env factory + time_limit = float("inf") + + if "sim_transfer_cube" in task_name: + xml_path = ASSETS_DIR / "bimanual_viperx_transfer_cube.xml" + physics = mujoco.Physics.from_xml_path(str(xml_path)) + task = TransferCubeTask(random=False) + elif "sim_insertion" in task_name: + xml_path = ASSETS_DIR / "bimanual_viperx_insertion.xml" + physics = mujoco.Physics.from_xml_path(str(xml_path)) + task = InsertionTask(random=False) + elif "sim_end_effector_transfer_cube" in task_name: + raise NotImplementedError() + xml_path = ASSETS_DIR / "bimanual_viperx_end_effector_transfer_cube.xml" + physics = mujoco.Physics.from_xml_path(str(xml_path)) + task = TransferCubeEndEffectorTask(random=False) + elif "sim_end_effector_insertion" in task_name: + raise NotImplementedError() + xml_path = ASSETS_DIR / "bimanual_viperx_end_effector_insertion.xml" + physics = mujoco.Physics.from_xml_path(str(xml_path)) + task = InsertionEndEffectorTask(random=False) + else: + raise NotImplementedError(task_name) + + env = control.Environment( + physics, task, time_limit, control_timestep=DT, n_sub_steps=None, flat_observation=False + ) + return env + + def _format_raw_obs(self, raw_obs): + if self.from_pixels: + image = torch.from_numpy(raw_obs["images"]["top"].copy()) + image = einops.rearrange(image, "h w c -> c h w") + assert image.dtype == torch.uint8 + obs = {"image": {"top": image}} + + if not self.pixels_only: + obs["state"] = torch.from_numpy(raw_obs["qpos"]).type(torch.float32) + else: + # TODO(rcadene): + raise NotImplementedError() + # obs = {"state": torch.from_numpy(raw_obs["observation"]).type(torch.float32)} + + return obs + + def _reset(self, tensordict: Optional[TensorDict] = None): + td = tensordict + if td is None or td.is_empty(): + # we need to handle seed iteration, since self._env.reset() rely an internal _seed. + self._current_seed += 1 + self.set_seed(self._current_seed) + + # TODO(rcadene): do not use global variable for this + if "sim_transfer_cube" in self.task: + BOX_POSE[0] = sample_box_pose() # used in sim reset + elif "sim_insertion" in self.task: + BOX_POSE[0] = np.concatenate(sample_insertion_pose()) # used in sim reset + + raw_obs = self._env.reset() + # TODO(rcadene): add assert + # assert self._current_seed == self._env._seed + + obs = self._format_raw_obs(raw_obs.observation) + + if self.num_prev_obs > 0: + stacked_obs = {} + if "image" in obs: + self._prev_obs_image_queue = deque( + [obs["image"]["top"]] * (self.num_prev_obs + 1), maxlen=(self.num_prev_obs + 1) + ) + stacked_obs["image"] = {"top": torch.stack(list(self._prev_obs_image_queue))} + if "state" in obs: + self._prev_obs_state_queue = deque( + [obs["state"]] * (self.num_prev_obs + 1), maxlen=(self.num_prev_obs + 1) + ) + stacked_obs["state"] = torch.stack(list(self._prev_obs_state_queue)) + obs = stacked_obs + + td = TensorDict( + { + "observation": TensorDict(obs, batch_size=[]), + "done": torch.tensor([False], dtype=torch.bool), + }, + batch_size=[], + ) + else: + raise NotImplementedError() + + self.call_rendering_hooks() + return td + + def _step(self, tensordict: TensorDict): + td = tensordict + action = td["action"].numpy() + # step expects shape=(4,) so we pad if necessary + # TODO(rcadene): add info["is_success"] and info["success"] ? + sum_reward = 0 + + if action.ndim == 1: + action = einops.repeat(action, "c -> t c", t=self.frame_skip) + else: + if self.frame_skip > 1: + raise NotImplementedError() + + num_action_steps = action.shape[0] + for i in range(num_action_steps): + _, reward, discount, raw_obs = self._env.step(action[i]) + del discount # not used + + # TOOD(rcadene): add an enum + success = done = reward == 4 + sum_reward += reward + obs = self._format_raw_obs(raw_obs) + + if self.num_prev_obs > 0: + stacked_obs = {} + if "image" in obs: + self._prev_obs_image_queue.append(obs["image"]["top"]) + stacked_obs["image"] = {"top": torch.stack(list(self._prev_obs_image_queue))} + if "state" in obs: + self._prev_obs_state_queue.append(obs["state"]) + stacked_obs["state"] = torch.stack(list(self._prev_obs_state_queue)) + obs = stacked_obs + + self.call_rendering_hooks() + + td = TensorDict( + { + "observation": TensorDict(obs, batch_size=[]), + "reward": torch.tensor([sum_reward], dtype=torch.float32), + # succes and done are true when coverage > self.success_threshold in env + "done": torch.tensor([done], dtype=torch.bool), + "success": torch.tensor([success], dtype=torch.bool), + }, + batch_size=[], + ) + return td + + def _make_spec(self): + obs = {} + from omegaconf import OmegaConf + + if self.from_pixels: + if isinstance(self.image_size, int): + image_shape = (3, self.image_size, self.image_size) + elif OmegaConf.is_list(self.image_size): + assert len(self.image_size) == 3 # c h w + assert self.image_size[0] == 3 # c is RGB + image_shape = tuple(self.image_size) + else: + raise ValueError(self.image_size) + if self.num_prev_obs > 0: + image_shape = (self.num_prev_obs + 1, *image_shape) + + obs["image"] = { + "top": BoundedTensorSpec( + low=0, + high=255, + shape=image_shape, + dtype=torch.uint8, + device=self.device, + ) + } + if not self.pixels_only: + state_shape = (len(JOINTS),) + if self.num_prev_obs > 0: + state_shape = (self.num_prev_obs + 1, *state_shape) + + obs["state"] = UnboundedContinuousTensorSpec( + # TODO: add low and high bounds + shape=state_shape, + dtype=torch.float32, + device=self.device, + ) + else: + # TODO(rcadene): add observation_space achieved_goal and desired_goal? + state_shape = (len(JOINTS),) + if self.num_prev_obs > 0: + state_shape = (self.num_prev_obs + 1, *state_shape) + + obs["state"] = UnboundedContinuousTensorSpec( + # TODO: add low and high bounds + shape=state_shape, + dtype=torch.float32, + device=self.device, + ) + self.observation_spec = CompositeSpec({"observation": obs}) + + # TODO(rcadene): valid when controling end effector? + # action_space = self._env.action_spec() + # self.action_spec = BoundedTensorSpec( + # low=action_space.minimum, + # high=action_space.maximum, + # shape=action_space.shape, + # dtype=torch.float32, + # device=self.device, + # ) + + # TODO(rcaene): add bounds (where are they????) + self.action_spec = BoundedTensorSpec( + shape=(len(ACTIONS)), + low=-1, + high=1, + dtype=torch.float32, + device=self.device, + ) + + self.reward_spec = UnboundedContinuousTensorSpec( + shape=(1,), + dtype=torch.float32, + device=self.device, + ) + + self.done_spec = CompositeSpec( + { + "done": DiscreteTensorSpec( + 2, + shape=(1,), + dtype=torch.bool, + device=self.device, + ), + "success": DiscreteTensorSpec( + 2, + shape=(1,), + dtype=torch.bool, + device=self.device, + ), + } + ) + + def _set_seed(self, seed: Optional[int]): + set_seed(seed) + # TODO(rcadene): seed the env + # self._env.seed(seed) + logging.warning("Aloha env is not seeded") diff --git a/lerobot/common/envs/aloha/tasks/sim.py b/lerobot/common/envs/aloha/tasks/sim.py new file mode 100644 index 000000000..ee1d0927b --- /dev/null +++ b/lerobot/common/envs/aloha/tasks/sim.py @@ -0,0 +1,219 @@ +import collections + +import numpy as np +from dm_control.suite import base + +from lerobot.common.envs.aloha.constants import ( + START_ARM_POSE, + normalize_puppet_gripper_position, + normalize_puppet_gripper_velocity, + unnormalize_puppet_gripper_position, +) + +BOX_POSE = [None] # to be changed from outside + +""" +Environment for simulated robot bi-manual manipulation, with joint position control +Action space: [left_arm_qpos (6), # absolute joint position + left_gripper_positions (1), # normalized gripper position (0: close, 1: open) + right_arm_qpos (6), # absolute joint position + right_gripper_positions (1),] # normalized gripper position (0: close, 1: open) + +Observation space: {"qpos": Concat[ left_arm_qpos (6), # absolute joint position + left_gripper_position (1), # normalized gripper position (0: close, 1: open) + right_arm_qpos (6), # absolute joint position + right_gripper_qpos (1)] # normalized gripper position (0: close, 1: open) + "qvel": Concat[ left_arm_qvel (6), # absolute joint velocity (rad) + left_gripper_velocity (1), # normalized gripper velocity (pos: opening, neg: closing) + right_arm_qvel (6), # absolute joint velocity (rad) + right_gripper_qvel (1)] # normalized gripper velocity (pos: opening, neg: closing) + "images": {"main": (480x640x3)} # h, w, c, dtype='uint8' +""" + + +class BimanualViperXTask(base.Task): + def __init__(self, random=None): + super().__init__(random=random) + + def before_step(self, action, physics): + left_arm_action = action[:6] + right_arm_action = action[7 : 7 + 6] + normalized_left_gripper_action = action[6] + normalized_right_gripper_action = action[7 + 6] + + left_gripper_action = unnormalize_puppet_gripper_position(normalized_left_gripper_action) + right_gripper_action = unnormalize_puppet_gripper_position(normalized_right_gripper_action) + + full_left_gripper_action = [left_gripper_action, -left_gripper_action] + full_right_gripper_action = [right_gripper_action, -right_gripper_action] + + env_action = np.concatenate( + [left_arm_action, full_left_gripper_action, right_arm_action, full_right_gripper_action] + ) + super().before_step(env_action, physics) + return + + def initialize_episode(self, physics): + """Sets the state of the environment at the start of each episode.""" + super().initialize_episode(physics) + + @staticmethod + def get_qpos(physics): + qpos_raw = physics.data.qpos.copy() + left_qpos_raw = qpos_raw[:8] + right_qpos_raw = qpos_raw[8:16] + left_arm_qpos = left_qpos_raw[:6] + right_arm_qpos = right_qpos_raw[:6] + left_gripper_qpos = [normalize_puppet_gripper_position(left_qpos_raw[6])] + right_gripper_qpos = [normalize_puppet_gripper_position(right_qpos_raw[6])] + return np.concatenate([left_arm_qpos, left_gripper_qpos, right_arm_qpos, right_gripper_qpos]) + + @staticmethod + def get_qvel(physics): + qvel_raw = physics.data.qvel.copy() + left_qvel_raw = qvel_raw[:8] + right_qvel_raw = qvel_raw[8:16] + left_arm_qvel = left_qvel_raw[:6] + right_arm_qvel = right_qvel_raw[:6] + left_gripper_qvel = [normalize_puppet_gripper_velocity(left_qvel_raw[6])] + right_gripper_qvel = [normalize_puppet_gripper_velocity(right_qvel_raw[6])] + return np.concatenate([left_arm_qvel, left_gripper_qvel, right_arm_qvel, right_gripper_qvel]) + + @staticmethod + def get_env_state(physics): + raise NotImplementedError + + def get_observation(self, physics): + obs = collections.OrderedDict() + obs["qpos"] = self.get_qpos(physics) + obs["qvel"] = self.get_qvel(physics) + obs["env_state"] = self.get_env_state(physics) + obs["images"] = {} + obs["images"]["top"] = physics.render(height=480, width=640, camera_id="top") + obs["images"]["angle"] = physics.render(height=480, width=640, camera_id="angle") + obs["images"]["vis"] = physics.render(height=480, width=640, camera_id="front_close") + + return obs + + def get_reward(self, physics): + # return whether left gripper is holding the box + raise NotImplementedError + + +class TransferCubeTask(BimanualViperXTask): + def __init__(self, random=None): + super().__init__(random=random) + self.max_reward = 4 + + def initialize_episode(self, physics): + """Sets the state of the environment at the start of each episode.""" + # TODO Notice: this function does not randomize the env configuration. Instead, set BOX_POSE from outside + # reset qpos, control and box position + with physics.reset_context(): + physics.named.data.qpos[:16] = START_ARM_POSE + np.copyto(physics.data.ctrl, START_ARM_POSE) + assert BOX_POSE[0] is not None + physics.named.data.qpos[-7:] = BOX_POSE[0] + # print(f"{BOX_POSE=}") + super().initialize_episode(physics) + + @staticmethod + def get_env_state(physics): + env_state = physics.data.qpos.copy()[16:] + return env_state + + def get_reward(self, physics): + # return whether left gripper is holding the box + all_contact_pairs = [] + for i_contact in range(physics.data.ncon): + id_geom_1 = physics.data.contact[i_contact].geom1 + id_geom_2 = physics.data.contact[i_contact].geom2 + name_geom_1 = physics.model.id2name(id_geom_1, "geom") + name_geom_2 = physics.model.id2name(id_geom_2, "geom") + contact_pair = (name_geom_1, name_geom_2) + all_contact_pairs.append(contact_pair) + + touch_left_gripper = ("red_box", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + touch_right_gripper = ("red_box", "vx300s_right/10_right_gripper_finger") in all_contact_pairs + touch_table = ("red_box", "table") in all_contact_pairs + + reward = 0 + if touch_right_gripper: + reward = 1 + if touch_right_gripper and not touch_table: # lifted + reward = 2 + if touch_left_gripper: # attempted transfer + reward = 3 + if touch_left_gripper and not touch_table: # successful transfer + reward = 4 + return reward + + +class InsertionTask(BimanualViperXTask): + def __init__(self, random=None): + super().__init__(random=random) + self.max_reward = 4 + + def initialize_episode(self, physics): + """Sets the state of the environment at the start of each episode.""" + # TODO Notice: this function does not randomize the env configuration. Instead, set BOX_POSE from outside + # reset qpos, control and box position + with physics.reset_context(): + physics.named.data.qpos[:16] = START_ARM_POSE + np.copyto(physics.data.ctrl, START_ARM_POSE) + assert BOX_POSE[0] is not None + physics.named.data.qpos[-7 * 2 :] = BOX_POSE[0] # two objects + # print(f"{BOX_POSE=}") + super().initialize_episode(physics) + + @staticmethod + def get_env_state(physics): + env_state = physics.data.qpos.copy()[16:] + return env_state + + def get_reward(self, physics): + # return whether peg touches the pin + all_contact_pairs = [] + for i_contact in range(physics.data.ncon): + id_geom_1 = physics.data.contact[i_contact].geom1 + id_geom_2 = physics.data.contact[i_contact].geom2 + name_geom_1 = physics.model.id2name(id_geom_1, "geom") + name_geom_2 = physics.model.id2name(id_geom_2, "geom") + contact_pair = (name_geom_1, name_geom_2) + all_contact_pairs.append(contact_pair) + + touch_right_gripper = ("red_peg", "vx300s_right/10_right_gripper_finger") in all_contact_pairs + touch_left_gripper = ( + ("socket-1", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + or ("socket-2", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + or ("socket-3", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + or ("socket-4", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + ) + + peg_touch_table = ("red_peg", "table") in all_contact_pairs + socket_touch_table = ( + ("socket-1", "table") in all_contact_pairs + or ("socket-2", "table") in all_contact_pairs + or ("socket-3", "table") in all_contact_pairs + or ("socket-4", "table") in all_contact_pairs + ) + peg_touch_socket = ( + ("red_peg", "socket-1") in all_contact_pairs + or ("red_peg", "socket-2") in all_contact_pairs + or ("red_peg", "socket-3") in all_contact_pairs + or ("red_peg", "socket-4") in all_contact_pairs + ) + pin_touched = ("red_peg", "pin") in all_contact_pairs + + reward = 0 + if touch_left_gripper and touch_right_gripper: # touch both + reward = 1 + if ( + touch_left_gripper and touch_right_gripper and (not peg_touch_table) and (not socket_touch_table) + ): # grasp both + reward = 2 + if peg_touch_socket and (not peg_touch_table) and (not socket_touch_table): # peg and socket touching + reward = 3 + if pin_touched: # successful insertion + reward = 4 + return reward diff --git a/lerobot/common/envs/aloha/tasks/sim_end_effector.py b/lerobot/common/envs/aloha/tasks/sim_end_effector.py new file mode 100644 index 000000000..d93c83306 --- /dev/null +++ b/lerobot/common/envs/aloha/tasks/sim_end_effector.py @@ -0,0 +1,263 @@ +import collections + +import numpy as np +from dm_control.suite import base + +from lerobot.common.envs.aloha.constants import ( + PUPPET_GRIPPER_POSITION_CLOSE, + START_ARM_POSE, + normalize_puppet_gripper_position, + normalize_puppet_gripper_velocity, + unnormalize_puppet_gripper_position, +) +from lerobot.common.envs.aloha.utils import sample_box_pose, sample_insertion_pose + +""" +Environment for simulated robot bi-manual manipulation, with end-effector control. +Action space: [left_arm_pose (7), # position and quaternion for end effector + left_gripper_positions (1), # normalized gripper position (0: close, 1: open) + right_arm_pose (7), # position and quaternion for end effector + right_gripper_positions (1),] # normalized gripper position (0: close, 1: open) + +Observation space: {"qpos": Concat[ left_arm_qpos (6), # absolute joint position + left_gripper_position (1), # normalized gripper position (0: close, 1: open) + right_arm_qpos (6), # absolute joint position + right_gripper_qpos (1)] # normalized gripper position (0: close, 1: open) + "qvel": Concat[ left_arm_qvel (6), # absolute joint velocity (rad) + left_gripper_velocity (1), # normalized gripper velocity (pos: opening, neg: closing) + right_arm_qvel (6), # absolute joint velocity (rad) + right_gripper_qvel (1)] # normalized gripper velocity (pos: opening, neg: closing) + "images": {"main": (480x640x3)} # h, w, c, dtype='uint8' +""" + + +class BimanualViperXEndEffectorTask(base.Task): + def __init__(self, random=None): + super().__init__(random=random) + + def before_step(self, action, physics): + a_len = len(action) // 2 + action_left = action[:a_len] + action_right = action[a_len:] + + # set mocap position and quat + # left + np.copyto(physics.data.mocap_pos[0], action_left[:3]) + np.copyto(physics.data.mocap_quat[0], action_left[3:7]) + # right + np.copyto(physics.data.mocap_pos[1], action_right[:3]) + np.copyto(physics.data.mocap_quat[1], action_right[3:7]) + + # set gripper + g_left_ctrl = unnormalize_puppet_gripper_position(action_left[7]) + g_right_ctrl = unnormalize_puppet_gripper_position(action_right[7]) + np.copyto(physics.data.ctrl, np.array([g_left_ctrl, -g_left_ctrl, g_right_ctrl, -g_right_ctrl])) + + def initialize_robots(self, physics): + # reset joint position + physics.named.data.qpos[:16] = START_ARM_POSE + + # reset mocap to align with end effector + # to obtain these numbers: + # (1) make an ee_sim env and reset to the same start_pose + # (2) get env._physics.named.data.xpos['vx300s_left/gripper_link'] + # get env._physics.named.data.xquat['vx300s_left/gripper_link'] + # repeat the same for right side + np.copyto(physics.data.mocap_pos[0], [-0.31718881, 0.5, 0.29525084]) + np.copyto(physics.data.mocap_quat[0], [1, 0, 0, 0]) + # right + np.copyto(physics.data.mocap_pos[1], np.array([0.31718881, 0.49999888, 0.29525084])) + np.copyto(physics.data.mocap_quat[1], [1, 0, 0, 0]) + + # reset gripper control + close_gripper_control = np.array( + [ + PUPPET_GRIPPER_POSITION_CLOSE, + -PUPPET_GRIPPER_POSITION_CLOSE, + PUPPET_GRIPPER_POSITION_CLOSE, + -PUPPET_GRIPPER_POSITION_CLOSE, + ] + ) + np.copyto(physics.data.ctrl, close_gripper_control) + + def initialize_episode(self, physics): + """Sets the state of the environment at the start of each episode.""" + super().initialize_episode(physics) + + @staticmethod + def get_qpos(physics): + qpos_raw = physics.data.qpos.copy() + left_qpos_raw = qpos_raw[:8] + right_qpos_raw = qpos_raw[8:16] + left_arm_qpos = left_qpos_raw[:6] + right_arm_qpos = right_qpos_raw[:6] + left_gripper_qpos = [normalize_puppet_gripper_position(left_qpos_raw[6])] + right_gripper_qpos = [normalize_puppet_gripper_position(right_qpos_raw[6])] + return np.concatenate([left_arm_qpos, left_gripper_qpos, right_arm_qpos, right_gripper_qpos]) + + @staticmethod + def get_qvel(physics): + qvel_raw = physics.data.qvel.copy() + left_qvel_raw = qvel_raw[:8] + right_qvel_raw = qvel_raw[8:16] + left_arm_qvel = left_qvel_raw[:6] + right_arm_qvel = right_qvel_raw[:6] + left_gripper_qvel = [normalize_puppet_gripper_velocity(left_qvel_raw[6])] + right_gripper_qvel = [normalize_puppet_gripper_velocity(right_qvel_raw[6])] + return np.concatenate([left_arm_qvel, left_gripper_qvel, right_arm_qvel, right_gripper_qvel]) + + @staticmethod + def get_env_state(physics): + raise NotImplementedError + + def get_observation(self, physics): + # note: it is important to do .copy() + obs = collections.OrderedDict() + obs["qpos"] = self.get_qpos(physics) + obs["qvel"] = self.get_qvel(physics) + obs["env_state"] = self.get_env_state(physics) + obs["images"] = {} + obs["images"]["top"] = physics.render(height=480, width=640, camera_id="top") + obs["images"]["angle"] = physics.render(height=480, width=640, camera_id="angle") + obs["images"]["vis"] = physics.render(height=480, width=640, camera_id="front_close") + # used in scripted policy to obtain starting pose + obs["mocap_pose_left"] = np.concatenate( + [physics.data.mocap_pos[0], physics.data.mocap_quat[0]] + ).copy() + obs["mocap_pose_right"] = np.concatenate( + [physics.data.mocap_pos[1], physics.data.mocap_quat[1]] + ).copy() + + # used when replaying joint trajectory + obs["gripper_ctrl"] = physics.data.ctrl.copy() + return obs + + def get_reward(self, physics): + raise NotImplementedError + + +class TransferCubeEndEffectorTask(BimanualViperXEndEffectorTask): + def __init__(self, random=None): + super().__init__(random=random) + self.max_reward = 4 + + def initialize_episode(self, physics): + """Sets the state of the environment at the start of each episode.""" + self.initialize_robots(physics) + # randomize box position + cube_pose = sample_box_pose() + box_start_idx = physics.model.name2id("red_box_joint", "joint") + np.copyto(physics.data.qpos[box_start_idx : box_start_idx + 7], cube_pose) + # print(f"randomized cube position to {cube_position}") + + super().initialize_episode(physics) + + @staticmethod + def get_env_state(physics): + env_state = physics.data.qpos.copy()[16:] + return env_state + + def get_reward(self, physics): + # return whether left gripper is holding the box + all_contact_pairs = [] + for i_contact in range(physics.data.ncon): + id_geom_1 = physics.data.contact[i_contact].geom1 + id_geom_2 = physics.data.contact[i_contact].geom2 + name_geom_1 = physics.model.id2name(id_geom_1, "geom") + name_geom_2 = physics.model.id2name(id_geom_2, "geom") + contact_pair = (name_geom_1, name_geom_2) + all_contact_pairs.append(contact_pair) + + touch_left_gripper = ("red_box", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + touch_right_gripper = ("red_box", "vx300s_right/10_right_gripper_finger") in all_contact_pairs + touch_table = ("red_box", "table") in all_contact_pairs + + reward = 0 + if touch_right_gripper: + reward = 1 + if touch_right_gripper and not touch_table: # lifted + reward = 2 + if touch_left_gripper: # attempted transfer + reward = 3 + if touch_left_gripper and not touch_table: # successful transfer + reward = 4 + return reward + + +class InsertionEndEffectorTask(BimanualViperXEndEffectorTask): + def __init__(self, random=None): + super().__init__(random=random) + self.max_reward = 4 + + def initialize_episode(self, physics): + """Sets the state of the environment at the start of each episode.""" + self.initialize_robots(physics) + # randomize peg and socket position + peg_pose, socket_pose = sample_insertion_pose() + + def id2index(j_id): + return 16 + (j_id - 16) * 7 # first 16 is robot qpos, 7 is pose dim # hacky + + peg_start_id = physics.model.name2id("red_peg_joint", "joint") + peg_start_idx = id2index(peg_start_id) + np.copyto(physics.data.qpos[peg_start_idx : peg_start_idx + 7], peg_pose) + # print(f"randomized cube position to {cube_position}") + + socket_start_id = physics.model.name2id("blue_socket_joint", "joint") + socket_start_idx = id2index(socket_start_id) + np.copyto(physics.data.qpos[socket_start_idx : socket_start_idx + 7], socket_pose) + # print(f"randomized cube position to {cube_position}") + + super().initialize_episode(physics) + + @staticmethod + def get_env_state(physics): + env_state = physics.data.qpos.copy()[16:] + return env_state + + def get_reward(self, physics): + # return whether peg touches the pin + all_contact_pairs = [] + for i_contact in range(physics.data.ncon): + id_geom_1 = physics.data.contact[i_contact].geom1 + id_geom_2 = physics.data.contact[i_contact].geom2 + name_geom_1 = physics.model.id2name(id_geom_1, "geom") + name_geom_2 = physics.model.id2name(id_geom_2, "geom") + contact_pair = (name_geom_1, name_geom_2) + all_contact_pairs.append(contact_pair) + + touch_right_gripper = ("red_peg", "vx300s_right/10_right_gripper_finger") in all_contact_pairs + touch_left_gripper = ( + ("socket-1", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + or ("socket-2", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + or ("socket-3", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + or ("socket-4", "vx300s_left/10_left_gripper_finger") in all_contact_pairs + ) + + peg_touch_table = ("red_peg", "table") in all_contact_pairs + socket_touch_table = ( + ("socket-1", "table") in all_contact_pairs + or ("socket-2", "table") in all_contact_pairs + or ("socket-3", "table") in all_contact_pairs + or ("socket-4", "table") in all_contact_pairs + ) + peg_touch_socket = ( + ("red_peg", "socket-1") in all_contact_pairs + or ("red_peg", "socket-2") in all_contact_pairs + or ("red_peg", "socket-3") in all_contact_pairs + or ("red_peg", "socket-4") in all_contact_pairs + ) + pin_touched = ("red_peg", "pin") in all_contact_pairs + + reward = 0 + if touch_left_gripper and touch_right_gripper: # touch both + reward = 1 + if ( + touch_left_gripper and touch_right_gripper and (not peg_touch_table) and (not socket_touch_table) + ): # grasp both + reward = 2 + if peg_touch_socket and (not peg_touch_table) and (not socket_touch_table): # peg and socket touching + reward = 3 + if pin_touched: # successful insertion + reward = 4 + return reward diff --git a/lerobot/common/envs/aloha/utils.py b/lerobot/common/envs/aloha/utils.py new file mode 100644 index 000000000..5ac8b9558 --- /dev/null +++ b/lerobot/common/envs/aloha/utils.py @@ -0,0 +1,39 @@ +import numpy as np + + +def sample_box_pose(): + x_range = [0.0, 0.2] + y_range = [0.4, 0.6] + z_range = [0.05, 0.05] + + ranges = np.vstack([x_range, y_range, z_range]) + cube_position = np.random.uniform(ranges[:, 0], ranges[:, 1]) + + cube_quat = np.array([1, 0, 0, 0]) + return np.concatenate([cube_position, cube_quat]) + + +def sample_insertion_pose(): + # Peg + x_range = [0.1, 0.2] + y_range = [0.4, 0.6] + z_range = [0.05, 0.05] + + ranges = np.vstack([x_range, y_range, z_range]) + peg_position = np.random.uniform(ranges[:, 0], ranges[:, 1]) + + peg_quat = np.array([1, 0, 0, 0]) + peg_pose = np.concatenate([peg_position, peg_quat]) + + # Socket + x_range = [-0.2, -0.1] + y_range = [0.4, 0.6] + z_range = [0.05, 0.05] + + ranges = np.vstack([x_range, y_range, z_range]) + socket_position = np.random.uniform(ranges[:, 0], ranges[:, 1]) + + socket_quat = np.array([1, 0, 0, 0]) + socket_pose = np.concatenate([socket_position, socket_quat]) + + return peg_pose, socket_pose diff --git a/lerobot/common/envs/factory.py b/lerobot/common/envs/factory.py index 269009db9..921cbad74 100644 --- a/lerobot/common/envs/factory.py +++ b/lerobot/common/envs/factory.py @@ -23,6 +23,11 @@ def make_env(cfg, transform=None): # assert kwargs["seed"] > 200, "Seed 0-200 are used for the demonstration dataset, so we don't want to seed the eval env with this range." clsfunc = PushtEnv + elif cfg.env.name == "aloha": + from lerobot.common.envs.aloha.env import AlohaEnv + + kwargs["task"] = cfg.env.task + clsfunc = AlohaEnv else: raise ValueError(cfg.env.name) diff --git a/lerobot/common/envs/pusht/env.py b/lerobot/common/envs/pusht/env.py index ff49f791e..4a7ccb2c8 100644 --- a/lerobot/common/envs/pusht/env.py +++ b/lerobot/common/envs/pusht/env.py @@ -11,61 +11,52 @@ DiscreteTensorSpec, UnboundedContinuousTensorSpec, ) -from torchrl.envs import EnvBase from torchrl.envs.libs.gym import _gym_to_torchrl_spec_transform +from lerobot.common.envs.abstract import AbstractEnv from lerobot.common.utils import set_seed _has_gym = importlib.util.find_spec("gym") is not None -class PushtEnv(EnvBase): +class PushtEnv(AbstractEnv): def __init__( self, + task="pusht", frame_skip: int = 1, from_pixels: bool = False, pixels_only: bool = False, image_size=None, seed=1337, device="cpu", - num_prev_obs=0, + num_prev_obs=1, num_prev_action=0, ): - super().__init__(device=device, batch_size=[]) - self.frame_skip = frame_skip - self.from_pixels = from_pixels - self.pixels_only = pixels_only - self.image_size = image_size - self.num_prev_obs = num_prev_obs - self.num_prev_action = num_prev_action - - if pixels_only: - assert from_pixels - if from_pixels: - assert image_size + super().__init__( + task=task, + frame_skip=frame_skip, + from_pixels=from_pixels, + pixels_only=pixels_only, + image_size=image_size, + seed=seed, + device=device, + num_prev_obs=num_prev_obs, + num_prev_action=num_prev_action, + ) + def _make_env(self): if not _has_gym: raise ImportError("Cannot import gym.") # TODO(rcadene) (PushTEnv is similar to PushTImageEnv, but without the image rendering, it's faster to iterate on) # from lerobot.common.envs.pusht.pusht_env import PushTEnv - if not from_pixels: + if not self.from_pixels: raise NotImplementedError("Use PushTEnv, instead of PushTImageEnv") from lerobot.common.envs.pusht.pusht_image_env import PushTImageEnv self._env = PushTImageEnv(render_size=self.image_size) - self._make_spec() - self._current_seed = self.set_seed(seed) - - if self.num_prev_obs > 0: - self._prev_obs_image_queue = deque(maxlen=self.num_prev_obs) - self._prev_obs_state_queue = deque(maxlen=self.num_prev_obs) - if self.num_prev_action > 0: - raise NotImplementedError() - # self._prev_action_queue = deque(maxlen=self.num_prev_action) - def render(self, mode="rgb_array", width=384, height=384): if width != height: raise NotImplementedError() @@ -122,6 +113,8 @@ def _reset(self, tensordict: Optional[TensorDict] = None): ) else: raise NotImplementedError() + + self.call_rendering_hooks() return td def _step(self, tensordict: TensorDict): @@ -154,6 +147,8 @@ def _step(self, tensordict: TensorDict): stacked_obs["state"] = torch.stack(list(self._prev_obs_state_queue)) obs = stacked_obs + self.call_rendering_hooks() + td = TensorDict( { "observation": TensorDict(obs, batch_size=[]), @@ -175,9 +170,9 @@ def _make_spec(self): obs["image"] = BoundedTensorSpec( low=0, - high=1, + high=255, shape=image_shape, - dtype=torch.float32, + dtype=torch.uint8, device=self.device, ) if not self.pixels_only: diff --git a/lerobot/common/envs/pusht/pusht_image_env.py b/lerobot/common/envs/pusht/pusht_image_env.py index 5f7bc03c8..0807e8492 100644 --- a/lerobot/common/envs/pusht/pusht_image_env.py +++ b/lerobot/common/envs/pusht/pusht_image_env.py @@ -25,7 +25,7 @@ def _get_obs(self): img = super()._render_frame(mode="rgb_array") agent_pos = np.array(self.agent.position) - img_obs = np.moveaxis(img.astype(np.float32) / 255, -1, 0) + img_obs = np.moveaxis(img, -1, 0) obs = {"image": img_obs, "agent_pos": agent_pos} # draw action diff --git a/lerobot/common/envs/simxarm.py b/lerobot/common/envs/simxarm.py index 24fd9ba45..d06126257 100644 --- a/lerobot/common/envs/simxarm.py +++ b/lerobot/common/envs/simxarm.py @@ -1,6 +1,8 @@ import importlib +from collections import deque from typing import Optional +import einops import numpy as np import torch from tensordict import TensorDict @@ -10,9 +12,9 @@ DiscreteTensorSpec, UnboundedContinuousTensorSpec, ) -from torchrl.envs import EnvBase from torchrl.envs.libs.gym import _gym_to_torchrl_spec_transform +from lerobot.common.envs.abstract import AbstractEnv from lerobot.common.utils import set_seed MAX_NUM_ACTIONS = 4 @@ -21,7 +23,7 @@ _has_simxarm = importlib.util.find_spec("simxarm") is not None and _has_gym -class SimxarmEnv(EnvBase): +class SimxarmEnv(AbstractEnv): def __init__( self, task, @@ -31,19 +33,22 @@ def __init__( image_size=None, seed=1337, device="cpu", + num_prev_obs=0, + num_prev_action=0, ): - super().__init__(device=device, batch_size=[]) - self.task = task - self.frame_skip = frame_skip - self.from_pixels = from_pixels - self.pixels_only = pixels_only - self.image_size = image_size - - if pixels_only: - assert from_pixels - if from_pixels: - assert image_size + super().__init__( + task=task, + frame_skip=frame_skip, + from_pixels=from_pixels, + pixels_only=pixels_only, + image_size=image_size, + seed=seed, + device=device, + num_prev_obs=num_prev_obs, + num_prev_action=num_prev_action, + ) + def _make_env(self): if not _has_simxarm: raise ImportError("Cannot import simxarm.") if not _has_gym: @@ -63,9 +68,6 @@ def __init__( if "w" not in TASKS[self.task]["action_space"]: self._action_padding[-1] = 1.0 - self._make_spec() - self.set_seed(seed) - def render(self, mode="rgb_array", width=384, height=384): return self._env.render(mode, width=width, height=height) @@ -90,15 +92,33 @@ def _reset(self, tensordict: Optional[TensorDict] = None): if td is None or td.is_empty(): raw_obs = self._env.reset() + obs = self._format_raw_obs(raw_obs) + + if self.num_prev_obs > 0: + stacked_obs = {} + if "image" in obs: + self._prev_obs_image_queue = deque( + [obs["image"]] * (self.num_prev_obs + 1), maxlen=(self.num_prev_obs + 1) + ) + stacked_obs["image"] = torch.stack(list(self._prev_obs_image_queue)) + if "state" in obs: + self._prev_obs_state_queue = deque( + [obs["state"]] * (self.num_prev_obs + 1), maxlen=(self.num_prev_obs + 1) + ) + stacked_obs["state"] = torch.stack(list(self._prev_obs_state_queue)) + obs = stacked_obs + td = TensorDict( { - "observation": self._format_raw_obs(raw_obs), + "observation": TensorDict(obs, batch_size=[]), "done": torch.tensor([False], dtype=torch.bool), }, batch_size=[], ) else: raise NotImplementedError() + + self.call_rendering_hooks() return td def _step(self, tensordict: TensorDict): @@ -108,10 +128,32 @@ def _step(self, tensordict: TensorDict): action = np.concatenate([action, self._action_padding]) # TODO(rcadene): add info["is_success"] and info["success"] ? sum_reward = 0 - for _ in range(self.frame_skip): - raw_obs, reward, done, info = self._env.step(action) + + if action.ndim == 1: + action = einops.repeat(action, "c -> t c", t=self.frame_skip) + else: + if self.frame_skip > 1: + raise NotImplementedError() + + num_action_steps = action.shape[0] + for i in range(num_action_steps): + raw_obs, reward, done, info = self._env.step(action[i]) sum_reward += reward + obs = self._format_raw_obs(raw_obs) + + if self.num_prev_obs > 0: + stacked_obs = {} + if "image" in obs: + self._prev_obs_image_queue.append(obs["image"]) + stacked_obs["image"] = torch.stack(list(self._prev_obs_image_queue)) + if "state" in obs: + self._prev_obs_state_queue.append(obs["state"]) + stacked_obs["state"] = torch.stack(list(self._prev_obs_state_queue)) + obs = stacked_obs + + self.call_rendering_hooks() + td = TensorDict( { "observation": self._format_raw_obs(raw_obs), @@ -126,23 +168,36 @@ def _step(self, tensordict: TensorDict): def _make_spec(self): obs = {} if self.from_pixels: + image_shape = (3, self.image_size, self.image_size) + if self.num_prev_obs > 0: + image_shape = (self.num_prev_obs + 1, *image_shape) + obs["image"] = BoundedTensorSpec( low=0, high=255, - shape=(3, self.image_size, self.image_size), + shape=image_shape, dtype=torch.uint8, device=self.device, ) if not self.pixels_only: + state_shape = (len(self._env.robot_state),) + if self.num_prev_obs > 0: + state_shape = (self.num_prev_obs + 1, *state_shape) + obs["state"] = UnboundedContinuousTensorSpec( - shape=(len(self._env.robot_state),), + shape=state_shape, dtype=torch.float32, device=self.device, ) else: # TODO(rcadene): add observation_space achieved_goal and desired_goal? + state_shape = self._env.observation_space["observation"].shape + if self.num_prev_obs > 0: + state_shape = (self.num_prev_obs + 1, *state_shape) + obs["state"] = UnboundedContinuousTensorSpec( - shape=self._env.observation_space["observation"].shape, + # TODO: + shape=state_shape, dtype=torch.float32, device=self.device, ) diff --git a/lerobot/common/envs/transforms.py b/lerobot/common/envs/transforms.py index 671c08270..4832c91bf 100644 --- a/lerobot/common/envs/transforms.py +++ b/lerobot/common/envs/transforms.py @@ -1,5 +1,6 @@ from typing import Sequence +import torch from tensordict import TensorDictBase from tensordict.nn import dispatch from tensordict.utils import NestedKey @@ -7,19 +8,45 @@ class Prod(ObservationTransform): + invertible = True + def __init__(self, in_keys: Sequence[NestedKey], prod: float): super().__init__() self.in_keys = in_keys self.prod = prod + self.original_dtypes = {} + + def _reset(self, tensordict: TensorDictBase, tensordict_reset: TensorDictBase) -> TensorDictBase: + # _reset is called once when the environment reset to normalize the first observation + tensordict_reset = self._call(tensordict_reset) + return tensordict_reset + + @dispatch(source="in_keys", dest="out_keys") + def forward(self, tensordict: TensorDictBase) -> TensorDictBase: + return self._call(tensordict) def _call(self, td): for key in self.in_keys: - td[key] *= self.prod + if td.get(key, None) is None: + continue + self.original_dtypes[key] = td[key].dtype + td[key] = td[key].type(torch.float32) * self.prod + return td + + def _inv_call(self, td: TensorDictBase) -> TensorDictBase: + for key in self.in_keys: + if td.get(key, None) is None: + continue + td[key] = (td[key] / self.prod).type(self.original_dtypes[key]) return td def transform_observation_spec(self, obs_spec): for key in self.in_keys: - obs_spec[key].space.high *= self.prod + if obs_spec.get(key, None) is None: + continue + obs_spec[key].space.high = obs_spec[key].space.high.type(torch.float32) * self.prod + obs_spec[key].space.low = obs_spec[key].space.low.type(torch.float32) * self.prod + obs_spec[key].dtype = torch.float32 return obs_spec diff --git a/lerobot/common/policies/act/backbone.py b/lerobot/common/policies/act/backbone.py new file mode 100644 index 000000000..6399d3390 --- /dev/null +++ b/lerobot/common/policies/act/backbone.py @@ -0,0 +1,115 @@ +from typing import List + +import torch +import torchvision +from torch import nn +from torchvision.models._utils import IntermediateLayerGetter + +from .position_encoding import build_position_encoding +from .utils import NestedTensor, is_main_process + + +class FrozenBatchNorm2d(torch.nn.Module): + """ + BatchNorm2d where the batch statistics and the affine parameters are fixed. + + Copy-paste from torchvision.misc.ops with added eps before rqsrt, + without which any other policy_models than torchvision.policy_models.resnet[18,34,50,101] + produce nans. + """ + + def __init__(self, n): + super().__init__() + self.register_buffer("weight", torch.ones(n)) + self.register_buffer("bias", torch.zeros(n)) + self.register_buffer("running_mean", torch.zeros(n)) + self.register_buffer("running_var", torch.ones(n)) + + def _load_from_state_dict( + self, state_dict, prefix, local_metadata, strict, missing_keys, unexpected_keys, error_msgs + ): + num_batches_tracked_key = prefix + "num_batches_tracked" + if num_batches_tracked_key in state_dict: + del state_dict[num_batches_tracked_key] + + super()._load_from_state_dict( + state_dict, prefix, local_metadata, strict, missing_keys, unexpected_keys, error_msgs + ) + + def forward(self, x): + # move reshapes to the beginning + # to make it fuser-friendly + w = self.weight.reshape(1, -1, 1, 1) + b = self.bias.reshape(1, -1, 1, 1) + rv = self.running_var.reshape(1, -1, 1, 1) + rm = self.running_mean.reshape(1, -1, 1, 1) + eps = 1e-5 + scale = w * (rv + eps).rsqrt() + bias = b - rm * scale + return x * scale + bias + + +class BackboneBase(nn.Module): + def __init__( + self, backbone: nn.Module, train_backbone: bool, num_channels: int, return_interm_layers: bool + ): + super().__init__() + # for name, parameter in backbone.named_parameters(): # only train later layers # TODO do we want this? + # if not train_backbone or 'layer2' not in name and 'layer3' not in name and 'layer4' not in name: + # parameter.requires_grad_(False) + if return_interm_layers: + return_layers = {"layer1": "0", "layer2": "1", "layer3": "2", "layer4": "3"} + else: + return_layers = {"layer4": "0"} + self.body = IntermediateLayerGetter(backbone, return_layers=return_layers) + self.num_channels = num_channels + + def forward(self, tensor): + xs = self.body(tensor) + return xs + # out: Dict[str, NestedTensor] = {} + # for name, x in xs.items(): + # m = tensor_list.mask + # assert m is not None + # mask = F.interpolate(m[None].float(), size=x.shape[-2:]).to(torch.bool)[0] + # out[name] = NestedTensor(x, mask) + # return out + + +class Backbone(BackboneBase): + """ResNet backbone with frozen BatchNorm.""" + + def __init__(self, name: str, train_backbone: bool, return_interm_layers: bool, dilation: bool): + backbone = getattr(torchvision.models, name)( + replace_stride_with_dilation=[False, False, dilation], + pretrained=is_main_process(), + norm_layer=FrozenBatchNorm2d, + ) # pretrained # TODO do we want frozen batch_norm?? + num_channels = 512 if name in ("resnet18", "resnet34") else 2048 + super().__init__(backbone, train_backbone, num_channels, return_interm_layers) + + +class Joiner(nn.Sequential): + def __init__(self, backbone, position_embedding): + super().__init__(backbone, position_embedding) + + def forward(self, tensor_list: NestedTensor): + xs = self[0](tensor_list) + out: List[NestedTensor] = [] + pos = [] + for _, x in xs.items(): + out.append(x) + # position encoding + pos.append(self[1](x).to(x.dtype)) + + return out, pos + + +def build_backbone(args): + position_embedding = build_position_encoding(args) + train_backbone = args.lr_backbone > 0 + return_interm_layers = args.masks + backbone = Backbone(args.backbone, train_backbone, return_interm_layers, args.dilation) + model = Joiner(backbone, position_embedding) + model.num_channels = backbone.num_channels + return model diff --git a/lerobot/common/policies/act/detr_vae.py b/lerobot/common/policies/act/detr_vae.py new file mode 100644 index 000000000..0f2626f74 --- /dev/null +++ b/lerobot/common/policies/act/detr_vae.py @@ -0,0 +1,212 @@ +import numpy as np +import torch +from torch import nn +from torch.autograd import Variable + +from .backbone import build_backbone +from .transformer import TransformerEncoder, TransformerEncoderLayer, build_transformer + + +def reparametrize(mu, logvar): + std = logvar.div(2).exp() + eps = Variable(std.data.new(std.size()).normal_()) + return mu + std * eps + + +def get_sinusoid_encoding_table(n_position, d_hid): + def get_position_angle_vec(position): + return [position / np.power(10000, 2 * (hid_j // 2) / d_hid) for hid_j in range(d_hid)] + + sinusoid_table = np.array([get_position_angle_vec(pos_i) for pos_i in range(n_position)]) + sinusoid_table[:, 0::2] = np.sin(sinusoid_table[:, 0::2]) # dim 2i + sinusoid_table[:, 1::2] = np.cos(sinusoid_table[:, 1::2]) # dim 2i+1 + + return torch.FloatTensor(sinusoid_table).unsqueeze(0) + + +class DETRVAE(nn.Module): + """This is the DETR module that performs object detection""" + + def __init__( + self, backbones, transformer, encoder, state_dim, action_dim, num_queries, camera_names, vae + ): + """Initializes the model. + Parameters: + backbones: torch module of the backbone to be used. See backbone.py + transformer: torch module of the transformer architecture. See transformer.py + state_dim: robot state dimension of the environment + num_queries: number of object queries, ie detection slot. This is the maximal number of objects + DETR can detect in a single image. For COCO, we recommend 100 queries. + aux_loss: True if auxiliary decoding losses (loss at each decoder layer) are to be used. + """ + super().__init__() + self.num_queries = num_queries + self.camera_names = camera_names + self.transformer = transformer + self.encoder = encoder + self.vae = vae + hidden_dim = transformer.d_model + self.action_head = nn.Linear(hidden_dim, action_dim) + self.is_pad_head = nn.Linear(hidden_dim, 1) + self.query_embed = nn.Embedding(num_queries, hidden_dim) + if backbones is not None: + self.input_proj = nn.Conv2d(backbones[0].num_channels, hidden_dim, kernel_size=1) + self.backbones = nn.ModuleList(backbones) + self.input_proj_robot_state = nn.Linear(state_dim, hidden_dim) + else: + # input_dim = 14 + 7 # robot_state + env_state + self.input_proj_robot_state = nn.Linear(state_dim, hidden_dim) + # TODO(rcadene): understand what is env_state, and why it needs to be 7 + self.input_proj_env_state = nn.Linear(state_dim // 2, hidden_dim) + self.pos = torch.nn.Embedding(2, hidden_dim) + self.backbones = None + + # encoder extra parameters + self.latent_dim = 32 # final size of latent z # TODO tune + self.cls_embed = nn.Embedding(1, hidden_dim) # extra cls token embedding + self.encoder_action_proj = nn.Linear(14, hidden_dim) # project action to embedding + self.encoder_joint_proj = nn.Linear(14, hidden_dim) # project qpos to embedding + self.latent_proj = nn.Linear( + hidden_dim, self.latent_dim * 2 + ) # project hidden state to latent std, var + self.register_buffer( + "pos_table", get_sinusoid_encoding_table(1 + 1 + num_queries, hidden_dim) + ) # [CLS], qpos, a_seq + + # decoder extra parameters + self.latent_out_proj = nn.Linear(self.latent_dim, hidden_dim) # project latent sample to embedding + self.additional_pos_embed = nn.Embedding( + 2, hidden_dim + ) # learned position embedding for proprio and latent + + def forward(self, qpos, image, env_state, actions=None, is_pad=None): + """ + qpos: batch, qpos_dim + image: batch, num_cam, channel, height, width + env_state: None + actions: batch, seq, action_dim + """ + is_training = actions is not None # train or val + bs, _ = qpos.shape + ### Obtain latent z from action sequence + if self.vae and is_training: + # project action sequence to embedding dim, and concat with a CLS token + action_embed = self.encoder_action_proj(actions) # (bs, seq, hidden_dim) + qpos_embed = self.encoder_joint_proj(qpos) # (bs, hidden_dim) + qpos_embed = torch.unsqueeze(qpos_embed, axis=1) # (bs, 1, hidden_dim) + cls_embed = self.cls_embed.weight # (1, hidden_dim) + cls_embed = torch.unsqueeze(cls_embed, axis=0).repeat(bs, 1, 1) # (bs, 1, hidden_dim) + encoder_input = torch.cat( + [cls_embed, qpos_embed, action_embed], axis=1 + ) # (bs, seq+1, hidden_dim) + encoder_input = encoder_input.permute(1, 0, 2) # (seq+1, bs, hidden_dim) + # do not mask cls token + # cls_joint_is_pad = torch.full((bs, 2), False).to(qpos.device) # False: not a padding + # is_pad = torch.cat([cls_joint_is_pad, is_pad], axis=1) # (bs, seq+1) + # obtain position embedding + pos_embed = self.pos_table.clone().detach() + pos_embed = pos_embed.permute(1, 0, 2) # (seq+1, 1, hidden_dim) + # query model + encoder_output = self.encoder(encoder_input, pos=pos_embed) # , src_key_padding_mask=is_pad) + encoder_output = encoder_output[0] # take cls output only + latent_info = self.latent_proj(encoder_output) + mu = latent_info[:, : self.latent_dim] + logvar = latent_info[:, self.latent_dim :] + latent_sample = reparametrize(mu, logvar) + latent_input = self.latent_out_proj(latent_sample) + else: + mu = logvar = None + latent_sample = torch.zeros([bs, self.latent_dim], dtype=torch.float32).to(qpos.device) + latent_input = self.latent_out_proj(latent_sample) + + if self.backbones is not None: + # Image observation features and position embeddings + all_cam_features = [] + all_cam_pos = [] + for cam_id, _ in enumerate(self.camera_names): + features, pos = self.backbones[0](image[:, cam_id]) # HARDCODED + features = features[0] # take the last layer feature + pos = pos[0] + all_cam_features.append(self.input_proj(features)) + all_cam_pos.append(pos) + # proprioception features + proprio_input = self.input_proj_robot_state(qpos) + # fold camera dimension into width dimension + src = torch.cat(all_cam_features, axis=3) + pos = torch.cat(all_cam_pos, axis=3) + hs = self.transformer( + src, + None, + self.query_embed.weight, + pos, + latent_input, + proprio_input, + self.additional_pos_embed.weight, + )[0] + else: + qpos = self.input_proj_robot_state(qpos) + env_state = self.input_proj_env_state(env_state) + transformer_input = torch.cat([qpos, env_state], axis=1) # seq length = 2 + hs = self.transformer(transformer_input, None, self.query_embed.weight, self.pos.weight)[0] + a_hat = self.action_head(hs) + is_pad_hat = self.is_pad_head(hs) + return a_hat, is_pad_hat, [mu, logvar] + + +def mlp(input_dim, hidden_dim, output_dim, hidden_depth): + if hidden_depth == 0: + mods = [nn.Linear(input_dim, output_dim)] + else: + mods = [nn.Linear(input_dim, hidden_dim), nn.ReLU(inplace=True)] + for _ in range(hidden_depth - 1): + mods += [nn.Linear(hidden_dim, hidden_dim), nn.ReLU(inplace=True)] + mods.append(nn.Linear(hidden_dim, output_dim)) + trunk = nn.Sequential(*mods) + return trunk + + +def build_encoder(args): + d_model = args.hidden_dim # 256 + dropout = args.dropout # 0.1 + nhead = args.nheads # 8 + dim_feedforward = args.dim_feedforward # 2048 + num_encoder_layers = args.enc_layers # 4 # TODO shared with VAE decoder + normalize_before = args.pre_norm # False + activation = "relu" + + encoder_layer = TransformerEncoderLayer( + d_model, nhead, dim_feedforward, dropout, activation, normalize_before + ) + encoder_norm = nn.LayerNorm(d_model) if normalize_before else None + encoder = TransformerEncoder(encoder_layer, num_encoder_layers, encoder_norm) + + return encoder + + +def build(args): + # From state + # backbone = None # from state for now, no need for conv nets + # From image + backbones = [] + backbone = build_backbone(args) + backbones.append(backbone) + + transformer = build_transformer(args) + + encoder = build_encoder(args) + + model = DETRVAE( + backbones, + transformer, + encoder, + state_dim=args.state_dim, + action_dim=args.action_dim, + num_queries=args.num_queries, + camera_names=args.camera_names, + vae=args.vae, + ) + + n_parameters = sum(p.numel() for p in model.parameters() if p.requires_grad) + print("number of parameters: {:.2f}M".format(n_parameters / 1e6)) + + return model diff --git a/lerobot/common/policies/act/policy.py b/lerobot/common/policies/act/policy.py new file mode 100644 index 000000000..d011cb762 --- /dev/null +++ b/lerobot/common/policies/act/policy.py @@ -0,0 +1,217 @@ +import logging +import time + +import torch +import torch.nn as nn +import torch.nn.functional as F # noqa: N812 +import torchvision.transforms as transforms + +from lerobot.common.policies.act.detr_vae import build + + +def build_act_model_and_optimizer(cfg): + model = build(cfg) + + param_dicts = [ + {"params": [p for n, p in model.named_parameters() if "backbone" not in n and p.requires_grad]}, + { + "params": [p for n, p in model.named_parameters() if "backbone" in n and p.requires_grad], + "lr": cfg.lr_backbone, + }, + ] + optimizer = torch.optim.AdamW(param_dicts, lr=cfg.lr, weight_decay=cfg.weight_decay) + + return model, optimizer + + +def kl_divergence(mu, logvar): + batch_size = mu.size(0) + assert batch_size != 0 + if mu.data.ndimension() == 4: + mu = mu.view(mu.size(0), mu.size(1)) + if logvar.data.ndimension() == 4: + logvar = logvar.view(logvar.size(0), logvar.size(1)) + + klds = -0.5 * (1 + logvar - mu.pow(2) - logvar.exp()) + total_kld = klds.sum(1).mean(0, True) + dimension_wise_kld = klds.mean(0) + mean_kld = klds.mean(1).mean(0, True) + + return total_kld, dimension_wise_kld, mean_kld + + +class ActionChunkingTransformerPolicy(nn.Module): + def __init__(self, cfg, device, n_action_steps=1): + super().__init__() + self.cfg = cfg + self.n_action_steps = n_action_steps + self.device = device + self.model, self.optimizer = build_act_model_and_optimizer(cfg) + self.kl_weight = self.cfg.kl_weight + logging.info(f"KL Weight {self.kl_weight}") + self.to(self.device) + + def update(self, replay_buffer, step): + del step + + start_time = time.time() + + self.train() + + num_slices = self.cfg.batch_size + batch_size = self.cfg.horizon * num_slices + + assert batch_size % self.cfg.horizon == 0 + assert batch_size % num_slices == 0 + + def process_batch(batch, horizon, num_slices): + # trajectory t = 64, horizon h = 16 + # (t h) ... -> t h ... + batch = batch.reshape(num_slices, horizon) + + image = batch["observation", "image", "top"] + image = image[:, 0] # first observation t=0 + # batch, num_cam, channel, height, width + image = image.unsqueeze(1) + assert image.ndim == 5 + image = image.float() + + state = batch["observation", "state"] + state = state[:, 0] # first observation t=0 + # batch, qpos_dim + assert state.ndim == 2 + + action = batch["action"] + # batch, seq, action_dim + assert action.ndim == 3 + assert action.shape[1] == horizon + + if self.cfg.n_obs_steps > 1: + raise NotImplementedError() + # # keep first n observations of the slice corresponding to t=[-1,0] + # image = image[:, : self.cfg.n_obs_steps] + # state = state[:, : self.cfg.n_obs_steps] + + out = { + "obs": { + "image": image.to(self.device, non_blocking=True), + "agent_pos": state.to(self.device, non_blocking=True), + }, + "action": action.to(self.device, non_blocking=True), + } + return out + + batch = replay_buffer.sample(batch_size) + batch = process_batch(batch, self.cfg.horizon, num_slices) + + data_s = time.time() - start_time + + loss = self.compute_loss(batch) + loss.backward() + + grad_norm = torch.nn.utils.clip_grad_norm_( + self.model.parameters(), + self.cfg.grad_clip_norm, + error_if_nonfinite=False, + ) + + self.optimizer.step() + self.optimizer.zero_grad() + # self.lr_scheduler.step() + + info = { + "loss": loss.item(), + "grad_norm": float(grad_norm), + # "lr": self.lr_scheduler.get_last_lr()[0], + "lr": self.cfg.lr, + "data_s": data_s, + "update_s": time.time() - start_time, + } + + return info + + def save(self, fp): + torch.save(self.state_dict(), fp) + + def load(self, fp): + d = torch.load(fp) + self.load_state_dict(d) + + def compute_loss(self, batch): + loss_dict = self._forward( + qpos=batch["obs"]["agent_pos"], + image=batch["obs"]["image"], + actions=batch["action"], + ) + loss = loss_dict["loss"] + return loss + + @torch.no_grad() + def forward(self, observation, step_count): + # TODO(rcadene): remove unused step_count + del step_count + + self.eval() + + # TODO(rcadene): remove unsqueeze hack to add bsize=1 + observation["image", "top"] = observation["image", "top"].unsqueeze(0) + # observation["state"] = observation["state"].unsqueeze(0) + + # TODO(rcadene): remove hack + # add 1 camera dimension + observation["image", "top"] = observation["image", "top"].unsqueeze(1) + + obs_dict = { + "image": observation["image", "top"], + "agent_pos": observation["state"], + } + action = self._forward(qpos=obs_dict["agent_pos"], image=obs_dict["image"]) + + if self.cfg.temporal_agg: + # TODO(rcadene): implement temporal aggregation + raise NotImplementedError() + # all_time_actions[[t], t:t+num_queries] = action + # actions_for_curr_step = all_time_actions[:, t] + # actions_populated = torch.all(actions_for_curr_step != 0, axis=1) + # actions_for_curr_step = actions_for_curr_step[actions_populated] + # k = 0.01 + # exp_weights = np.exp(-k * np.arange(len(actions_for_curr_step))) + # exp_weights = exp_weights / exp_weights.sum() + # exp_weights = torch.from_numpy(exp_weights).cuda().unsqueeze(dim=1) + # raw_action = (actions_for_curr_step * exp_weights).sum(dim=0, keepdim=True) + + # remove bsize=1 + action = action.squeeze(0) + + # take first predicted action or n first actions + action = action[0] if self.n_action_steps == 1 else action[: self.n_action_steps] + return action + + def _forward(self, qpos, image, actions=None, is_pad=None): + env_state = None + normalize = transforms.Normalize(mean=[0.485, 0.456, 0.406], std=[0.229, 0.224, 0.225]) + image = normalize(image) + + is_training = actions is not None + if is_training: # training time + actions = actions[:, : self.model.num_queries] + if is_pad is not None: + is_pad = is_pad[:, : self.model.num_queries] + + a_hat, is_pad_hat, (mu, logvar) = self.model(qpos, image, env_state, actions, is_pad) + + all_l1 = F.l1_loss(actions, a_hat, reduction="none") + l1 = all_l1.mean() if is_pad is None else (all_l1 * ~is_pad.unsqueeze(-1)).mean() + + loss_dict = {} + loss_dict["l1"] = l1 + if self.cfg.vae: + total_kld, dim_wise_kld, mean_kld = kl_divergence(mu, logvar) + loss_dict["kl"] = total_kld[0] + loss_dict["loss"] = loss_dict["l1"] + loss_dict["kl"] * self.kl_weight + else: + loss_dict["loss"] = loss_dict["l1"] + return loss_dict + else: + action, _, (_, _) = self.model(qpos, image, env_state) # no action, sample from prior + return action diff --git a/lerobot/common/policies/act/position_encoding.py b/lerobot/common/policies/act/position_encoding.py new file mode 100644 index 000000000..94e862f6d --- /dev/null +++ b/lerobot/common/policies/act/position_encoding.py @@ -0,0 +1,101 @@ +""" +Various positional encodings for the transformer. +""" +import math + +import torch +from torch import nn + +from .utils import NestedTensor + + +class PositionEmbeddingSine(nn.Module): + """ + This is a more standard version of the position embedding, very similar to the one + used by the Attention is all you need paper, generalized to work on images. + """ + + def __init__(self, num_pos_feats=64, temperature=10000, normalize=False, scale=None): + super().__init__() + self.num_pos_feats = num_pos_feats + self.temperature = temperature + self.normalize = normalize + if scale is not None and normalize is False: + raise ValueError("normalize should be True if scale is passed") + if scale is None: + scale = 2 * math.pi + self.scale = scale + + def forward(self, tensor): + x = tensor + # mask = tensor_list.mask + # assert mask is not None + # not_mask = ~mask + + not_mask = torch.ones_like(x[0, [0]]) + y_embed = not_mask.cumsum(1, dtype=torch.float32) + x_embed = not_mask.cumsum(2, dtype=torch.float32) + if self.normalize: + eps = 1e-6 + y_embed = y_embed / (y_embed[:, -1:, :] + eps) * self.scale + x_embed = x_embed / (x_embed[:, :, -1:] + eps) * self.scale + + dim_t = torch.arange(self.num_pos_feats, dtype=torch.float32, device=x.device) + dim_t = self.temperature ** (2 * (dim_t // 2) / self.num_pos_feats) + + pos_x = x_embed[:, :, :, None] / dim_t + pos_y = y_embed[:, :, :, None] / dim_t + pos_x = torch.stack((pos_x[:, :, :, 0::2].sin(), pos_x[:, :, :, 1::2].cos()), dim=4).flatten(3) + pos_y = torch.stack((pos_y[:, :, :, 0::2].sin(), pos_y[:, :, :, 1::2].cos()), dim=4).flatten(3) + pos = torch.cat((pos_y, pos_x), dim=3).permute(0, 3, 1, 2) + return pos + + +class PositionEmbeddingLearned(nn.Module): + """ + Absolute pos embedding, learned. + """ + + def __init__(self, num_pos_feats=256): + super().__init__() + self.row_embed = nn.Embedding(50, num_pos_feats) + self.col_embed = nn.Embedding(50, num_pos_feats) + self.reset_parameters() + + def reset_parameters(self): + nn.init.uniform_(self.row_embed.weight) + nn.init.uniform_(self.col_embed.weight) + + def forward(self, tensor_list: NestedTensor): + x = tensor_list.tensors + h, w = x.shape[-2:] + i = torch.arange(w, device=x.device) + j = torch.arange(h, device=x.device) + x_emb = self.col_embed(i) + y_emb = self.row_embed(j) + pos = ( + torch.cat( + [ + x_emb.unsqueeze(0).repeat(h, 1, 1), + y_emb.unsqueeze(1).repeat(1, w, 1), + ], + dim=-1, + ) + .permute(2, 0, 1) + .unsqueeze(0) + .repeat(x.shape[0], 1, 1, 1) + ) + return pos + + +def build_position_encoding(args): + n_steps = args.hidden_dim // 2 + if args.position_embedding in ("v2", "sine"): + # TODO find a better way of exposing other arguments + position_embedding = PositionEmbeddingSine(n_steps, normalize=True) + elif args.position_embedding in ("v3", "learned"): + position_embedding = PositionEmbeddingLearned(n_steps) + else: + raise ValueError(f"not supported {args.position_embedding}") + + return position_embedding diff --git a/lerobot/common/policies/act/transformer.py b/lerobot/common/policies/act/transformer.py new file mode 100644 index 000000000..b2bd3685e --- /dev/null +++ b/lerobot/common/policies/act/transformer.py @@ -0,0 +1,370 @@ +""" +DETR Transformer class. + +Copy-paste from torch.nn.Transformer with modifications: + * positional encodings are passed in MHattention + * extra LN at the end of encoder is removed + * decoder returns a stack of activations from all decoding layers +""" +import copy +from typing import Optional + +import torch +import torch.nn.functional as F # noqa: N812 +from torch import Tensor, nn + + +class Transformer(nn.Module): + def __init__( + self, + d_model=512, + nhead=8, + num_encoder_layers=6, + num_decoder_layers=6, + dim_feedforward=2048, + dropout=0.1, + activation="relu", + normalize_before=False, + return_intermediate_dec=False, + ): + super().__init__() + + encoder_layer = TransformerEncoderLayer( + d_model, nhead, dim_feedforward, dropout, activation, normalize_before + ) + encoder_norm = nn.LayerNorm(d_model) if normalize_before else None + self.encoder = TransformerEncoder(encoder_layer, num_encoder_layers, encoder_norm) + + decoder_layer = TransformerDecoderLayer( + d_model, nhead, dim_feedforward, dropout, activation, normalize_before + ) + decoder_norm = nn.LayerNorm(d_model) + self.decoder = TransformerDecoder( + decoder_layer, num_decoder_layers, decoder_norm, return_intermediate=return_intermediate_dec + ) + + self._reset_parameters() + + self.d_model = d_model + self.nhead = nhead + + def _reset_parameters(self): + for p in self.parameters(): + if p.dim() > 1: + nn.init.xavier_uniform_(p) + + def forward( + self, + src, + mask, + query_embed, + pos_embed, + latent_input=None, + proprio_input=None, + additional_pos_embed=None, + ): + # TODO flatten only when input has H and W + if len(src.shape) == 4: # has H and W + # flatten NxCxHxW to HWxNxC + bs, c, h, w = src.shape + src = src.flatten(2).permute(2, 0, 1) + pos_embed = pos_embed.flatten(2).permute(2, 0, 1).repeat(1, bs, 1) + query_embed = query_embed.unsqueeze(1).repeat(1, bs, 1) + # mask = mask.flatten(1) + + additional_pos_embed = additional_pos_embed.unsqueeze(1).repeat(1, bs, 1) # seq, bs, dim + pos_embed = torch.cat([additional_pos_embed, pos_embed], axis=0) + + addition_input = torch.stack([latent_input, proprio_input], axis=0) + src = torch.cat([addition_input, src], axis=0) + else: + assert len(src.shape) == 3 + # flatten NxHWxC to HWxNxC + bs, hw, c = src.shape + src = src.permute(1, 0, 2) + pos_embed = pos_embed.unsqueeze(1).repeat(1, bs, 1) + query_embed = query_embed.unsqueeze(1).repeat(1, bs, 1) + + tgt = torch.zeros_like(query_embed) + memory = self.encoder(src, src_key_padding_mask=mask, pos=pos_embed) + hs = self.decoder(tgt, memory, memory_key_padding_mask=mask, pos=pos_embed, query_pos=query_embed) + hs = hs.transpose(1, 2) + return hs + + +class TransformerEncoder(nn.Module): + def __init__(self, encoder_layer, num_layers, norm=None): + super().__init__() + self.layers = _get_clones(encoder_layer, num_layers) + self.num_layers = num_layers + self.norm = norm + + def forward( + self, + src, + mask: Optional[Tensor] = None, + src_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + ): + output = src + + for layer in self.layers: + output = layer(output, src_mask=mask, src_key_padding_mask=src_key_padding_mask, pos=pos) + + if self.norm is not None: + output = self.norm(output) + + return output + + +class TransformerDecoder(nn.Module): + def __init__(self, decoder_layer, num_layers, norm=None, return_intermediate=False): + super().__init__() + self.layers = _get_clones(decoder_layer, num_layers) + self.num_layers = num_layers + self.norm = norm + self.return_intermediate = return_intermediate + + def forward( + self, + tgt, + memory, + tgt_mask: Optional[Tensor] = None, + memory_mask: Optional[Tensor] = None, + tgt_key_padding_mask: Optional[Tensor] = None, + memory_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + query_pos: Optional[Tensor] = None, + ): + output = tgt + + intermediate = [] + + for layer in self.layers: + output = layer( + output, + memory, + tgt_mask=tgt_mask, + memory_mask=memory_mask, + tgt_key_padding_mask=tgt_key_padding_mask, + memory_key_padding_mask=memory_key_padding_mask, + pos=pos, + query_pos=query_pos, + ) + if self.return_intermediate: + intermediate.append(self.norm(output)) + + if self.norm is not None: + output = self.norm(output) + if self.return_intermediate: + intermediate.pop() + intermediate.append(output) + + if self.return_intermediate: + return torch.stack(intermediate) + + return output.unsqueeze(0) + + +class TransformerEncoderLayer(nn.Module): + def __init__( + self, d_model, nhead, dim_feedforward=2048, dropout=0.1, activation="relu", normalize_before=False + ): + super().__init__() + self.self_attn = nn.MultiheadAttention(d_model, nhead, dropout=dropout) + # Implementation of Feedforward model + self.linear1 = nn.Linear(d_model, dim_feedforward) + self.dropout = nn.Dropout(dropout) + self.linear2 = nn.Linear(dim_feedforward, d_model) + + self.norm1 = nn.LayerNorm(d_model) + self.norm2 = nn.LayerNorm(d_model) + self.dropout1 = nn.Dropout(dropout) + self.dropout2 = nn.Dropout(dropout) + + self.activation = _get_activation_fn(activation) + self.normalize_before = normalize_before + + def with_pos_embed(self, tensor, pos: Optional[Tensor]): + return tensor if pos is None else tensor + pos + + def forward_post( + self, + src, + src_mask: Optional[Tensor] = None, + src_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + ): + q = k = self.with_pos_embed(src, pos) + src2 = self.self_attn(q, k, value=src, attn_mask=src_mask, key_padding_mask=src_key_padding_mask)[0] + src = src + self.dropout1(src2) + src = self.norm1(src) + src2 = self.linear2(self.dropout(self.activation(self.linear1(src)))) + src = src + self.dropout2(src2) + src = self.norm2(src) + return src + + def forward_pre( + self, + src, + src_mask: Optional[Tensor] = None, + src_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + ): + src2 = self.norm1(src) + q = k = self.with_pos_embed(src2, pos) + src2 = self.self_attn(q, k, value=src2, attn_mask=src_mask, key_padding_mask=src_key_padding_mask)[0] + src = src + self.dropout1(src2) + src2 = self.norm2(src) + src2 = self.linear2(self.dropout(self.activation(self.linear1(src2)))) + src = src + self.dropout2(src2) + return src + + def forward( + self, + src, + src_mask: Optional[Tensor] = None, + src_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + ): + if self.normalize_before: + return self.forward_pre(src, src_mask, src_key_padding_mask, pos) + return self.forward_post(src, src_mask, src_key_padding_mask, pos) + + +class TransformerDecoderLayer(nn.Module): + def __init__( + self, d_model, nhead, dim_feedforward=2048, dropout=0.1, activation="relu", normalize_before=False + ): + super().__init__() + self.self_attn = nn.MultiheadAttention(d_model, nhead, dropout=dropout) + self.multihead_attn = nn.MultiheadAttention(d_model, nhead, dropout=dropout) + # Implementation of Feedforward model + self.linear1 = nn.Linear(d_model, dim_feedforward) + self.dropout = nn.Dropout(dropout) + self.linear2 = nn.Linear(dim_feedforward, d_model) + + self.norm1 = nn.LayerNorm(d_model) + self.norm2 = nn.LayerNorm(d_model) + self.norm3 = nn.LayerNorm(d_model) + self.dropout1 = nn.Dropout(dropout) + self.dropout2 = nn.Dropout(dropout) + self.dropout3 = nn.Dropout(dropout) + + self.activation = _get_activation_fn(activation) + self.normalize_before = normalize_before + + def with_pos_embed(self, tensor, pos: Optional[Tensor]): + return tensor if pos is None else tensor + pos + + def forward_post( + self, + tgt, + memory, + tgt_mask: Optional[Tensor] = None, + memory_mask: Optional[Tensor] = None, + tgt_key_padding_mask: Optional[Tensor] = None, + memory_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + query_pos: Optional[Tensor] = None, + ): + q = k = self.with_pos_embed(tgt, query_pos) + tgt2 = self.self_attn(q, k, value=tgt, attn_mask=tgt_mask, key_padding_mask=tgt_key_padding_mask)[0] + tgt = tgt + self.dropout1(tgt2) + tgt = self.norm1(tgt) + tgt2 = self.multihead_attn( + query=self.with_pos_embed(tgt, query_pos), + key=self.with_pos_embed(memory, pos), + value=memory, + attn_mask=memory_mask, + key_padding_mask=memory_key_padding_mask, + )[0] + tgt = tgt + self.dropout2(tgt2) + tgt = self.norm2(tgt) + tgt2 = self.linear2(self.dropout(self.activation(self.linear1(tgt)))) + tgt = tgt + self.dropout3(tgt2) + tgt = self.norm3(tgt) + return tgt + + def forward_pre( + self, + tgt, + memory, + tgt_mask: Optional[Tensor] = None, + memory_mask: Optional[Tensor] = None, + tgt_key_padding_mask: Optional[Tensor] = None, + memory_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + query_pos: Optional[Tensor] = None, + ): + tgt2 = self.norm1(tgt) + q = k = self.with_pos_embed(tgt2, query_pos) + tgt2 = self.self_attn(q, k, value=tgt2, attn_mask=tgt_mask, key_padding_mask=tgt_key_padding_mask)[0] + tgt = tgt + self.dropout1(tgt2) + tgt2 = self.norm2(tgt) + tgt2 = self.multihead_attn( + query=self.with_pos_embed(tgt2, query_pos), + key=self.with_pos_embed(memory, pos), + value=memory, + attn_mask=memory_mask, + key_padding_mask=memory_key_padding_mask, + )[0] + tgt = tgt + self.dropout2(tgt2) + tgt2 = self.norm3(tgt) + tgt2 = self.linear2(self.dropout(self.activation(self.linear1(tgt2)))) + tgt = tgt + self.dropout3(tgt2) + return tgt + + def forward( + self, + tgt, + memory, + tgt_mask: Optional[Tensor] = None, + memory_mask: Optional[Tensor] = None, + tgt_key_padding_mask: Optional[Tensor] = None, + memory_key_padding_mask: Optional[Tensor] = None, + pos: Optional[Tensor] = None, + query_pos: Optional[Tensor] = None, + ): + if self.normalize_before: + return self.forward_pre( + tgt, + memory, + tgt_mask, + memory_mask, + tgt_key_padding_mask, + memory_key_padding_mask, + pos, + query_pos, + ) + return self.forward_post( + tgt, memory, tgt_mask, memory_mask, tgt_key_padding_mask, memory_key_padding_mask, pos, query_pos + ) + + +def _get_clones(module, n): + return nn.ModuleList([copy.deepcopy(module) for _ in range(n)]) + + +def build_transformer(args): + return Transformer( + d_model=args.hidden_dim, + dropout=args.dropout, + nhead=args.nheads, + dim_feedforward=args.dim_feedforward, + num_encoder_layers=args.enc_layers, + num_decoder_layers=args.dec_layers, + normalize_before=args.pre_norm, + return_intermediate_dec=True, + ) + + +def _get_activation_fn(activation): + """Return an activation function given a string""" + if activation == "relu": + return F.relu + if activation == "gelu": + return F.gelu + if activation == "glu": + return F.glu + raise RuntimeError(f"activation should be relu/gelu, not {activation}.") diff --git a/lerobot/common/policies/act/utils.py b/lerobot/common/policies/act/utils.py new file mode 100644 index 000000000..2ce920949 --- /dev/null +++ b/lerobot/common/policies/act/utils.py @@ -0,0 +1,477 @@ +""" +Misc functions, including distributed helpers. + +Mostly copy-paste from torchvision references. +""" +import datetime +import os +import pickle +import subprocess +import time +from collections import defaultdict, deque +from typing import List, Optional + +import torch +import torch.distributed as dist + +# needed due to empty tensor bug in pytorch and torchvision 0.5 +import torchvision +from packaging import version +from torch import Tensor + +if version.parse(torchvision.__version__) < version.parse("0.7"): + from torchvision.ops import _new_empty_tensor + from torchvision.ops.misc import _output_size + + +class SmoothedValue: + """Track a series of values and provide access to smoothed values over a + window or the global series average. + """ + + def __init__(self, window_size=20, fmt=None): + if fmt is None: + fmt = "{median:.4f} ({global_avg:.4f})" + self.deque = deque(maxlen=window_size) + self.total = 0.0 + self.count = 0 + self.fmt = fmt + + def update(self, value, n=1): + self.deque.append(value) + self.count += n + self.total += value * n + + def synchronize_between_processes(self): + """ + Warning: does not synchronize the deque! + """ + if not is_dist_avail_and_initialized(): + return + t = torch.tensor([self.count, self.total], dtype=torch.float64, device="cuda") + dist.barrier() + dist.all_reduce(t) + t = t.tolist() + self.count = int(t[0]) + self.total = t[1] + + @property + def median(self): + d = torch.tensor(list(self.deque)) + return d.median().item() + + @property + def avg(self): + d = torch.tensor(list(self.deque), dtype=torch.float32) + return d.mean().item() + + @property + def global_avg(self): + return self.total / self.count + + @property + def max(self): + return max(self.deque) + + @property + def value(self): + return self.deque[-1] + + def __str__(self): + return self.fmt.format( + median=self.median, avg=self.avg, global_avg=self.global_avg, max=self.max, value=self.value + ) + + +def all_gather(data): + """ + Run all_gather on arbitrary picklable data (not necessarily tensors) + Args: + data: any picklable object + Returns: + list[data]: list of data gathered from each rank + """ + world_size = get_world_size() + if world_size == 1: + return [data] + + # serialized to a Tensor + buffer = pickle.dumps(data) + storage = torch.ByteStorage.from_buffer(buffer) + tensor = torch.ByteTensor(storage).to("cuda") + + # obtain Tensor size of each rank + local_size = torch.tensor([tensor.numel()], device="cuda") + size_list = [torch.tensor([0], device="cuda") for _ in range(world_size)] + dist.all_gather(size_list, local_size) + size_list = [int(size.item()) for size in size_list] + max_size = max(size_list) + + # receiving Tensor from all ranks + # we pad the tensor because torch all_gather does not support + # gathering tensors of different shapes + tensor_list = [] + for _ in size_list: + tensor_list.append(torch.empty((max_size,), dtype=torch.uint8, device="cuda")) + if local_size != max_size: + padding = torch.empty(size=(max_size - local_size,), dtype=torch.uint8, device="cuda") + tensor = torch.cat((tensor, padding), dim=0) + dist.all_gather(tensor_list, tensor) + + data_list = [] + for size, tensor in zip(size_list, tensor_list, strict=False): + buffer = tensor.cpu().numpy().tobytes()[:size] + data_list.append(pickle.loads(buffer)) + + return data_list + + +def reduce_dict(input_dict, average=True): + """ + Args: + input_dict (dict): all the values will be reduced + average (bool): whether to do average or sum + Reduce the values in the dictionary from all processes so that all processes + have the averaged results. Returns a dict with the same fields as + input_dict, after reduction. + """ + world_size = get_world_size() + if world_size < 2: + return input_dict + with torch.no_grad(): + names = [] + values = [] + # sort the keys so that they are consistent across processes + for k in sorted(input_dict.keys()): + names.append(k) + values.append(input_dict[k]) + values = torch.stack(values, dim=0) + dist.all_reduce(values) + if average: + values /= world_size + reduced_dict = {k: v for k, v in zip(names, values, strict=False)} # noqa: C416 + return reduced_dict + + +class MetricLogger: + def __init__(self, delimiter="\t"): + self.meters = defaultdict(SmoothedValue) + self.delimiter = delimiter + + def update(self, **kwargs): + for k, v in kwargs.items(): + if isinstance(v, torch.Tensor): + v = v.item() + assert isinstance(v, (float, int)) + self.meters[k].update(v) + + def __getattr__(self, attr): + if attr in self.meters: + return self.meters[attr] + if attr in self.__dict__: + return self.__dict__[attr] + raise AttributeError("'{}' object has no attribute '{}'".format(type(self).__name__, attr)) + + def __str__(self): + loss_str = [] + for name, meter in self.meters.items(): + loss_str.append("{}: {}".format(name, str(meter))) + return self.delimiter.join(loss_str) + + def synchronize_between_processes(self): + for meter in self.meters.values(): + meter.synchronize_between_processes() + + def add_meter(self, name, meter): + self.meters[name] = meter + + def log_every(self, iterable, print_freq, header=None): + if not header: + header = "" + start_time = time.time() + end = time.time() + iter_time = SmoothedValue(fmt="{avg:.4f}") + data_time = SmoothedValue(fmt="{avg:.4f}") + space_fmt = ":" + str(len(str(len(iterable)))) + "d" + if torch.cuda.is_available(): + log_msg = self.delimiter.join( + [ + header, + "[{0" + space_fmt + "}/{1}]", + "eta: {eta}", + "{meters}", + "time: {time}", + "data: {data}", + "max mem: {memory:.0f}", + ] + ) + else: + log_msg = self.delimiter.join( + [ + header, + "[{0" + space_fmt + "}/{1}]", + "eta: {eta}", + "{meters}", + "time: {time}", + "data: {data}", + ] + ) + mega_b = 1024.0 * 1024.0 + for i, obj in enumerate(iterable): + data_time.update(time.time() - end) + yield obj + iter_time.update(time.time() - end) + if i % print_freq == 0 or i == len(iterable) - 1: + eta_seconds = iter_time.global_avg * (len(iterable) - i) + eta_string = str(datetime.timedelta(seconds=int(eta_seconds))) + if torch.cuda.is_available(): + print( + log_msg.format( + i, + len(iterable), + eta=eta_string, + meters=str(self), + time=str(iter_time), + data=str(data_time), + memory=torch.cuda.max_memory_allocated() / mega_b, + ) + ) + else: + print( + log_msg.format( + i, + len(iterable), + eta=eta_string, + meters=str(self), + time=str(iter_time), + data=str(data_time), + ) + ) + end = time.time() + total_time = time.time() - start_time + total_time_str = str(datetime.timedelta(seconds=int(total_time))) + print("{} Total time: {} ({:.4f} s / it)".format(header, total_time_str, total_time / len(iterable))) + + +def get_sha(): + cwd = os.path.dirname(os.path.abspath(__file__)) + + def _run(command): + return subprocess.check_output(command, cwd=cwd).decode("ascii").strip() + + sha = "N/A" + diff = "clean" + branch = "N/A" + try: + sha = _run(["git", "rev-parse", "HEAD"]) + subprocess.check_output(["git", "diff"], cwd=cwd) + diff = _run(["git", "diff-index", "HEAD"]) + diff = "has uncommited changes" if diff else "clean" + branch = _run(["git", "rev-parse", "--abbrev-ref", "HEAD"]) + except Exception: + pass + message = f"sha: {sha}, status: {diff}, branch: {branch}" + return message + + +def collate_fn(batch): + batch = list(zip(*batch, strict=False)) + batch[0] = nested_tensor_from_tensor_list(batch[0]) + return tuple(batch) + + +def _max_by_axis(the_list): + # type: (List[List[int]]) -> List[int] + maxes = the_list[0] + for sublist in the_list[1:]: + for index, item in enumerate(sublist): + maxes[index] = max(maxes[index], item) + return maxes + + +class NestedTensor: + def __init__(self, tensors, mask: Optional[Tensor]): + self.tensors = tensors + self.mask = mask + + def to(self, device): + # type: (Device) -> NestedTensor # noqa + cast_tensor = self.tensors.to(device) + mask = self.mask + if mask is not None: + assert mask is not None + cast_mask = mask.to(device) + else: + cast_mask = None + return NestedTensor(cast_tensor, cast_mask) + + def decompose(self): + return self.tensors, self.mask + + def __repr__(self): + return str(self.tensors) + + +def nested_tensor_from_tensor_list(tensor_list: List[Tensor]): + # TODO make this more general + if tensor_list[0].ndim == 3: + if torchvision._is_tracing(): + # nested_tensor_from_tensor_list() does not export well to ONNX + # call _onnx_nested_tensor_from_tensor_list() instead + return _onnx_nested_tensor_from_tensor_list(tensor_list) + + # TODO make it support different-sized images + max_size = _max_by_axis([list(img.shape) for img in tensor_list]) + # min_size = tuple(min(s) for s in zip(*[img.shape for img in tensor_list])) + batch_shape = [len(tensor_list)] + max_size + b, c, h, w = batch_shape + dtype = tensor_list[0].dtype + device = tensor_list[0].device + tensor = torch.zeros(batch_shape, dtype=dtype, device=device) + mask = torch.ones((b, h, w), dtype=torch.bool, device=device) + for img, pad_img, m in zip(tensor_list, tensor, mask, strict=False): + pad_img[: img.shape[0], : img.shape[1], : img.shape[2]].copy_(img) + m[: img.shape[1], : img.shape[2]] = False + else: + raise ValueError("not supported") + return NestedTensor(tensor, mask) + + +# _onnx_nested_tensor_from_tensor_list() is an implementation of +# nested_tensor_from_tensor_list() that is supported by ONNX tracing. +@torch.jit.unused +def _onnx_nested_tensor_from_tensor_list(tensor_list: List[Tensor]) -> NestedTensor: + max_size = [] + for i in range(tensor_list[0].dim()): + max_size_i = torch.max(torch.stack([img.shape[i] for img in tensor_list]).to(torch.float32)).to( + torch.int64 + ) + max_size.append(max_size_i) + max_size = tuple(max_size) + + # work around for + # pad_img[: img.shape[0], : img.shape[1], : img.shape[2]].copy_(img) + # m[: img.shape[1], :img.shape[2]] = False + # which is not yet supported in onnx + padded_imgs = [] + padded_masks = [] + for img in tensor_list: + padding = [(s1 - s2) for s1, s2 in zip(max_size, tuple(img.shape), strict=False)] + padded_img = torch.nn.functional.pad(img, (0, padding[2], 0, padding[1], 0, padding[0])) + padded_imgs.append(padded_img) + + m = torch.zeros_like(img[0], dtype=torch.int, device=img.device) + padded_mask = torch.nn.functional.pad(m, (0, padding[2], 0, padding[1]), "constant", 1) + padded_masks.append(padded_mask.to(torch.bool)) + + tensor = torch.stack(padded_imgs) + mask = torch.stack(padded_masks) + + return NestedTensor(tensor, mask=mask) + + +def setup_for_distributed(is_master): + """ + This function disables printing when not in master process + """ + import builtins as __builtin__ + + builtin_print = __builtin__.print + + def print(*args, **kwargs): + force = kwargs.pop("force", False) + if is_master or force: + builtin_print(*args, **kwargs) + + __builtin__.print = print + + +def is_dist_avail_and_initialized(): + if not dist.is_available(): + return False + if not dist.is_initialized(): + return False + return True + + +def get_world_size(): + if not is_dist_avail_and_initialized(): + return 1 + return dist.get_world_size() + + +def get_rank(): + if not is_dist_avail_and_initialized(): + return 0 + return dist.get_rank() + + +def is_main_process(): + return get_rank() == 0 + + +def save_on_master(*args, **kwargs): + if is_main_process(): + torch.save(*args, **kwargs) + + +def init_distributed_mode(args): + if "RANK" in os.environ and "WORLD_SIZE" in os.environ: + args.rank = int(os.environ["RANK"]) + args.world_size = int(os.environ["WORLD_SIZE"]) + args.gpu = int(os.environ["LOCAL_RANK"]) + elif "SLURM_PROCID" in os.environ: + args.rank = int(os.environ["SLURM_PROCID"]) + args.gpu = args.rank % torch.cuda.device_count() + else: + print("Not using distributed mode") + args.distributed = False + return + + args.distributed = True + + torch.cuda.set_device(args.gpu) + args.dist_backend = "nccl" + print("| distributed init (rank {}): {}".format(args.rank, args.dist_url), flush=True) + torch.distributed.init_process_group( + backend=args.dist_backend, init_method=args.dist_url, world_size=args.world_size, rank=args.rank + ) + torch.distributed.barrier() + setup_for_distributed(args.rank == 0) + + +@torch.no_grad() +def accuracy(output, target, topk=(1,)): + """Computes the precision@k for the specified values of k""" + if target.numel() == 0: + return [torch.zeros([], device=output.device)] + maxk = max(topk) + batch_size = target.size(0) + + _, pred = output.topk(maxk, 1, True, True) + pred = pred.t() + correct = pred.eq(target.view(1, -1).expand_as(pred)) + + res = [] + for k in topk: + correct_k = correct[:k].view(-1).float().sum(0) + res.append(correct_k.mul_(100.0 / batch_size)) + return res + + +def interpolate(input, size=None, scale_factor=None, mode="nearest", align_corners=None): + # type: (Tensor, Optional[List[int]], Optional[float], str, Optional[bool]) -> Tensor + """ + Equivalent to nn.functional.interpolate, but with support for empty batch sizes. + This will eventually be supported natively by PyTorch, and this + class can go away. + """ + if version.parse(torchvision.__version__) < version.parse("0.7"): + if input.numel() > 0: + return torch.nn.functional.interpolate(input, size, scale_factor, mode, align_corners) + + output_shape = _output_size(2, input, size, scale_factor) + output_shape = list(input.shape[:-2]) + list(output_shape) + return _new_empty_tensor(input, output_shape) + else: + return torchvision.ops.misc.interpolate(input, size, scale_factor, mode, align_corners) diff --git a/lerobot/common/policies/factory.py b/lerobot/common/policies/factory.py index a956cb4bc..c5e45300c 100644 --- a/lerobot/common/policies/factory.py +++ b/lerobot/common/policies/factory.py @@ -17,6 +17,12 @@ def make_policy(cfg): n_action_steps=cfg.n_action_steps + cfg.n_latency_steps, **cfg.policy, ) + elif cfg.policy.name == "act": + from lerobot.common.policies.act.policy import ActionChunkingTransformerPolicy + + policy = ActionChunkingTransformerPolicy( + cfg.policy, cfg.device, n_action_steps=cfg.n_action_steps + cfg.n_latency_steps + ) else: raise ValueError(cfg.policy.name) diff --git a/lerobot/configs/env/aloha.yaml b/lerobot/configs/env/aloha.yaml index 5b5ecbb7e..df464c753 100644 --- a/lerobot/configs/env/aloha.yaml +++ b/lerobot/configs/env/aloha.yaml @@ -15,11 +15,11 @@ env: task: sim_insertion_human from_pixels: True pixels_only: False - image_size: 96 + image_size: [3, 480, 640] action_repeat: 1 - episode_length: 300 + episode_length: 400 fps: ${fps} policy: - state_dim: 2 - action_dim: 2 + state_dim: 14 + action_dim: 14 diff --git a/lerobot/configs/policy/act.yaml b/lerobot/configs/policy/act.yaml new file mode 100644 index 000000000..a52c3f541 --- /dev/null +++ b/lerobot/configs/policy/act.yaml @@ -0,0 +1,58 @@ +# @package _global_ + +offline_steps: 1344000 +online_steps: 0 + +eval_episodes: 1 +eval_freq: 10000 +save_freq: 100000 +log_freq: 250 + +horizon: 100 +n_obs_steps: 1 +n_latency_steps: 0 +# when temporal_agg=False, n_action_steps=horizon +n_action_steps: ${horizon} + +policy: + name: act + + pretrained_model_path: + + lr: 1e-5 + lr_backbone: 1e-5 + weight_decay: 1e-4 + grad_clip_norm: 10 + backbone: resnet18 + num_queries: ${horizon} # chunk_size + horizon: ${horizon} # chunk_size + kl_weight: 10 + hidden_dim: 512 + dim_feedforward: 3200 + enc_layers: 4 + dec_layers: 7 + nheads: 8 + #camera_names: [top, front_close, left_pillar, right_pillar] + camera_names: [top] + position_embedding: sine + masks: false + dilation: false + dropout: 0.1 + pre_norm: false + + vae: true + + batch_size: 8 + + per_alpha: 0.6 + per_beta: 0.4 + + balanced_sampling: false + utd: 1 + + n_obs_steps: ${n_obs_steps} + + temporal_agg: false + + state_dim: ??? + action_dim: ??? diff --git a/lerobot/scripts/download.py b/lerobot/scripts/download.py deleted file mode 100644 index ac935f483..000000000 --- a/lerobot/scripts/download.py +++ /dev/null @@ -1,22 +0,0 @@ -# TODO(rcadene): obsolete remove -import os -import zipfile - -import gdown - - -def download(): - url = "https://drive.google.com/uc?id=1nhxpykGtPDhmQKm-_B8zBSywVRdgeVya" - download_path = "data.zip" - gdown.download(url, download_path, quiet=False) - print("Extracting...") - with zipfile.ZipFile(download_path, "r") as zip_f: - for member in zip_f.namelist(): - if member.startswith("data/xarm") and member.endswith(".pkl"): - print(member) - zip_f.extract(member=member) - os.remove(download_path) - - -if __name__ == "__main__": - download() diff --git a/lerobot/scripts/eval.py b/lerobot/scripts/eval.py index 6435310a5..7ba2812e2 100644 --- a/lerobot/scripts/eval.py +++ b/lerobot/scripts/eval.py @@ -38,27 +38,18 @@ def eval_policy( successes = [] threads = [] for i in tqdm.tqdm(range(num_episodes)): - tensordict = env.reset() - ep_frames = [] - if save_video or (return_first_video and i == 0): - def rendering_callback(env, td=None): + def render_frame(env): ep_frames.append(env.render()) # noqa: B023 - # render first frame before rollout - rendering_callback(env) - else: - rendering_callback = None + env.register_rendering_hook(render_frame) with torch.inference_mode(): rollout = env.rollout( max_steps=max_steps, policy=policy, - callback=rendering_callback, - auto_reset=False, - tensordict=tensordict, auto_cast_to_device=True, ) # print(", ".join([f"{x:.3f}" for x in rollout["next", "reward"][:,0].tolist()])) @@ -85,6 +76,8 @@ def rendering_callback(env, td=None): if return_first_video and i == 0: first_video = stacked_frames.transpose(0, 3, 1, 2) + env.reset_rendering_hooks() + for thread in threads: thread.join() diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index f4b226045..c063caf87 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -1,4 +1,5 @@ import logging +from pathlib import Path import hydra import numpy as np @@ -192,6 +193,8 @@ def train(cfg: dict, out_dir=None, job_name=None): num_episodes=cfg.eval_episodes, max_steps=cfg.env.episode_length // cfg.n_action_steps, return_first_video=True, + video_dir=Path(out_dir) / "eval", + save_video=True, ) log_eval_info(logger, eval_info, step, cfg, offline_buffer, is_offline) if cfg.wandb.enable: diff --git a/poetry.lock b/poetry.lock index db4f8f3e7..59de0ec55 100644 --- a/poetry.lock +++ b/poetry.lock @@ -340,69 +340,69 @@ files = [ [[package]] name = "cython" -version = "3.0.8" +version = "3.0.9" description = "The Cython compiler for writing C extensions in the Python language." optional = false python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" files = [ - {file = "Cython-3.0.8-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:a846e0a38e2b24e9a5c5dc74b0e54c6e29420d88d1dafabc99e0fc0f3e338636"}, - {file = "Cython-3.0.8-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:45523fdc2b78d79b32834cc1cc12dc2ca8967af87e22a3ee1bff20e77c7f5520"}, - {file = "Cython-3.0.8-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:baa0b7f3f841fe087410cab66778e2d3fb20ae2d2078a2be3dffe66c6574be39"}, - {file = "Cython-3.0.8-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e87294e33e40c289c77a135f491cd721bd089f193f956f7b8ed5aa2d0b8c558f"}, - {file = "Cython-3.0.8-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:a1df7a129344b1215c20096d33c00193437df1a8fcca25b71f17c23b1a44f782"}, - {file = "Cython-3.0.8-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:13c2a5e57a0358da467d97667297bf820b62a1a87ae47c5f87938b9bb593acbd"}, - {file = "Cython-3.0.8-cp310-cp310-win32.whl", hash = "sha256:96b028f044f5880e3cb18ecdcfc6c8d3ce9d0af28418d5ab464509f26d8adf12"}, - {file = "Cython-3.0.8-cp310-cp310-win_amd64.whl", hash = "sha256:8140597a8b5cc4f119a1190f5a2228a84f5ca6d8d9ec386cfce24663f48b2539"}, - {file = "Cython-3.0.8-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:aae26f9663e50caf9657148403d9874eea41770ecdd6caf381d177c2b1bb82ba"}, - {file = "Cython-3.0.8-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:547eb3cdb2f8c6f48e6865d5a741d9dd051c25b3ce076fbca571727977b28ac3"}, - {file = "Cython-3.0.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5a567d4b9ba70b26db89d75b243529de9e649a2f56384287533cf91512705bee"}, - {file = "Cython-3.0.8-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:51d1426263b0e82fb22bda8ea60dc77a428581cc19e97741011b938445d383f1"}, - {file = "Cython-3.0.8-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:c26daaeccda072459b48d211415fd1e5507c06bcd976fa0d5b8b9f1063467d7b"}, - {file = "Cython-3.0.8-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:289ce7838208211cd166e975865fd73b0649bf118170b6cebaedfbdaf4a37795"}, - {file = "Cython-3.0.8-cp311-cp311-win32.whl", hash = "sha256:c8aa05f5e17f8042a3be052c24f2edc013fb8af874b0bf76907d16c51b4e7871"}, - {file = "Cython-3.0.8-cp311-cp311-win_amd64.whl", hash = "sha256:000dc9e135d0eec6ecb2b40a5b02d0868a2f8d2e027a41b0fe16a908a9e6de02"}, - {file = "Cython-3.0.8-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:90d3fe31db55685d8cb97d43b0ec39ef614fcf660f83c77ed06aa670cb0e164f"}, - {file = "Cython-3.0.8-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e24791ddae2324e88e3c902a765595c738f19ae34ee66bfb1a6dac54b1833419"}, - {file = "Cython-3.0.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2f020fa1c0552052e0660790b8153b79e3fc9a15dbd8f1d0b841fe5d204a6ae6"}, - {file = "Cython-3.0.8-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:18bfa387d7a7f77d7b2526af69a65dbd0b731b8d941aaff5becff8e21f6d7717"}, - {file = "Cython-3.0.8-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:fe81b339cffd87c0069c6049b4d33e28bdd1874625ee515785bf42c9fdff3658"}, - {file = "Cython-3.0.8-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:80fd94c076e1e1b1ee40a309be03080b75f413e8997cddcf401a118879863388"}, - {file = "Cython-3.0.8-cp312-cp312-win32.whl", hash = "sha256:85077915a93e359a9b920280d214dc0cf8a62773e1f3d7d30fab8ea4daed670c"}, - {file = "Cython-3.0.8-cp312-cp312-win_amd64.whl", hash = "sha256:0cb2dcc565c7851f75d496f724a384a790fab12d1b82461b663e66605bec429a"}, - {file = "Cython-3.0.8-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:870d2a0a7e3cbd5efa65aecdb38d715ea337a904ea7bb22324036e78fb7068e7"}, - {file = "Cython-3.0.8-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7e8f2454128974905258d86534f4fd4f91d2f1343605657ecab779d80c9d6d5e"}, - {file = "Cython-3.0.8-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c1949d6aa7bc792554bee2b67a9fe41008acbfe22f4f8df7b6ec7b799613a4b3"}, - {file = "Cython-3.0.8-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c9f2c6e1b8f3bcd6cb230bac1843f85114780bb8be8614855b1628b36bb510e0"}, - {file = "Cython-3.0.8-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:05d7eddc668ae7993643f32c7661f25544e791edb745758672ea5b1a82ecffa6"}, - {file = "Cython-3.0.8-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:bfabe115deef4ada5d23c87bddb11289123336dcc14347011832c07db616dd93"}, - {file = "Cython-3.0.8-cp36-cp36m-win32.whl", hash = "sha256:0c38c9f0bcce2df0c3347285863621be904ac6b64c5792d871130569d893efd7"}, - {file = "Cython-3.0.8-cp36-cp36m-win_amd64.whl", hash = "sha256:6c46939c3983217d140999de7c238c3141f56b1ea349e47ca49cae899969aa2c"}, - {file = "Cython-3.0.8-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:115f0a50f752da6c99941b103b5cb090da63eb206abbc7c2ad33856ffc73f064"}, - {file = "Cython-3.0.8-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c9c0f29246734561c90f36e70ed0506b61aa3d044e4cc4cba559065a2a741fae"}, - {file = "Cython-3.0.8-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1ab75242869ff71e5665fe5c96f3378e79e792fa3c11762641b6c5afbbbbe026"}, - {file = "Cython-3.0.8-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6717c06e9cfc6c1df18543cd31a21f5d8e378a40f70c851fa2d34f0597037abc"}, - {file = "Cython-3.0.8-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:9d3f74388db378a3c6fd06e79a809ed98df3f56484d317b81ee762dbf3c263e0"}, - {file = "Cython-3.0.8-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:ae7ac561fd8253a9ae96311e91d12af5f701383564edc11d6338a7b60b285a6f"}, - {file = "Cython-3.0.8-cp37-cp37m-win32.whl", hash = "sha256:97b2a45845b993304f1799664fa88da676ee19442b15fdcaa31f9da7e1acc434"}, - {file = "Cython-3.0.8-cp37-cp37m-win_amd64.whl", hash = "sha256:9e2be2b340fea46fb849d378f9b80d3c08ff2e81e2bfbcdb656e2e3cd8c6b2dc"}, - {file = "Cython-3.0.8-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:2cde23c555470db3f149ede78b518e8274853745289c956a0e06ad8d982e4db9"}, - {file = "Cython-3.0.8-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7990ca127e1f1beedaf8fc8bf66541d066ef4723ad7d8d47a7cbf842e0f47580"}, - {file = "Cython-3.0.8-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4b983c8e6803f016146c26854d9150ddad5662960c804ea7f0c752c9266752f0"}, - {file = "Cython-3.0.8-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a973268d7ca1a2bdf78575e459a94a78e1a0a9bb62a7db0c50041949a73b02ff"}, - {file = "Cython-3.0.8-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:61a237bc9dd23c7faef0fcfce88c11c65d0c9bb73c74ccfa408b3a012073c20e"}, - {file = "Cython-3.0.8-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:3a3d67f079598af49e90ff9655bf85bd358f093d727eb21ca2708f467c489cae"}, - {file = "Cython-3.0.8-cp38-cp38-win32.whl", hash = "sha256:17a642bb01a693e34c914106566f59844b4461665066613913463a719e0dd15d"}, - {file = "Cython-3.0.8-cp38-cp38-win_amd64.whl", hash = "sha256:2cdfc32252f3b6dc7c94032ab744dcedb45286733443c294d8f909a4854e7f83"}, - {file = "Cython-3.0.8-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:fa97893d99385386925d00074654aeae3a98867f298d1e12ceaf38a9054a9bae"}, - {file = "Cython-3.0.8-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f05c0bf9d085c031df8f583f0d506aa3be1692023de18c45d0aaf78685bbb944"}, - {file = "Cython-3.0.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:de892422582f5758bd8de187e98ac829330ec1007bc42c661f687792999988a7"}, - {file = "Cython-3.0.8-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:314f2355a1f1d06e3c431eaad4708cf10037b5e91e4b231d89c913989d0bdafd"}, - {file = "Cython-3.0.8-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:78825a3774211e7d5089730f00cdf7f473042acc9ceb8b9eeebe13ed3a5541de"}, - {file = "Cython-3.0.8-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:df8093deabc55f37028190cf5e575c26aad23fc673f34b85d5f45076bc37ce39"}, - {file = "Cython-3.0.8-cp39-cp39-win32.whl", hash = "sha256:1aca1b97e0095b3a9a6c33eada3f661a4ed0d499067d121239b193e5ba3bb4f0"}, - {file = "Cython-3.0.8-cp39-cp39-win_amd64.whl", hash = "sha256:16873d78be63bd38ffb759da7ab82814b36f56c769ee02b1d5859560e4c3ac3c"}, - {file = "Cython-3.0.8-py2.py3-none-any.whl", hash = "sha256:171b27051253d3f9108e9759e504ba59ff06e7f7ba944457f94deaf9c21bf0b6"}, - {file = "Cython-3.0.8.tar.gz", hash = "sha256:8333423d8fd5765e7cceea3a9985dd1e0a5dfeb2734629e1a2ed2d6233d39de6"}, + {file = "Cython-3.0.9-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:296bd30d4445ac61b66c9d766567f6e81a6e262835d261e903c60c891a6729d3"}, + {file = "Cython-3.0.9-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f496b52845cb45568a69d6359a2c335135233003e708ea02155c10ce3548aa89"}, + {file = "Cython-3.0.9-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:858c3766b9aa3ab8a413392c72bbab1c144a9766b7c7bfdef64e2e414363fa0c"}, + {file = "Cython-3.0.9-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c0eb1e6ef036028a52525fd9a012a556f6dd4788a0e8755fe864ba0e70cde2ff"}, + {file = "Cython-3.0.9-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:c8191941073ea5896321de3c8c958fd66e5f304b0cd1f22c59edd0b86c4dd90d"}, + {file = "Cython-3.0.9-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:e32b016030bc72a8a22a1f21f470a2f57573761a4f00fbfe8347263f4fbdb9f1"}, + {file = "Cython-3.0.9-cp310-cp310-win32.whl", hash = "sha256:d6f3ff1cd6123973fe03e0fb8ee936622f976c0c41138969975824d08886572b"}, + {file = "Cython-3.0.9-cp310-cp310-win_amd64.whl", hash = "sha256:56f3b643dbe14449248bbeb9a63fe3878a24256664bc8c8ef6efd45d102596d8"}, + {file = "Cython-3.0.9-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:35e6665a20d6b8a152d72b7fd87dbb2af6bb6b18a235b71add68122d594dbd41"}, + {file = "Cython-3.0.9-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f92f4960c40ad027bd8c364c50db11104eadc59ffeb9e5b7f605ca2f05946e20"}, + {file = "Cython-3.0.9-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:38df37d0e732fbd9a2fef898788492e82b770c33d1e4ed12444bbc8a3b3f89c0"}, + {file = "Cython-3.0.9-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ad7fd88ebaeaf2e76fd729a8919fae80dab3d6ac0005e28494261d52ff347a8f"}, + {file = "Cython-3.0.9-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:1365d5f76bf4d19df3d19ce932584c9bb76e9fb096185168918ef9b36e06bfa4"}, + {file = "Cython-3.0.9-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:c232e7f279388ac9625c3e5a5a9f0078a9334959c5d6458052c65bbbba895e1e"}, + {file = "Cython-3.0.9-cp311-cp311-win32.whl", hash = "sha256:357e2fad46a25030b0c0496487e01a9dc0fdd0c09df0897f554d8ba3c1bc4872"}, + {file = "Cython-3.0.9-cp311-cp311-win_amd64.whl", hash = "sha256:1315aee506506e8d69cf6631d8769e6b10131fdcc0eb66df2698f2a3ddaeeff2"}, + {file = "Cython-3.0.9-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:157973807c2796addbed5fbc4d9c882ab34bbc60dc297ca729504901479d5df7"}, + {file = "Cython-3.0.9-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:00b105b5d050645dd59e6767bc0f18b48a4aa11c85f42ec7dd8181606f4059e3"}, + {file = "Cython-3.0.9-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ac5536d09bef240cae0416d5a703d298b74c7bbc397da803ac9d344e732d4369"}, + {file = "Cython-3.0.9-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:09c44501d476d16aaa4cbc29c87f8c0f54fc20e69b650d59cbfa4863426fc70c"}, + {file = "Cython-3.0.9-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:cc9c3b9f20d8e298618e5ccd32083ca386e785b08f9893fbec4c50b6b85be772"}, + {file = "Cython-3.0.9-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:a30d96938c633e3ec37000ac3796525da71254ef109e66bdfd78f29891af6454"}, + {file = "Cython-3.0.9-cp312-cp312-win32.whl", hash = "sha256:757ca93bdd80702546df4d610d2494ef2e74249cac4d5ba9464589fb464bd8a3"}, + {file = "Cython-3.0.9-cp312-cp312-win_amd64.whl", hash = "sha256:1dc320a9905ab95414013f6de805efbff9e17bb5fb3b90bbac533f017bec8136"}, + {file = "Cython-3.0.9-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:4ae349960ebe0da0d33724eaa7f1eb866688fe5434cc67ce4dbc06d6a719fbfc"}, + {file = "Cython-3.0.9-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:63d2537bf688247f76ded6dee28ebd26274f019309aef1eb4f2f9c5c482fde2d"}, + {file = "Cython-3.0.9-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:36f5a2dfc724bea1f710b649f02d802d80fc18320c8e6396684ba4a48412445a"}, + {file = "Cython-3.0.9-cp36-cp36m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:deaf4197d4b0bcd5714a497158ea96a2bd6d0f9636095437448f7e06453cc83d"}, + {file = "Cython-3.0.9-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:000af6deb7412eb7ac0c635ff5e637fb8725dd0a7b88cc58dfc2b3de14e701c4"}, + {file = "Cython-3.0.9-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:15c7f5c2d35bed9aa5f2a51eaac0df23ae72f2dbacf62fc672dd6bfaa75d2d6f"}, + {file = "Cython-3.0.9-cp36-cp36m-win32.whl", hash = "sha256:f49aa4970cd3bec66ac22e701def16dca2a49c59cceba519898dd7526e0be2c0"}, + {file = "Cython-3.0.9-cp36-cp36m-win_amd64.whl", hash = "sha256:4558814fa025b193058d42eeee498a53d6b04b2980d01339fc2444b23fd98e58"}, + {file = "Cython-3.0.9-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:539cd1d74fd61f6cfc310fa6bbbad5adc144627f2b7486a07075d4e002fd6aad"}, + {file = "Cython-3.0.9-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c3232926cd406ee02eabb732206f6e882c3aed9d58f0fea764013d9240405bcf"}, + {file = "Cython-3.0.9-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:33b6ac376538a7fc8c567b85d3c71504308a9318702ec0485dd66c059f3165cb"}, + {file = "Cython-3.0.9-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2cc92504b5d22ac66031ffb827bd3a967fc75a5f0f76ab48bce62df19be6fdfd"}, + {file = "Cython-3.0.9-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:22b8fae756c5c0d8968691bed520876de452f216c28ec896a00739a12dba3bd9"}, + {file = "Cython-3.0.9-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:9cda0d92a09f3520f29bd91009f1194ba9600777c02c30c6d2d4ac65fb63e40d"}, + {file = "Cython-3.0.9-cp37-cp37m-win32.whl", hash = "sha256:ec612418490941ed16c50c8d3784c7bdc4c4b2a10c361259871790b02ec8c1db"}, + {file = "Cython-3.0.9-cp37-cp37m-win_amd64.whl", hash = "sha256:976c8d2bedc91ff6493fc973d38b2dc01020324039e2af0e049704a8e1b22936"}, + {file = "Cython-3.0.9-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:5055988b007c92256b6e9896441c3055556038c3497fcbf8c921a6c1fce90719"}, + {file = "Cython-3.0.9-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d9360606d964c2d0492a866464efcf9d0a92715644eede3f6a2aa696de54a137"}, + {file = "Cython-3.0.9-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:02c6e809f060bed073dc7cba1648077fe3b68208863d517c8b39f3920eecf9dd"}, + {file = "Cython-3.0.9-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:95ed792c966f969cea7489c32ff90150b415c1f3567db8d5a9d489c7c1602dac"}, + {file = "Cython-3.0.9-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:8edd59d22950b400b03ca78d27dc694d2836a92ef0cac4f64cb4b2ff902f7e25"}, + {file = "Cython-3.0.9-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:4cf0ed273bf60e97922fcbbdd380c39693922a597760160b4b4355e6078ca188"}, + {file = "Cython-3.0.9-cp38-cp38-win32.whl", hash = "sha256:5eb9bd4ae12ebb2bc79a193d95aacf090fbd8d7013e11ed5412711650cb34934"}, + {file = "Cython-3.0.9-cp38-cp38-win_amd64.whl", hash = "sha256:44457279da56e0f829bb1fc5a5dc0836e5d498dbcf9b2324f32f7cc9d2ec6569"}, + {file = "Cython-3.0.9-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:c4b419a1adc2af43f4660e2f6eaf1e4fac2dbac59490771eb8ac3d6063f22356"}, + {file = "Cython-3.0.9-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4f836192140f033b2319a0128936367c295c2b32e23df05b03b672a6015757ea"}, + {file = "Cython-3.0.9-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2fd198c1a7f8e9382904d622cc0efa3c184605881fd5262c64cbb7168c4c1ec5"}, + {file = "Cython-3.0.9-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a274fe9ca5c53fafbcf5c8f262f8ad6896206a466f0eeb40aaf36a7951e957c0"}, + {file = "Cython-3.0.9-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:158c38360bbc5063341b1e78d3737f1251050f89f58a3df0d10fb171c44262be"}, + {file = "Cython-3.0.9-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:8bf30b045f7deda0014b042c1b41c1d272facc762ab657529e3b05505888e878"}, + {file = "Cython-3.0.9-cp39-cp39-win32.whl", hash = "sha256:9a001fd95c140c94d934078544ff60a3c46aca2dc86e75a76e4121d3cd1f4b33"}, + {file = "Cython-3.0.9-cp39-cp39-win_amd64.whl", hash = "sha256:530c01c4aebba709c0ec9c7ecefe07177d0b9fd7ffee29450a118d92192ccbdf"}, + {file = "Cython-3.0.9-py2.py3-none-any.whl", hash = "sha256:bf96417714353c5454c2e3238fca9338599330cf51625cdc1ca698684465646f"}, + {file = "Cython-3.0.9.tar.gz", hash = "sha256:a2d354f059d1f055d34cfaa62c5b68bc78ac2ceab6407148d47fb508cf3ba4f3"}, ] [[package]] @@ -488,6 +488,37 @@ files = [ {file = "distlib-0.3.8.tar.gz", hash = "sha256:1530ea13e350031b6312d8580ddb6b27a104275a31106523b8f123787f494f64"}, ] +[[package]] +name = "dm-control" +version = "1.0.14" +description = "Continuous control environments and MuJoCo Python bindings." +optional = false +python-versions = ">=3.8" +files = [ + {file = "dm_control-1.0.14-py3-none-any.whl", hash = "sha256:883c63244a7ebf598700a97564ed19fffd3479ca79efd090aed881609cdb9fc6"}, + {file = "dm_control-1.0.14.tar.gz", hash = "sha256:def1ece747b6f175c581150826b50f1a6134086dab34f8f3fd2d088ea035cf3d"}, +] + +[package.dependencies] +absl-py = ">=0.7.0" +dm-env = "*" +dm-tree = "!=0.1.2" +glfw = "*" +labmaze = "*" +lxml = "*" +mujoco = ">=2.3.7" +numpy = ">=1.9.0" +protobuf = ">=3.19.4" +pyopengl = ">=3.1.4" +pyparsing = ">=3.0.0" +requests = "*" +scipy = "*" +setuptools = "!=50.0.0" +tqdm = "*" + +[package.extras] +hdf5 = ["h5py"] + [[package]] name = "dm-env" version = "1.6" @@ -584,43 +615,6 @@ files = [ {file = "einops-0.7.0.tar.gz", hash = "sha256:b2b04ad6081a3b227080c9bf5e3ace7160357ff03043cd66cc5b2319eb7031d1"}, ] -[[package]] -name = "etils" -version = "1.7.0" -description = "Collection of common python utils" -optional = false -python-versions = ">=3.10" -files = [ - {file = "etils-1.7.0-py3-none-any.whl", hash = "sha256:61af8f7c242171de15e22e5da02d527cb9e677d11f8bcafe18fcc3548eee3e60"}, - {file = "etils-1.7.0.tar.gz", hash = "sha256:97b68fd25e185683215286ef3a54e38199b6245f5fe8be6bedc1189be4256350"}, -] - -[package.dependencies] -fsspec = {version = "*", optional = true, markers = "extra == \"epath\""} -importlib_resources = {version = "*", optional = true, markers = "extra == \"epath\""} -typing_extensions = {version = "*", optional = true, markers = "extra == \"epy\""} -zipp = {version = "*", optional = true, markers = "extra == \"epath\""} - -[package.extras] -all = ["etils[array-types]", "etils[eapp]", "etils[ecolab]", "etils[edc]", "etils[enp]", "etils[epath-gcs]", "etils[epath-s3]", "etils[epath]", "etils[epy]", "etils[etqdm]", "etils[etree-dm]", "etils[etree-jax]", "etils[etree-tf]", "etils[etree]"] -array-types = ["etils[enp]"] -dev = ["chex", "dataclass_array", "optree", "pyink", "pylint (>=2.6.0)", "pytest", "pytest-subtests", "pytest-xdist", "torch"] -docs = ["etils[all,dev]", "sphinx-apitree[ext]"] -eapp = ["absl-py", "etils[epy]", "simple_parsing"] -ecolab = ["etils[enp]", "etils[epy]", "etils[etree]", "jupyter", "mediapy", "numpy", "packaging", "protobuf"] -edc = ["etils[epy]"] -enp = ["etils[epy]", "numpy"] -epath = ["etils[epy]", "fsspec", "importlib_resources", "typing_extensions", "zipp"] -epath-gcs = ["etils[epath]", "gcsfs"] -epath-s3 = ["etils[epath]", "s3fs"] -epy = ["typing_extensions"] -etqdm = ["absl-py", "etils[epy]", "tqdm"] -etree = ["etils[array-types]", "etils[enp]", "etils[epy]", "etils[etqdm]"] -etree-dm = ["dm-tree", "etils[etree]"] -etree-jax = ["etils[etree]", "jax[cpu]"] -etree-tf = ["etils[etree]", "tensorflow"] -lazy-imports = ["etils[ecolab]"] - [[package]] name = "exceptiongroup" version = "1.2.0" @@ -846,13 +840,13 @@ numpy = ">=1.17.3" [[package]] name = "huggingface-hub" -version = "0.21.3" +version = "0.21.4" description = "Client library to download and publish models, datasets and other repos on the huggingface.co hub" optional = false python-versions = ">=3.8.0" files = [ - {file = "huggingface_hub-0.21.3-py3-none-any.whl", hash = "sha256:b183144336fdf2810a8c109822e0bb6ef1fd61c65da6fb60e8c3f658b7144016"}, - {file = "huggingface_hub-0.21.3.tar.gz", hash = "sha256:26a15b604e4fc7bad37c467b76456543ec849386cbca9cd7e1e135f53e500423"}, + {file = "huggingface_hub-0.21.4-py3-none-any.whl", hash = "sha256:df37c2c37fc6c82163cdd8a67ede261687d80d1e262526d6c0ce73b6b3630a7b"}, + {file = "huggingface_hub-0.21.4.tar.gz", hash = "sha256:e1f4968c93726565a80edf6dc309763c7b546d0cfe79aa221206034d50155531"}, ] [package.dependencies] @@ -971,37 +965,22 @@ setuptools = "*" [[package]] name = "importlib-metadata" -version = "7.0.1" +version = "7.0.2" description = "Read metadata from Python packages" optional = false python-versions = ">=3.8" files = [ - {file = "importlib_metadata-7.0.1-py3-none-any.whl", hash = "sha256:4805911c3a4ec7c3966410053e9ec6a1fecd629117df5adee56dfc9432a1081e"}, - {file = "importlib_metadata-7.0.1.tar.gz", hash = "sha256:f238736bb06590ae52ac1fab06a3a9ef1d8dce2b7a35b5ab329371d6c8f5d2cc"}, + {file = "importlib_metadata-7.0.2-py3-none-any.whl", hash = "sha256:f4bc4c0c070c490abf4ce96d715f68e95923320370efb66143df00199bb6c100"}, + {file = "importlib_metadata-7.0.2.tar.gz", hash = "sha256:198f568f3230878cb1b44fbd7975f87906c22336dba2e4a7f05278c281fbd792"}, ] [package.dependencies] zipp = ">=0.5" [package.extras] -docs = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (<7.2.5)", "sphinx (>=3.5)", "sphinx-lint"] +docs = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] perf = ["ipython"] -testing = ["flufl.flake8", "importlib-resources (>=1.3)", "packaging", "pyfakefs", "pytest (>=6)", "pytest-black (>=0.3.7)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-mypy (>=0.9.1)", "pytest-perf (>=0.9.2)", "pytest-ruff"] - -[[package]] -name = "importlib-resources" -version = "6.1.2" -description = "Read resources from Python packages" -optional = false -python-versions = ">=3.8" -files = [ - {file = "importlib_resources-6.1.2-py3-none-any.whl", hash = "sha256:9a0a862501dc38b68adebc82970140c9e4209fc99601782925178f8386339938"}, - {file = "importlib_resources-6.1.2.tar.gz", hash = "sha256:308abf8474e2dba5f867d279237cd4076482c3de7104a40b41426370e891549b"}, -] - -[package.extras] -docs = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (<7.2.5)", "sphinx (>=3.5)", "sphinx-lint"] -testing = ["pytest (>=6)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-mypy", "pytest-ruff (>=0.2.1)", "zipp (>=3.17)"] +testing = ["flufl.flake8", "importlib-resources (>=1.3)", "packaging", "pyfakefs", "pytest (>=6)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-mypy", "pytest-perf (>=0.9.2)", "pytest-ruff (>=0.2.1)"] [[package]] name = "iniconfig" @@ -1031,6 +1010,50 @@ MarkupSafe = ">=2.0" [package.extras] i18n = ["Babel (>=2.7)"] +[[package]] +name = "labmaze" +version = "1.0.6" +description = "LabMaze: DeepMind Lab's text maze generator." +optional = false +python-versions = "*" +files = [ + {file = "labmaze-1.0.6-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:b2ddef976dfd8d992b19cfa6c633f2eba7576d759c2082da534e3f727479a84a"}, + {file = "labmaze-1.0.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:157efaa93228c8ccce5cae337902dd652093e0fba9d3a0f6506e4bee272bb66f"}, + {file = "labmaze-1.0.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b3ce98b9541c5fe6a306e411e7d018121dd646f2c9978d763fad86f9f30c5f57"}, + {file = "labmaze-1.0.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4e6433bd49bc541791de8191040526fddfebb77151620eb04203453f43ee486a"}, + {file = "labmaze-1.0.6-cp310-cp310-win_amd64.whl", hash = "sha256:6a507fc35961f1b1479708e2716f65e0d0611cefb55f31a77be29ce2339b6fef"}, + {file = "labmaze-1.0.6-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:a0c2cb9dec971814ea9c5d7150af15fa3964482131fa969e0afb94bd224348af"}, + {file = "labmaze-1.0.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2c6ba9538d819543f4be448d36b4926a3881e53646a2b331ebb5a1f353047d05"}, + {file = "labmaze-1.0.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:70635d1cdb0147a02efb6b3f607a52cdc51723bc3dcc42717a0d4ef55fa0a987"}, + {file = "labmaze-1.0.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ff472793238bd9b6dabea8094594d6074ad3c111455de3afcae72f6c40c6817e"}, + {file = "labmaze-1.0.6-cp311-cp311-win_amd64.whl", hash = "sha256:2317e65e12fa3d1abecda7e0488dab15456cee8a2e717a586bfc8f02a91579e7"}, + {file = "labmaze-1.0.6-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:e36b6fadcd78f22057b597c1c77823e806a0987b3bdfbf850e14b6b5b502075e"}, + {file = "labmaze-1.0.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d1a4f8de29c2c3d7f14163759b69cd3f237093b85334c983619c1db5403a223b"}, + {file = "labmaze-1.0.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a394f8bb857fcaa2884b809d63e750841c2662a106cfe8c045f2112d201ac7d5"}, + {file = "labmaze-1.0.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0d17abb69d4dfc56183afb5c317e8b2eaca0587abb3aabd2326efd3143c81f4e"}, + {file = "labmaze-1.0.6-cp312-cp312-win_amd64.whl", hash = "sha256:5af997598cc46b1929d1c5a1febc32fd56c75874fe481a2a5982c65cee8450c9"}, + {file = "labmaze-1.0.6-cp37-cp37m-macosx_10_12_x86_64.whl", hash = "sha256:a4c5bc6e56baa55ce63b97569afec2f80cab0f6b952752a131e1f83eed190a53"}, + {file = "labmaze-1.0.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3955f24fe5f708e1e97495b4cfe284b70ae4fd51be5e17b75a6fc04ffbd67bca"}, + {file = "labmaze-1.0.6-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ed96ddc0bb8d66df36428c94db83949fd84a15867e8250763a4c5e3d82104c54"}, + {file = "labmaze-1.0.6-cp37-cp37m-win_amd64.whl", hash = "sha256:3bd0458a29e55aa09f146e28a168d2e00b8ccf19e2259a3f71154cfff3536b1d"}, + {file = "labmaze-1.0.6-cp38-cp38-macosx_10_12_x86_64.whl", hash = "sha256:33f5154edc83dff55a150e54b60c8582fdafc7ec45195049809cbcc01f5e8f34"}, + {file = "labmaze-1.0.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:0971055ef2a5f7d8517fdc42b67c057093698f1eb911f46faa7018867b73fcc9"}, + {file = "labmaze-1.0.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:de18d09680007302abf49111f3fe822d8435e4fbc4468b9ec07d50a78e267865"}, + {file = "labmaze-1.0.6-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f18126066db2218a52853c7dd490b4c3d8129fc22eb3a47eb23007524b911d53"}, + {file = "labmaze-1.0.6-cp38-cp38-win_amd64.whl", hash = "sha256:f9aef09a76877342bb4d634b7e05f43b038a49c4f34adfb8f1b8ac57c29472f2"}, + {file = "labmaze-1.0.6-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:5dd28899418f1b8b1c7d1e1b40a4593150a7cfa95ca91e23860b9785b82cc0ee"}, + {file = "labmaze-1.0.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:965569f37ee33090b4d4b3aa5aa7c9dcc4f62e2ae5d761e7f73ec76fc9d8aa96"}, + {file = "labmaze-1.0.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:05eccfa98c0e781bc9f939076ae600b2e25ca736e123f2a530606aedec3b531c"}, + {file = "labmaze-1.0.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bee8c94e0fb3fc2d8180214947245c1d74a3489349a9da90b868296e77a521e9"}, + {file = "labmaze-1.0.6-cp39-cp39-win_amd64.whl", hash = "sha256:d486e9ca3a335ad628e3bd48a09c42f1aa5f51040952ef0fe32507afedcd694b"}, + {file = "labmaze-1.0.6.tar.gz", hash = "sha256:2e8de7094042a77d6972f1965cf5c9e8f971f1b34d225752f343190a825ebe73"}, +] + +[package.dependencies] +absl-py = "*" +numpy = ">=1.8.0" +setuptools = "!=50.0.0" + [[package]] name = "lazy-loader" version = "0.3" @@ -1076,6 +1099,99 @@ files = [ {file = "llvmlite-0.42.0.tar.gz", hash = "sha256:f92b09243c0cc3f457da8b983f67bd8e1295d0f5b3746c7a1861d7a99403854a"}, ] +[[package]] +name = "lxml" +version = "5.1.0" +description = "Powerful and Pythonic XML processing library combining libxml2/libxslt with the ElementTree API." +optional = false +python-versions = ">=3.6" +files = [ + {file = "lxml-5.1.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:704f5572ff473a5f897745abebc6df40f22d4133c1e0a1f124e4f2bd3330ff7e"}, + {file = "lxml-5.1.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:9d3c0f8567ffe7502d969c2c1b809892dc793b5d0665f602aad19895f8d508da"}, + {file = "lxml-5.1.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:5fcfbebdb0c5d8d18b84118842f31965d59ee3e66996ac842e21f957eb76138c"}, + {file = "lxml-5.1.0-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2f37c6d7106a9d6f0708d4e164b707037b7380fcd0b04c5bd9cae1fb46a856fb"}, + {file = "lxml-5.1.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2befa20a13f1a75c751f47e00929fb3433d67eb9923c2c0b364de449121f447c"}, + {file = "lxml-5.1.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:22b7ee4c35f374e2c20337a95502057964d7e35b996b1c667b5c65c567d2252a"}, + {file = "lxml-5.1.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:bf8443781533b8d37b295016a4b53c1494fa9a03573c09ca5104550c138d5c05"}, + {file = "lxml-5.1.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:82bddf0e72cb2af3cbba7cec1d2fd11fda0de6be8f4492223d4a268713ef2147"}, + {file = "lxml-5.1.0-cp310-cp310-win32.whl", hash = "sha256:b66aa6357b265670bb574f050ffceefb98549c721cf28351b748be1ef9577d93"}, + {file = "lxml-5.1.0-cp310-cp310-win_amd64.whl", hash = "sha256:4946e7f59b7b6a9e27bef34422f645e9a368cb2be11bf1ef3cafc39a1f6ba68d"}, + {file = "lxml-5.1.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:14deca1460b4b0f6b01f1ddc9557704e8b365f55c63070463f6c18619ebf964f"}, + {file = "lxml-5.1.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:ed8c3d2cd329bf779b7ed38db176738f3f8be637bb395ce9629fc76f78afe3d4"}, + {file = "lxml-5.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:436a943c2900bb98123b06437cdd30580a61340fbdb7b28aaf345a459c19046a"}, + {file = "lxml-5.1.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:acb6b2f96f60f70e7f34efe0c3ea34ca63f19ca63ce90019c6cbca6b676e81fa"}, + {file = "lxml-5.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:af8920ce4a55ff41167ddbc20077f5698c2e710ad3353d32a07d3264f3a2021e"}, + {file = "lxml-5.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7cfced4a069003d8913408e10ca8ed092c49a7f6cefee9bb74b6b3e860683b45"}, + {file = "lxml-5.1.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:9e5ac3437746189a9b4121db2a7b86056ac8786b12e88838696899328fc44bb2"}, + {file = "lxml-5.1.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:f4c9bda132ad108b387c33fabfea47866af87f4ea6ffb79418004f0521e63204"}, + {file = "lxml-5.1.0-cp311-cp311-win32.whl", hash = "sha256:bc64d1b1dab08f679fb89c368f4c05693f58a9faf744c4d390d7ed1d8223869b"}, + {file = "lxml-5.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:a5ab722ae5a873d8dcee1f5f45ddd93c34210aed44ff2dc643b5025981908cda"}, + {file = "lxml-5.1.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:9aa543980ab1fbf1720969af1d99095a548ea42e00361e727c58a40832439114"}, + {file = "lxml-5.1.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:6f11b77ec0979f7e4dc5ae081325a2946f1fe424148d3945f943ceaede98adb8"}, + {file = "lxml-5.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:a36c506e5f8aeb40680491d39ed94670487ce6614b9d27cabe45d94cd5d63e1e"}, + {file = "lxml-5.1.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f643ffd2669ffd4b5a3e9b41c909b72b2a1d5e4915da90a77e119b8d48ce867a"}, + {file = "lxml-5.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:16dd953fb719f0ffc5bc067428fc9e88f599e15723a85618c45847c96f11f431"}, + {file = "lxml-5.1.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:16018f7099245157564d7148165132c70adb272fb5a17c048ba70d9cc542a1a1"}, + {file = "lxml-5.1.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:82cd34f1081ae4ea2ede3d52f71b7be313756e99b4b5f829f89b12da552d3aa3"}, + {file = "lxml-5.1.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:19a1bc898ae9f06bccb7c3e1dfd73897ecbbd2c96afe9095a6026016e5ca97b8"}, + {file = "lxml-5.1.0-cp312-cp312-win32.whl", hash = "sha256:13521a321a25c641b9ea127ef478b580b5ec82aa2e9fc076c86169d161798b01"}, + {file = "lxml-5.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:1ad17c20e3666c035db502c78b86e58ff6b5991906e55bdbef94977700c72623"}, + {file = "lxml-5.1.0-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:24ef5a4631c0b6cceaf2dbca21687e29725b7c4e171f33a8f8ce23c12558ded1"}, + {file = "lxml-5.1.0-cp36-cp36m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8d2900b7f5318bc7ad8631d3d40190b95ef2aa8cc59473b73b294e4a55e9f30f"}, + {file = "lxml-5.1.0-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:601f4a75797d7a770daed8b42b97cd1bb1ba18bd51a9382077a6a247a12aa38d"}, + {file = "lxml-5.1.0-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b4b68c961b5cc402cbd99cca5eb2547e46ce77260eb705f4d117fd9c3f932b95"}, + {file = "lxml-5.1.0-cp36-cp36m-musllinux_1_1_aarch64.whl", hash = "sha256:afd825e30f8d1f521713a5669b63657bcfe5980a916c95855060048b88e1adb7"}, + {file = "lxml-5.1.0-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:262bc5f512a66b527d026518507e78c2f9c2bd9eb5c8aeeb9f0eb43fcb69dc67"}, + {file = "lxml-5.1.0-cp36-cp36m-win32.whl", hash = "sha256:e856c1c7255c739434489ec9c8aa9cdf5179785d10ff20add308b5d673bed5cd"}, + {file = "lxml-5.1.0-cp36-cp36m-win_amd64.whl", hash = "sha256:c7257171bb8d4432fe9d6fdde4d55fdbe663a63636a17f7f9aaba9bcb3153ad7"}, + {file = "lxml-5.1.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:b9e240ae0ba96477682aa87899d94ddec1cc7926f9df29b1dd57b39e797d5ab5"}, + {file = "lxml-5.1.0-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a96f02ba1bcd330807fc060ed91d1f7a20853da6dd449e5da4b09bfcc08fdcf5"}, + {file = "lxml-5.1.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3e3898ae2b58eeafedfe99e542a17859017d72d7f6a63de0f04f99c2cb125936"}, + {file = "lxml-5.1.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:61c5a7edbd7c695e54fca029ceb351fc45cd8860119a0f83e48be44e1c464862"}, + {file = "lxml-5.1.0-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:3aeca824b38ca78d9ee2ab82bd9883083d0492d9d17df065ba3b94e88e4d7ee6"}, + {file = "lxml-5.1.0-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:8f52fe6859b9db71ee609b0c0a70fea5f1e71c3462ecf144ca800d3f434f0764"}, + {file = "lxml-5.1.0-cp37-cp37m-win32.whl", hash = "sha256:d42e3a3fc18acc88b838efded0e6ec3edf3e328a58c68fbd36a7263a874906c8"}, + {file = "lxml-5.1.0-cp37-cp37m-win_amd64.whl", hash = "sha256:eac68f96539b32fce2c9b47eb7c25bb2582bdaf1bbb360d25f564ee9e04c542b"}, + {file = "lxml-5.1.0-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:ae15347a88cf8af0949a9872b57a320d2605ae069bcdf047677318bc0bba45b1"}, + {file = "lxml-5.1.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:c26aab6ea9c54d3bed716b8851c8bfc40cb249b8e9880e250d1eddde9f709bf5"}, + {file = "lxml-5.1.0-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:342e95bddec3a698ac24378d61996b3ee5ba9acfeb253986002ac53c9a5f6f84"}, + {file = "lxml-5.1.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:725e171e0b99a66ec8605ac77fa12239dbe061482ac854d25720e2294652eeaa"}, + {file = "lxml-5.1.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3d184e0d5c918cff04cdde9dbdf9600e960161d773666958c9d7b565ccc60c45"}, + {file = "lxml-5.1.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:98f3f020a2b736566c707c8e034945c02aa94e124c24f77ca097c446f81b01f1"}, + {file = "lxml-5.1.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:6d48fc57e7c1e3df57be5ae8614bab6d4e7b60f65c5457915c26892c41afc59e"}, + {file = "lxml-5.1.0-cp38-cp38-win32.whl", hash = "sha256:7ec465e6549ed97e9f1e5ed51c657c9ede767bc1c11552f7f4d022c4df4a977a"}, + {file = "lxml-5.1.0-cp38-cp38-win_amd64.whl", hash = "sha256:b21b4031b53d25b0858d4e124f2f9131ffc1530431c6d1321805c90da78388d1"}, + {file = "lxml-5.1.0-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:52427a7eadc98f9e62cb1368a5079ae826f94f05755d2d567d93ee1bc3ceb354"}, + {file = "lxml-5.1.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:6a2a2c724d97c1eb8cf966b16ca2915566a4904b9aad2ed9a09c748ffe14f969"}, + {file = "lxml-5.1.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:843b9c835580d52828d8f69ea4302537337a21e6b4f1ec711a52241ba4a824f3"}, + {file = "lxml-5.1.0-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9b99f564659cfa704a2dd82d0684207b1aadf7d02d33e54845f9fc78e06b7581"}, + {file = "lxml-5.1.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4f8b0c78e7aac24979ef09b7f50da871c2de2def043d468c4b41f512d831e912"}, + {file = "lxml-5.1.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9bcf86dfc8ff3e992fed847c077bd875d9e0ba2fa25d859c3a0f0f76f07f0c8d"}, + {file = "lxml-5.1.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:49a9b4af45e8b925e1cd6f3b15bbba2c81e7dba6dce170c677c9cda547411e14"}, + {file = "lxml-5.1.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:280f3edf15c2a967d923bcfb1f8f15337ad36f93525828b40a0f9d6c2ad24890"}, + {file = "lxml-5.1.0-cp39-cp39-win32.whl", hash = "sha256:ed7326563024b6e91fef6b6c7a1a2ff0a71b97793ac33dbbcf38f6005e51ff6e"}, + {file = "lxml-5.1.0-cp39-cp39-win_amd64.whl", hash = "sha256:8d7b4beebb178e9183138f552238f7e6613162a42164233e2bda00cb3afac58f"}, + {file = "lxml-5.1.0-pp310-pypy310_pp73-macosx_10_9_x86_64.whl", hash = "sha256:9bd0ae7cc2b85320abd5e0abad5ccee5564ed5f0cc90245d2f9a8ef330a8deae"}, + {file = "lxml-5.1.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d8c1d679df4361408b628f42b26a5d62bd3e9ba7f0c0e7969f925021554755aa"}, + {file = "lxml-5.1.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:2ad3a8ce9e8a767131061a22cd28fdffa3cd2dc193f399ff7b81777f3520e372"}, + {file = "lxml-5.1.0-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:304128394c9c22b6569eba2a6d98392b56fbdfbad58f83ea702530be80d0f9df"}, + {file = "lxml-5.1.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d74fcaf87132ffc0447b3c685a9f862ffb5b43e70ea6beec2fb8057d5d2a1fea"}, + {file = "lxml-5.1.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:8cf5877f7ed384dabfdcc37922c3191bf27e55b498fecece9fd5c2c7aaa34c33"}, + {file = "lxml-5.1.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:877efb968c3d7eb2dad540b6cabf2f1d3c0fbf4b2d309a3c141f79c7e0061324"}, + {file = "lxml-5.1.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3f14a4fb1c1c402a22e6a341a24c1341b4a3def81b41cd354386dcb795f83897"}, + {file = "lxml-5.1.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:25663d6e99659544ee8fe1b89b1a8c0aaa5e34b103fab124b17fa958c4a324a6"}, + {file = "lxml-5.1.0-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:8b9f19df998761babaa7f09e6bc169294eefafd6149aaa272081cbddc7ba4ca3"}, + {file = "lxml-5.1.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5e53d7e6a98b64fe54775d23a7c669763451340c3d44ad5e3a3b48a1efbdc96f"}, + {file = "lxml-5.1.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:c3cd1fc1dc7c376c54440aeaaa0dcc803d2126732ff5c6b68ccd619f2e64be4f"}, + {file = "lxml-5.1.0.tar.gz", hash = "sha256:3eea6ed6e6c918e468e693c41ef07f3c3acc310b70ddd9cc72d9ef84bc9564ca"}, +] + +[package.extras] +cssselect = ["cssselect (>=0.7)"] +html5 = ["html5lib"] +htmlsoup = ["BeautifulSoup4"] +source = ["Cython (>=3.0.7)"] + [[package]] name = "markupsafe" version = "2.1.5" @@ -1188,42 +1304,40 @@ tests = ["pytest (>=4.6)"] [[package]] name = "mujoco" -version = "3.1.2" +version = "2.3.7" description = "MuJoCo Physics Simulator" optional = false python-versions = ">=3.8" files = [ - {file = "mujoco-3.1.2-cp310-cp310-macosx_10_16_x86_64.whl", hash = "sha256:fe6b3542695a5363f348ee45625b3492734f29cdc9f493ca25eae719f974370e"}, - {file = "mujoco-3.1.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:f07e2d1f01f1401f1a503187016f8c017d9402618c659e1482243640a1e11288"}, - {file = "mujoco-3.1.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:93863eccc9d77d96ce62dda2a6f61cbd880379e8d774f802568d64b9613fce39"}, - {file = "mujoco-3.1.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3586c642390c16fef58b01a86071cec6814c471586e2f4115c3733c4aec64fb7"}, - {file = "mujoco-3.1.2-cp310-cp310-win_amd64.whl", hash = "sha256:0da77394c664945b78f199c627b609fe091ec0c4641b9d8f713637344a17821a"}, - {file = "mujoco-3.1.2-cp311-cp311-macosx_10_16_x86_64.whl", hash = "sha256:b6f12904d0478c191e4770ecf9006e20953f0488a2411a8ddc62592721c136dc"}, - {file = "mujoco-3.1.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f69b8d42b50c10f8d12df4948fc9d4dd6706841e7b163c1d7ce83448965acb1c"}, - {file = "mujoco-3.1.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:10119e39b1f45fb76b18bea242fea1d6ccf4b2285f8bd5e2cb1e2cbdeb69bdcd"}, - {file = "mujoco-3.1.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3a65868506dd45dddfe7be84857e57b49bc102334fc0439aa848a4d4d285d89b"}, - {file = "mujoco-3.1.2-cp311-cp311-win_amd64.whl", hash = "sha256:92bc73972e39539f23a05bb411c45f9be17191fe01171ac15ffafed381ee4366"}, - {file = "mujoco-3.1.2-cp312-cp312-macosx_10_16_x86_64.whl", hash = "sha256:835d6b64ca4dc2f6a83291275fd48bd83edc888039d247958bf5b2c759db4340"}, - {file = "mujoco-3.1.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2ce94ca3cf14fc519981674c5b85f1055356dcdcd63bbc0ec6c340084438f27f"}, - {file = "mujoco-3.1.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:250d9de4bd0d31fa4165faf01a1f838c429434f1263faacd95b977580f24eae7"}, - {file = "mujoco-3.1.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6ea009d10bbf0aba9bc835f051d25f07a2c3edbaa06627ac2348766a1f3760b9"}, - {file = "mujoco-3.1.2-cp312-cp312-win_amd64.whl", hash = "sha256:a0460d2ebdad4926f48b8c774da473e011c3b3afd0ccb6b6be1087b788c34011"}, - {file = "mujoco-3.1.2-cp38-cp38-macosx_10_16_x86_64.whl", hash = "sha256:4ca7cae89e258a338e02229edcf8f177b459ac5e9f859ffffa07fc2c9fcfb6aa"}, - {file = "mujoco-3.1.2-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:33b4fe9b5f891b29ef0fc2b0b975bc3a8a4b87774eecaf4364a83ddc6a7762ba"}, - {file = "mujoco-3.1.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6ed230980f33bafaf1fa8b32ef25b82b069a245de15ee6ce7127e7e054cfad16"}, - {file = "mujoco-3.1.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:41cc610ac40f325c9d49d9885ac6cb61822ed938f6c23cb183b261a7a28472ca"}, - {file = "mujoco-3.1.2-cp38-cp38-win_amd64.whl", hash = "sha256:90a172b904a6ca8e6a1be80ab7c393aaff7592843a2a6853a4f97a9204031c41"}, - {file = "mujoco-3.1.2-cp39-cp39-macosx_10_16_x86_64.whl", hash = "sha256:93201291a0c5b573b4cbb19a6b08c99673f9fba167f402174eae5ffa23066d24"}, - {file = "mujoco-3.1.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:0398985bb28c2686cdeeaf4ded46e602a49ec12115ac77474144ca940e5261c5"}, - {file = "mujoco-3.1.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d2e76b5cb07ab3088c81966ac774d573df027fa5f4e78c20953a547528a2a698"}, - {file = "mujoco-3.1.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cd5c3f4ae858e812cb3f03332693bcdc343b2bce55b164523acf52dea2736c9e"}, - {file = "mujoco-3.1.2-cp39-cp39-win_amd64.whl", hash = "sha256:ca25ff2646b06609526ef8681c0e123cd854a53c9ff23cb91dd5058a2794dab4"}, - {file = "mujoco-3.1.2.tar.gz", hash = "sha256:53530bc1a91903f3fd4b1e99818cc38fbd9911700db29b2c9fc839f23bfacbb8"}, + {file = "mujoco-2.3.7-cp310-cp310-macosx_10_16_x86_64.whl", hash = "sha256:e8714a5ff6a1561b364b7b4648d4c0c8d13e751874cf7401c309b9d23fa9598b"}, + {file = "mujoco-2.3.7-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:a934315f858a4e0c4b90a682fde519471cfdd7baa64435179da8cd20d4ae3f99"}, + {file = "mujoco-2.3.7-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:36513024330f88b5f9a43558efef5692b33599bffd5141029b690a27918ffcbe"}, + {file = "mujoco-2.3.7-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6d4eede8ba8210fbd3d3cd1dbf69e24dd1541aa74c5af5b8adbbbf65504b6dba"}, + {file = "mujoco-2.3.7-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ab85fafc9d5a091c712947573b7e694512d283876bf7f33ae3f8daad3a20c0db"}, + {file = "mujoco-2.3.7-cp310-cp310-win_amd64.whl", hash = "sha256:f8b7e13fef8c813d91b78f975ed0815157692777907ffa4b4be53a4edb75019b"}, + {file = "mujoco-2.3.7-cp311-cp311-macosx_10_16_x86_64.whl", hash = "sha256:779520216f72a8e370e3f0cdd71b45c3b7384c63331a3189194c930a3e7cff5c"}, + {file = "mujoco-2.3.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9d4018053879016282d27ab7a91e292c72d44efb5a88553feacfe5b843dde103"}, + {file = "mujoco-2.3.7-cp311-cp311-macosx_11_0_x86_64.whl", hash = "sha256:3149b16b8122ee62642474bfd2871064e8edc40235471cf5d84be3569afc0312"}, + {file = "mujoco-2.3.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c08660a8d52ef3efde76095f0991e807703a950c1e882d2bcd984b9a846626f7"}, + {file = "mujoco-2.3.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:426af8965f8636d94a0f75740c3024a62b3e585020ee817ef5208ec844a1ad94"}, + {file = "mujoco-2.3.7-cp311-cp311-win_amd64.whl", hash = "sha256:215415a8e98a4b50625beae859079d5e0810b2039e50420f0ba81763c34abb59"}, + {file = "mujoco-2.3.7-cp38-cp38-macosx_10_16_x86_64.whl", hash = "sha256:8b78d14f4c60cea3c58e046bd4de453fb5b9b33aca6a25fc91d39a53f3a5342a"}, + {file = "mujoco-2.3.7-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:5c6f5a51d6f537a4bf294cf73816f3a6384573f8f10a5452b044df2771412a96"}, + {file = "mujoco-2.3.7-cp38-cp38-macosx_11_0_x86_64.whl", hash = "sha256:ea8911e6047f92d7d775701f37e4c093971b6def3160f01d0b6926e29a7e962e"}, + {file = "mujoco-2.3.7-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7473a3de4dd1a8762d569ffb139196b4c5e7eca27d256df97b6cd4c66d2a09b2"}, + {file = "mujoco-2.3.7-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40e7e2d8f93d2495ec74efec84e5118ecc6e1d85157a844789c73c9ac9a4e28e"}, + {file = "mujoco-2.3.7-cp38-cp38-win_amd64.whl", hash = "sha256:720bc228a2023b3b0ed6af78f5b0f8ea36867be321d473321555c57dbf6e4e5b"}, + {file = "mujoco-2.3.7-cp39-cp39-macosx_10_16_x86_64.whl", hash = "sha256:855e79686366442aa410246043b44f7d842d3900d68fe7e37feb42147db9d707"}, + {file = "mujoco-2.3.7-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:98947f4a742d34d36f3c3f83e9167025bb0414bbaa4bd859b0673bdab9959963"}, + {file = "mujoco-2.3.7-cp39-cp39-macosx_11_0_x86_64.whl", hash = "sha256:d42818f2ee5d1632dbce31d136ed5ff868db54b04e4e9aca0c5a3ac329f8a90f"}, + {file = "mujoco-2.3.7-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9237e1ba14bced9449c31199e6d5be49547f3a4c99bc83b196af7ca45fd73b83"}, + {file = "mujoco-2.3.7-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:39b728ea638245b150e2650c5433e6952e0ed3798c63e47e264574270caea2a3"}, + {file = "mujoco-2.3.7-cp39-cp39-win_amd64.whl", hash = "sha256:9c721a5042b99d948d5f0296a534bcce3f142c777c4d7642f503a539513f3912"}, + {file = "mujoco-2.3.7.tar.gz", hash = "sha256:422041f1ce37c6d151fbced1048df626837e94fe3cd9f813585907046336a7d0"}, ] [package.dependencies] absl-py = "*" -etils = {version = "*", extras = ["epath"]} glfw = "*" numpy = "*" pyopengl = "*" @@ -1519,13 +1633,13 @@ files = [ [[package]] name = "nvidia-nvjitlink-cu12" -version = "12.3.101" +version = "12.4.99" description = "Nvidia JIT LTO Library" optional = false python-versions = ">=3" files = [ - {file = "nvidia_nvjitlink_cu12-12.3.101-py3-none-manylinux1_x86_64.whl", hash = "sha256:64335a8088e2b9d196ae8665430bc6a2b7e6ef2eb877a9c735c804bd4ff6467c"}, - {file = "nvidia_nvjitlink_cu12-12.3.101-py3-none-win_amd64.whl", hash = "sha256:1b2e317e437433753530792f13eece58f0aec21a2b05903be7bffe58a606cbd1"}, + {file = "nvidia_nvjitlink_cu12-12.4.99-py3-none-manylinux2014_x86_64.whl", hash = "sha256:c6428836d20fe7e327191c175791d38570e10762edc588fb46749217cd444c74"}, + {file = "nvidia_nvjitlink_cu12-12.4.99-py3-none-win_amd64.whl", hash = "sha256:991905ffa2144cb603d8ca7962d75c35334ae82bf92820b6ba78157277da1ad2"}, ] [[package]] @@ -1580,13 +1694,13 @@ numpy = [ [[package]] name = "packaging" -version = "23.2" +version = "24.0" description = "Core utilities for Python packages" optional = false python-versions = ">=3.7" files = [ - {file = "packaging-23.2-py3-none-any.whl", hash = "sha256:8c491190033a9af7e1d931d0b5dacc2ef47509b34dd0de67ed209b5203fc88c7"}, - {file = "packaging-23.2.tar.gz", hash = "sha256:048fb0e9405036518eaaf48a55953c750c11e1a1b68e0dd1a9d62ed0c092cfc5"}, + {file = "packaging-24.0-py3-none-any.whl", hash = "sha256:2ddfb553fdf02fb784c234c7ba6ccc288296ceabec964ad2eae3777778130bc5"}, + {file = "packaging-24.0.tar.gz", hash = "sha256:eb82c5e3e56209074766e6885bb04b8c38a0c015d0a30036ebe7ece34c9989e9"}, ] [[package]] @@ -2016,6 +2130,20 @@ files = [ {file = "PyOpenGL-3.1.7.tar.gz", hash = "sha256:eef31a3888e6984fd4d8e6c9961b184c9813ca82604d37fe3da80eb000a76c86"}, ] +[[package]] +name = "pyparsing" +version = "3.1.2" +description = "pyparsing module - Classes and methods to define and execute parsing grammars" +optional = false +python-versions = ">=3.6.8" +files = [ + {file = "pyparsing-3.1.2-py3-none-any.whl", hash = "sha256:f9db75911801ed778fe61bb643079ff86601aca99fcae6345aa67292038fb742"}, + {file = "pyparsing-3.1.2.tar.gz", hash = "sha256:a1bac0ce561155ecc3ed78ca94d3c9378656ad4c94c1270de543f621420f94ad"}, +] + +[package.extras] +diagrams = ["jinja2", "railroad-diagrams"] + [[package]] name = "pysocks" version = "1.7.1" @@ -2030,13 +2158,13 @@ files = [ [[package]] name = "pytest" -version = "8.1.0" +version = "8.1.1" description = "pytest: simple powerful testing with Python" optional = false python-versions = ">=3.8" files = [ - {file = "pytest-8.1.0-py3-none-any.whl", hash = "sha256:ee32db7af8de4629a455806befa90559f307424c07b8413ccfc30bf5b221dd7e"}, - {file = "pytest-8.1.0.tar.gz", hash = "sha256:f8fa04ab8f98d185113ae60ea6d79c22f8143b14bc1caeced44a0ab844928323"}, + {file = "pytest-8.1.1-py3-none-any.whl", hash = "sha256:2a8386cfc11fa9d2c50ee7b2a57e7d898ef90470a7a34c4b949ff59662bb78b7"}, + {file = "pytest-8.1.1.tar.gz", hash = "sha256:ac978141a75948948817d360297b7aae0fcb9d6ff6bc9ec6d514b85d5a65c044"}, ] [package.dependencies] @@ -2052,13 +2180,13 @@ testing = ["argcomplete", "attrs (>=19.2)", "hypothesis (>=3.56)", "mock", "pygm [[package]] name = "python-dateutil" -version = "2.8.2" +version = "2.9.0.post0" description = "Extensions to the standard Python datetime module" optional = false python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,>=2.7" files = [ - {file = "python-dateutil-2.8.2.tar.gz", hash = "sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86"}, - {file = "python_dateutil-2.8.2-py2.py3-none-any.whl", hash = "sha256:961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9"}, + {file = "python-dateutil-2.9.0.post0.tar.gz", hash = "sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3"}, + {file = "python_dateutil-2.9.0.post0-py2.py3-none-any.whl", hash = "sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427"}, ] [package.dependencies] @@ -2483,13 +2611,13 @@ test = ["asv", "gmpy2", "hypothesis", "mpmath", "pooch", "pytest", "pytest-cov", [[package]] name = "sentry-sdk" -version = "1.40.6" +version = "1.41.0" description = "Python client for Sentry (https://sentry.io)" optional = false python-versions = "*" files = [ - {file = "sentry-sdk-1.40.6.tar.gz", hash = "sha256:f143f3fb4bb57c90abef6e2ad06b5f6f02b2ca13e4060ec5c0549c7a9ccce3fa"}, - {file = "sentry_sdk-1.40.6-py2.py3-none-any.whl", hash = "sha256:becda09660df63e55f307570e9817c664392655a7328bbc414b507e9cb874c67"}, + {file = "sentry-sdk-1.41.0.tar.gz", hash = "sha256:4f2d6c43c07925d8cd10dfbd0970ea7cb784f70e79523cca9dbcd72df38e5a46"}, + {file = "sentry_sdk-1.41.0-py2.py3-none-any.whl", hash = "sha256:be4f8f4b29a80b6a3b71f0f31487beb9e296391da20af8504498a328befed53f"}, ] [package.dependencies] @@ -2515,7 +2643,7 @@ huey = ["huey (>=2)"] loguru = ["loguru (>=0.5)"] opentelemetry = ["opentelemetry-distro (>=0.35b0)"] opentelemetry-experimental = ["opentelemetry-distro (>=0.40b0,<1.0)", "opentelemetry-instrumentation-aiohttp-client (>=0.40b0,<1.0)", "opentelemetry-instrumentation-django (>=0.40b0,<1.0)", "opentelemetry-instrumentation-fastapi (>=0.40b0,<1.0)", "opentelemetry-instrumentation-flask (>=0.40b0,<1.0)", "opentelemetry-instrumentation-requests (>=0.40b0,<1.0)", "opentelemetry-instrumentation-sqlite3 (>=0.40b0,<1.0)", "opentelemetry-instrumentation-urllib (>=0.40b0,<1.0)"] -pure-eval = ["asttokens", "executing", "pure_eval"] +pure-eval = ["asttokens", "executing", "pure-eval"] pymongo = ["pymongo (>=3.1)"] pyspark = ["pyspark (>=2.4.4)"] quart = ["blinker (>=1.1)", "quart (>=0.16.1)"] @@ -2769,7 +2897,7 @@ tests = ["pytest", "pytest-benchmark", "pytest-instafail", "pytest-rerunfailures type = "git" url = "https://github.com/pytorch/tensordict" reference = "HEAD" -resolved_reference = "551331d83e2979dd4505db1f49895740e6e5c95f" +resolved_reference = "ed22554d6860731610df784b2f5d09f31d3dbc7a" [[package]] name = "termcolor" @@ -2888,13 +3016,13 @@ tensordict = ">=0.4.0" torch = ">=2.1.0" [package.extras] -all = ["ale-py", "atari-py", "dm-control", "git", "gym", "gym[accept-rom-license]", "gymnasium", "h5py", "huggingface-hub", "hydra-core (>=1.1)", "hydra-submitit-launcher", "minari", "moviepy", "mujoco", "pandas", "pettingzoo (>=1.24.1)", "pillow", "pygame", "pytest", "pytest-instafail", "pyyaml", "requests", "scikit-learn", "scipy", "tensorboard", "torchsnapshot", "torchvision", "tqdm", "vmas (>=1.2.10)", "wandb"] +all = ["ale-py", "atari-py", "dm_control", "git", "gym", "gym[accept-rom-license]", "gymnasium", "h5py", "huggingface_hub", "hydra-core (>=1.1)", "hydra-submitit-launcher", "minari", "moviepy", "mujoco", "pandas", "pettingzoo (>=1.24.1)", "pillow", "pygame", "pytest", "pytest-instafail", "pyyaml", "requests", "scikit-learn", "scipy", "tensorboard", "torchsnapshot", "torchvision", "tqdm", "vmas (>=1.2.10)", "wandb"] atari = ["ale-py", "atari-py", "gym", "gym[accept-rom-license]", "pygame"] checkpointing = ["torchsnapshot"] -dm-control = ["dm-control"] +dm-control = ["dm_control"] gym-continuous = ["gymnasium", "mujoco"] marl = ["pettingzoo (>=1.24.1)", "vmas (>=1.2.10)"] -offline-data = ["h5py", "huggingface-hub", "minari", "pandas", "pillow", "requests", "scikit-learn", "torchvision", "tqdm"] +offline-data = ["h5py", "huggingface_hub", "minari", "pandas", "pillow", "requests", "scikit-learn", "torchvision", "tqdm"] rendering = ["moviepy"] tests = ["pytest", "pytest-instafail", "pyyaml", "scipy"] utils = ["git", "hydra-core (>=1.1)", "hydra-submitit-launcher", "tensorboard", "tqdm", "wandb"] @@ -3051,13 +3179,13 @@ test = ["covdefaults (>=2.3)", "coverage (>=7.2.7)", "coverage-enable-subprocess [[package]] name = "wandb" -version = "0.16.3" +version = "0.16.4" description = "A CLI and library for interacting with the Weights & Biases API." optional = false python-versions = ">=3.7" files = [ - {file = "wandb-0.16.3-py3-none-any.whl", hash = "sha256:b8907ddd775c27dc6c12687386a86b5d6acf291060f9ae680bbc61cc8fc03237"}, - {file = "wandb-0.16.3.tar.gz", hash = "sha256:d789acda32053b18b7a160d0595837e45a3c8a79d25e1fe1f051875303f480ec"}, + {file = "wandb-0.16.4-py3-none-any.whl", hash = "sha256:bb9eb5aa2c2c85e11c76040c4271366f54d4975167aa6320ba86c3f2d97fe5fa"}, + {file = "wandb-0.16.4.tar.gz", hash = "sha256:8752c67d1347a4c29777e64dc1e1a742a66c5ecde03aebadf2b0d62183fa307c"}, ] [package.dependencies] @@ -3078,8 +3206,9 @@ async = ["httpx (>=0.23.0)"] aws = ["boto3"] azure = ["azure-identity", "azure-storage-blob"] gcp = ["google-cloud-storage"] +importers = ["filelock", "mlflow", "polars", "rich", "tenacity"] kubeflow = ["google-cloud-storage", "kubernetes", "minio", "sh"] -launch = ["PyYAML (>=6.0.0)", "awscli", "azure-containerregistry", "azure-identity", "azure-storage-blob", "boto3", "botocore", "chardet", "google-auth", "google-cloud-aiplatform", "google-cloud-artifact-registry", "google-cloud-compute", "google-cloud-storage", "iso8601", "kubernetes", "kubernetes-asyncio", "nbconvert", "nbformat", "optuna", "pydantic", "typing-extensions"] +launch = ["PyYAML (>=6.0.0)", "awscli", "azure-containerregistry", "azure-identity", "azure-storage-blob", "boto3", "botocore", "chardet", "google-auth", "google-cloud-aiplatform", "google-cloud-artifact-registry", "google-cloud-compute", "google-cloud-storage", "iso8601", "kubernetes", "kubernetes-asyncio", "nbconvert", "nbformat", "optuna", "pydantic", "tomli", "typing-extensions"] media = ["bokeh", "moviepy", "numpy", "pillow", "plotly (>=5.18.0)", "rdkit-pypi", "soundfile"] models = ["cloudpickle"] perf = ["orjson"] @@ -3088,13 +3217,13 @@ sweeps = ["sweeps (>=0.2.0)"] [[package]] name = "zarr" -version = "2.17.0" +version = "2.17.1" description = "An implementation of chunked, compressed, N-dimensional arrays for Python" optional = false python-versions = ">=3.9" files = [ - {file = "zarr-2.17.0-py3-none-any.whl", hash = "sha256:d287cb61019c4a0a0f386f76eeaa7f0b1160b1cb90cf96173a4b6cbc135df6e1"}, - {file = "zarr-2.17.0.tar.gz", hash = "sha256:6390a2b8af31babaab4c963efc45bf1da7f9500c9aafac193f84cf019a7c66b0"}, + {file = "zarr-2.17.1-py3-none-any.whl", hash = "sha256:e25df2741a6e92645f3890f30f3136d5b57a0f8f831094b024bbcab5f2797bc7"}, + {file = "zarr-2.17.1.tar.gz", hash = "sha256:564b3aa072122546fe69a0fa21736f466b20fad41754334b62619f088ce46261"}, ] [package.dependencies] @@ -3125,4 +3254,4 @@ testing = ["big-O", "jaraco.functools", "jaraco.itertools", "more-itertools", "p [metadata] lock-version = "2.0" python-versions = "^3.10" -content-hash = "c4d83579aed1c8c2e54cad7c8ec81b95a09ab8faff74fc9a4cb20bd00e4ddec6" +content-hash = "3d82309a7b2388d774b56ceb6f6906ef0732d8cedda0d76cc84a30e239949be8" diff --git a/pyproject.toml b/pyproject.toml index 398f63ef5..85af7f825 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -42,13 +42,14 @@ mpmath = "^1.3.0" torch = "^2.2.1" tensordict = {git = "https://github.com/pytorch/tensordict"} torchrl = {git = "https://github.com/pytorch/rl", rev = "13bef426dcfa5887c6e5034a6e9697993fa92c37"} -mujoco = "^3.1.2" +mujoco = "2.3.7" mujoco-py = "^2.1.2.14" gym = "^0.26.2" opencv-python = "^4.9.0.80" diffusers = "^0.26.3" torchvision = "^0.17.1" h5py = "^3.10.0" +dm-control = "1.0.14" [tool.poetry.group.dev.dependencies] diff --git a/sbatch.sh b/sbatch.sh index da52c472a..cb5b285af 100644 --- a/sbatch.sh +++ b/sbatch.sh @@ -17,6 +17,7 @@ apptainer exec --nv \ ~/apptainer/nvidia_cuda:12.2.2-devel-ubuntu22.04.sif $SHELL source ~/.bashrc -conda activate fowm +#conda activate fowm +conda activate lerobot srun $CMD diff --git a/tests/data/aloha_sim_insertion_human/action.memmap b/tests/data/aloha_sim_insertion_human/action.memmap new file mode 100644 index 000000000..f64b29898 --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/action.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d789deddb081a9f4b626342391de8f48949d38fb5fdead87b5c0737b46c0877a +size 2800 diff --git a/tests/data/aloha_sim_insertion_human/episode.memmap b/tests/data/aloha_sim_insertion_human/episode.memmap new file mode 100644 index 000000000..af9fb07fd --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/episode.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7a12e561363385e9dfeeab326368731c030ed4b374e7f5897ac819159d2884c5 +size 400 diff --git a/tests/data/aloha_sim_insertion_human/frame_id.memmap b/tests/data/aloha_sim_insertion_human/frame_id.memmap new file mode 100644 index 000000000..dc2f585cf --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/frame_id.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c202d9cfc7858fd49d522047e16948359bbbb2eda2d3825d552e45a78d5f8585 +size 400 diff --git a/tests/data/aloha_sim_insertion_human/meta.json b/tests/data/aloha_sim_insertion_human/meta.json new file mode 100644 index 000000000..2a0cf0a25 --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/meta.json @@ -0,0 +1 @@ +{"action": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "episode": {"device": "cpu", "shape": [50], "dtype": "torch.int64"}, "frame_id": {"device": "cpu", "shape": [50], "dtype": "torch.int64"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_human/next/done.memmap b/tests/data/aloha_sim_insertion_human/next/done.memmap new file mode 100644 index 000000000..44fd709f9 --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/next/done.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cc2786e1f9910a9d811400edcddaf7075195f7a16b216dcbefba3bc7c4f2ae51 +size 50 diff --git a/tests/data/aloha_sim_insertion_human/next/meta.json b/tests/data/aloha_sim_insertion_human/next/meta.json new file mode 100644 index 000000000..3bfa9bd75 --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/next/meta.json @@ -0,0 +1 @@ +{"done": {"device": "cpu", "shape": [50, 1], "dtype": "torch.bool"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_human/next/observation/image/meta.json b/tests/data/aloha_sim_insertion_human/next/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/next/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_human/next/observation/image/top.memmap b/tests/data/aloha_sim_insertion_human/next/observation/image/top.memmap new file mode 100644 index 000000000..d3d8bd1cd --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/next/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5c632e3cb06be729e5d673e3ecca1d6f6527b0f48cfe3dc03d7eea4f9eb3bbd7 +size 46080000 diff --git a/tests/data/aloha_sim_insertion_human/next/observation/meta.json b/tests/data/aloha_sim_insertion_human/next/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/next/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_human/next/observation/state.memmap b/tests/data/aloha_sim_insertion_human/next/observation/state.memmap new file mode 100644 index 000000000..1f087a60a --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/next/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e231f2e07e1cd030137ea2e938b570b112db2c694c6d21b37ceb8f8559e19088 +size 2800 diff --git a/tests/data/aloha_sim_insertion_human/observation/image/meta.json b/tests/data/aloha_sim_insertion_human/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_human/observation/image/top.memmap b/tests/data/aloha_sim_insertion_human/observation/image/top.memmap new file mode 100644 index 000000000..00c0b783e --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a1ba64c89f4fcf9135fe34c26abf582dd5f0d573506db5c96af3ffe40a52c818 +size 46080000 diff --git a/tests/data/aloha_sim_insertion_human/observation/meta.json b/tests/data/aloha_sim_insertion_human/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_human/observation/state.memmap b/tests/data/aloha_sim_insertion_human/observation/state.memmap new file mode 100644 index 000000000..a1131179a --- /dev/null +++ b/tests/data/aloha_sim_insertion_human/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:85405686bc065c6ab6c915907920a0391a57cf097b74de058a8c30be0548ade5 +size 2800 diff --git a/tests/data/aloha_sim_insertion_human/stats.pth b/tests/data/aloha_sim_insertion_human/stats.pth new file mode 100644 index 0000000000000000000000000000000000000000..869d26cd0528611dc3ffb548c5b35d0cff50f6ef GIT binary patch literal 4434 zcmbuD4Qx}_6~|u)f#7^E84wyM43atw5`V@vypQ5gC#_pZ9AGY^HIDt3=hks@?3XO0 zn6!kXrJY0ys#>5VK-*2ItlEdFt_!?$oiv43Vgs6Xo9H&grb=`}lrl7J)3kfv_3V2M zDGGbhmEYIz{Lel2+;iVei#K;R$K~g9w;aV>1(#5RYN9?IRD*ThPewiNQf_P3@${^a zD#sFC@o*%h)&gBvS-r`}H?=AM`48wxGp-@*e zDu-|n5{8ZOupF1eq?-$CeNd^wA|KqNTS=&4s8W!=Ql=35W>~D~c9*2>-b?H*-K$`H znF`-Y zVC^A;+#XazN+1#Gm%)~bSsS`AfW3AI8hqgJ7okw0#0i8Woq<@eQ%-<$Lr=RtevwWb zYnMKLYm%^*8b4llPwnakL4PbJL82btZ&XScw{5Tvxt*(m8@X*nqmheRjtY%Na)!^> zlMXzfg2x9<3LAAhG!p|4vIZWa40wrwhgEpQ2OAVN?hUY!7-(S)v{D9q#6X)0n|!cY zVI%K=EyTdLSOb2_z@x;#Ru#VOgKa&EO>rnVoQd>V=AJ$QVsf7fkLe+NJP83RgxeJ| zwSq}#r*4OgN`X?SkUjahc2rmAwt=BB75YV@FeOs znnqF7Z8D8INy5cQXS-DB_5oy#mkZ(qOQbQCU_AuuRpGln=%Yqy7IMvOf*pkGPjgQZ zZYSZAD(v#X05v!|XNIQ<_e`4GO}IhA?NMRK2g8~8XU^(cymRwigAe|*2~{oJTBa?_ zB^;kB%k4W<8P#1m?r}SBsmobqdfLlqL{+0QmLC!>SK_h3ZF>1a?tW@js5g1s{9S8f zr+S}wbM0Hd;kEJ+UYhN@_taa5FNqa(L*qqPmq=^=eD?GwzultUW2uq04SK{MzgH#o zU0+f0qmkW2+FXDdUC(i=)NKD z6;ui9zxmN~ccG60KKj?Z2Z){PyMe(|^O ziMu`>kk+5SB%a*%oHShUx;Xk}n^-=2ShBqLi1ed(4@ftTxW2egB#J(v0=3 ztp2&rU)1)!-!rke^oZDAGpwCi@Nez&6H^*WDXw|t4Qugd8)bWYhl?uJZC zO*_|b_rN$hB0gJrK>YrK{ra4GwEXWCGuCgodwq@@XymvkY6Fe9|K$^7r)I40_=^TNRVxL*I9Ile`A*3Z*$9o~}Eqdh<*7>)Gn`+z_s>~WiBJPXV=li6lBH`uH$ zyVY(sIqf!w$=qPEo9r%!$z?U!8>|+a%Za^QeQ7Aqh&;rt#hZhjP4ArO#k&|kU=DU4 zmCe#CZwbS_j6MYjn_ld*VR{k7iJLj*qm?`(TyM%I>E(+hCt1>*P0|Yw{(8?G&1j!T zX_{{lrPmA=oyu)pKzEY}|Y=7xO&61NWY0W0-a?Fy=^B7HAHc1y!mVA{Z z?b#$<0$H-kz-TsPlXUT7$yZs@kxkO2ge9xcR-KA1nh0#-(?x(KCt1>!P12K|O@(G; zh-jutMm9>%#Hvj8p|kyI^!7EP#XD!tsuZy#cXgUAO`ZMk_h)zmj}B+bGsNM4VQ|+{ VFW`NCi#HE{EOVvk55G^|{V(LZF2Mi* literal 0 HcmV?d00001 diff --git a/tests/data/aloha_sim_insertion_scripted/action.memmap b/tests/data/aloha_sim_insertion_scripted/action.memmap new file mode 100644 index 000000000..e4068b757 --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/action.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:1f5fe053b760e8471885b82c10f4a6ea40874098036337ae5cc300c4775546be +size 2800 diff --git a/tests/data/aloha_sim_insertion_scripted/episode.memmap b/tests/data/aloha_sim_insertion_scripted/episode.memmap new file mode 100644 index 000000000..af9fb07fd --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/episode.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7a12e561363385e9dfeeab326368731c030ed4b374e7f5897ac819159d2884c5 +size 400 diff --git a/tests/data/aloha_sim_insertion_scripted/frame_id.memmap b/tests/data/aloha_sim_insertion_scripted/frame_id.memmap new file mode 100644 index 000000000..dc2f585cf --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/frame_id.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c202d9cfc7858fd49d522047e16948359bbbb2eda2d3825d552e45a78d5f8585 +size 400 diff --git a/tests/data/aloha_sim_insertion_scripted/meta.json b/tests/data/aloha_sim_insertion_scripted/meta.json new file mode 100644 index 000000000..2a0cf0a25 --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/meta.json @@ -0,0 +1 @@ +{"action": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "episode": {"device": "cpu", "shape": [50], "dtype": "torch.int64"}, "frame_id": {"device": "cpu", "shape": [50], "dtype": "torch.int64"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_scripted/next/done.memmap b/tests/data/aloha_sim_insertion_scripted/next/done.memmap new file mode 100644 index 000000000..44fd709f9 --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/next/done.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cc2786e1f9910a9d811400edcddaf7075195f7a16b216dcbefba3bc7c4f2ae51 +size 50 diff --git a/tests/data/aloha_sim_insertion_scripted/next/meta.json b/tests/data/aloha_sim_insertion_scripted/next/meta.json new file mode 100644 index 000000000..3bfa9bd75 --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/next/meta.json @@ -0,0 +1 @@ +{"done": {"device": "cpu", "shape": [50, 1], "dtype": "torch.bool"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_scripted/next/observation/image/meta.json b/tests/data/aloha_sim_insertion_scripted/next/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/next/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_scripted/next/observation/image/top.memmap b/tests/data/aloha_sim_insertion_scripted/next/observation/image/top.memmap new file mode 100644 index 000000000..83911729e --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/next/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:daed2bb10498ba2557983d0d7e89399882fea7585e7ceff910e23c621bfdbf88 +size 46080000 diff --git a/tests/data/aloha_sim_insertion_scripted/next/observation/meta.json b/tests/data/aloha_sim_insertion_scripted/next/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/next/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_scripted/next/observation/state.memmap b/tests/data/aloha_sim_insertion_scripted/next/observation/state.memmap new file mode 100644 index 000000000..aef69da09 --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/next/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:bbad0302af70112ee312efe0eb0f44a2f1c8f6c5ef82ea4fb34625cdafbef057 +size 2800 diff --git a/tests/data/aloha_sim_insertion_scripted/observation/image/meta.json b/tests/data/aloha_sim_insertion_scripted/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_scripted/observation/image/top.memmap b/tests/data/aloha_sim_insertion_scripted/observation/image/top.memmap new file mode 100644 index 000000000..f9f0a759b --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:aba55ebb9dd004bf68444b9ebf024ed7713436099c06a0b8e541100ecbc69290 +size 46080000 diff --git a/tests/data/aloha_sim_insertion_scripted/observation/meta.json b/tests/data/aloha_sim_insertion_scripted/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_insertion_scripted/observation/state.memmap b/tests/data/aloha_sim_insertion_scripted/observation/state.memmap new file mode 100644 index 000000000..91875055a --- /dev/null +++ b/tests/data/aloha_sim_insertion_scripted/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:dd4e7e14abf57561ca9839c910581266be90956e41bfb3bb21362ea0c321e77d +size 2800 diff --git a/tests/data/aloha_sim_insertion_scripted/stats.pth b/tests/data/aloha_sim_insertion_scripted/stats.pth new file mode 100644 index 0000000000000000000000000000000000000000..0f3f9d2f19a42274b1627a80bab0de242a430228 GIT binary patch literal 4434 zcmbuDe{7S-8OPrc0>Md~l=7=^$}* zB~UNWkaTTVt+Z7sQ3VlV(x$0W>DrEMBp%y9(X?nA6Dw26D%NWIW9_uEA@!HG-M#18 zcZReJd!v)z_r3c(-{+pYd+xoo`HB}xQfaAl)1{Y|Nhut{sfI`hhwA%#V_r{{w5#Ac zv>=R?cq);MM8mi~h$Ffk+G8_$)PYoc7>d%czz|qW><1&tU^J{iaciKAKITDK$Xgk} z(O60sY{$uHyn9Qh2-s0`yoGOX4Iv&u=OYakknWE~6+HtL|t!1|CPEkoT3 z+`$l?H*lIjKiq}k3x2p;vy#FQs8)%-dWXvFo8XJ8W_NYY?mf)zm!425 zz6QfuKdjU6zR-TC5%5O%GQ;o9;a_36f#J0n?(@S}86J&8oq(I+eumfQ@CJq(8E(SR z=m+xv8|1DK4y(ab^ne1EY|PrpgAS~)| ziji)!Wz@$eT%2__fuY|IP%vIjNHQ#y!!W}J7&eIE5kKtbMri?Y&18fj#vRCU2O0M$ zi;YQ>gqXdgm@WHnhwwUoNfZc7+C`*WuSdsuyytKKbVV+_g@)b_pzR$Vv~+eU>bZ6l&75gO zuJ2(U103A-(Z&bh5J50Z@8cT z;3zV@GA@U@J7oB9ldS8RkR|DmeC7w&-QB5EXf3I0dVaUulHMxUnNDhTRR8qshK~8` zlK^n~Q-64Os@Fb~xw!W&cl?LDGULaOPgUB-GbE(ajoMG9EPH1%_kD87UGmgUt?uyS zr?fh%fA8CWdh_%3%OxTHjbi-Y`0)+*mgkP5vMtBu-}HCLuie-zqpk`0&Dt?}dg!_v z4V*@YA3QEE4|K{kPqxZeI#0?!`PPt3^?&x-H{YALzFE{?_4>P08>?qBwL53s>atF) zkLT;gGcD;~p?m)I@s!s$lle>OWw-K1K&xAM`jl2j_5b~H@1yh9w}|?q>(+XPo7Q;N zMAmtzO|)SD*>VzlT0Uz|Kfuo^tJh=8PpLWA`mHLSt~ux4v^nDre>$nHsoCzI{(Rp0 zw%ga2q~Rt>>LF#giS}Q=`(n?$_3i(UKAq|8qWX!8mk-Wc-*Nl;wwG6zV3N(ck{gG zpHrNFm(T~U4J)spy1zbzMta!ZyV>HjHa0r#79;iY zdqpqS7>I|owE2ptv$>NKzj^Cvg>Z@Is6v+Cc`F6(82J=nY;LnJg!xU7PTc&pg6!mZ z;RezL(Pe)763JHk#zVi}^H&Qw=W&{*n?(6NLqw+w(3@2GbT9hbLXNMTYGa|l ze4-Y~X^}J+l6*QA$(AL8rlpYN6RAkPB$C!bl23smS*;T^ZG|MCyhQRPk+c_*d@2#i zYI0QPV(Ta*`6M8c(<13CB>6=zPK6d?h-qe1Mj^_t#OnO)BX`f{&|Bw-Hs7K}by;F{ t@%=frDtq_e-?Q`pPcBE+Gs4k-VMu?^HlXMHHeU(-SeB~DA8pUt{s-#IH4gv) literal 0 HcmV?d00001 diff --git a/tests/data/aloha_sim_transfer_cube_human/action.memmap b/tests/data/aloha_sim_transfer_cube_human/action.memmap new file mode 100644 index 000000000..9b4fef337 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/action.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:14fed0eed3d529a8ac0dd25a6d41585020772d02f9137fc9d604713b2f0f7076 +size 2800 diff --git a/tests/data/aloha_sim_transfer_cube_human/episode.memmap b/tests/data/aloha_sim_transfer_cube_human/episode.memmap new file mode 100644 index 000000000..af9fb07fd --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/episode.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7a12e561363385e9dfeeab326368731c030ed4b374e7f5897ac819159d2884c5 +size 400 diff --git a/tests/data/aloha_sim_transfer_cube_human/frame_id.memmap b/tests/data/aloha_sim_transfer_cube_human/frame_id.memmap new file mode 100644 index 000000000..dc2f585cf --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/frame_id.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c202d9cfc7858fd49d522047e16948359bbbb2eda2d3825d552e45a78d5f8585 +size 400 diff --git a/tests/data/aloha_sim_transfer_cube_human/meta.json b/tests/data/aloha_sim_transfer_cube_human/meta.json new file mode 100644 index 000000000..2a0cf0a25 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/meta.json @@ -0,0 +1 @@ +{"action": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "episode": {"device": "cpu", "shape": [50], "dtype": "torch.int64"}, "frame_id": {"device": "cpu", "shape": [50], "dtype": "torch.int64"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_human/next/done.memmap b/tests/data/aloha_sim_transfer_cube_human/next/done.memmap new file mode 100644 index 000000000..44fd709f9 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/next/done.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cc2786e1f9910a9d811400edcddaf7075195f7a16b216dcbefba3bc7c4f2ae51 +size 50 diff --git a/tests/data/aloha_sim_transfer_cube_human/next/meta.json b/tests/data/aloha_sim_transfer_cube_human/next/meta.json new file mode 100644 index 000000000..3bfa9bd75 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/next/meta.json @@ -0,0 +1 @@ +{"done": {"device": "cpu", "shape": [50, 1], "dtype": "torch.bool"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_human/next/observation/image/meta.json b/tests/data/aloha_sim_transfer_cube_human/next/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/next/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_human/next/observation/image/top.memmap b/tests/data/aloha_sim_transfer_cube_human/next/observation/image/top.memmap new file mode 100644 index 000000000..cd2e7c06f --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/next/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:2f713ea7fc19e592ea409a5e0bdfde403e5b86f834cbabe3463b791e8437fafc +size 46080000 diff --git a/tests/data/aloha_sim_transfer_cube_human/next/observation/meta.json b/tests/data/aloha_sim_transfer_cube_human/next/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/next/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_human/next/observation/state.memmap b/tests/data/aloha_sim_transfer_cube_human/next/observation/state.memmap new file mode 100644 index 000000000..37feaad64 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/next/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:8c103e2c9d63c9f7cf9645bd24d9a2c4e8e08825dc75e230ebc793b8f9c213b0 +size 2800 diff --git a/tests/data/aloha_sim_transfer_cube_human/observation/image/meta.json b/tests/data/aloha_sim_transfer_cube_human/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_human/observation/image/top.memmap b/tests/data/aloha_sim_transfer_cube_human/observation/image/top.memmap new file mode 100644 index 000000000..1188590c4 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7dbf4aa01b184d0eaa21ea999078d7cff86e1ca484a109614176fdc49f1ee05c +size 46080000 diff --git a/tests/data/aloha_sim_transfer_cube_human/observation/meta.json b/tests/data/aloha_sim_transfer_cube_human/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_human/observation/state.memmap b/tests/data/aloha_sim_transfer_cube_human/observation/state.memmap new file mode 100644 index 000000000..9ef4cfd62 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_human/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:4fa0b9c870d4615037b6fee9e9e85e54d84352e173f2c7c1035232272fe2a3dd +size 2800 diff --git a/tests/data/aloha_sim_transfer_cube_human/stats.pth b/tests/data/aloha_sim_transfer_cube_human/stats.pth new file mode 100644 index 0000000000000000000000000000000000000000..0fa5667cfdcd4af6a412f62df1bbf40286287343 GIT binary patch literal 4434 zcmbuDe{7S-8OPt?Bm@(j1ZW2(Kq+N7YjNzvc5LF;FAda$xFxO=m=~bNv0w7OjbrDr z&*9fh6Cjjs6%>kEs?wHf%i2yrr)|2{qQ&8H?_w#wxI}N~4Cxdy{fvD1_8_3}z}sr78`xjEZifQm&Bq^u|C1mLUGi zFk5@0It_D}Hw?xA?zk`@hhk6@M)5>gF$MF=3As0=Mk9F#gF{Vvs5R0)B=MV}J{jsL zqW47OA=E{0>S1o64BIrrynqh>h6htH-)lf{&l6t3Tjn(!f_uFNZ`mRE+Oy$sJQ|h5 zqz6fTXCfjerBjYTp8j70vFFg59Om?)}dy1Yd^W z0Y5C)@PW`Sc#y-JUH$w5VT>pjd(P4xRoJTYour7d>!q; zqX;~HSg-I=w?R8Kuz@$w!5HvT1CJqi+z%TSKJIqtqy~JvfhQOPerli#LAM_^DSYHx zU^6xFP2NC&G4L&Fpa;PgKWt4YR;5KD;Y=3Jiube$5R-Qy*rtW>$utC+5N=oK)C#4c zm$@A_DzlYpg$_z24Knj=haxKO+esDg1uF4yhqT0pK226hgUZ-=s&wQW(2u)~r%@Dl zn@*zvns71N**JnhKS0TNIUzx@WC24IOHphH!A?KyVn%5OcFkgj-IUu?;Pz7P+muTq z*yo3*nZeOG3k*|kq`>W`+yTlRL@?@yL&f+P&rCk=%qr)B4WF;aRf{y=lx4X_aOKN# z?`|aHx+^C&5^^XgjHmn-7Arv!1NtlSlGf8rWXeb;sK%l+ck zBgb6+rE5iLZn@a1c8U|16fxTIo_OuxdXebY{pf?9JL}I8=5YErWV4D6gvJ`g-=Dsk zc_IF~^kK~g*RS6?oKfUMVJMLaTbNuG{ z_j{M-jBgx}>O?8C_{$sF)$?A?plvyKr?fO}3_|fii@eSpR);}Ek%(dl}=Un|Az2cb@CtNi@UoC#V zPbcoPb&KeksCc92qWG65k8Abs`|0Hm-C4g_|Ayp55`XV<^`}`+qJHVMzD;BiC2i`g zuNSQOtT&M@Nh96^sG+F3N81Mk)rhCfJndOvv6?Mbo5gNzcG{Y47PG@jH0`A% zTfBJk6i?!G=F^ugB|KS=x9Uu69i=2&1bFfSPdZCUcGB~y(2fmJ&3wryMcJ8HU(7yy zcD#VzzDD@Gm6Z?Yi6y#K1-3SS_P^h8vVq5kBkvjJ$iFazPxCL3eZJ3IK|Yp+TKq@e Hr|"} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_scripted/next/done.memmap b/tests/data/aloha_sim_transfer_cube_scripted/next/done.memmap new file mode 100644 index 000000000..44fd709f9 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/next/done.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cc2786e1f9910a9d811400edcddaf7075195f7a16b216dcbefba3bc7c4f2ae51 +size 50 diff --git a/tests/data/aloha_sim_transfer_cube_scripted/next/meta.json b/tests/data/aloha_sim_transfer_cube_scripted/next/meta.json new file mode 100644 index 000000000..3bfa9bd75 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/next/meta.json @@ -0,0 +1 @@ +{"done": {"device": "cpu", "shape": [50, 1], "dtype": "torch.bool"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/meta.json b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/top.memmap b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/top.memmap new file mode 100644 index 000000000..8e5f533e1 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:30b44d38cc4d68e06c716a875d39cbdbeacbfdc1657d6366f58c279efd27c52b +size 46080000 diff --git a/tests/data/aloha_sim_transfer_cube_scripted/next/observation/meta.json b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_scripted/next/observation/state.memmap b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/state.memmap new file mode 100644 index 000000000..e88320d13 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/next/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:9f484e7ea4f5f612dd53ee2c0f7891b8f7b2168a54fc81941ac2f2447260c294 +size 2800 diff --git a/tests/data/aloha_sim_transfer_cube_scripted/observation/image/meta.json b/tests/data/aloha_sim_transfer_cube_scripted/observation/image/meta.json new file mode 100644 index 000000000..cb29a5ab0 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/observation/image/meta.json @@ -0,0 +1 @@ +{"top": {"device": "cpu", "shape": [50, 3, 480, 640], "dtype": "torch.uint8"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_scripted/observation/image/top.memmap b/tests/data/aloha_sim_transfer_cube_scripted/observation/image/top.memmap new file mode 100644 index 000000000..d415da0a7 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/observation/image/top.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:09600206f56cc5b52dfb896204b0044c4e830da368da141d7bd10e52181f6835 +size 46080000 diff --git a/tests/data/aloha_sim_transfer_cube_scripted/observation/meta.json b/tests/data/aloha_sim_transfer_cube_scripted/observation/meta.json new file mode 100644 index 000000000..65ce1ca2d --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/observation/meta.json @@ -0,0 +1 @@ +{"state": {"device": "cpu", "shape": [50, 14], "dtype": "torch.float32"}, "shape": [50], "device": "cpu", "_type": ""} \ No newline at end of file diff --git a/tests/data/aloha_sim_transfer_cube_scripted/observation/state.memmap b/tests/data/aloha_sim_transfer_cube_scripted/observation/state.memmap new file mode 100644 index 000000000..be3436fb5 --- /dev/null +++ b/tests/data/aloha_sim_transfer_cube_scripted/observation/state.memmap @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:60dcb547cf9a6372b78a455217a2408b6bece4371fba1df2a302b334d45c42a8 +size 2800 diff --git a/tests/data/aloha_sim_transfer_cube_scripted/stats.pth b/tests/data/aloha_sim_transfer_cube_scripted/stats.pth new file mode 100644 index 0000000000000000000000000000000000000000..b00756e6ca73299de068ca8e72fb9c809d771666 GIT binary patch literal 4434 zcmbuDdvFuS9mh|Ihb@e45@Y9K9tkwa6l^^$$=2x{kt&Xr+U9^pB@OCXx^Mzn;wPOP za1f7xNkZBZ0!e^jN-~8`Qs`ttNZPTD6efvl2&7?3nDmk15B^Cz!_c(pw51c$-CI@K zJ#ZM)^Q?WZ&+q%&-~RTux9$!aCvsd_8F$@L$<=UaRZ`PUQAw2=*RF{N{MFnF-LZK> zM3ociWGWhqsEuJYYFegUK7cMwz%^_ELl!2OLsO9ba8&M#MPx8`hNj}n5(pD%D;YHw zPn*I^)l@98sw)v+PmE1M#wMFJG})7uQ+<*eOD157f>p}0P;OR?oytT7zh^RsCLsyz zzYJ5gH!89)je4Wf96}xEdSxjARS`9riYSfYf^tgk$;9H(f`j2cn+dATqz`HIrnE|i z=>#za;z>zeN^Y9qwvYkYw7~5lBl;Uzn}M2Or3y2a1i7FgSh*c)gOx$UcBp$c5=qA6 zas>AvZR$!z<&+#H-MphgggaHZON6^MD`_Pun5*Hv(mI&O;5PUc!S5^L^9gPyc!LTHMEEwrV+mNu;C5I<@WvwEL~skitt!|= zuxH31_eg3)38!QIGB^q`TZ%4B;A|LxW)WPWX(&`Eal+A9Z#W_K%4u+SW_q;oi}m7I zd$jRu$wDhNeqPNzHMtge?XfQl0`<7ftW+^>JK%ogwowH?a@&kX!-$$eg~euahR+`$ z9r%t40TCWl*r+?9ofvqCHPAsB2oeJitMFYBIu$nV&Co>*bh8GQPzFR|V5thrL|Cq{ zk$1uOh=E5~10l-5_lbcODm*H}4>F2FaVa>Q>Ec=Go;Cpz@;VhB(?Ym13t=jRKUB!n zlCsc4-Hw=*sY-=H1|^yWnR@oP!YjTTNtNz}CZpk&w8V#1nyiwA7-eI%e&pP+26Y=v zqd4j|nMS=N;S!{?Nfp+L0J`z=K#E}LBBl~7L$E#-o)BRjHA)kZYgP-aCtQD#dy;S) z2$xl1qX?U*!O=J?Y$n{6BKH*Gwi0fe3Iif+FU7xf*4Q1KQs&wE(A5V~)xxcN%(7g? zc?)H^XT2(;x+|vwe)n~CSy!gVyo|?GH7;ZM0shjRcx-SRTfTy8qgI6`OTh2FWo_)# z7c1TvI_bKWtGVqd;dA%Np^JUS{L$o2;grE5e7^Fqw_?_7xeNXO^8N9p-w$v7YO%2G zgM0b1D-HpBY^dqj?MB|>_DvpF(jHp_eiP+!*UsjaDT_bhf8KRB|EFE9)`5=Q{KCv7 z{_6&wpS|Ek@B4E`c=_O)d}qgq_sZ*0KDlQm|J&LQ9_#+~aneDD~5|L@-SNqbHU9Jg6W|LjX&@9G`C!$fIi0`ycel_sd&BUeqs#KSo+k!TNV(6Bzmq$%{KNc? zf7YG2++oY_-?uOK{CO#lpJ9E;Vfe+(^(#0g{x&xL?`4`={oeML>Zgwg1DAiv-(EB7 zd*;w-;r!bP!94Rz-}1KSd;`1p3vK_X6Q*`PBUEkNA)J4Gn>PN3YTx+Fxb^L<{)@-v z3|}~KI{)TbkMQcs9}OE$F3D%VIzD)C%WwGFuiwr&=Y5!8Q&xWBP>A$DI3nfSvuCvN zKl|FnE92I8u=<}3&hsz(Vy@P3OcN~+pRYji#qFDNx`oauXTaZFN~tmD`i&ms9)H>A z*}hk6SpQV_)$n)er(+OuK!0LXEQmlesbiKC&#VtzIFXa z&b&2rGV!IS0dM`I z@A7;19^=KUr@W2EDF5y&v-q=n_G$UwZ(b?fT)$NR`s7p^eeW{$$8N$=KljsB%kd(L z+t^uO&p8TN--x#)O=u4glj5;{Z66ShMFW1zxMzXYVX-=#)@Fy@|Gx89(?w|oXTiiL(i+3e{z#Qy8O3%_OZxzG6j6MYj zTU_k*Fue%k#4R1QXeBQRH(B%~y?n9cC`+Qwvz?_E9{lxQI@-}bkJ7YWCrYmwEIO(~ zuT!PVJ?n2f+P+e%Hod=ep=QZZmbB|hx*W4)dpV=&(35l_Wyu39>C}^S31rE76QkLz zC+XtFk_TAQr6=i9!jko9t4_t%ttaUsz>=dZ>Cuz)q-Rs19T_5;g_5C1>6utx%06`V zLJ_@jjpz@UkfkbeSUXv68>1`s?iUA HpS=5Dpf52C literal 0 HcmV?d00001 diff --git a/tests/data/pusht/stats.pth b/tests/data/pusht/stats.pth index c34e6a9423b18ee837d11b40fb05da04539f95ed..037e02f0fbe9a84fb24d2119174addd4a5a913dd 100644 GIT binary patch delta 538 zcmbQFd`WSG1`8J(0|P^1a!F=>-eg@C@p_F6{tN*PjSRsIp$JBxltp1mhKM&)NnvWB zH-k5$H&a_-nm3a-V_RW*XNH7kP+>+%VP;TaR)!3UHp{|nh_)QKwp@s|JczdZlEQ+Z z!omy{xHcxBZHDy*g+&mJ#c+)!5RIh}jb$Z;q|3CGR!k9{7RD$EWH44c8=oCX0Sr12mH}b}5SlC~=x?-x2O<*S e&BhL56$n81pvVpIW(7q*g8&fjU}j)|s09GF9f}G7 delta 749 zcmb7?O-~a+7=Wisx2?3>F2o3iCTjGsBt}>$Wmj(;^e_g?9!x_tv8B})Kd5gzMNpT5 zA65L8N&EvIypnh^>94RS4*U#%0P~TQ<>+oEnP;DQW|GPFFYI01cjBEGA*6!$fK2XS zCB&)&LyHgxQ{YNj$`!0BSr74kL_ScGAt<>T;=_o1q~t0-R`N-RYZ2K{vVl*f>>!5N zjM$d4YsggE4sksqpE-~N+i_q7M%6kGH{dii7;Y|6LSxkE;&W=ySQlUH!uVu>FBygb zZbAM;=3_@^+nqtTqq|qSd(H4ofN$Z_pfki>xYO9x;k!ZiUU$2?`@ryHfS=&<$k zy8ANdzN)T<-*ot$;a-5e4F#A7Z?Ro%{rBv+y;7pd)Ow@o_e?^1Cbu*BvpJF?EmmQz zsp=-HH=4D2^ZG)ZEHD4wGRKk={#?= 0.0 diff --git a/tests/test_envs.py b/tests/test_envs.py index b51c441b6..aad13ed89 100644 --- a/tests/test_envs.py +++ b/tests/test_envs.py @@ -1,6 +1,8 @@ import pytest from tensordict import TensorDict +import torch from torchrl.envs.utils import check_env_specs, step_mdp +from lerobot.common.datasets.factory import make_offline_buffer from lerobot.common.envs.factory import make_env from lerobot.common.envs.pusht.env import PushtEnv @@ -83,9 +85,24 @@ def test_pusht(from_pixels, pixels_only): [ # "simxarm", "pusht", + "aloha", ], ) def test_factory(env_name): cfg = init_config(overrides=[f"env={env_name}"]) + + offline_buffer = make_offline_buffer(cfg) + env = make_env(cfg) + for key in offline_buffer.image_keys: + assert env.reset().get(key).dtype == torch.uint8 + check_env_specs(env) + + env = make_env(cfg, transform=offline_buffer.transform) + for key in offline_buffer.image_keys: + img = env.reset().get(key) + assert img.dtype == torch.float32 + # TODO(rcadene): we assume for now that image normalization takes place in the model + assert img.max() <= 1.0 + assert img.min() >= 0.0 check_env_specs(env) From f9258898ff85cfb47c5f8247105c6322efb43bfb Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Tue, 12 Mar 2024 12:24:10 +0100 Subject: [PATCH 2/7] CI fix attempt --- .github/workflows/test.yml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index e9edad051..3efcb1099 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -18,6 +18,7 @@ jobs: env: POETRY_VERSION: 1.8.1 DATA_DIR: tests/data + TMPDIR: ~/tmp steps: #---------------------------------------------- # check-out repo and set-up python @@ -69,7 +70,9 @@ jobs: key: venv-${{ steps.setup-python.outputs.python-version }}-${{ env.POETRY_VERSION }}-${{ hashFiles('**/poetry.lock') }} - name: Install dependencies if: steps.restore-dependencies-cache.outputs.cache-hit != 'true' - run: poetry install --no-interaction --no-root + run: | + mkdir ~/tmp + poetry install --no-interaction --no-root - name: Save cached venv if: | steps.restore-dependencies-cache.outputs.cache-hit != 'true' && From 29c73844b129d1f8cd04e7c387371028d77819c3 Mon Sep 17 00:00:00 2001 From: Cadene Date: Tue, 12 Mar 2024 13:52:53 +0000 Subject: [PATCH 3/7] Update test.yml --- .github/workflows/test.yml | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 3efcb1099..483f235f0 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -19,6 +19,8 @@ jobs: POETRY_VERSION: 1.8.1 DATA_DIR: tests/data TMPDIR: ~/tmp + TEMP: ~/tmp + TMP: ~/tmp steps: #---------------------------------------------- # check-out repo and set-up python @@ -27,11 +29,13 @@ jobs: uses: actions/checkout@v4 with: lfs: true + - name: Set up python id: setup-python uses: actions/setup-python@v5 with: python-version: '3.10' + #---------------------------------------------- # install & configure poetry #---------------------------------------------- @@ -41,6 +45,7 @@ jobs: with: path: ~/.local # the path depends on the OS key: poetry-${{ env.POETRY_VERSION }} # increment to reset cache + - name: Install Poetry if: steps.restore-poetry-cache.outputs.cache-hit != 'true' uses: snok/install-poetry@v1 @@ -48,6 +53,7 @@ jobs: version: ${{ env.POETRY_VERSION }} virtualenvs-create: true installer-parallel: true + - name: Save cached Poetry installation if: | steps.restore-poetry-cache.outputs.cache-hit != 'true' && @@ -57,8 +63,10 @@ jobs: with: path: ~/.local # the path depends on the OS key: poetry-${{ env.POETRY_VERSION }} # increment to reset cache + - name: Configure Poetry run: poetry config virtualenvs.in-project true + #---------------------------------------------- # install dependencies #---------------------------------------------- @@ -68,11 +76,16 @@ jobs: with: path: .venv key: venv-${{ steps.setup-python.outputs.python-version }}-${{ env.POETRY_VERSION }}-${{ hashFiles('**/poetry.lock') }} + - name: Install dependencies if: steps.restore-dependencies-cache.outputs.cache-hit != 'true' run: | mkdir ~/tmp + echo $TMPDIR + echo $TEMP + echo $TMP poetry install --no-interaction --no-root + - name: Save cached venv if: | steps.restore-dependencies-cache.outputs.cache-hit != 'true' && @@ -82,11 +95,13 @@ jobs: with: path: .venv key: venv-${{ steps.setup-python.outputs.python-version }}-${{ env.POETRY_VERSION }}-${{ hashFiles('**/poetry.lock') }} + #---------------------------------------------- # install project #---------------------------------------------- - name: Install project run: poetry install --no-interaction + #---------------------------------------------- # run tests #---------------------------------------------- @@ -94,6 +109,7 @@ jobs: run: | source .venv/bin/activate pytest tests + - name: Test train pusht end-to-end run: | source .venv/bin/activate @@ -107,6 +123,7 @@ jobs: save_model=true \ save_freq=1 \ hydra.run.dir=tests/outputs/ + - name: Test eval pusht end-to-end run: | source .venv/bin/activate From 5881eec3768006d481ef3098213c45b9346b96b7 Mon Sep 17 00:00:00 2001 From: Cadene Date: Tue, 12 Mar 2024 14:14:39 +0000 Subject: [PATCH 4/7] Add DEVICE constant from LEROBOT_TESTS_DEVICE --- .github/workflows/test.yml | 3 +++ tests/test_datasets.py | 4 ++-- tests/test_envs.py | 5 +++-- tests/test_policies.py | 3 ++- tests/utils.py | 2 ++ 5 files changed, 12 insertions(+), 5 deletions(-) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 483f235f0..46d579454 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -21,6 +21,9 @@ jobs: TMPDIR: ~/tmp TEMP: ~/tmp TMP: ~/tmp + PYOPENGL_PLATFORM: egl + MUJOCO_GL: egl + LEROBOT_TESTS_DEVICE: cpu steps: #---------------------------------------------- # check-out repo and set-up python diff --git a/tests/test_datasets.py b/tests/test_datasets.py index b3aa7da6f..b7d1e6f8a 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -3,7 +3,7 @@ from lerobot.common.datasets.factory import make_offline_buffer -from .utils import init_config +from .utils import DEVICE, init_config @pytest.mark.parametrize( @@ -20,7 +20,7 @@ ], ) def test_factory(env_name, dataset_id): - cfg = init_config(overrides=[f"env={env_name}", f"env.task={dataset_id}"]) + cfg = init_config(overrides=[f"env={env_name}", f"env.task={dataset_id}", f"device={DEVICE}"]) offline_buffer = make_offline_buffer(cfg) for key in offline_buffer.image_keys: img = offline_buffer[0].get(key) diff --git a/tests/test_envs.py b/tests/test_envs.py index aad13ed89..7776ba3c7 100644 --- a/tests/test_envs.py +++ b/tests/test_envs.py @@ -1,3 +1,4 @@ +import os import pytest from tensordict import TensorDict import torch @@ -8,7 +9,7 @@ from lerobot.common.envs.pusht.env import PushtEnv from lerobot.common.envs.simxarm import SimxarmEnv -from .utils import init_config +from .utils import DEVICE, init_config def print_spec_rollout(env): @@ -89,7 +90,7 @@ def test_pusht(from_pixels, pixels_only): ], ) def test_factory(env_name): - cfg = init_config(overrides=[f"env={env_name}"]) + cfg = init_config(overrides=[f"env={env_name}", f"device={DEVICE}"]) offline_buffer = make_offline_buffer(cfg) diff --git a/tests/test_policies.py b/tests/test_policies.py index 03f20bd02..f00429bcb 100644 --- a/tests/test_policies.py +++ b/tests/test_policies.py @@ -2,7 +2,7 @@ from lerobot.common.policies.factory import make_policy -from .utils import init_config +from .utils import DEVICE, init_config @pytest.mark.parametrize( @@ -19,6 +19,7 @@ def test_factory(env_name, policy_name): overrides=[ f"env={env_name}", f"policy={policy_name}", + f"device={DEVICE}", ] ) policy = make_policy(cfg) diff --git a/tests/utils.py b/tests/utils.py index 40dc6de09..557093300 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -1,8 +1,10 @@ +import os import hydra from hydra import compose, initialize CONFIG_PATH = "../lerobot/configs" +DEVICE = os.environ.get('LEROBOT_TESTS_DEVICE', "cuda") def init_config(config_name="default", overrides=None): hydra.core.global_hydra.GlobalHydra.instance().clear() From 2c5d49cad59da1c2428ff4cdd345d43f1e2a6e3f Mon Sep 17 00:00:00 2001 From: Cadene Date: Tue, 12 Mar 2024 14:30:28 +0000 Subject: [PATCH 5/7] Add sudo apt-get install -y libegl1-mesa-dev --- .github/workflows/test.yml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 46d579454..10acb3a19 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -99,6 +99,9 @@ jobs: path: .venv key: venv-${{ steps.setup-python.outputs.python-version }}-${{ env.POETRY_VERSION }}-${{ hashFiles('**/poetry.lock') }} + - name: Install libegl1-mesa-dev (to use MUJOCO_GL=egl) + run: sudo apt-get update && sudo apt-get install -y libegl1-mesa-dev + #---------------------------------------------- # install project #---------------------------------------------- From 7331df81d2c01c1ffcc25126c126390e04f34f63 Mon Sep 17 00:00:00 2001 From: Cadene Date: Tue, 12 Mar 2024 14:44:23 +0000 Subject: [PATCH 6/7] info --- .github/workflows/test.yml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 10acb3a19..3262543e8 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -80,6 +80,11 @@ jobs: path: .venv key: venv-${{ steps.setup-python.outputs.python-version }}-${{ env.POETRY_VERSION }}-${{ hashFiles('**/poetry.lock') }} + - name: Info + run: | + du -sh /tmp + df -h + - name: Install dependencies if: steps.restore-dependencies-cache.outputs.cache-hit != 'true' run: | From 998dd2b874732ff6d3159579eac44228f929aaea Mon Sep 17 00:00:00 2001 From: Cadene Date: Tue, 12 Mar 2024 14:45:35 +0000 Subject: [PATCH 7/7] info --- .github/workflows/test.yml | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 3262543e8..2b1613105 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -82,8 +82,8 @@ jobs: - name: Info run: | - du -sh /tmp - df -h + sudo du -sh /tmp + sudo df -h - name: Install dependencies if: steps.restore-dependencies-cache.outputs.cache-hit != 'true'

K_&zoKU6m*yZ$}3Y8Lh&v8lCW~wR$z`oDz7(F-zlrMa#e30Xn=3zLB@q zRN$5Szd-OF;CG^o^@d-47Kj>cs1~my{D!kYn3Z6|zQ!D_E1|6oZ6d)~D1Pb7(H?%c z+f`Gz2okErh;aB7Zh`2wRZ3`&q^;tthTm#4${BunU9eGOt5l0~N%$Rgf#|kXN@$Oy zt>Q|CU)wXD7=Alnun}9OT3kQEFX0PBx2;k_dn9cYeGz^y0V6Sd%b;K*wu&AAwCDkZ z?>-cWZd;{<_DI?)`iAHqdS~HV22E_#REr+jcW;#v+9PSJ=(l4m(Z3E~4QSRX)uOlj z-S40h+9PSJxbwnu#~o7meSWi6sTTJ;-+iSgdelu7gx^0yb+9PSJIDg=GqMV7s??ekWVyje(&vy9LXMyOpRZ3`& zc&lh5<6MhYan=sMsV&$bQBy6>gWVF{wn_=@k+fA@mv9HU!gYJ)u~n+YHKW_!?Y31) zXpf|=;u?<8PH&*wQ4(9FT3lbd9f{qxN(t?ev{m$XFf-6|>h_6>tx_%eBHcc<-L^^z z?UA%q^bIj*(97(0_KB@hE&6TU&T!qfN(t=|%W7qLu!bKrq5AMN&l+m;_>Vh3{OI!z z%W2}}Q`i2y19SWJlZSU&)%Lf_8r8}?Bi4Apvxd6X1yf$_uJ#qER9hURQ%Lg2SZ)B*A{a(AUUOjk1^|I-nHPp5Gz3_U6<$3b*1&h5= zAli@g+?mxmLp*D!Yn^uJTOF2t%FC};-!2e&c9rVs*Lv1a*BWxfSN3~O{5tQ)`PFKx ztgjjy+m$~u&9jEO*6FA9oNXDvyj*{`r~OxnE!L>kUoc{=2Rv)2YmMBj-)zeU<>je6 z^(zo>TTZ=JyYgR$tf8*;`31|)wp>D9ZaHz;0&&lgot145oKSsqh-VFTt=4f%&$g^R zUhezKQU&5k%Vc)IUK6TYP4TRuuJxzQde7!PFJA{TvRT%*>dMb}*3dW_EO(95=mpD4 zXMU=SaP-!sg2Jp-<@Ucsdi5Ctf8?k%k$%9 z^jk_?e8LM(96ZFchPu|h@AjE(nTWg$dnxg6%a-=)L>na`Yp84Cu35gKNT)=eEv;&K zmyk8owdS3;%xufSiU zpYk$BWlGp+uW+=hgfjz1yJfg?8c#u%t#8@V?$~`oHG9CbhPq_;NBYfHLTj?GcvwD2 zjKph0*3ej&wlF1DvuvA#Z1%Y+WDSj@gtN~>(z@cl6RLee z)=-yJ_UJ!biPT2tSMysjO5R!ESwmx8mSxP#xTci2>yVaNu(4Fg8X8+=8QGjbt1NSx zmti~0>^f%gIxHibOVC~=QXBTXWoXrlA!}%?%krzma!S~B%;I%erZ?B}`yuvH!tP+5 zcTi_FrBlLYxH@Mzm2hsysI-iHZaa*zJinTcUCZw05{z~ww5BXO*K*6^I?fJRL!H3b zwfuTs4x_JYCbIkk15QTh9=e(;Dt~hvtEqkHU;d!*@yw2y` zG9kJIGlLRZQ_QdC&$-s6y^s=nTYj}A_McFl5VD5Gab@`+-5%yd%iHMXFcaA28dc{SrR%HGDS^z^ zT%#<*rrW?;WSKX;j5R7H=mB7j(p6vSlz<07Z%HL=A-pBpgBO)$&*j&#+!W6m>MeQw zv`;&f(3-OB*8DoQe8#heI)S>_D)=ZVk!R1YTJ~%^Yv~%*yn~O={;-2RJ#O?zMptc= zSZ>+s)Q~mQZG5}Z2OUaiO_m=nWY4ZPCVAFSCr}sf2d*h47C-R?Hj&&TVw4xSdWhB^VijpGV*N}Ol;2Q8~^^|+8VG_)#P(7|T~9$-qeTdu~t zcb!oEdB_^-1iVQ;QR9qGi3K(@ST@?~kACb~L!H>M_iG)Tqu`gOgn7tyddMo_{0I-3 zGZ8%JEc>C&qIcOkxai-WHPmg4-RG4KCA22{N}A1ZXw}shdDhTy9ab0TE3_~r%nP4I zFI**DKj4LPU4eI=WxHGU>;bk$^$S@;-Nvcamphcun(TLXU(cU~R=vEyvxYi>y0{wP zno=UOe;}R2lR3Qw)prM-|6H=Ezy$L6d1Le|i(RW0}QF~iZn4)co5iO7ZRb0YTun6K#RgGg;O z%x}jiS!al64fSz_y7Zb-!sbNxMKLFGKY)2q?WKgR2EOycYQQ}X)(oXn!d3&{d0{o+ zehDi8cST{9(RiCfTS{9=O5{x*E5^teBE9r<)LM1xJw5BZE z@7~R-);G0B-`l`#;5uMK$8Jjez`pVO!HK_V?`gmDQi&26F=$~}uYU6UR&L{#BYw~* zYQY|~QlcgQz4O=``ZZLdBN3w=Ho|Dni5dyktItGAEIZV{osbP z%y2qiVIITZ!z`K;H4>-`gwA#;@#p+Yp3m4Xq*bDXjxk#Y&+K2_cj}~>=l*<0Ctw5C zb*4^+Q8^K4}>yz8@ zUC!G0-X}JST4+18QUcoH|7ytN9_vzX34TzQjUvH%)muu5uk){-&b8}Mi4rC=jh)y_lFb|-y_R?3h-)tU$N|Z?VxaMW} zmBY&@YQYA4hLkuaf9Gz#{We@BD3eHc-Z@btp;{6f zXy$ISRH6iJ2Opj`NWccHvsKVaiAzIY)o#0SNL?jLun&V5UL;@x^|E)Nl@j{BSCuG% zs1f=q>?W@N#W9T)TeqCK&lUUCRZC-JDe)V7GjsieZyx=y?O0TzgpQaj``(-*8|zGZ zb!Lyj=hjtA<5wwRdmMiTvByzKkwA|G?=>efBPt{iNkti2D6_TU+(>LVp;{jxn8OYuS}A_NPhhV+Nm_#9rA8IPFV`o9%wsILh|FV!z~xDiUa6 zu(4>FFz>!+zXs%dg_t+zT}10SAERtvBo#s>piwVqt;zRlem`v9bsN;;jLLXB##M;7 z?`E^;H&cGoK5OQXq*Y3AencET%l>RLwOx4a=STdYTGWC)Xr;uq`MkT<4gIPrL74<+ zz7TKEi5dyjLK#{qF+YFTd1d=Gph{3Cq2n#fwy~M|<4fLYU%TI;Btp*_6{i3xA@goB zc8dh;g|pOg`4?#Jwy!$Ud%?L1y&9D1ap3GF%W|Sd0(DUfWoQ+ME>EVa5|l~MGYDrz z;>kFnS|~#+C2}t#GcTj65|l~kIL@*Ur}S@J_TZ$Mqqf=632M=+!3kDMylcJ>o~XCh z-ny!iB7vI1^Ksk3FU^{G&7tjc>{rD7i)%lD`Hj-^&R`1op33-v-P zC5~Jp?1~oH_g+Ti9Sd28 z7{LDXd$r?!aDR?I;m#Yq%h*7;=ZFEIRa3V*yjs-ay-5ihCBD1EC{YRH45(LoJ! z$5l}aHgIoJ!bZE>z-U(q$|UqY+1ze%p93~HzYWhhV={Qw7?Z(M%Xmzltlb z*mGXgf(>Y;gv76^Dq(C11S1w{fT4*7(Qo?)&+>Z=i zhDuN-p?B8348MaUR10O?|CF$q+HGK_Rtd@^bSz}qK#QbKpLKlurgJ~2F#hT1=kgX3 zBdoy#m}QYvjH^qRT~uK#6e}`guh2?~W%7vdspe&sgi)IGd;xwfqj67oHLlr%vu5v`FZEviFwkI<`A|QhPt!P0$ARGQ1|7 z>99w_KFWM*zjE`blan7k$4Lp>dHMaoUQH!R;6w=iZrBgzgzxT(TDT5qrG)Ju-3E4$ zD$$cBoFOIqTE7kwtXEH(x+OB~gjJ#hZHN7N-YVZa7qwsyS}9>WdcO|r=vBh&0Kq;C zJC>aA7(h`AHlURf`5p9KkxJOp#gU(7lb$@Zj`?cq&ZDh$TUsyv!S?6NZh`W)$G7I? ziT?Mk`YvsM&xsld)j~OFDS`TJDrw+<=B^uZ3{2W`h1rMvEaU>Po$u^JpZ%eYV|;V@ zd-mV(FZ`xK3Dvr6Fnr$uoxj*_`2wL@mED8Z8#}EqyF}F3D%HB_ZoIuUptILv-4NEW z&?>Dr4!LG>u)o4Stju{!WvPR$8B?6G! zP>B*}{uXaN4d`6v1njoMzd-EspYWx9+}qh#g);8o&}YI|{xNzIqNZBsuG8Z6Vk|W$ zRHDTBcZF;PaU|Aw9V;%6_h|=o_8tFP$AJq&`KUMMckD6+C)fizzpTI6;jJQ3Q>}&T zjB%}B-TOv!BGbB*_{p3=|KdozBX0j{ydSDH@tE+X?8~ostD`BAsYHq8UI_Fjliu%u zi7p$e_0J2&`gPnm^SzFyM5YoY&buwpD_?@MRJEa6R~#C?@?PotQAblEQ;8B=Z4>CR zZ!ZisV8%z{-Tw?(h9EiiU1Uce(0RaF3p)emhJ?&O z<=$1TZ4V4BLGPA`XhS7R%pCrGzozmiQLW2Q3oXGYDG||zN|cy>ba-mxXpe+G+sn6w zmK^x$GP6t1d5!l&wXVG;wCdB}E?p*~4XsOw)nQeOt8*>Cj+$z{KQ7RC&PznJp%NuJHw>$2*~?I^DGvlKco`)k z+E9rScbwO1Bd|MfNwxZ{ihWe@mP$mlp%NvAJh-XTWv@@QjvBL>Yr*R)5z&T9lu)0@ zlw~BU*7z+)yA61+B_i5Ti4y8Xxs6EZ`g+<5Te%IaoTat4#!;eLhi@7PjNKAJ8<|R! z*!{+^o|m6N)jDT#uz_c=DUqo}iOxLdOKC2tsn(f)2{tg7G$&M|M4#Kjb(H4Bnrf|h zT(E&Tu|%-1YAR9Utet|5(%fECtv`N0*udOgBBBkID6vyL_;BSlO0_;ZDYT?wYgCDd zHdLa-2JeQMsJzyy)`ou%Ex}q_BBBkID4{c-Da#Y3TK7*4ErHKaB4{I1i4ryKsZWRUyYrsvND1}AmU=e$JJ?N>JhB>}LDjmjPuQzr$5J9< zt5l-IJMRS=dmnFAw4quz?Gm(h89BeBL_`}ZQDUR>e&F*;qk=c^q0Z}2t*@2|TBCZs z+)*L``C6+IB`(@!Ew{1x=`VGdve;0qcmBJkYn`(3yp9q9$Ze=ZiH>n0=5TY%iybi0 zbsehp-hYRVls;kd!|f88(NnVeGd=x#s7V_!<6O9RqMmeg4S8PJ=0Ml0Qr@xM2U`TLw3i{ z|MyG>Omy|GYAtbU(7I-~r#ngnpwPQgmlFCsrZ!Y-&SK$7{c_P$$rJ2Ew4rq=QF_j6 zY}H3+hX@3Ear3uA8TX^VpSQ?8Cs9+ag`bBQ3GR7QB2$SHo418%OL^?7*7sHpUIxZ) zQzBD|5|gF}Z>jtYs@94t2X6__U{fMfi4u<=9K62rT%uaNJ`P%#OPUgyN|exekl*uo zKU8b{^x(Z>PAn0Ig^{QdB{YJR*vNGJ9JgLrOR#3>x{?qz)f(|lATV~D5}8Vr*nC3B z8d`n^RqKmC1T8#+O^Hk;O6XINUWaP+zc)M|m`h4T>|K>8q0f!IGtuKZKT+KE+e51w z9n^?mD6f>qsgV=ulLfc8Sr#SFc#E%?U$MgqvzZ_1uBE=0N4ZH{F?iSdb-#I}<$*kZ zEeL2ax6|KGD-xe?H>v*2V$<5!S^Jo3h?s}Elz3-d%yuhv9)2jI=l34)(yZ6dx?|MS z_U3?UG5gdv_kC}6N?e}xt&bYN^2`TMJHDzCC7xX#v)xLaZ`}zS`@GRQYp3^)8FhO5 ziB**-fnN!Mc;w+creE7-ms{Jv{q{u9c#A7XOPHMt<&-cRt+b&MCDwfpQTFLl_;^&GZ@G0-OC5>TDkm`-?!rqsur`Q;clkH z7u!v$4Bz9DmUZn8sziy>xT-Ad`A;8Ls>Q5t7-K1M@T-5TOdd6@WzF7)RaK&dj_E8L zZ)fyxv|ZWuah~y(W0%?MrtGnNA$q>;rY}_9d;ZTY?HBHwJReHv&eGm?vERx}y5-Mp zPwx^k-oggzWfs11BbO`eQtOBJuAX<}1ub(X?^4yel+Yb=mR)D>OpM!jYTHA3##`7x zz04-K>kIt~yX_A*9a!DyowHj;JpA*j)}@5*^zGi;@4OZtaZcM)dB$7VK)uY0_|mq0 zXQ#xP!-iFFe)+VPWA1CIszeEmSa|;P>VJ-#(#DLpuz`A+-SOaymnlR)-d%Ca>cF3! z)Uw-!YgM%_B{cGqWyoK<g z@RI-hzU>@4KUXbg4IO#y;)VU-$3H))`mgnW+cIL{-4(4%3Ehi^T&Dfoe%r>3x3~_} z%j~B&AKk04ububxSXpAG|$o*=c(QTGh*E8P2hAqCc*{Z3vMTL0DaF*7k zgvM$@UtRsPAEB>e{#w+_e!H&kXN9=Wb;lf6-F>COE!AJGTi3dj(3n%W=O-*V823Ep zuSLBaCFjrhs1U#U@L;>=zx`gz?N^^!*SeI@bE+&m(8lg>8{ccY!`|6eEso<|PJh2} z=5^X>2UedxYKfL!U)1YbmlAs37M{V|&R7!9pl7_r{Xo5ZYR^6A?ZVmJrO)nJUF)S! zM;^QK|LR(o5_)bJ=91I@^4ScVOFZK(Y@lAwK5IVtX5kES%4s`R-}%i;BmeT_{tc~5 z2|fP|bK<85y)?t-M9+8&8>pAF=(vfm70yy$pS4AGn-lIG`PzDGH?%G#)YlIAYY$xa zz8TDT3md4HtHHRfUn%(QkKMXqb@{Vz7};~<(G9Ij3EeYT&SG1mc6|K$8E@nnZ{3E~ z%T?{r^It0LKYCuYYIV(}&l|Z-zik>?mlC@7$+AOjt!=yYyczG??^0EZtMkW|7YqBS z({JioU4NN_M(%Xxgof6ogzn+8>^Acm2Hiht#((UWVX8$h zkKC`Jbt$2H(Jb5C-u}Gl#FiO{*zeU;i+<3BZx{EqLss}}<;y2}j{M|?!x~zb61oG( zGV{VK$6VBFhWT(Ye=X{zKlhK1io1y`&Yw^jIOVEMZeRM?hSsHo?qu8xZ=Lkb6?Y*o zfNIe%?LGOK!mj9|7w5HpcJk9B9zE%VhSsHo?#O&sluiA|lXqelsao{HVWT;r5+yWZ z5q1+hJowxQT!(6LXMw&-i4iZ(n|1ONSKjrwU584PNMkbC6^-8LnoV#&REzs4+?xV% z{)GD0pY@)B`=JsgG=k*gs=mRiy+>kPsTQ-*V(g}bjjQ^gy*8bJaitO^G!o{|M}2JP zW+U-@s1~!);u%Z{dp_#N%{XKRo)48Mp)o*z&Kv(5d&EdQ=c>hQw3tg$!k+U+^|%XX z;5k=`5*o|QvUdAb(_?$TqR2ATO{t6G#=QmUkm&a)nYbU_&zCNeo15T!&YyDU!oEv z^lcdTuNt*^tG8(WTGY#IwD7f3!u+eoKD(^n2LDPWO6Zxl`-zP;x7wfuexhnI8!dds zlrTTBF=Dq-ZSWISqJ*B^yT99b{_mq(;P0xI((?{ZUu8jkS1*N|exd zRkLiKtx>-_n!zPSZ)IMt&6fLLEjSRAgt;Fdeu5QkHV68hG3 zmaX^d-|8baoz}9UMF&+&_FcRaoB{YsTRK94FZ`Rni82xl%S6q;>p2^x2mRE_y#&`AiqUZB2$SH^tGdnT7KpJ zZFSa*FQv0wBCKJduT-K0_YASGq7Bu;7ueZXB_i5Ti4xo);XawNHHp`uTKI}RY~T)- z2ta<%RiXsq79WO!N?TW-PDF^A>RaSAa6>Eh&EKB1S4$l zA5t5tg*+CpfjlN9BHB=i5{v=D4@zyQ7IJ~W2C}P^h-gD4N-*LHe=fD5TF4jz8_4ET zBBBkID8a}r{L<8hY9SK|Y#_TziHJ5-qJ&1EQyZ!!xondtw-dBc)4G(PZR`_L8>&Tn z$c|7Vq79WO!9K)(C$*tk>^EdxC=tOL8nNLbYw4o9uxOO4Vl-f`&u2;yFQX--al_`i zcAFC_QG$EX(leN;7P1<_2A;v@gi4g)p1L%bWU7TMO0a>sq&cAyB^Vnh&54<6AY`_<7PN+l)jV&j0d!|~F<#u*+LM2Mjc6o20TC|6~ zL5bk{k*P!p_F;LCqgw1Y>~Ts&w4o9uI2PhwjYLhgc>l3iYf5A)QG#PS?m43k)#5nD zp0g>DsYD4rn{n?PZKxKXN9>)O5}8Vr;2aZU0MUkOab7_Tped25Lrz5n z8`?x0Hrl-fJH67l~yZ3r@sVsg~_OoH%FM_r7DRl+YeYTV=ac zuNVDeyGbvj-%71AEIc2oWqU&>zI&^b&>l%!WpM_t7h}od0ba%!Yu+l=vfaHC-~A3M zp*@ne$|6NxFP=M#=y(~=WAj$2mc?hBnERbayAs+XX{#*O=k;QavY4EgF?Tg@m1HT8pZB*);6yQiWO6{usuUYLWi#v#1iFXJUsxEV%`ruE8HIQMM6VrCJ=XEB~?^qT5y}p*@neiu1?l zWBP2tnW*>Xeg2PDsTQB@W#3t{Omy2SCA3GpRWVsHqm$jBb0k+g2%|J(9MHYdA(by@75=NoCA3GVbotp=(lw{ z!*$y#CA3GpRUrH~)pk}i=HZ7A>3sd>uYAQp87q#RQ~BSozZbqQ)Jb3#r55Hyl(Alw z2taN_B}&+No6|#H`KDk)wJ_Jh2G)-f5pAeM2|G7*+7xY;fI3^HT3D}O!{l3(2ta-v zDp7*A-#fQpqo!K4hx=b5q79WO!9HC7`-`R5QBy7U8^%?Mh&EKB1jj<(>x(v2i}xQR zu|z~0DpA7D4ZWv79g1}q>UrnTz#Lp6q79WO zVdsWUU$U@hL$$D;yAAUIN<_4w5+&^1(CN9`!mEKg`%1Ooali&vgAxJA`${EB*tub# z|6H`8T3GdA1FL9>h&EKBgq<5Yece+<8>$5_12(WamxyRXB}&-2q0_hYfX@hZ_LXYE z4}uM>=OqG=_mxVNuyaGFZx~#(p<3`oU;}r%qvjQ;n*rDssJ;J3jBp24OBVwSNk zB`jX*e=pA^ss%q0HZYeoB@la!btz$SU;le~PE;*;vakVvw<&=ba;!@Ui(mWS%X7PG z!JBj&Hn%q=5DSlWDPeJV|9g3jQZ0C|uz@wIDS?=NtV;B&*ILzre+?U0Ynu`{ zn}~HOVdo%PEl%Va>-k_#hw1>SxiQxKCQ;8Dn!_pq7rdsSb>~Ts&w4o9uI2N$KGG+hgt253Z zy?;}~4%?Xt#!7;t^H8|N&8>+=|jObuB+p^XD#Kw4qv@=MfigPN+l) zu3fuM#3_*Wm1=RlLcF~>p%Nvy2G4p7XH#lJwYcsgLf@QFi4ycB{;_k>hHBA&z{y5) zLM2MjCz}4{r-kcKE&4$?F=B-sQBS_2XhXH=m*Q-y zIiV6I=xawCHSRxDi~coiln5IrVgI2LCAepZeHCq}7WWD0s}d1ys6+|wed0Z*jZC$; z-@!dE5z&T9l;9pNj@@WOwYYD?*ewy!hDwy+UNk;~(S~Yq|A}X?L_`}ZQG$EwIG02l zs>OXY=8_T-ZKy;E#s=b?7;UH);{lixOGLDx5+xYph;w_ip<0Y+=P6V}=i5pAeM3C7N%&k${>7UN~`8A?R7p%Nt+ z1B|{;w4qvz`@#1q5wKCU|H&|yWZ52_h$mp~V)>eUrrP7xy?W$a7` zejg{}dvyNx{yd5k39KKGV2^BHK=ty~W)E{d{+{g5(W;ti-P{tidJgY~ppBZ=r3B`D z*hu0GZbP;9KPhMp8{d125)o~vL<#LTQ?~Z!y<1Z)`|7E;#ySNlrWa``cfMzQ9`dTAu`Mis24kT%tR<7QefW~_3|(O znn!C53-?1u^;&Ce=32N8eG1%0jf85A@73zWkGA{22(3#A%*SY95-;(wt6C2&3R+jJ z-pgai-4dDBrG)lEave3*I_j3tKR4f%_L~#-KcTO*E+tC68~X|#0NRTgz`jE2Wy}m% zwej~Ps^(X&S~I>0S{S=ciA*I*=-icFxoTN10B;GNs1m^|uc<@{9X*MSOrPi9t{>)L z%(Xfnr-W+R_hr3Rm`j=yDp3Ny9eTGsC#u#ZCj>3biA{-2B}(X>O|GM+T08zb+;hzB zC4#-1sYD4K3vMG4h#KGu5rM$&9%ZbSFHQ-6-}sz7YEa|Y<-803oc)F}dwtAE*&Fys z#AzSuMbruFE6Rv+t#x$x`@Ze@X|@`H_cCT2?050^BxdP0RO^gi1}!{; zC4x3;Dp3OaUDznkC91Vaub_pwq(np;Dp5k`d{efr&3m_|S~o2UHZUia2tc@Uk0GPI zSU;4|RRVhW7YOz)JV^EeJXZGMZ`&nm;5PK$@_EF4*0B%_@H$kBtMfONZiv__txE~| z63Jf8@40Hxf0*{GPkmpD9*IP>p>-)ipD6CtBEdNkJ1jm$^~*o?y&7zk2z*=J#}Bml z3@*Cl{~+R1i@KEHj8VFdnrd;Dz?C;8;_QREl+Y*G?;x){&OWG@vmNeWQzClEm<^QB z(UaK7xEf$@$RPuo(e6&{>(Clc=?apOI*~STF$kY z&p8KUp5I{r-htht^KUojZ`Q zO7NPJa~!v!THiZ4T;B8cQ1$M2wOO}R9zQAcdq!{7brmdLa& zCD`l9IgZ; z!8=$}i4t5t%6kKP7U&at9PkEiS+J_N@JH(wJpk5)wTL#JnEZvu+i`tK^uv2swRlZ< zCfM3Y@H+fNk##A-K1`w?ZbP-+JwEjApAY)dPa05DB%%$iO9`BEfJmYr;X0(=WA+Ii z*~&*P@)MJUh&Hq?CD`jp^uuka)}t>5Pp@^AuM!W?s`r1vXVAKoDEW!Tq<#rzQTip* z_x#LH8gLy+9L`&%TJ(edeP1_3v_bz0bt$1pR{5;{Ut zg1c?36WncMHJ}fdL^=J+Rf~QbR-6(MTcr{uv=7r(aTdih!C4zm6zAj8^HEbRt_*k{ zn-Vc(2q|PxtdNa(E3H5@Z1*Y@O8ALA-hEz5o9J>Bb@tV~23T9*=d zD-=&{a;on(RBOXyf{mjt%KQz}?g_0+3B273!Wz?cs_!;b>(ajj8_;S_s6+|cPEPgx z8B{IWTjA+%{Ec6npUl?v`7nTIbvsR%EoQM4(}QKUAUw-g8L$iq}z7ttUW{h);LO3i+d_~$R#4$P>B-iub8s`3$u@oYR-0uA<{=J z@4Qrt-Ya%qCBm$@jhaf7ps!utL8=!0YwRFPM6{t2CAeoO?Q3hQ#oYvU!X<(>{EbG; z45&*9?qskx%(9+CHg3G~@$kmU=RG;=p=~!Gv++NF+xdq>vn{w@VJ3R}`{D2Q6)z)t z81bwT`(5zlEY;!~h50HaezVW8#*>SUXsos2Q18m%E#7agSckJZ4YVmo*NKA=SZd|*u(ig)Uo1An`T_sBF zHoxN6(bfhVV~zOg^WlwmPClouT6`Wc5>w)pWd=3=X;*&ro!8e@qQpVV1{;G`$0%8D z*+Gq`jF@o8^>x+aQ;U(95=WlAYGdzSBN~fcb5C6*O8n`6t$rP6tpgi>HDVtlcE9?b zx@vJYz<5oGoyV@&*!%6_jq`>*Qdfx*zw8@q4EqCY{Md-`MhyM&BX!l{eh1Nyl=yte z(v7zFhBq#FenDL&N?iB-&HOqB-U}O-t-W;PT_g5;c0paWxZgpHBqc^p>(%(O=ZMCP zNek;LQKI*MH+372KLHz4F6-5Jz=%zcSXfsr?ssthkrFGc^F@8G-NCg^?b%R?5?^02 z+HHKc22OZi_~94z2aVXq2-V_#2j?FtapnH=>zgkc-Wa^?vJI6evFiL$ZsRXo!Nxz0 z7-PiBMyM8dML7RRi9`Q2x4zle!y9XkT%n;7B~}_9Y}6;hM(YD}>%TE#!X_&;RExVU zoK&Yok2y2zui2IF(6U-XB}$xs%SgYDou|RZn1^Q8A2Q+wBUFp=UA*s+5@%1IUSH5- zMB`_@1~*iq#NOKl8|U2!8?PQey}qj5^B?sX+)ypXjdA*#5@*eyS|9ko;f*b~AJR~X z5??R3iC;(G$6(_hFHfz%_~G!zhQA!rP%TE!af+N0-%Q!Re$ku58`m7YenTZne0QT@bz~zNbI%^$P>B-Tyta|s=r;g1-u!yUS$7$+zzEgi*$qzIQvxo=J9g!tu05im z5+&{!xS`lkLbZ5S2pcIeqxbk$wCW{ml}ePDcHB_ut9f7V*xE4SKSrn)&kE63De?C~ zZLPDdcYkQTs}d#t_3IzGjd0Ju`hHvM1395u+*9G6r^E)Gt5tfwHoP&%Mu|$4cQt;=ERh^?WpOMHEb5G_Z-|%i4uqW zGS~=ndyf;QR~Fh#y{*l=s>MAZ=Ju4RKQyxfU-URz4OF7U+jG|T>j-PqWFww4;tV5H zi}78oQ7Q4Of6cAzXsg!4~eZj7}yB`({4eq{?= zod?^ZGhb++B}-UlqKt3-+4yt<~_2tM4Fm-ni^WyILS7S>gZ zk$?DbDe?4>rK@k6*Y|7l6IG(bt^fOh+X%ks1#2%|on=J-=N8mei>F!eMN{I^u`5=$ zH}7>>^LJIE#NmB|jo?%N!U%ZC*BhZ)x(7^&!%kkc3NQQ{^TJi4#MF-l`*no9!SN@p zT0O*wMc3X_S1sLhro?H>4643ucd*Z0*Vk2|#9vnrHo_ify=4bgXBaWr_8+RHyW*6X zcH`RB&uv%q3)@GjM2UfS4)W^=d$s+I=xsZ%rEMRjTDrSWiT5{MuiD#ocgNd)P$f$2 zab&O&_MDT9Si^`#$4#!QmPRR3;)=6}R$sC!f7^DcDp8_y(HedoVei~-1fGw+MyQs? zPEumaeTG&4YrE~mZGWy3C02Sh*a$Izi;Q^2h|O((u38#_Oo?TNY+QZDq6X(!oIxc@ zY;t?Bf%t=EA6jeU>dQv#VQ~i4(nxAbtn%9MD&~^g77U!F5+yGEOR!-ciP>1rh)0aL z_^pAnR7+#MDY3i}j~cQ4n*&=_q6BUCS^Zm!SFdWseMVgQ*1%TPqCLdIQ^F!F)u-&r z2TpymRV7NW567K=@0VB2(5+~Xne9i9QTYL1cs6+{lg}XO{ z4U5TC^O#IUwRrz=(vT7sld0x0nTkr3;FxaT6K|wkZ^XmaSKGWerlMLL$B3k+#9Q`6 zEp1QKkw;Iis6+`qo453Vjc1Km+=xSunOspVK97jKro>R28G6{v@S{`Csi;H=&M_DK z32#mAV#JC@d~?z{71iRrg4kJuVJpr)w&HxU z(IXX=D8aSs%093$!H6A<->^O3$iFl%P+vd>fGZI-R7L<#zK zj~oFTD;QBR;!j4X7X3M#ZKs6AWGZ<~rm7Mp=%b#x32fYIzUcPmi~ePk6{@O5zZ7pk zq{KxJ&a5B;`9#ZVRh1|~Uwfz7c#HK?Bk)8$W`t_dzs7qRDKYNk>6I_d)8A;Z!Bv$g z!9Byve}|0$wl{dmh`oCZuBsOI2{>I!iGHt6tvqjgocY@isj5T??tNb06E=p~uIM8p zPBTKaxZlAkSxStzz1khN^E&V7^{XmTf_u0R2f{|n8T(frHDVhhREzsIoc5)}XP=L) z%(a=}w6R00Dp7)a(O<3t8$BK$Te;ncDL)xnRW0s6aR!+Zzq)@lAMG!`y-`&qN^nno z#DDQy2&+jrqwYZPQ8?7nPX)%E7Y)3!lvW=@MQG&67*-yj9T5GhmUS-5D zj8HAc1MsG7N<3+?j4LfN@#)#at13}~F^*RsgN-Qz#<%{{h=+_&EygwQ26jrAKa=G# znW{>ZV5}zCkeEzWwHTj)jg;uI#Q0fvhL}uMB}y>n6#D9l0pn*~ZNxmg4%K3u34N6k z4_S96p08msvcKhoYB64hd!7~zNd^)@5+G(xo)hs9iy5}&;?wZ711p9gIAQHc_aEr&UA ztVNyY8F8r*s>OIR=ERg(=A`NM7i<>2*5+N6D8U$cnA`iDFunf15#w#%RV~KFF}J70 zXAjQwJJ_(*KqX2r)*sfW?Tx_s;7dlR7UTO^qf%lUJDb?eR<%AOSE#B)37%PmwRRUf zo7milgKZsDEuK?gtxbtZljhf3ZFN4tR%ewc!Lyg(Gc0SwSR>9fLbZ6_0-qrzzOb{R zd+o~Sm|vn2C3uDue4m@`tOz^$;ivYjsus_U;QOS+2s^=g#k{5I=3l8q37&-oAMR)) z<{7bu5vs-WFZggN@uHpGy<}eB-p?=c(NISc`$B5sUpQu_q$Ad4L5);R+ z*ns!?SMy#~q6E(-gHQcKBla|6(2pOfs20y7;ZvuC#bo?s)M7Ffl_mTc15e( zK1wA@@XR~x)okb0Siy)FPCloiT0G~*UM(eFwiEXiZFje??FUt&1kdino^zSa)@v+d z#LJT>S5%AV_1JT!1l}CLYVh?7V=5|9g6|-Nz4LS<9y8*nwy#w!zITAVb4nbSzX9>4 z?ax)B1mC3yF@V#Jz>a=|5vs-aClCWjiBH$sxG~?N2FqBSK_yD?osbaASk~VCKosW> z7H3c`z6XL>MoN6&&OR`gOt5%~N|gBB@4~wuAtv*UX=C2q{QZHgs-`q<7Fc* zv$&5+l%VYpTk3BF&TF@Sf8Z?DqCLFzk`f2~;+O_JrmL>r&)+Y}vPvi7ZM-)q@B1#^ zXs&c_xCpVO4Q`y=*yWieN6r4?^yG~cju=D)Q)1&eN5V$-@}P6;Dp3Mu*a-2&LuVY~ zM0JZ>k~dN~@)6lgiL0JCu(9l8qucK|X_gbLO9?!i_v?NB!FsvE;RGWkUbug=#)2cxnX%?O8#Gj+1lC|&M>t~{d(Nibs;^szHi}xX2d$J? zWO>~2e7yIBTwkx77QIJ;Z2 z*NWb%ht}CXc_W1$Ahc3q{8v4l*k_js{(cGTQUX3I{vOUCiv;=#_0p4tR!S`M+bgep)7M+25+x9MfsN3++2Ygd4<9zX?c$veOZtlYHrUX9%d$V*cBbFK z7p+xAE!=-xM@sCv`mRp&>UC_=yWD^JmD@WkXjOQhp-8Y^?uwy>au>1YwEk{m)q{`s zcUUMPc?bzNY zHdLYn;t#M9-eEcOt&3)1v~RTiiOE|pj8Z@=C7>PtujcQtur4JKN8#U1w?N=JP%on` zEO!wbzj=Eru;c7Hv@Rt+?2Rwpu&=KE??tUAzV>|)Z)EK2^%FKGK?#gFkXgw@pQok##ok(Ja}5=lAHc9`c!+) zRZE|hl$hRoy4(1hJs-uV2(7|Xls-}GEc=9C$Ior{VU!bEjH+V3N{OSse5Uf~(Mz?j zZF8bZltA1U*AeF3pMLw6+ZbhYVo?jNf>uhb^i|I)`sys3+f~ANG6=-4VI!;`IZ-3Q zdKu-0R!Z0!-n+$2ccE9r);e)YT=rol@jIw_;tW%PzlN;a4rHH!7s@P_cDrFAfS~J=KHt} z_&zG(c?*am+VSnBN@wt|%=fAOcG|)j@O@N^r$F$pQo?+=>e-L}tpz@uN|eAk6>J1Q z(R?^>6@0j&7On$YDeC_u-_HqJR|2Pi z_4M>-1aXZ*s6Mo-VrIer&K2JpJGOXs_xYE~$=s%RGJ6 z;+ZFQ6Sah}-Gtk~ZbBtWpbXn#$8yk&L#n@DV#ArOwkzU!Ep|dYAI9G4FDu|nG2E*i z@QY)rtwX;z`byi~sYD5!V1o#6SsXQeQuU%f56Jt}C}arxVz77TbW8Je>tQWP=Drlv|f@vrEb(MXB6avPtv@8)lEur4Losu2As60ia5Y!$Rp zV*C8c7oNRhMYY%qh}@(EdiTexdG9)bR-s-cct1jHX{~wT4z9QUHp!bD&_WBLl@b=q z@ZPmphQF5q8`L7f5qfnWy!&C1iR!t}4;%HLLFXoKa&ROfl9m!O5=#VZfKWQiESBM; z#9|rAn;d+)5D`p?9qswJ{ngR!EvL+K0@s0hmEg<}VwRs>JIQU_x55L-n;d+)pp_C= zUKnPdt)|TP_cCCETDT6BIV&Bx5#Ig4oOsVC{}}bdev6VfIXH77LYorvZBDdtl&$>a z2PFbFKq#GM7R&JKu$j8bSrl5FwGnAf30V!Cz;zS}t{)*5E-Ow|>*eYLt(3qzi0iO* zu&NRzxITVyF5a2II+({YoWRwhUapCV{HMevotsr3{nMXj-2VOsRh1~gbv~R;96x1K z@2idNB(A6hd(cXW^Og;M$sR9^^7k^(SJWaweSp_cCxD)WUV3Og}iB-Q`4$gleG-tpf4YGrl*t zd*}W9y$sl(776ldUA2A`D*>>3Ea-t@JvswVl_2SIum( zomcX<2zOys^(gOoDsS@E$-;)JUin%Fs%Q_ow#vaaB9`cz^c;_ncZJxTjui9^T8q-uccOFGDQD z32Jd4jkg|BVy{nbZ~bAPbKA!EKC!A2B^VnB?`0qcfM?KR0Lj}Tj0Zp~C7^BpXa8#c z?gy@eT4*84jD7?gP!0bV2-VUuYqGa@KD`|gmTU*R4y}vv64c9BP3SAcWY*i|i#ChN zByWo_ii5sN3A-QlCExEc3im@LN-!D~?m1#hxDMQpq89H>O4uj?kztgmgz+oX%cxoy zyB5o+kDuGVr9LRd@zVPpw}Eo?6vn^c3?|O1!w}nfgbM zFV+5(&50^ef)U{`@2&|(?Yq86?L zS}7r?WL2JXL5nA5@Lp3wPU4)vNGuXOyMtHj9*QG>f8l_^TVFxLv;mJD_ zJU_?&GbQp9_YAvKl_-HSY{#9jUk7%=s-^EXq=fCZ8{BQHL=;`r}4>4d$l9(qgw1Y#FkRRqET)G(I}M^3A8rYuoj_F zRs64Iyq%q8ll?j@Gp(0Hmh_F{-=T+p;ae}3|G_25|6qA$y^Ne#mU}%VY9v&PHuCK9 zDM1_d->$lp(AJug{|l|MOdDPoGI&@<3@;Q`0lMzLVF}_mE{ccdNGzPx0jbO#+tWEwJcMY z6W{#~Dxp1+w#u@;dA)e8UcH_zMW zWz1b#Q$o}%3t!Z-Yq`jaQH)xozxynz zg!V{cBV*fPgbc(b8?jZY#b+D&giA!Xtx`gJ#9I|@aIQtGIBO$^bjb#Znrd+#?3U=ZRZ3`& zq^;t*ggeL;uG=e*tx_$n8Qu17x2;k_dn9cY*Kmw>dIQ~#lGrNM;`-X{NbI&%N@$Oy zt)jn!nSq{Dw@*}Tm1@x!>GrAZwpB`KkEE@lZ-_aAUS_wmPi&QH(QoT^hU>OfN@$OG zt3bdLM?T@%$fS$!R$_ic87q!`k<`n{H)WkrEzF4^uwIpjXhS7R*!NSNj^E#{u~n*t zxfV9^JiI9pZD?Ie*mq!^FhzTUp-vmBh4l(HOpb5L#xel>3w@;$C1^YOrmXLCREzd- z|4T%)p%Nw7hsif(-G*wh-}3ypR{682?G zCz7vhx((IBN{0K9=i5$+XhZ8#!oHd5MDmqQx1m~CIbkEu8=ex;hSsHosymL~NJ%csXg2w?HSPe=`T6Z{&UfWYGKuf4XmOiBHB=i z681%6r<06q-dCyxF9SBPI+uuOLnTVsmzAAP@F~(RHB6Cd~zB&HBDLWxoW}pfem;|B_i5Ti4vBtsEG~Lf_Fw6O$lT; zighVrd6)d}<-Sracu4H4rUWuI#k!QR+;0B&@;z5Acx14Fd)|~l#;I7B5|($#|6U%u zss*1BHZXRZ63Dw0>r%pUKKb8~g)_b9ss+CdHt-BKC6Gla)}@5yR`9=<=MvR|p9mY6 zOPUgyN|dnd5l)xqMAd>P3mfovn-a)35$jUIa$We}%X7PG!JBj&Hn%q=kT)aNrG#bk z@V}SWDAj`Z3L99Xni9zW5$jUIzVYpUFR!(#1^*g0u+}yuGL@%nqd|cRo z&(M^>ch6&8O4v8o{qNC}spVc@O|{@t!v=hxrUbs<9_v!VGCug?C#=7dU=pzYG$pr%^1 zhrL0GFvIS**Hoee`>?dfsi_wG4SSpt5pAeM366y%FMzMLs>S=C=c)F7D-&9m5**Vp zFF-+2xiZOD?_scJfG*IcN=9w>r#SiSIjsSZKxL4 zE5zHI6Dm=HYjDhp7;UH)*Ih*Dn-eNgg1$t|7!qx$7X1gDY&0iSq6B@SB%`O_bJe0B zgcFnIgi4g4ZdCzgn4LnTTu#t~=gXhXFa*TCFfBBBkID8X1wTydfe)na@GYgCDd zHdLYnV@`49j5bt@aVD&_B_i5Ti4u&RMGqj_P%XyG;4_qnXhS7RFa{VsnP@|`825wk zlM-*_zu>vGzFVt$eJJaDAn-E7>0(aQNT?Rd&{E$n%dWHE_f-(v9)Uqrm zY9v$(W!&?Wcq;!L%eMAA7L}k(LOr!C%ZVBZ)j}C#Hzf|VUp3->e0qJqs!IMp%H9O- zuj$(VKQfdcM1vqvNr_pCBqYf9Boef@s3E0onwp1PQ>r|shC{XH;Tq~1DwODt-lAGE z@O;0`qX=nA%wrK_P!vfJ;s5#Ub=LR!tn7ZWe{a2X9reF`H&+Rdols9L%SxhfLbZ6zu{{!-l)wMzkKcc& zgvU;(rH9?D-lJbi z-yC@QjMH{aCsd2aoTDOvSuNS%tfmqkJE5Lhng^2& zCsd2aoNFV2**V$Z?5q+VJE5Lhn$MFBCsd2a^cf-nFC*EYm!T3KJE0z6@=KBpCsd2a z^nD@$Zzysi>ILlWMHwgaY0c)Q+j)QUuT&*>r8RicDH3$|ybO3((|^{0edktm;C zddPK^DB;gER~^E$n}~EBXxE>1YDMCGdk2e!kAF~Ci4y*9+8(AVK^tt>-&$%#VmBL0 zimmXSJC!KmV~p*3suHxpc761rRwTyRm{`0xYj8s)O88jGoeEi2C1``~`Y1}RNR(qc zJ>-T;l<+a%cA-@X+F-jr8&E3}N7)=zeEPTVHdLa7&t0}}tx6;tXxC>oYDMA$xIL<#q`%|?}=4NBa<_G6CiMwFg@#_Q0wl<=6r z`l=+-l~=X=nj(STt>Mfv-Vc>{{K0lT_OW|j5``1qu17`GibNTCF;;7+LF#04L9IsU3@i__44cM4i5^031YS9L@B2i{0GLE|{@jL?w&vDq;UJ_}f zu4*M47=t5$*&tm9=MR;5zJ%?1uEyr5l1MX7Rf{&L6$#90$p+^^m3ZEVgy)=Wt}Tf) zb5^xzgIbZm?3`?HK39q7uSj_A%zTEDNFG2{i#Dhg3CZ=?8S^P(g?Cu_cFNzkWGgtzP2 zT53fC-fOZ!e^(_+Xl^-q$Rr9UXoKx));SV<$L$|~pD_;c#SHk;y)hT9B*){%>@j6j zhy5MeMJExoW_M~;2m{h@KvXg=5c76FE!u#cbXKZ0yHji2n9gGufHwab(Rm$eV_GHM+=aqD zA^f}TFY&L7IpOh=?i`84?d7vO_twERl_K6i(0vt?SN_NSs%W?Q@YYQHc`V6G9udc2^R(A4bpyt?SN_NGu&- zbJRA-`=~?-?g^m{TZ1f#!U@`-b=^4%FM%FM%FMjpe4l_@U$lzeA-o_dri0}gf{FQEQ$1fRJCY>T9Lq8+rVAS_|~dK_nL4|2yNI{QWEJs zuWHc-wIZ?MKW*LMXpC1X(Y+?z6G9s{CYD6ugtx0ZMle^u3@4QfRKUSD}X2G>;LzriEH-~7>r z`JyF}{KTpjZBQ!`<+olkdao++-x8AGZx?9;uj+d7A zBJpUsZg42RFs>3Me2lT*m{bYcV7or9P%9GG+n88Py?1a!B}({MX}^`J612f~eSD-= zBxIy+s6+`L^X)f3Rf0CyuFnS4iiFHK4V5V2bC>;gsY=iW+x1zET9J^Mv!N0td=9qX zU{wj)V7or=QY#YT0W?&ig!>ZqTe2!a8*JD82Wmy)X4^AS9Dw|;N|bP)$bJ)7C1``~ zx*tTXNQg()P>B-m+u3jXsswGYUH9jx6$$Yy8!A!4eN_7$WR;)|w(EW=wIab$+WspV zDpA6HZT+n!DI;iu68FOWn6rTqIIFa$2tIW~+fu?~2J5Smpii9$x8czQwIYGuP5E~C z)D4v=;jxe1^OB%Xoe1wMkBX=j2|Ojq2A?aHDB&@jJ-a25p2Vsa?NKWdc-oT<_|y%R zcsxkLV^MntOM*UiBD`IXQmGXQytO&*IeqGeN|f-J+QyQSpii9$+F-jLZBr`}k^^X{ zLbzLQ%PbA^FO!MJN zfO{~6+x2WMwITuUHQAuQs}dzNx19Fk zkSLs>4YsSlaEt`saRAAV&gVMsqUwC|+kf&v`J3t{p|gRG+Ni^whyxBSe|g^|bi6`! z=%jTcW(FNAc}8jONY|oTs9Bwe?!%TtxQ#;FQbNc4XhXG7dpp_KW_)%2NR0JWp=~Ll zy%24v7HWtm8)qJ9b7JQ_C^pjf09>L(*S)JFHELET8>c)~oj+isDDQcpTBxL*i0yk| z)w0Z4+8iZkRj5P>y-%j^Hgs%91?psD+mov^j-Hijp)PhJ`1I-ZMH?znLa#3oMR``4 zdSriD+cIf<64e_FM4?*WS;6vR?5i$`OeIR_+ZAo7R_y@Gi}4P&5Wvz~Tc|{dmbbQf z<@)^m_DRcy@=evZIh<9dT60%0g3oT(gi4f9A2rx0RBO_imObS=*d>vvLDwZ_ zLguDX1wLH|tIN9|Y1*F0Mu zzjTqJ+*qc1ljDmiJqaFSAOFlbEuvv@Ip{ zEinDkM*0E``-E#A{^Sq6=!>-1#P4i8E7kILZ~4QrRsxvaK|d=#B}(`i@`(vHnm)C! z@bXM}>>kdT?H3u*w4oz_k0tZlPzNjQ!~=R|oCcx>`D~@;bCFCH%dy zRWh}qTK-1;@3Eh!-6^!uBnYLaUE5N^-+x;rQyZ$~?|i?LmZn`cw9zD*Hnc4zd>pe? zGPR*vK6Z^-_lvY!h&Gx;(}uRCgg!k`PXFx6eNN@7uFss)4qB3Sr_hG2*8(W~4yu;V z)DQi2IRv59yY2z7EhXIhu=QHCp<3>7+;Z8cX%%WuaPr{~616Nn|Qf!Xy0_zobwt&mho~>5|A)qJ(FVT0Jt=^1KE;vKFG* zyDCva$73kVQ=(d){i2`PLNsltL)50;bsFG>09?4uXr2@ZA%Ha-I@bX zEw{%UKnnpw_718<3GYLWsNt*%)$)F0oY^IjsYD6Cv#lewO8kjo?Cc{(OH@>-mX9Tj zqq-zg)dluD+fu?uzGie+lzmmGmXCIf2V00{@2W%zAHkbZYSV^l`KZmfwuNZgP>B*c zR^k`AgNHU=`FL34tV^G0-|nsrX0y5*>(BY!Ww~F0coW3X1N+of%kMu&hDh9Y;gH5-3x+j5 zeSS<`B}$-zeY(C4zekVk4iGPb=ng`){E4C87KtZz+`RG4uZA`DJGrf{5+w%QZ8kPL zjW!ApD}h*dN?TpE{E6W_7>WP+{l<+IKO5HA`OJ&zDpBI5^#`Tvm@$Jkeg@+6Plq-7 zo^?@Owfu?Ud>)CJs}5}3i7U_VxwWnmB~ZaW*%-J!YcTcbJ+Sc_h&}#%YhAVcxuRbZ zi6hTiukq6!!y6yncwb#5N}#fRvT?ztv~l*C>opDs(R12;b=C6cmHt&E&KtW{-k5XL;<`$dSlVx+WaF{)?MrN5_*SEo#? zuZMfSRkuM6)$&-DtKpHjV8P|}0sk7-7`NBphDww`ZTfT_t365^e|-7!`U@WpYkX_( z!41{&h@PwZkvRRFN%bq<9M-t~04V5T?+VsiB4?d=i_ir0pzY@gg?+j_EmS=RhwjGJ0qksLkxPzO& zyLCe)N}z&$vhm<5-0w4YPXGE65U0Mgbwjm0qr)}&NZc@RM*G8yhc!01c4$K-N}x7< zva!Khw9##Y8SNb)wgRDAp7-HigGl_o=lJ%&WWyUzUO23w5+zWY_8rv#@edHH<@rnYRV4o3z!{@vqjxt!@2W%z)TU21?4Ez|jTxinl!R(|Mu+!2 z5?glkuXTS7J&UJAB}$-zeX?QC?#d7MuicK`?Es-#o&(~u8;Jup99KIRPx~{Yhcr~8 z#K%838}<%fb=%n58z4UZ_K=2Zc@Bv0U?eU%XHxB5ytRAdJy(em%huQ~U5AY&pIkJl zHWkF$AXLk9KpaaV@z8?HYmZ~}ITz!VN|ZR{d)p@)HYWb!<;!b*F~Thcp<13P;+PnT z{oAJ124WOlyT_o0N|gAY+s%fJ?Y&N)R(l^K^>~cCs^u9dj_r{cICoajs>oBC-2}kJlz*R_ld%P$f#Nx4>-JT>GOrkJmnc&=ci-44 z*)SjOh--V~pMc0tSX@^vUs0kD7m2xpSIIwy*S8z|M3pG9_iCe(4f93o8?TZ#K->sF zQMG)Pl)h*r4jsEzPVe<5c&{o^;^Kdq4fClt0dWwBf!ofjtCp{l(x;BZ@n@}2VtE7x^A~E&%8|R-QD%ulqluDF%{lD^b9Tuw%0nrzc*Yk*@RLj>=8LLI& zfoXI)5scJggk>vlt7*OWP|yKEL*zK(EMc(2O`g)TDnIg66?M;EazBq=UW5X zRieb?y zaR%<-Yq*085A0J@i4y)S+`AKPASaWTIhmSj`Tb|ME)vMe=q!hO4WC(uS;5H%1NgHSE^=eY6{3FKsIWlknni4yLkp1mDyjDj!vL-?W-w(Fa# zmiwjL2M~$Z9-dYE2m0#v5&d(ODB-^L_h)lY>VY8UfmjGawcNkv&VfiQDW=u_1yBFd z6$a%hQNm+}m;WDatb^F#B@l;n8PJ(US4|+G0uX$2IneK!egJ;52B52 z5EXp{;#VM4%i|rc(MRGb#Al%)N_Z@~_qw#v?Xj`7yFi??>yTWvJpSYkh)C@JK>zf#zwpl1xk{Aq znEHgbm%zqN5B9G;k9&R(2-Wg9n!9%*(SaPm?-0?Cxpru-5+yu0F#9Rm*l2?pqiz7P zCkWN@d;oXvL}CDP8P_8-@yUh5a+N6IIgVE!rH%8}89(YS5OYDOmghCND=ZT5XR$;srZ<@p)fh{SZ{mhQ2fOs*0oJm+M6^_z9Zx8DfjMO=q!d7g=V6^TcX zBb$oe{Wf}6B}#bi%2!v{R9+qQCB$m8#d3`ZPpE($PRHB6EmTgQNi>&jD zAg%$STAoklm>7w}&YD(#4x{KE7|z0e9gk<+WWCKk%Rah z=0Vl+bqdb4kvQt81@%#wosY)stP&-B?ZteC-XO+;I3I*+`Faa|hDdydwW9lR<#XYe zs6+{0Lo(mz4_GUD2gIqhi_A~F2h9*tMvElq>Bq!J~3EzEql?_*+KsFtrs(x;9Dax#rFCsR|2628W2vB4CqrB23Jvh?Qr zYO3Yys*DXHu>fnrZ{QC8714xBl<>7;i*Z)NnlK}lAAnFTUms?S6N&y5|3GN)=Y_RP4F*TJa;d>A)cAf^}Q4rroT&r5X?|`v$Bz|7*fOr$}xk{Aqy%d%M zI2QyX`r#l{%lA((2M~!x8x3tNK-OSYarunOoWtUoiX8 z(<_afjc+HYmOnAf2u5P)+!JXddwJj`b(JW=W7@EM;!mefPDH-*?O{iXKl#jTM&bs1 z|El++JIws^neB=2wv^zz$-i6f^}K0Er7K@^jX7aQioe0sio_k4AC`#T7c5BoOS~;5 zic`(TgKu#U%i;K9)@fJeBNyTe8>;0a5i`w^*kix}>B=`T|Gk=tb z2M_AmP%R%(nK6&VE%?UPmtRetaU;Ghq7o%I=F^7d^!NXCpLFH>bX%iQ)#A=7YDMCc zXLm`&*H8RrLnS_!kT_xHhRH_v8QlBv%pKzz?V~On@!c0UOoX@VGaOeiBJunKJ2l=q z;iBmqzPn{ZB}#A(=5^Q_%h-!{OlP%h)R0D1i}t7$iKVNi+D^qk@f~`V_}or{z65R9 zT2YnocHQHkRwUkgpnp26g&Ti2?Jx1Rl<0K_zYS39`1=9e2XIQCfsLI$ykO=N5APOs zq`2qAm9a={e|n$BZm0Jd`PM%BHdLYneLLE)wY!yitd-8{kxlmsJ5t;Oq*f%>{vv&s zv$)_#6VmGSk`(PHEMk4*bZye%c@&-3rLUc2j8 z3+pfU={sw?KOGWwq_{`U71v0t-+O+&?b%yr)$W`W_I@zlVY^(dM#c zaLz72OS>#wYlm;~n*+6u!=9=Vb1#`$-*=A{cR1vKj}3cRl!#}w@A^NkP5kk%XMKim zQ+Y(s)qBq%@T?wujNeN!ds%kso#)q9==0Ug=Z*t==;F@_P9=T*@t^XIRrL$6r z63o2NhV|~vJ*U+detX!ATlPCX^p(eLw4wcmy=r%#&o9IlTjH#$TDqdN_^OpU&5$$e7pwt zmmI%oxBAM1uN!gPdq&U(+x6(4J6$3%^v%24$KHSOjGy;BqoEQdn17%R+rx6>+gGOg zgWK+PM%eY@Sqf@Jf<0^h6=@HPx1|L0DE@coRtR1P+x2XVA9oUuzj;^scH61A4sA<` zKA-c8H{Mt0FT8Tp7O#9dV{2T8YI)X(eH97ZkJ`)ob|1<6p%Nwd7SM*>bKDPpC9UB7 zsA~DWi3FaK^j$SRS1PH#U9`bxEX%e(ZffnS|NG+(XX8CrEqzz`K6Vn>*QO;KzsCDf zeT#Tje2d~6wQ2A9={o)kqmO4fspVN!j#rUb<@2X&UmUyg%p7B)N|a#UmuF?;?!n6z zCL8x)Oss10tf&=<@n6{Y;SR&tt`g5DlVJXuHf;VViNXnQ*R$NziUj7UoR1^tD3vI& zWG}N}^C0G^yxS-DZO=JMwLDwTc`y=~Yx6Oe44lciRwYVsJ%QI@^ZBWL2J)bRF~=RO0ItB)Bd@8|IgkMDjAKTC_o}NWk|=Ht74P#MfI$T)68_$%gq? z@O|>1OkF&kzK?48DiHmvNWh27FZ}y0Bk04aL;gb$a_iauObi`PM|NUZwl zKB;%>@GO1Ji(0!3dpl+ddSHJJ>;qu&x%@+XdiGu zx{hmlFHJi+ye(f{On&<>&4zjUH{e@(-7m;T_J*ggTE6DVXrc%NqKRaK(S%Br;4y7m z#B%KP$@zb;_^nx^5Ec1)Eh8acA7<=y#C!Zkj>l?8?|Di-YRH;9T#x8ZB}#Awn}qGM zIBD8Z`IWsMp49_Uk=jsN&oIjd&pk1}d*|DBcm~m(YS9MUfJ=} ztk|v+em^X?w9$)p2RGkh_pp#wlUXP0vpq%N%Z!t2yFU9+D-xUs@jhgj2XmDu;q&8Xmwb-C;yhU9G7`b7WxGBnGV>pa zt2%bd|9#=!iEbuXOx*qq(MP7e3A zxS|w^PtNI+pZ%THN7i=VH&=-g?mya^7yU$>Q~^IR?BsBtky?@XWm!jY!H*`SeHpwC z*Wz{X*!^HzyDN#p3Dx2;wIcCCSr76_)Jjo_`_v@dpSN|+%~pM$n z`|w<;jKqPzm|2_m%N2K+cg?YB&jhc7Z7Jc=%l6;reuiHT`fREx*dip2Yu_en8laom)& z_k;J`wVd#ny8nyZm%-Ti?%!X_Tt*^X%j0P7dWb}~MR$#Q`D>TV*r(?ixk{Aq+<@)N zU=D!qAaVd(%uhVhimZ+dF~WE zxDIX0^CfK8b2Zji%*jld_}L8PWWsI{&*HGJB7yr+U+MjBBY8hmqJ(Fo?4C2X#OvVw zsA~DWi3FY!5*eQol~mtgUb#KH$Ys>WPfNLs@Sf}Y=y^CJrXkly8_4yAeHnaHc~*P} zTi)7q9eit5%d@8(uOhJ<>PP+c`ITqhi!o6pN_a-t#@#hmdnegA8e?Kri)TfxNbF{{ zu(K6WKT0K@Lnh&wZJR$zqHx07^~^T4B7r%o!M@@gr4l7P4{!4z^X(fSelK$wVV8wx z=s6EYg6js4G*T`jSBVn7(qQv>eT{)Ut71Op+Nu_>iCU3>2av9V9)L=C?1Zn2m|s#7 z$!Dl)k)T#2;QJ&S^nFy~Yb+#ueaHMO_&$xRF8*{neIM2GH68j_k>Gk%najvkqJ*zg znV-n@DBeNjGV-bxuY+2VkX5qW*SVB zAGIPOD~f3c1Z}t$uY%VuNy>(+ETpsjnDKXj@9~ zn6^o086uW+9gJ91%hzie6-5G3QNyDml_=qB!i>UF&4=qQAyienkmkyrEypL*mzcIHI31p*^4Q8WM zQYCn{W}~cRmfcZj7H7XPM;!hodXm|p{l;uN^xbrfdeZ6dm%YcQ-D{sYp;|nqRwPi_ zI^983wyvp!$4;OwcCvBM%N%`5g0-*{p;|nqRwPiNJJ~=@@0v<@>;x)zCma9s55|Kf z!J6KQP%R!)D-x(Qo@{)4R(nk)Jaz(g%9D-FKBT`}5``10#batk;>oi9;2szgRl;K@ zP)R-6_;}sLuu&3)6RO2yYDMChvX0^+)KOFkkDWk8_+;bwgFb-|Egn-V5^Jn) z^&tD99;8Zm>;x*?CmWB?{RlQnqHsdBcucKG^eTOZSKu?KgvU;-@#445#>9WYMoAP- zs8%|LRwSmsXZ1PjsL!bq9y{^J3wKF2>is{2jglywP%R!)D-xTOeqw+4i7Mf-6E}Y` zCfS(S>jT&*iNXoh;xV-%@%d7#mpTvru1a|9#I@Vil8rYudmlDRqHsdBcucKGEVJ5Y z*2Wx#6bbXJv@ISxas9)aNnhbQ0-;(wW?w}Dy<6jTuy<9$V<-B}8k}s{ zJ+Bg~#batk0#8Y@!KXweJa*!+hX*Aa_Uu*()#5R=B7vtp+2GTz5*|D8pTdNWtJF(}_)=M^QEU6Nz#batk0;5l|!O=%0Ja*!P4f`b;YPBu6@tAxi+Y`JmoWW#)hDxq3D zrdA~2Wh5K)GE~B2C$_$Bm1M(wpDLkRJf>D8;4LK^^p;e@V<(P1W94MSe7Gv1T0Ev! zB;fTW8}#~A!eb|Pc%oObVZLaUP%R!)D-vbxvx45MN_gzVHCLMrysL;Ns)TCsm|Br| zy<8bRqrqsRvn?Jw;kKvu;{M%|D4b9&9#bn4<&|gXtGY`3I!JgQey)>11HyOnhmx591_l_=q3%x;ge zdR<8rPS6J1_0fk~kr-!VV)o*!!3~ut;bUdLYrX~>B~ds*8*JA{QEEk^9H}#m?G2SE z;bVTky;p<{8QT*<8*JBS18PO$D4V0QPyhDahDwz1xoglzv{4d;6UheJ^;wNtkvOAV zS9=5d$W)?)&%yhgwi0ZVMBxN&uw9>>sTGM~<+|EZR6kXT67Ea%ewQ{%qHuyX*sgmS z)QUvu$5XjHZQnj(ST>r^t|j3ywT&euk>2yF7Hv=~5*U4w4URr4@%WsC=LT#{EQvH;Rkdh? zT9Lpgnrv{~Rf*>rNO+FJ#`cn6E+Y}%u4g}}6$#7+$p&Wwl_=r48k?g^BF!IFE!v}2 zBrvNb8=Tct;&~quo^!Ifwj|O#Sk z;AJEm^h;FYc{mcD12o^KB$(?!lt68#WaG9$RU4|M9$*X6 zw4o9uP{AqL7>%#2LRp?&)lv_zg=pGPi4v&u)rAe!QV+08g0%sgZ7G2|UtRQ-YN-d< zC6TE_3Dhx4Hd^j^rdsL&c1@^63Dhx4Hd>zDOtsVl?3z%C5~yR8Y_z%lnPF@D`$JLnTW1v(Q?#N45O^ zGpFAr!K%8c-`SQD{!BNk_V`&9s^!ly*Cx6oGLlwP{1Oe7@ouWS0c1%cs6#TT1vG%$k~LKK--kPPKgALNsltL}V zN_dW=Ikq=#sFvq7IJUPCO&cmv!gDpvIjU(xwLCw=IjV(d+E9rSo^xu>wM`qU<#{H~ zwJk)`hDwz1+*#9SXxdOM&zI3>Xd#+5RHB6E0Gqx~(}rq!-jBXd3(>Tp5+zVyF^w^; zKAdX#$~b+v7NTiGB}$-9WU|rfi>j8d@Y5GKQra2th6 zlyKWEu|c6)ZjU+S7NTiGB}#Z7w!}Ei>!|K}Xd#+5RN_6&EVn-kEwNgmT7LhTdyho9 zFFf1hzKNq4f8ZO}9qf0FMHn;i?{?39C%F@z^VY~B61SH*{kgXeuBk)`#tgJ!&u&Q+ zPS6IeYh)3L&C0cj7qH()B}y=6pbdKmOQLXsHfUWVi%9HNuCW}C-=C{Q3C0YxVPi>2 z6i(0vt!rcvi8sr&qOW29l}eOg%s?A9CYD6u1Z~i|Mi!AcuUzw*i+yA&QGzi8ZP?ge z61X2m&<3q*WD$v_18nVX8|;Tui4u$%Xv5~Hk|>;@4O-X8A`*L-YmnDrU!O{pV9Y=p zHrJL!;RJ2ax<(d}_-DD6dL{NJszeFK476cBLrD})&<3q*WD$uapWB-72<)>|i4u$% zXv2J;k|>;@4O-X8A`%_={UF}!?0W1MRf!Ue8EC_NxRNNGpbc8r$RZMJooZ|JH(}qa zN|a#CKpW5+xWjblOPzLeK`SYh)1#oK@N#&9hR8 z5{wx-`>IN~4UH@!f!?k0I@r4^QGzi8ZP-1p65dxDSwsR)NwUGGL?ucvW}ppwcB=$! z(7Hwzk-*cQZ18DUi4u$%Xv5yYDnT2xu8~C~@Yd$+E55ZVQGzi8ZP-{+C1``zHL{4r zhX1tv)JJ2yQi&3b8EC`C#414>w62jwB-SnWQ_sh^s}dy`Gth>O?Nx#{Xk88B}y=6pbeX&sswG&x<(d}z^s;Ra8^@^5{wyW!{*v5K^wHLkwqjhJ0}~QomHX) zV+PtVpP@?72CZvk5eax1$p*a)l_){4k2cKrsS>n7>+Ty;D-!UQk_~!GDp7(yDs7k# zS0!kJ?YbvRtw_M@EAPkPno5+QuT2}~i&hERV7u;-Q!5hiUXu-auPRZ3F#~PjT}Av+ zC1``~YGe_KatC%cuYF>>N|bQh7JvAjZ6|1h*8Qxg6^Zi7GkC~#l_=qTXz_>iRU&AE z?RxK0D-z`$%y7@^DpA6p1&crAo+pAf*seb%)QZH}A}~l<;TT*1SrhaDq12 zu0QS6io`F={nTyv2AxWj@ORVJ?nO=AEXq718V~njqmPFwM zZLnP*eW(?Q>upTTrrtZap%Nv0thBY%k|>;@4Yuo}D77L{j?@{(_J&H7@G;-kgk@|` z1Z}WgpAD!LiE_rtFh@01qJ+;~wze&ER3d1D?fR@ntw@wJXNI}9p%Nv04z@LVnQIe4 z8*JBSXKF>F^Z@8nH&mj8`x3U-KzxQo&<5LeFN0cS7mK}gytSV8$eIna4Q4)m{ zw83`WTcTDZN{=jq57$tM67JjCJ{j@h53B0up_7&fAl_=pcwT&euK`%TJ zw83^g+NM?{BnQw?i4vY0urX0`0EwUtw(D5~YDGeF84Z;v;W-W)+a;Hg2-;w~p8cR! zBrqGKzT#}45+yuWV{=qVr1_(&MSIkW1ZK5lgR`1SJnuuob51tbmPDEdt6H={tw>;Y zPBu6@tHkqHBs_O!K0`^Q`Mjz{8`O#fyo_XnUWQ6|?1bk4&G#vZmlL z7PG4EGanDjk3>CT)w<}fMzCgaBz}mBw@<7vJnx6P$SP3+Unxm8>}w=tjof@F>LRNa z>hYwrV(sNflr?hmPf@K|B}(AiJIRLCd_nag)-2AugHSEh6-qXaKn>|gpu$o9&98># z`=L&?N|eBNf07NWg`bfzJYhg#?e^Bvu#m|Q2JEPvVN|eCYh>{Ka zO7qV^eE#XMyf5l)s}|}!B^#{i9f_H!8-6FQJiq5wR*7l0r3Ajil>TmCwC;f#xvzoP z19ihy3-zj!4b~=)#F40Y`_mr7^N&!?TqR22ds4}U)mT6K%=PlaLG+wSjQ29N-50&3l3-!a24c3Z}L|G#@zYO*0 zRiXsG)|G5n&HIy3Blnem4$EIdJ$ltb9kgVFHSZ%adTNjS{qDo_IY%w7t3(NWbu8Ji z@3&99u1Ee5h~tl6TvsjBb4xbJ8>)pmfyu_U zC&RxA#NCg~sy&CkI&nmQ)|F|tr3Aj+m;P?`4So&+wc_(jK&Te#9VQz;d7uaD$_Vko zNz-Z{b{n3*-F*~P%YG-Og6Uf(UY}ngg6~F za<6!ESbqD-Td*EWQ=$aEvYP(R+ALXi^+l6vZ-RK@q%9h%g*uwa#*K&*A~AQfakV8F z89vO1u!2joEhX^f$nB1F;AzxG?)!Oh>@ znl)dV5+(3$%k+1v|1oz?|Jo7|r@pgwL$y%XG}+i@d{5SV5#k2a$bES6uzZ7ShqC5N zQ=$aEzM1~c3MHuZiyFBdAhrUbTBy&OY@B&uPu71C;`cqrkNQhCJb&`SVXWZNlqi93 zji$d_&6hWp?K^5Zh&Mo}7V69<8wVWPlQmz2U|fJ2x%r}vhqLBOQ=$aEtlIoL^|QhW z)k3}8rj1B+TXB5*-8ie4a8@c&0^fd3Hmt8+T()m}1H?Z-s21w}Hv1|P{|_~CXQOvF zLGP+W34G}`*|2;5#W!ZO&nXGjLjB@ogZDfVTXyuXcYkeIJ{M1kN|eC2c#{o#c2|D5 zfBkm!ZU+d}LLKI0gU@ax4%l#9{aifl&x{_zx=YQrl)%@5)8FkKyy~{G^*2C#{OutP z)j~b#WP|TuBrZXX+;{QT?v3|cB}(Ai$jOF{C7)b0sXi6N+8|U5b+MBTjwO+J2o-N1 z$LMn|#w(R5f$vBs8#X5X;^oWheKEo<1)*A~@11OLOpL_-ZPV%lF^aC;V-PFRG}}@F z-@{ISx3Rq!YUI9;k$ODFUDZOJ@??W!dn5+VomGDjckn381}aekU;j=vY>wLEky-VZ zL0knwwNP(8+29-%iQQ2ncOquBUYG|}q6EHAo^04$`=dFJ*GGdm4)dUDp>BM#!MQdP z*G^hc-x;&>K+Mi6Q379MPd3bFxElmLfOSBq)+0;J27QJ|3_^|Ehj8Uv!pl&J68K(x zvSGf@qo|R~xpr3&s&&%sw(EhuPb3bS+M_WW_q^xPi|Z;;0$;RGHq3`R0#$WC0g;`s zxUO2qEH)eT;UX~?HF7_O*S8z|M3pFk@AoGg=8M)*BewzKM)--Ug%5wF`$1nc5{IJV zExp&9;JvCu2~-$JHq58q1jIog25vjAu38f(+HM;9)R8D_tyj=^? z-4TcfRiXsyX(SsKbKVSMAc*5mZL6!+MkkvM#+;G(4JzKE#(Mq^qEwYAfvP0QhQ-b^ zLGb-p4TNg#v(7H|o+EaS#5h#EeH-!l*ASnpL zs7jM;z$1Zw^(AW8G6yjF{Q>Q&bbL*C&St`so&X_68=ov7nE-W@i!2= zqrS6h`E$$~(vet*H)<8UQ758KwMvxmchhQN_uOgo#+o3WYHO>hmcNgzg&m0vFfx1{ zBf~({+g6DZKE~MBrZ)$%Hi&0XZ(Fr|TwzV`Nc6KR;Q4S=0au99z60B$>BaZM#kxG!Pfp>G56GKc{nRLlK`TQ2*Q^>NZ$U_?87pAT>c z|L+&wSs$kGWCb~ew^JsS1tF09{TGN*2hUL8FBDY3+m(GksYynZ&tf$ zN|bQlj$i!Gvc4c{AT9=>TJFzHJ7~$6NFXOu-wB>2ax$!TlWedpCEQ1~`Ua!mi~bPA zgzfs~s^xy^wW}{-eVo*i5wATwtNssM`Ryb6vp!B!qJ;a}R;S@W5U78iF9e}l?q82P zaWU)Tq?U|WQcSD=3!eU^D-2?_o2Enwj~Q4=0;`vZ4PF9qNVh?`YI&Tn+V>Z;@=a>V zh}B=cy#5?woCSLgW?h-4LAV}@hcFjil~U75+ytqwQ3&S z9vfS~3&c6Q4#`!^Aq)~sFAlqlgbwbe1X>B0W>=W);P z0ijwRM^D{<5o_0^mW=2?4&Zl)=*L_;l$B_j5+yu0z)CAww$TPN+HU}{CkWN@e888r zMPni{0J)6ok(v19!eOjLlWedpB|OJrb!E<5XMFozAm)NlEzfI=*?tjg*QA!3m1sOC z!`d}Xi4vZxX(d$4^E0#&iRs8K-D5c!R-$RzP{MOg)>pq-XZ)xeLA;3TP%Y0hv9BWW z2y$do(YxP9@2W%z&z;#F+yFVUTS`K;JYU9p9*JEa=wG8x{SclKl_=pkKzkDJe6W9Q zE{F#}sFvsb`0PgF8=sA>-HxaI*0Doaqbl_k+fu@Fnf4C8{^;1+JP^m={ZK8>U-BJ{ z#J7-posYNn1ia@eQNnYwHZpwwyh*hgAPxedTAqjHSQ3dPuUuYRjL~NfMjw?Z;kjiS z;l?8C{33{JK&Y1IlQ||v;;^%()tEnml@FB*w! z#;%p`1@E;t{9TnO;cJuTQ|}4l5D>S5P%U4Nq)#0QPX`Ga!BdLbZH-m@!Ty`eUWK zAEKi55l5*+319QJSZxxBo*-619Hm;m&dpdY67OThy(gl(DToJEqJ*#ATg=H-{gpu+ zbxK=JwS2vvF=r&WbAYqKGQ_niQNs5iSnNCv#G@d-jks2|eBS|M=Sch9HCPpS29+q`dqOOi(Hna|o(6Fm@(ilw z`#_k>h{QLr_QA1a0`es)Q3BO<()?&SnKeMrZ~yhe0i#swh{J8~2el&cbr63CaU1eJ zDpA61TW)D>5OY9WyKq3eYPmh;mLh?wJ^3|##*Zwk_P`I^Htmz~ek*J6q`zApPAfuJ zwYbZMTD-Gt$q1<@oc6G|#P2_~P{An?-&)H273&Fq{2I=7SD=W zk?}cMOoVM%ZBMGHL zJ>iCG`KZmTd?ZkjEkE?}Cq~?eeSIoXg7XT`(AEu5^)2<)KHb)6RJGVw)QZF>&o=7` zH&o*D6$#X+OE$XC;5Xt~Pxz@@XU;$^xvnamHS>W4exIqlPr9TC_*4NGx5|>Iwf7d+1f-{sRg6E3{$jQ6*70;qAItL#;?i zJ>j&6#oJN>wGWexzaPN;45#!Nn2#JgbL0~b?-q8wxOc|Yw@7S%dY}A*|H@~+wa>l{ zl_){~k+yApQ0fVXT`%rsQY#W`f02F@mtF9q326_Dx1|LAVE*0KIZL8&f_=qy-CL$s zBu@G~{kAXLc>g2Q9u{v)3C0ZkyR8Y2`)XnBsk?UGVfdd83A*uO&Bp$wGX6>~N zhR!MX^^Tj8 z_Q|+J3DmVs#K&uJpA72>KREsGGf=-a?5yz&0(Xc+V(6Q9jXExCA8}gGGa4#Uf;kS_ zwtX_F!<&Bfi#ohvXN_kItJlci6+? zIa0oZEpKhQ4!*Uj<(XTKSCLrd^QY_E?y~*J9AlzNlwfX|*J0!C!OIpV8~0#LtZMO| zQ!5hVzp&qC9EP!7C7!b;!5lel*!)ovg%jScXVR$^3CvMx?>Xlvl_;@fFSB9uAnOUQ zw#nzyQBOGRNbwZ`&V!L)J>gX^9Y1p6#@}tILicM6F1` z14!3F4?rcp7D9q+FSKEPNl7H1p{hk2)QSXrpJao+k4k(^hs1@uawpHW9p+!b_i6MR zz2OM@KC0y_P4urK0UxgM{ij}>@%0nG*-(iRTnnQO^An|>aHFcl>!4O7R{eAzUPn=f zXX)!|)be#adasc<6u(N@<@qN@tbnilt3(N|H1e!$x5!`5{86%jdcuvW7SD=Wk!T-q zKv!Yfc{0mL2^{W!!aY2GRJZJ+g!^`k5G&$kz>OPQ2Xw71kDB-p(!%`(^ zgVz15s1*sVq^w%r3(O8hg1vjh;(eLRsHsE=@AcM-&{Zv-A+;i*Ri{1RflSXcjZ$PL-2_G3+D~(sR zcvjSkgjO?GiNB8|d{naf=l5YueD2(LXI|ZVY1l2|BWJ3yUXEi%3>ad+?c4G34_XMG z6$zzd<#!)NspX?Kv)Pf5*&tVm5rS8N@pBnl_IUH4I_6$$!R>?`nrofiCPLfZSm>u@bz2anwkw)Md(p;|nqRwTAq^_}E}FTCTBu=m3~a;|Mg z;ssQ-dhNmOM?Q%!8>vJIj{t1-_5PLTCmT=RIVtS@@W_H%kvRAlGf8BRUUO{P$-ygk zEnWwYJ>J>=``pRF7-z55mdrqm6ZU?1W`b+YkwDgQNrUWTMd8iqVv;r z%sRd;?EUZz3$-F~@gR%t9>&+KRHB4OeYUD!5``1ITDI$v99MzzWe0z9SIT9K$8~61 zo^xQko)xjaV)kQRpTQ%M{Rn$MJYT}TiUjUQt?zzY&E)-1i4vaov3t%e4zC~HgM7~;fsuh%o<;_hDB+n@(x@|9eu?c~j8`gA!t=W} ziekK~oxK0#kxyW}QZ3KDa!icGZm70-+^8#Nu81$OsYD6SQ`>CtwbkCKU3ctnb~p&* zu4;J>nP(CS+Tc^-Hh2eJi^ps?5}2bB!8uALJa)qK@HP)J-@e~EpE8$`2-orqJ?Ftl zaNS_f$5JjMSBVn7(qQv>eT{+Xtmb2`t!mL8wITrzAQAKcRKjB?d|kx+k}9EEJf>D8 z;QJ&S^nFy~Yb+#ueaHMO_&)h_=WH~BzK?48nhyP|NN_!>%w^;%QNq`$%unQc6z@6K zqw=a2uY+2V;JO+KtgGcJ@ii|JzTRegCb+J4bFU9aU|lT{-mb5)(cg^(av8}6av6D5 zi!|Gf#2#3K&Z7IQH+O~)VF-{^zAjVNGU%O?56p2MQAC;fE)8ixW?>i?DzIMyq8%l>& zTR*;g+Qyd>?i;Q6|i6TY@>5hT~Px8HR5Ok^g)z6@VKXOtQVS#hta zL$4mHBKmaYi!WTOR@LH_Q!5h4 z8YE)T%!z52g}3E<7)Wqu1pkgcMJ}UCc)PlPA`<2I`Z8ueRHB5RmE~mo3x7_~2Ce&9 zQ7aP2;-ubX7DpvYc#qgGk>(wl<=Y-RA>aJw58AzVTlYz9J?7T7Vda(IH8`(51!B>I zi|RfPwywS@@rN(37`6V<6Y?n+b_?rK?$y{DloD@0eMNnT<0j-g-TqwNV;SbyJwmdK zxf1_%a!36;#~{Ah@UHY5Mc%2_ys;8{{;hlCv>#5$SGeW%`#g)&nzK@3&XHMTIIeu) z%^!@?oJ`EBC^3JXy#6wX@eePmX=I{tLY67<@+()=#^TDq{k!LCI@ju)7>NZZbkz35 zmEW`RU1=vEue^1ZQ5!G)U|H>$gD2!K{i<&m8T1W~HvTxeTmEzO)%2%sgWucPmOn9k zxBYpucM!dsvv*g%`SqRjX;(TD=-u3VSIlk$O*fdgmTXC%Iw4G%`&Un5y1w^sY z6=_E!iPqUtiLbvkxAx|t6Y{r@`CU!tbDekNS#`VM?qp-NTN*X>WYpt`#B0~wP^wY zvTVYn5u?^SVnV*^;oU=Yr-ZhIr{v28qu5tZzLkYIO0OvrUrid(P8+MhhDtOlj&Uun zqusAVBX=dVCCn7~cRJ4Msb$?mB&-o@Byb(=ejS=;PpqI=DuCLn5IiwXSVy@BSIraVmQEzNc<$*S7qu%r{hGt@GZi{~7b(+ec2S>sk37pee`0JsTd!j?ydN)N9$b3N@9O?eaJ}E3D_fUW;<)qgPS4e}TN-tLCt7zT zDDeTtl9`wXH#=c|-Nz4llS;?y=(*mx={m01W`G*wEaGKYis`2y2r{lRS9h=%kb7FpPFy2wxzug ziJ!u6UjgIQp+7h?j&QQy+%rWsu3${8`IzXrm$Yw1h-hOR{B}Mimtefow)C1Jfibb> zW1`0c90%22BrqG)d^YeHhjWI~k-%(_`)uIx5@!I9ifoqAd+w1J<64cpl#Vv|4kA(1 z;QwXi-ff4zI~#{Pv%)TqSq+SY|DAgLX9VllQo`DBte4AU)^KYf3MW*{ZLlI+3(>Tp z5+(F(c}DzaXT?gfJQG&;V`W+%vkITKWa>_+7VG7bU`@RiqG>}VN@$NH8%=^WS=lb@ zGqMIOk6A}iTZ(6;TC7Z)2vkLEA(}Q+qJ;KHJgbGf?2y`Jg-uplr43fX)Ry8|sTOO% zl3-oS7Gk+)rG)lKJS)~2WxK3j%DSe0++w5fJE&T$wn~DPNn42Jo|O{XBk`Hv8ClC8F^A-0zyN?d(s?ZjbhCwb48))$)6= z;>Y~uL+8_D7M6EbN@$M+qVRWOpVL;_+25`~AFbGGqj^@U<C3_xd+yrCR=O_kMS!R${qlrG)lKI;+C3!^c{lm5$R%%RMV4v`6Auxo^lZ!@bPqjy}z^ zQZ4t}mOH{N_pFrA9^qN}8_VOBFqY3K$8$gKjW>$NH$n-$?4d<{)jMdCWEeU|;=_k+t7MQh8njIdawt>fHZ zb%%|TC^`w%nw+#EvAxxB%TC6Qc$L_(5f&k}bzHntPuM7lqLWaq$w?~`hnH*g&!BFG zO6=GOi`&{dUR>}s*eHpjlTfY6Nh=cEYrwnR?+N?8bCy|Kre%ahmTetpp0E;Zltj@< zsMh496^T8{dR`mh7b7aMVbnsOO~;B`hn_*750OyD-z{ystmiS%HIiFTS{2A zrLAMXDXYPT?7u1rYuB_UC#?$ch5b$#JI~7B30qrASPrPIWBZ*}rwt>DPQuzXt;tC% z64#dXybeO$C6y>)*{`;a1Lo02Nfe!gwQE|FlU5{7+`xYO`WAj!tP&+`C9bWb-?#d} zMoAQ%gtcp0lap2??mRBlmd*Z#s#Ypd!ZL+z9kl~#qa=z>!rC>h$w?~`e8=sd|1Q zre%b!tGUlm5(R!GR1&I%euHNb33wT)ujpl{#Ey-yH8%HsN+S6sty<=zL;~JYvO#Z2 zC3b9ttu(q1R}#s;YSl7dD-!Vfk_~!&DzRfDYz5PO(UM4hVyl+FvhfuaNC1V_+oUYjZQ+fCU;OP64#V{ zb!YSUgKeT^g!kcxAAJfNB~f$|sx`TTT9MePyyxSwms2I)(Pz4V5208PQu#t z`%kS%$g^Aiwy&+DQ)_ZM_Gfyx9X^5$d3H-ewI+8^D-ylS-`$;9{_c+Vqf^TWe`~*5 z`vcf0iK3HGt;rqKio}R=EE#*->gDh5+C<9;AAL^Q_&wMtiK3HGt;rqKio`d|F|j-9 zhO5NKD-u3d{_3X-VWT99PQu#t@sV1Q7*zfy?vdti;@UbowI-)yAMBXlfbZbJyz6zYZHRN0o$XP41vpBxJ5Ff3MaiT1NQnyl>CfU_<8G zl2EP59n^}%5v9-YLG#yVZK7p_dl{FV^D1nVMA1p8*5nRqMM8X^^4Di=qGg2pL}L$o z1vbR@DGAk@+(E5KoHfvVxM!Qc3~LiDBi!qof8)!rQ4&Qbp<0tWs1=E2$Cxkr_!*~{ zzYJ>=EhF4VJv*n3k|;U})tcNvtw?0{ufSkk?p13OEhF3uHyf>lYU#1Hlx1fhlVXG7 z30#M^s+F*IJ({3aB+$DxoLTB!l_=q{kKOZD!uraiB5FkfPf4-?pE~`b zieqA@mfcN{;q2LMB~;6vu}D0zG{v07)6HKy*|Y2MAlvmQ)!xBY!rJvHm0FRINVxp9 zlf8pVc(iR}Nh@LRphw%(iUdZVoc9Ahb@|&R8%vb%+<=XVt%Qvwo;9FWBru958yrPd zqJ(EZY;12OY)tg*2el%B*&x~AY@iY)Jd0yI-~23S{^qAG&16b= z&dKK5R>I~e&qh%z5>Hr;tk}E!Jr1AUPA!{7J*#FuLo1)AnSMFQSZvO#Z2B}#ZM(|ovA!h9dka#AZ2@cNPsdVMNU!n3vJ zi?$Nx!+ExrT9GJo$OXMul_+7mNW`a3XVpoVFKSxm`$pnlKisdKqxH~R_$!;OXIswu zJ>*_^%)Iz}V{V+kMf&@y1NirnC^`w%nlYPNk@({_15*y5-*Z3DRbt0Rd~y3G$;NBP z(MCxWorG%5m`$xneDaI4lZ}PDo|LP^j*a;JO&cZ~SA9+!B~f$|sx@OawIcD`)21gI zL%%vUSBV`P(evI7l8tGzxbL7OicUhcX3VBmB;Nh$+sVd)bq>u{V#h{g*??r@lRt1D zNJ$i(glf&0ZCXlv@0e8@yyx5hX+PX^mGIbzHK(kTY&c1Y)Yc&Bvfn0Y-&Z~;~vA44gCLHC3bAY&|SZtZ1ldK zI~7Wz=pLbYbhrdA|g-Swno zW9zfeuBpV1jd_4#0s(8vrI{=+0JqDmI)b zRLf&ETZ5_)%RMV4v`6Au>3W2&Y_z-|&9hQ1U2kb2mU~u8XpdCRDt#f+a{9W4&|;%` zR;s1zA1%ak&q@jHk$6^`WA_}Ht!G#6NAs*y%X4J^`O~h1u7$+2^6V+cD9?-9j)bnx zO0_gw|DW}h651o_tnhzqg!9Zcy?f15x7cX*m1;TtpO2zSXph9R@^fdj<-K6hRu_Gh zsg}2Eu~UU;Ub$YO5`Kmj71?=NU-^AzgzZm^#mf~N-dCAw`8}}cw?ZuUtd!6mv2*e} z=r|;#-n1Rc~+|B&#UDxD#UWnN(t?ecve1sFw5m5k>#u^HkxOpTK;ZZ2C70V z|E$s%zb$K|Jrd8#$6B71kJ^?Itl03gYL4xlSx3v_>C+Q!sKiH3(%K`D@Og=M(C5K_ zd*y{{`JA!b-i4u7Peuvtk$6@?Ak`5T6*qXpOs3KSb6_TlD*5e;{Gf9XV;e!9{*iFoUlEm{efvHPKCqC}TxRs4UAojr>tMHGb#vrWasz(5v+H8gidObj(M zQ6oR_17yKO#I^r`xgcr_f{~bMgF0&mCcBsl{soiWKw;6ud(U~R>gle2(Sc!#>GRaR zU3Kf$tzvkG^TBr-Mz?uI)oTxbDzBdX{Ih2UqIy;Mgal_c#PJgTo^CS|-OlsiHYyX? z6I8KXWBU46mx{uBKir6)j_{0Ex0f~B9`$9-xhdrwK^5nzly5(LA#F@IK7QnqD$mEV z<_sPZr4zHPli+NY^2I~`Y^s;v`sacw&-1co^c@nV6SF)av5k`FulfJ{{Q1Y73#vT- z%bF|okSLv)SIe6D>X0a%nB@rxX1n;m;Sc<|QIG%n z(T`MlbuDY=!9${SVwNW)xHe1q{xQGDcjduPR5?p5Yi8|3qI6=GCnT6-N_p~~_cc~G zzkL0QDrfCw&E4RTD4m$)2?^%>_@u@AH)Z3g7r(xu%6WcSb2m67N+)J{LV~+Q{O!m3 zhHU(N>-Q_FoP(D&cgsVfbYhk#B$&bDvqk>)r`Fw%|5r^FbK)UUIx))=63nhjqPKe{ z-RH!bIrI0BX%yT+@3@0gDMFGCu3@;jeU)uLTJ zRU)*f>UFf?6%}5IaFyY{tDSB=-b1QW&9Ef~8>bc3Jc)Tyd#u~}B<4n{%!$?8_8wDx zd#YljMP#NPh(oVP#99%Zdr64(Rp+F?c|@O7r`=iYtOhKvUa_x;e5rgM=sj%-sv_D& zw-rZlF=jHQ}}5Dr2xQRj;V>dUVY&5Qkooi2ZRpgN@)QI`X~a z3^tlqRC#rIzZ!^UgHK3sL_*xYbh>N)+V@svwBL7mj@PIhWU_z4NOeOf9dPIqZz%Cj0( z%m#;qPIr7l!fl`WbV`+tJabYtW}h9QQ!4u+;kHk&I&I5Fo}H;0^W%=tX`6kKaNDQw z_{*AWZ_7sB0Z=t&?H!?81NKG2ZQmy7_Cq%EE`zFZ$Jr6O{a{}t-1e=AZgFHI?_{VN t_rx8cTO9U9!foH~=x#|i@-~X9no&=;QIQjOMCn9*;(hmYmnFjOe*t`u``7>g literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_8_gripper_prop.stl b/lerobot/common/envs/aloha/assets/vx300s_8_gripper_prop.stl new file mode 100644 index 0000000000000000000000000000000000000000..36099b4221155b491a2ad61fb799c7fd7d443b77 GIT binary patch literal 31684 zcmb`Qci0_OwZ<1wZ!i!DV3Zb`G(n<3EHXsrDp4{(+D58{t&! z2|4?nkC;JEX(Wl4T>Yg+&3)2ocwwg1lk zqh}1WGkxGgNv$2Mntts`raErYcVnXTAyeMor{#SNd3C@38Bbj@-k&1 zt@zHEaMPN04Q^QU{kR>jYzM1mEm_xy-yM8VOsE%}T|SFUyt^~*w{2%`Fkn^c5L#b7 z7fG&n;=sb@@;+Y{8P(o*+#1$CUpB&(K1Q@o9Pp}S*>C&by>_gXXFm7){zLEkaG(GC zuk>B2N5l^;=QGM@dac)I*_l4*w=+SwvgNG0edLb@{BdtTbY6c%s2liT3loFaf6;v0 zdH2O(t%57aS8eqFPPUfswRCKa;Oji~nzzRIS{-opsQ8+f?GRQyKj^-OCuU9BE+)!$ z1U&;2{QRrferP#g+eO=<|JZtdE8}|s^734`n{*$)IagVx#Irg_fzH#_*#v< z_v!eFa^<;V)jqE-Fyhj2PsW70>2j`!7$lDxeb=x2pZK9xY`GwLMy*M{;-QCPAFiww ztDZROB_oo>3t~du#I<7L`%_;x`j-0!^iTXyE4J)C|2?%P`Dv{=u@6_)idAQv_rA6# z4twOLm{2!yt(f39D(X}c+_z7;=AGTWk8LJQ4Ep(iaI8B1+|}*bPTD8*CWLz*Cb*X{ zAFgaUs}8#DIP)>;nZy6h=bVY&y$|2jub#cI&$s-R`~TXg|VzWVS= z2tF1QI}eN>@cwT7_RIPwez=0){K9*E-g5q^JNw@J`unuUO!CE}ZtlBwt4#*%?{65S z_ksRgc?G$5zF>n(2E1z4=Lhd@LsT{iqePAD$?Fryl?M{dSkEckp&?eg{Kdwu4pQ8Mkxh&(*D4Y#tMe z!3Q6U2^|gEwb7BK9>vQ`f>qD`Zie}|>+JR05#b?ymx^Nx6Z$qVA3Czsws~bqujnM&V-&7OqtUCnoUHokwrpXpz|^H2R# zf3B<*tL9z(VxL!KUtieQn_vqQy`K+Oy|eT+^Kr%g?f8lE6|-}|$6|t?O%>Y@#DXtg zq-2u!zxi1Ie4B04_U!o)gn9cVr_ z9dTvN2dnt}L`3OB_?_|g(7}4VBp)^Yy7+E)<=JJ`^Vwq3o?s~+6x zk@%@C+u>NX^^mQNn6=~LnCST6nlN$BT6-A1+k+3)YLy&)iCO-<_CWvgdoHu`jqlD| z$rHt@=}WFK;$MsBu7u$Giix4W`mxam|L8X>sTI@QKJh}zNO>o63z>Lf#d${0 z|F8RN=Zeqb{4K9C)gI$+?|nTSs}9^B*Wmc!vwIUkFUrJ_O>q5BTQaLwE4JKm!=+ZM zrE`DL+lOP-`7d5%#HO=v>`er`IeQW3B)fpVIozj|iE zWb<+JHQTjV758v8LMj3lCQwdu-=m6LcKS5)vGCpR%x6{H2iFLx2w0dvIn8}PFLK5s z=0mnPVE7nT#czh*1T0LToaT5tPo6o&w?m|VXoFSp`@A;+3lk`(xgS61tnvD@%*UN` zPH(U(9&z+0U||B~H20$#k6(+-iI4`+y|O$VImwe6ok|XR-v5c7-ej>^#Rt7758t{WK}#a z=}o}G1j=dd$3Y^?zVj*banblsHdz&qoO%`^Mu|6EKH!B z+FV3r{eKOZk8H$AO;*LTm)-;{OrV_Rew9Mxl({p_NAq73o2=qF)v5>_iwTrdTNM#` z^v)g4$Al4+o2=qd*s2H|iwTs|Vs>}%pbK<7D00*IX-!teqrTn*EKH!B=6;kZve9ZA z&Q}-i7mKDfSrv~uevi1+xZFwIfzBZ-Fs(7?qBcvi=VFKke$2{tR z)uxz_jfb7pWK}%#su5BVurPsgn){ia$if3|GaoPi^OPp5;<;gskcxnX36#?ut5IM4 z@N?!P-|^TctK#*U8X*+{3lk`(xnDIBIpOCY%>4D3{n)`xR>kW~H9{%^7A8qZw9pFXuE^74PZP2&o8Im_RwT z9e$CE#!WIG%hyU8tm0j{u7p$sj>QDZY3}1dM2>vpTi%CU^`Wmd*usR)gxexEckb&D zt|AgU7E~5L(H9bXJadlucxvs@4Yn}BF*+i>2v(t-=74yH10s;GZ#;_b{zlJC+4#%j#Q`- zQW3B)fpVJrXb6#Qp75)3;!gY4XIrd_<0oo_R0J$cpq%E2thxM;XPA#~PrS6nsyG&> zMo2}#!UW1`?qh#MUOVGN??Zk%>fRP2g!HYZaYP&~#IZ)b309$;=00vsv zV#|zGail_xkcxnX36yo-uF()8gPz*Sd>p>b=!{iy{6vkAihzX)l+zq>8O?L>t{vRJ zZ^o)PlA}gQMZm%Y%KGlo$Ptm#&mLm!*#5wSGgig1CN)AT0v0AvPA#5A;~qDA!NxvU z?{G}UsyG6sMo2}#!UW1`j>wv8m)q{Mn>FX;j8z=H)0L2lz_FM>In90SkM<=`o^S2= z+u}1bR>jdmH9{%^7A8THDah)B)RRp3jIZ87mK7FH|D;f6WnHgJ{K-@`c(WW8=;VJ@Ar5v3S692do z5eNVCz{wd~n80p-TEwsvgsTX|x^hfFNL(}9ul9=!-v5}4ElgmyKP@5$3c^(cB4{`! zAS9;jV$Yx~I_KbwElglHQ&({;vZf$hMIdg0_dG*l*huS3syP2u&*NYT{ zs|bw{Q186w84^F3VSS?9an|UJEleOjKv%*v4n(9NTty&SfTIXP;;!|qZ#3JtUEWa21i5 zcaC8SiC5P?)xSUFqvK|^c*MdZ86K~Q6ojjY#Kt&0k_ibNAve7b9aFb-9Nk}x&j(OO z6tj+Z_3sluLe~29B3Om8jf0iYF}3&Mbc8&gRXX;y`7X*&Q1j;rJ)?P%% z)Yc9iA@9yA9s8OOAKkPn0>@$kWg7?U(REC1K6HdUhE+QDH6K-MRBr+nCQ!CySM90+TLr2IBR_T3ZK73Trst6p536yP2tv>K` zng5gTYTj4n=f?C-ZxSO|#dl>yC}xC@plkbk*U#egI$PP#wh*(eyEWw(BOQWOdNqxx zVz#>w!pCAluZPi?6@*{1XjMLBo&RVrJ~Dtuj$=Kkvno>QBL4uL4v zH21ODh}ll_D$2VY0gw;JD#VDV6iH5mhy3+$+;Sdq;5(Ky?|jG7Ay~!Zhu#ERn7}tQ zseMDEhp*06@vRK%%k7AWvR1-ZO7C#HYJQ%{?K2-G;aG)!7qiBmL~xfd5%#o-vXufEs%=s2ZF~}i0e!#UbGx1D&Ptqj#Y>@)seTxZ1ZRk9?Dv=g$W*` zh6G!f;QQE!POVslsB)c6c4E)FJcGi=VuGLluvXkB@}0qFJ**Y0@O_N#>F8H<5usRo z1)1QxC-6~xC4_5>*!(p2Uj{`!TVi0n`E>RW(S-B(QX?nPOJZx3|l-T9`0dg@Ng z`B+SFpKmSi5Qs2M?Rzd>#}C)ry}WEWVmVWb|3~bx&QkQd0DcP0M@cwVA#z!FvpTWP z81tm64jPr`o_*EtpwJ;ztV z?+IS5;~pcd6{~pdttSz@qnHR+)#&UBTXj1oFcI#nu@8Qpb*yD~eieIOuE`MLScS;-H1`ql++(QTerP#cnBd+O z@}lLARfxdXw^}Doe^os-6a1DaDpmA8{AS@jT7DCSwPF?Txb`H9ueR`3V}h?u=z~?f z;~Ei);q0=7iRhYl2!6kE-NRjdFE4$tiX(F)qT_=tOoY)1?1NPtvl|f|A8cVFjK)=Y zhu|1Nj^*PcL0;a8tm4SLi0JrW6-UiQge!fpieuv3S!R_E^voI=*YE^ud!ZBWm#o{BG4_BTmj^*N* ztBB}YD<;DDEAvu3wS13qWH+CYpjN^vj=GMBPOaF&L>Ph1wc-|XY-Jb&=^d2kid)E$ zV0>jGaa|GN-PlZ+ElluzY(6>!w~%AO`HUFhN*}D^$nJ>f_+SeY{M-aS9G^vw z_~iD51gkiHGa@>*Vha=etk_z3(<8bT-rx}c%C;`v$M5-W1gjDs6Hp_pC1_5@YnJhf zC%y}T)Yr;i6IP)N6@PCcGUeD4tsR?8ySKshMH#i?uj@L5)CpGc=tJb$Espd)Wa*q& z8?1`I48%C78vzRwJVwz7y6ImsANTGwtjVhQdqs?cx)HE25srOk|9VgJ@$%rUnyljQ zc2`C4Y#U$U^PE~_*5f;xkDa&NwaLegzZ1q>y&C}w6Fl=4nY8I9=41HS{hF+bzhuVj zz8e7x6XA^hw1L&l$E(L5(qt7@rgVQ;*T_~yVC{_wUe^-Y=bnSS4|m)b)@kxw24&=N z;#H$=1gjETjS7jSFC1Y$ZkhR7gDoh72v?(Gf>p>T6B0kX0MFnR`8^G`pbUanKSg4K zRmgG^5*yB(XzjRf!9@+WpbUc7NJV0TRmh$c5)V9VyM1ol(YrR-f-;D3?KLJ?g=|eB zG50gr?OXo2E61<}We~igr*TUW!K%bo2SZ}rzhJj-_nH5g#}<@9@QR*DLAZ)wm3|?u zxkW-^`1Sa@=B-q`! zRmj{D679RbY0vp9pSZcj7L-Bou9HYXxQbvEvVeue-lN8wkEw6}sl^tQLGb#6NI|%Y zU{zv!ULkS!#)q1Z7p@zeu?1xiyka3z5UwIvmDuV>Nc`Z6{mjQB_m9Zff-(qRvCt?B z5UwIvmDqYoNGyG9wE6hqHalf(K^X+kclE6d!c_#T5?e0`iAx7>X+E;=@0GCyWe_~y z6)6Z;5v)QEvXI#Fn6=Euvewv)EhvNF`L4zef^ZeVDr8s)i9dYmV+}tpdG_qd#rp$q z1AdqAzM)7jf>kId#jfSRis{~m``L;!o2=qp#IA%?1dhc7%E`n6J;zjR?k_o55JRRrb(P$i}ciO;3y zn2)Ld9MfV86Pq8tr`{K7{_^oa9pU8+^a(3l?SF+ zJI2rWj|N+qxN7gA=3~ZTC#a8ta20{$LY3rR6%uFs_AK+U?6apf*uuo3c?;(G>oIir zMDN(( zT$V3su!V`am#?K7{Vx6XM12&5s|XwyD$OUPs*qUY8;6>Yb+#YeWD66AE}URK4n69- z>Z2fBMc}wlCAn9H#EnnyXFhH}Wki!LOx(ELEc3D8?wRVNAY4V@xKJgzSB1nILw7YF zvzPDKWD65#p1aI^ymi~f>Z2fBMc}wlCAn9H#Jk&XX+91)X|E<*nE2FHA0F`6~^ZZo*IGno3Tx{FrjZ}^P#zr)JH+MiokK9viEsAB=qo3|I?pq z@`?xdkKyWvm*T&Y;G7&>rWFhvSy(9)hVf(^Ok` zQmm|B(bWj9JNLo79#ps}YQ-wL&=2?)>KFEHU3<5(ehJ^!6}_ha zd;M}UY=`6X!_P`|u3UL`S;cpLPr~Pc>?_YZ6S}8of3F#7QLBy*R`H$RlMuErp?gK< zL%+MLwOrS!2YjtGvq@W5pslPKNLF&L_`LJGgs+nnKir9|;x|K2BDm&E@HsRWuDl+s z;x|J?D2BV8EllupQ#7L>_&LzM!ajfA^sCP{KQ~6W(g&+_=g$cJhBGDb7MaAf4G9W5^u-V90_gRwX(A2 zRf~PNvR16py{XKfQO!&c6H*fVr0UL(`Ous`G12kCD&0LXLh~HPMCl`FITN~*VzlPo z3HuV^zE<}sOr^OWV;`<;2di{H$_UN%5ff6LUA`Vn=-!Lbn#H45E4JuWkATI|D> zwPKa-u^6FQHDW@#)rtwe7gVhBlF)rF8*OXGgSPH-**&J23EH}Qruh{tLqhHOV3qF5 z*Z=(`f1B~9DWi(nP^b|RWr&HM0q z)tanAKbY9~p)29@suhIgRckX5_M)0s&3tHnN>=T$2R%d6IAf}b?Yt7bklOIm|f zc)AjM2D=hIuUbJ^UbQw8{A^lYHS?ia(i*J7GpIS@^{MSj_`GTbf!=@#eu70bubTPL zENKl^;R)7NReiR*5iOnGemY*5c!0RAYIsgZXENkczOpYHcQXOyutm|8q_MKVI47 z6$H$qYHI+V5X?X9Usow+@rlocQ_MfGV&QfEXFddT0L!7@#@rzB8DWaq1lCa?FA44$ zxF^EMAPHyNRx8Xua4hzL89IaXo5llWXXD`^KGiwQm>){e5}{@(@Y^Iv-UIWpG} zb87n+V=w}6<@I0{uXsg7#|K-Oz+BXFz|?%OidXI;qV!R$GvHWE@Y=1z&vtQhn@y?t;W#l2lbROia(&gcP{;Qlx~S6E>|AB7bJ%XQ!TIrq8l z`}}?7*D0|ckoc@+y$Ru-fe9Wh2etCK?#+ikF1NNPA#7oSN6zNMm3Jbm_zv$$2tUuf zHxcy=9UrXX9g~RAs^N{p7AE*92;0Fb-ua1$(nqn@hqo6K{4|@7l5qS)@l(X-Fsv1; zFe}!mr_KsXw|5jDiwS-ru-_FPQ}Y-;YPl<)4_5KaA|lFm1XqxW@Lj99aWh4HZrqH=gWLy)*Sr_O zDwHh)uC`pW>3Sbdv*~86itno$Ar%1&6DV5-T=k*Zbj^om)6G~F-}yB{DgqWJP__)X z>O-^Xnh(vUo3Sc>9&3bD1T0LTY#DIXhi20?ADT@!V^#d#tr0%|Zb87p1j_oAxxU*i zn{LZr56z~Vv5I?~u7uCOTM#%F6DZr)5$Z#;>6#DCrkk-U?%`^LR0J$cpo}$Z%cg5S zG@EY5Dt;cj5>gR37859223&22X45qvnoT!j6+hcu38@GiiwRzt6wz$Dx)Li+v*~86 ziu)4FnX9!b2%mqqAYfqv<#K&jv+0iUJ~TIO#;Ults}Vk%Zb87p1j?2HS8Ju&bQ|7> z=Eluf75Bk4!e`Sh2w0dv*)rg&56z})J~TIO#wvbOcO`r_-Gacem_S+g*lZ11v+0@- z&5fI}iu>BGgwLj15I7bSD3^P}noZYyXl~q$Rq+V0M)+*H1px~aC|d?xJy)7dx9P8k z=Eluf6^~?VgwLj15U?eHx&;9X6TJUv*>uf^=Eluf z#WU=#gj9rO(`_?>GWJz1o38oL+_)L5;u(F7@Y!?=0v0AvwhXv>t~8sj`Ow_B8LQ$o zhZ^Ct=@tYmOrUHTaMg!q(={KO8@I(OUUTS5_-wibfnza&vSq+kADT_qd}wam7OQy8 zp)29D=@tZz#RSTlB!R`EQcE8(;076gvP1j=PZ$_+ar3)Ij5cu0#a VOkg%qW)~|6R}onK;5kP~{2$;m(f0rV literal 0 HcmV?d00001 diff --git a/lerobot/common/envs/aloha/assets/vx300s_9_gripper_bar.stl b/lerobot/common/envs/aloha/assets/vx300s_9_gripper_bar.stl new file mode 100644 index 0000000000000000000000000000000000000000..eba3caa21990c28559553fe0003ae379514e7215 GIT binary patch literal 379484 zcmb@vdAyF*_s6{@Boc~9nxsiean5nXxzACdG^m8;Zz{)3QX#{ICR9QSjY_jn=E}Lx zeMM0eissUwnM$M-p7q)LUYF0lu5*6R^T%^uufEpzUhBQr+T%6t!I=Ml|7JDR^n$cV zfiX8^)|`KPcutLKZAa{#8bYpUo-ESejcJjwgjhO)tyFeaE~SV-@+r%Tj|)b$u|AM4 zFy^EiPi(n5(kH*8A>S##VjSI-+}@I8iiXUdaXNYf^_4E+}Z|9@%gvZWgt$zIdO~no zkhOGuqP`GU39%)$pnx@T0(7Ur2NW68SBT4ncu9zlp6C=R!9)s5lLo$nSOr;87i?$NQb8a4IZ%(Ht>v*mXCH}7Xo8D?Vp@ia&yTw zsqO^}3fStnimNlb4{a6>`*BQ>Pux6hUdd$fF;;xAhKYISt;zg*QM0hgyJN)1r;pAn z`Ad8>mz0m-Y%Td!RTh+%Tnx+k!D)Np9wOys@SEBs(;aahevk*HGHvWmAW&J(vDV}25%j`$cI%Q=WP z^K--9A3Wi;N@IQ#;t(P35Q5WU;;{YKW~S}R4c|UwrbP9P)OlkeawH#Ix6M<1!sG9| zF>HU-U9naYijUqxRF<-0t9iS7hZXW}3_sj)M~wJXh=D@9Cw0#4iirGU0F1!!rz&&Qu}an^Hs4L zM33qsKDJ5D*=lwEKbfMA?ZaA^$BDb82A2u(sFW_(ITKw6@5;;>-#+Yf%__;qn8)Xp z%$NSLNeFJEjjQwyf05Q+;oixy{&B4296m5Iu+^5w^g%D~;JE^)aIK zn$%tS3ktXtx2)56IG0gRUM>T4l>m0rtZ_#f@oW`?%U3opFz zsn}R@j@0=RQXe-->9W;DFRslTI6W^sGI%;hd@lWCfcRJ~t%S!CCh9d^m$`mxUij5B zvm~mM#78|LS_!dTYN_oR#o=LJOf5R$#p3XRcE#aoFHViM-5ufsImfumR^RU^4xj5* z95x*gCmLmY?K47f+hv0LjWHdi*M1^C+DOi;zx{ru=;dZ%`ou9sldoNyshn;Wp7cw+ zpLcjEnBU*xKB7IuQ)s-FHY1E9|wz% zfw5l8#Jj!vgv*a94!?NhK4~TQ2ywI!&q+S`TD0ore>2y;**=_dR{W}lduoi-i==ef z>Z5P|%cQrr57!+KC)x^u`}X)5LuE9O^Jn85E2yvkh zY}NVC^_hP6=Y+GGJY3`xz2zD;Ponxm^1&J=THg0wX6u+{;rn_;F~N6g#{%bkm z{iShY*^~21u9woym+^}8!Ng}jtj#Q2l@l(xc!t#AO%hdWiK>N^E?*}Q;lu4(hF#xy zCRT%OWb}Dfh_2aus1-_j&XX;};ib>Uh{Zw-7vdEmxCWU(3w`O|mf@he&q-8=Pm;SO z$@$BYbB-5RwHcq~gcp84BUV=DJtgCnuO?=>5 z%Vos`uEB3r$_R-5=o=BZlego8d`5zG1GLf~#`i4dOEkZqYs zz0V2r=Drmp?w7JcAKW1M;Iev{2<~a}Y#?_T6NGq3d~m!yj#-=er(te5X2GMeoL85! zI!emwZ1KTXxJNmmWp4P)C6C33kvwrgIrcj@KdpStETVa>Q0|z-*Vusn#u?N z{&MLFr;m(&cW>3QL{OGhlBj=v6Z@WTWkEr@X6xpX*1)jsp2JEZ|MlCoR-U^2jBxMX z0pYH*Yn2+4B?2Yb3NoyGqRr5{*2hx~E=scovJ!W+bw2*Qs+#!75`hwI1sPU8@yp)5 z@>bB8FXmsJW({N|+Aluc=3`lx%HktS1WK?KWLWvc)YMw**pPn~!Q8_sDzTED@xD^Ok`GoXZ>jS-(HIS9KZfO&n4>y)% z3ER)(Rv=*I6EgZpdo%{44{IPRaZ#T0;l{))VaKbu6$n`Qgp8ur2S!oWKvrTy`ed6A zjK_A|1!2eCxD^Ok`2_Ot=l(e<`7hmiS0>YOTVc2%cX(05HDTtM!G+=I(?%A(yZW`v zn$-ni&mOoJmA^mgwxEJSkAe0 z*=pDLw==t^qWe`yfa``YZ`S6u~4Mqgl+RrVQXI8FBg@bMgVo~)9>My>sa!zVO z#hf%--L`CbrtV{@@Z%M6;;5SM<(@A&e?)T5Q8D4yV55`Y&n=PCJxNM;!5O8QCC{`C z8~3`UsKHC6nT6HchNrE$Ef&>?7n|pPEJO_<*y^6MGMW8uFAD!TWLS(q-O^5rI}~9_X{^(@j$GVO#J+Z=9Q#feJ$;Ztxl3W4Y|Bucz%niF=EV=8X-Oz(?Br0e^jyYLiiAS=Pqy8GRa?;D>lSI*SS4P8`Mp803# z2Q`oro&QdR0b9(gw)aXyz%eSAND^W43Fp(UeWyTQjS)hV4tsKeRO+& zL@I7obV8>PdGd+V9&2TZaf@#Eat|7n!8cHe4H-A*C$I3C^D_t7TeN zH3wI=Wrf_n^Je9!tT%%9c&OsQ|Icp#*!TGa&utfXd<~A-W^rBbCRod4FDO$Nh z?ls9qg|-{F(zeU_lbIaV2iU04KUf1<3C^D#uS#^h+W)2fZCPQ&nf~Yg(Rjtt8YBJO zMumPJx6*#@6Ec?As4$kW2C@>IKRdRUEbQmT_LWDus4zNTe#8FJ*v`?)Y^qM%ZB%3b z`Jc3Q-%7_spOA6aMul;gHIS9y{28-#MT7LM)vC4n?)Z+WMUPdCu1jOTs2E)bIa*@| zRH$X2akl+^Nh)ro*AJgKI#UURxw-unDb_$%g7asu&X&N{nF&OQ>p8Bq9If}{W%Hp{ zXCChe+yRtH7NVrK;u0;=s6-= zBG9s8E2THB`Moefs1L&$CbZ>)wmuTXu@W!S4?eu!Mm2NBU9qT6UVpsJ`Kad#mp$-_ zlTm{jZItss^TAe1uh}-dAVEY?v4)B2Z#aMdRbEx#=Y!+j^X)nt`-I>7N2QDWSwf>S zY*pc0M|}F&g-IfcO3MdnG0|Y{gwY^D zXjB1f$|5k@c|M}jz2oHVg?a~A&}w&~)@(FhMfqSWy*qnn_P`&!?JUB6o@rNF(w_rX?rB|AvQ-2@?6vY#`d z*F;={Js(D`P|xZQtt8y>yG%B{z*zq1NK?r7Z9dB>J ziV{Q=6@Sg(?_8V`f{LOF*lPb4?#r0z??-3}K=z8mX)(bOS{Km>AOF&TXD2-U@;8Kt z2;c}Bwt|dr6FzaHye$BCw|pBu;lEv(Lry(E?DJu@3}g_HFaF?Pm(r^T$-m_hYz2AR zqK;t~ORSZ*9*Ahqkh*EMy5xcXY`RapcChu4AdC{KVFL19EjosvWj&63VSta>@~xh& z>YcvZ`gq`nTA4BlqlBi#1mtsHI4=Zk%*S8!vOe}JT3fG6|!Ero{y0V8pp0Xk(7-In4U#@=fOw zwyJ-H^HEx@ex^*qD4}UF0lCel4k2h`ev~)!$VXoNjmy|-(e2Jh=LromWfDdSO^XT0 z-3mK|pe6O}SOp<&g|<7O#*vva3802GN-Ht>iT0M3m0{U@d{=K{8@AFs?SKE#)<=Rc zN~nej$g}sh3qi}Q$!vW*_f6*lw$i$(S+S8Vs{~<`Pz@81dv$LYg7(@~0b6Msd!Owql9Xhfc()bXN90`Badb$jGFp>X682qVY=0rBFH-b zrccd%vLyoPOle50VM1l3WX$&LyWMT_FV^;*`}DP8uN%h{A`)CnCRRDvt_DPZ#P2@A zR+^6_ao+QzY($MezI2&>)qi`}v{Jn$;@z}f?c96n|7xCYi4NbkjArlP4Xw`0nO|#| zl@S$W`R+XHED*tw4H`$Ycc9U^I3xBST{dBq(6pF zdZ+c5AdC{KVFEIK2W?Efr@C7oFCV_OgspVu$i(gAO3NgS5}FnhknuZcW3Ft`-}-1Y z@%0k6()lHo-n+lFOu{IkX)ysAzk`-Oxbs%)?1f@WA6XOMiqQeIwZyELe||K$|MX3U*i*?-A)L{zT!rP)4uJ{rpvK;cIG19 zG(*PxM98n7!xT-fz5`e)<9OG<#*19`?{1R0wvfAGOTjU>I9uYm=sfG!?BLiLb(;YN=2iSG<$<`n4yF4O#x>F4k zdS?mRyL*kE?x4{-*^SdrwEl4a=n>J=ooblSJ7mz_U3m0#2aVp5=j0x5{oy{?Bci7} z)i9xV`k>2xx`RfaEKbNYvi@*C?-9|{ooblSCl=6UKixs2Pe@aWjL8CeUw%`csBSAz@cdB6m zavOOP2JO{H^mGS}*5Jlf^{u}If%>q7YM6kGr*P256ldQWEXY2qp?sjxmYCb)FzYWt z7$sE01Z2ET0PXdU=;;m`?NJL3uVeisi0J7~HB3OpTM^J@Kixs2BSW~Qw)K}FqNh96 zFaa5FcR-i@bO()&aKkp&wEhxA^mL~hCLrT273i{`?x4|e7tc6l64BG0ro{wgeWpSi zckdD*VOGdrzYVY}6nKV+{*L>ghzLXq;#O!euqu-P8u?JGIDzLY*zN1J>VpZLGlOUy zL3d=!_`Z$r=k#97eTj<`SUCkBdUpmZpU^w9W`%W2Si^+gYq?n#aRNS&uHK!&$|v-W z?EW=F?A;x%$Z7=|vfgXq+tj{$I3?H$GOT<;@5ovXpKb5%;6tsH(0i>-c3wuDU@OS5 z@`*RxJzTK;$4~9u9ek*j5_+$N@9M_H3ATa^E1!7D-NOavJyOx$-NA=iDWUgT_sW-e zW8wr`L57u29O&-hf`y~%*}FUVP%9<$Udzq*i4$xE8CE{=qPvF+X8zK|-rd26S}B1$ zGW_o50mKQmf($F4kT)#$J`rzN_)9fpq>K3_`u*I^F9C7v?veAcc7m<;)ce^IH%U)T z66m||!J0U+Z|)$hwXgSIK&#=9Qv|NG{uDZv^h@O}m~R##aE>ce1t z1T_v%GYzgf3QTL z`M_RC$T@aQ!j319u}4a4SzQMitLuCp_=*G#zH{O05@dXjDxbh=Cs<)k6qg&;G2wTt zeDb0S*oxCl5Q4eu6#Kv$BczM|=r41vJvqXZH8U=0)8daRE!3B51TrwRCT zPZN%D`QZBCoMWdc5ZIf{_ra|}-zQ<+6}KKs1lm8?O5bu}omYYo%tgf-CiFcV)|Gia z4EI{@j|U&(+S}4CxA}y3&u~Dv+~)S!B|{6#B@AnrDEVZCrE|It_I=p)`$F$D_u@YWe{BdUQ|*4fR)w__RmWYkq_1| zk!V+eMui<6P(Ij;5qmU3#;%T>k{=aY;R`qjd^1lFWk$sWk1^IqL~x7KH_ceRs(Er> z0briZN5EG4#vH3<6GY^LHB6L${ooeYdcU`A&JWr$AlY`+N5ED`v~;8Bq`Uf-Pk61J ziH*0p@py65-i4C9{d4V#HKog3eO&od&+>f)Y;{a!SLbIe`#%UTDkkzTaIL5Gg*?p2x1zLk__3TPF<9Am{|0E%fT+Vr9U}EVGcZFN|@t{~#+H3Xs z3~d+BZRK7$105OksSyO8CKE&y6>IcrpwG3S-IFlPHRl`^(oxf+#a8CbZn#J2LWN`0fRJVWC8^ zS6pKB3AA+C3cE6azz$XkB8rMNOz>DK#`e#(M7~493VHazI(kmYnQK&Rh1~=|VE=&x zA(->Q8YZyc0ch-s;QL@JtZ|1GR>dcX$Omhfz>0j(*hj(oP$J-!A-n@3uO#uKVk_Q1 z(I>L|OxRr`@HBy^2F&c$Ckx0t``4|HTE1ffRxhV@Mk8kb>3Xc=U)>QSUfYPT2PUX= zc*k_y3Tu%ukI?tQyI-&dvJxDvx56#0vnDaaP}g?7)c@~7j@Fp$%CJCIhNa_HSQ&;q z`9ya0nUU3JUd~~q1n19~wCs3N)L~ryQL^KS&Y;8mL|q3rZPBhmj@GVT#`i(2UQWlY zu!;_O@`>z9JtHgiyqv>I3C^GFteX3{T{-!%?De8E3^7wu*9_h>_P;`o)|i@Z#bL0y z(@p8P6;>P~Pd<_Vn_bmtx{mGZxkKyy1ugC+W1_~7Y?$k zGlLVh3`xhWusSn2`?Gsby8_hQdCM(c&QS_VaQ@ti+`WZ%^>SM0Sz?y2u0?%%`kq3L z)|j?0*_Et8>irSvxD{5iB2PXs=MlSF);zN4b}#3!QiAhm`?>k1zFobX*14RBO4sfF z`FVUEa@VnT)o*b3Pot!@yVc8Tg;l@Fnad4cuq%sA)!b2D&QS_VaQ@s%Z!IgGBZ}PW z8fTOhM{A7uz`M=>KH^sD!zUykScPqn57t0dg7fEA#cR9L*{Wz6x*iZ1Tr zp+4ePS|2_kbq>Oy&RGLl3C^GGgLVf2+Xs10b9M&-^g)i+7-_pUDzsf)VXs!&c6~zn zhm8vTgEf$q;QZO~szAppo^`GJ3}C$CdDimw{5Q8t0s48|O8dD_$XH^d!dSu@$Vzbj zyqzi1Jd<4aWWdWwq1waPT^ zn8tj3y)Nng6}S#^w8qfx7wNc_UO#*yyTgW&9X7n2!%7LxpW9mmEfH5|PD@t|;9ASk z`up{<6|es(lfdd_FXv1^)_VzK*321a_Z%qsYgAgFYo7l7%2GTbRsG|-aP<*aSsC{} zkd3J@au?Q(1ltZ7nP#hZMy|^I+5d*HsO!}+;>!>JTXxicV_MER&=Hyz6Z#By;&oSx zkK!MSOLi?Av!vbSL(^>4yl`da*k5~uInP~N>Jz0R>cFDqJh&KsI$4HNn_x!-Ho zijO-Qzfkh%{i~OBfAXd@Tj7bdX3t*X$fK_>^@)3CzEC1LH_wc}Da{%t^m!Mw>_fKx zQxHMLn~KwHmG|?COoM5C!m(!+m-8+}pR*C;mIJa{BB$2eq12<%%?Gn9%o3Q-0|yKGr{T zMEbHb$Gz5j*m-HT!W%FB2IUitUpm6RZ|`>Nd1=-#q3_Gw7p%E=u5NwZ-YZ%!-aJZX z8@_Abv3K~!Z;5E3cw3Ja8nxX3ZI@djw_~4J(R~T7YUYz2BW-Kfw3xtiJAOa?3$*qu z5h#KBfOmbmhm}vXAK$@_qT3I=J>@T3nP>94L4A6X($0zQzgz7K$vPYgeQy7e)% zXmFY}OyGS0eDv9No%qNSffDe6boH$PtbF3oDXXoIOJDAtW(^Z~&j25-s`n5dSt3vZ zK9H`yjewO;TrqaH^)aybHEGr`fp;A6aq=;J#7CA0lz%WaszC zE=se83B1LHk86&-Nql69KneIjy85mcRz5LscO&Z~_rbH%tYPAnzRm}}8_BK_b(*9a zw)rD}=70iAzz5RRcXDm_+*axnx3@jj`lvhZ%rtA5fQ-4rpe4)p&ptZ`SOEs?}~YNKDRWcVsne~_7W4&+xv7O<6;0={M?2pHSEu!f05R1u*q5%0yY-W_?u zS8HuO(HpNoqhc$pMFoLx&eXBEdIkj#iSF%Fy~?E3Co=fpy{u z0+4MbtYL!NG+f}%Z;9w@+KwS>8*}{}=1Q;?=Qcq^K3KzqM(f5a_Q6(Mx(Pyk$ZQdJ z9YhP)7K7auw7p?>2QjvPF6T<%%E{M0{T(U!1Y7a-s$3$9YU7-q@^yM&gqjlGr29VD zieoRAFsxxhBaGg+2U>${#eF_ONNBEIv4#olH+Wlb^AY)AEA1;7i4uhR2vmb>E!V&L zc6S*t*L<**ws7nRks#EEVGR@7SE4oU>cj3|f_?{$_D8Iv=aeLQii)kY&tt8Af&gT% z2CQL%+k)?dt#pLL-T(Bkang>jK;kP5age zSR&Azvz5wNJ@EhT16E9Mw9ZF%*P)c|G=x!2cOZhSZ=-wF|EJU^*h=3t!^$UQW{n+l zF&77`_|Zx*n?_gkL&p9b_}$I-$r5(@%WQ24k`W z=7n2A)8*Yrd_rccTOTr8-R`8KX)%F42k^U_f0ZRLzdhP}1=l6snZPGx*1h#1v+he+ z!vyv?fDdK$V@=%19Jyi!vuDwfDbo6F-rtWzz4kR z{uQwDiGyAlWqmxqyTdZpFoFG~;KN-9vqYc-d>~!kb;>6s(`nnU27a6K|Lz!cUYC6{SmVE6}LlEoInoM3NoyGLT2gN8kBi`Db_$%Li>ta z{}CtH3NoyGf_hZ6Z;)Ckp?$@zV~G=N1sPU8K|QK~HIS9izT(#7#0j>73@e|I*`Kzo zu!4s*kd@HB;?@<#3ATa^E1%FFg_TIGfvkk~6}LVrPOueZSowtZD6FVr4P+&>uefzy zae}QN!^$V9N3~%MWF@$F$zHFn*P;(vf~_Er7u!aeJ$ANn-IpugrgS>WP{iIO(?FRd;=(ii}>&#_n z%=9)#wmfLRoYbdPa=d+=^?MZddhv-byR2EfL3a7CCHwZXh6(+G{)3pht13%f7oyr{{eo z5mk}M*h;@Bq1XDvF?IGV_*>FPKW7aS`t=O`-s?VU2zz!+u+wlI*-% zGH_}8+BvDmceb$m(BoU0+Yfo)UiUt6XF>J6p%PJlDJ$0K*Ej5r&uvW3bFcgFlIhiQ zQWxxLA!FjcboGlOcK-5-Z~r2XeGKcjWH))b6EcFe_Nz}Iw;5PT#ql6 zNLRm9qSk!k*rWc<(YDJPCUgy!+pXv0`VTIByIxM}h(B6*`|0cVTC^*lc)j=3h4my4 zve&P@M(J)nOmKTM=IhFR^Y?CRk=k5WT08A;uit@_t$mN#ykwT-y6C?aUfX4Y$4Xh< z|7o?wT_mbW5*4>Gw$j-&sB@n{|Hz(#;YGy+UssG-xw7fv znkK8$u)uZUfMxJ?_g zZqcmVSHwD3D7L~Z#%|d?eSG4bN9Qb%^F?qrhu1%t;E~Um>pw2dZ6)cyECgFY)_r(< zqSDtb7OfX+jMl7Sf=6)q3O;3Z>vjiR*?Pg|Q7Qd)hdI0Yt_SZH`5mA!b+TU+ufO%Y zlzutHni&0}2wA^0Vm`ewZ^~E8Ct8hr?bczA(6xQ~1@p~rLt_Me8BK9oOz0O=H|w6h zzNXkpzr@z6Ik?a#=nHR(HB9I?Va%=ez9OgMR`^m4E1#e*)hX6MRzkmEV>Y(;HQW+v zrC-LE-`uy*C+LfNiZx8=mv}d4o4)F&*h;_fuWi)3&?ji-K#Da?p!MLn9j(Wkosf!K zVLk(_e1c{`*p{eiajQg2#P9CSc9y_*XRqyYd-VzWikxB%6L?<=AMVX|oWPS1yz5(4 zSos8fMNYAX3A~Ml5BFv}PQVA!)pypg@(KEioMH_VcrOkgcrWgKceVt4AYFcY?i0UE zw%?tDt6uJ%Vht1cdIBHrYhRpz4|vyaEU@y4QSQ5Q(4)7UjZA4Vfv+;~;l7N<3HU&| z`t1f*K5@4D?i}Pic9H$IrD-vNZ%FtZUrFUTDn`Hu($z0bu=0rw@)g<03#Nw#6r@t%8l`qvR*QZ;3KILpnzz5RR=Nd^Ywqm5G`|cc^IPOgQRHSLe3Ei_w);M1| zB=yM^L-1uk(9s!lJal}-j1>Ldy@zWp#B)~;DVT8mKP}iwM?1`u@d@%_RKr&Tq^l`m zoR`uSA4iLiRqr-gpaiVghfg4?mxPdf7}hYMGRAqCVJd|DXLGI^o#Uf(iu89!oGHYD zETPvvM5QvWgFF%$Qx<`*eM*2!_EYYYqUC8cj zHd2ZaK;@4$&Ic1;uRcP^Y(4@AAUNI9ZuLALju>Cdp0*j>baO%afIn{*i~b>207Aw} zZ^&2n8*G1fYewS)TS11EPaOG1oirl4Yt}_+)<9Nb={DyB>xbq2Rg7RO$guK>>#o{e z0w3dVk(o}E7GxzJ8GVb*M-KCs3}?f_y0TS11EPdvS%z4cLg=az3ycRCZ5_5o`q+Rz5NI_{nxg z{Nx>@(yW23#A}ZavH5U&E@z2A3ATa^E1y_hu-DG#s9a%Wnl+G>__AoI^?{Y_#$<^= z3ATa^E1wuOqECU8l^NP-Xqq*UmH75+=L0L`jmZ*$5^Mz-RzA_Pi<^7?aqpYbtbwe= zw&BBUKCrILm@E+}!B&uAtE)G(K6ajbUYa$KmDvBN;Wi&` zy;_zClwd2!u=0t);px`L+?FlVtbwdV*Qw5jTX&Zw0wvfAGOT>!?g3|8AOAb)xHM}Z zEAjRo=fmyKkR<{o*a|YNeB$~~J6j($&a9DU4P+&by<&tdE4M#GmI#z!E6A|&iQuE| z*2j+*ZYg06WF@*j>wI8u2pM)95h%e{kYVK$jq|a8i!txr`g#d#AS-e2H_iw4gD@sb z1WK?KWLWvc>`k{?ABWz0cL{4CD^b11NLyC!{MsxLD8W{cVdWE@7Yw&P9(=n|32PuL zarueP2X-lu*|?4flwd2!u=0ujX1aL*gD<&q8EYUbal+}&2X;S^^&gH1l<=+Gj_*Fv zY{tBji__PnY8Eai(e<30CREDkdd?1iG{~$Q@xQQ9jc(a}gj)&GS%{sf1tn~C${St6 zOV{Cau@*5RCB$(;d?r3PEhcWS-aQ<4!R3~geQVuLo73@e|IZ^CJ5h<08EYalD3^RL`&kvPFtkYVK$@@?Dt!2A-{KvqKMd%0OJae}QN z!^$UQo{aT@c`~eltc1=;bF+8i1Y1Fdl~2fA1M36xeOLoo37uKzW+BB1wt@^RpEy6e z3)D|CZ;3UKmC%`hn9pQPoM0=+u<{Aomov>8$V%wULpLidPOueZSouVaxppVdpt;OE zV+~{_bZ(?O?=DWT6=Xd>4DUD`k!|g!@9!PjaG&75qV3qtt=0aa1k&PO1S_A&wss@) zmTb>KBx(g3vbJN)<=wZ_trBbn8CE`#ZS6+-hwVA=p;k(0J9g)*QU8eg8VGIqu=0uQ zo@WNLURc9~wqwi$HAZ(yQv#9b*-nsQvJKeGdvJ%>kF+bIqED`?ALcaK>6SH2pno8LZf1X$2$X;iq^rFMRzATerq^uU+ zzmKbRWTCf4F%`E00V|)t8SA){!6~k+fvm(GZJm$NC)E=lSt3w^tsuk7C*In-*FLfQ zDCe252C@?E7oTqPaekvi#7CA0lwd2!u=0tia{f8;agv;W&Kk%{^f=D>Fb5qhKC(oh z1Y1Fdl~2@`ok-zhwCqgE8pukFoY2hXqt3Q!;v-80O0X4VSouW%A39qfpUBzdtbwe= znOje@K2o1m6(3n5P=c)>!^$Um*WPHKQuoR^AgqC`M3)Plk1O9hKzwA0Knb>j3@e|I zVhZFx`3q94fvm*Dmru3%a6Vw_{&NIdv5bBbMTNHp22pWZkd=7xAm_uCmE^;|XHbHz zAj8Thq;yN*1EtFv$VwCsY)W;WC2W1ftw5m8eL`A^^?_Ex8pukF{OAA_XaZ#T0;l{))VaKbu6$n`Q1nsJlVhv;^Hl$Cs`M?31%yee?;82#8Al0)2|Z)0WBy|Ne5R zlcgQ&ob3d`Ryc2>e1gw*QMqRicVdj59^=B%$Z!=#t^K>`p`xnYzskzvi>gih!^(p` zUs2=}tYPBeA=@mGH}@?enl)>@06s>vJ8q%Y!Qs=}7u{K-*w)~iReXQOymr&3`5@Xg z{k{cTee{hxWo+F6tGo!ksDe#v)>-d$UYu66Y5aOC|NhLwMYn(RzLj@>@Px}ppgI31 z)ze1O=9H;LC%ovQI_<@&MW1f!Wq;rD4c>*zUqrAKM_4|=8YW)caE0}O67hTlY{lhP zE@4>1MEh6Hw?2|Pn6cI4=hcd=$|VeInBe;^*++Q(FAGt+uN>1bm#r`w=*Unu@%n`7 zOIX7Mk1@tvHn(IkeC)mRl*QaKR=xbMt>-CcmC;JH1_QS0I(U~Q`dm{6foiw?kXtwt ztMmV{bgj!*xf+ZJ)(oofx3!wwybK>vRBSc*y}vAR+18ciw|2u(G0}b24j0w9oVBuwPJ=lXdyGbL75T#EbOwcVD_hAL&$ zN0f868glEOme|wt?f;K8$b>(NO8oNYS|ZoSyxlJ6AMUurs~cyoIcKZpsXn$g+aGmT zl8Ah8eK0X|pre28e79fcrtc)DX*=bfqIY{a`HM&HD=MF0t2c5SvEu#vlSC91r^N(E zYjdtdz)`iF>3o!K9Op%7i9pMWtv-4p8&!h|NkV-X&Ic16?{oB=YwnGe6}Pwvm%7$h zxM51N?P^qptuB1eU9Y-Md@xBwQE_W$g0FUBZ2w%l;&GSnefeJ7C;U4AcmFVG?sL-G z_uWf42U@zSft8Lv!%Lq{5`yWtyDu#!RK~U4_n{i3t9Juk-*_hS7ZH&UC7@xVUQ>53 z@zpc4Vj}}ichM(T)AtE1{Y>fP@s@ysQU z`DJDJYM}DK$&VK$2=x)L56#ns-_P*;iLw22<1Slix!qqny?nxpiV3Y7+}n9R4Bs2@ z^A5LZj|kX`pTf!|3~QL+zT){X{M^s)88{_ZP})D(ir;=D2*Jwewe-G(-_Q6_v4-Ci zC42-L6pH9LoV5|5J{0RalVOl~pOh6uTdA|@l z{>ynq`%c0vV5|5U0SN*pVOl~pOhBHpq;H6G2)vUp3)m`tazTQ?Ntl*U4HJ;RI;3yt zPQjp)Fx#+I{M?KLVdU&gOQ?nk$a%N)v1g&1?4KLq)Q6rFi}x^i`@wHpd_r40&V6Mo z%((^ac6$>h&=HQUbQUvq=t&TO?DHUNn9wyFZr3^&m%9#XZt;Ex>x2;rWc}Tpc*{|- zmA+5HiNFaWii-2WR!Y0~SL~xKEBHtdkq_3Wtfw3!PwuRE@?o%+3>rPV9WvIBVLc9H zcX~DxtkK=yLFn%0?ksE}0NMJ`dHUF0it9t?*1P@TV6Jt}RyuDUJ0_J&81|uS53s8a zr-X2y?vSN*18E|?sr{qV)Ryxk(EadVD)-b`NtLGy+bwN*JM-4WY zv)j2pS|Z4nRiOPGR#>A70_&XDyG~jAK+B4)ct5Ig38SafVLur?6%V_^=!}A0 zXV)rqF=-9*jxf4c6lgrXqTC`vqcUv8`{I;Ou!af!64!RmVJ@o32U}^~;2EcUf;CL| zt9~W#>LXw)twHP!kRSlr{-GNA|Akr#x)&D8%FR_1b0q>iK|)ilRwo&BO;25eemv5oRW=7eHgY<8hh`QPq2mwE(PBQTWM~whfsou z^1&J=v=rQ4NY+cXU1{r+vMbb9iIIrgo3q!_Wh?C~m^)Z5VOYZiw_`u&+OE(>wRhqB zIk#z_U@P`lKEWC$@cs&|Hv{w)TLnbRHqDIOP(CHB9IU#L<`-lob`9+|0ghOiBc7 zrFp{jDnSV5dM#_1&}gG;l=`r5&(U7d545kajK1PW#a7xMF}qEFPY{MROsE{Sc8$uu zbw*T3S4ULLZc7kR&RN3*k4iQl5yAaV?A|I?_LhH%Rhl6>x z1_Q1sZA%zyl|Y{tdm`A1&!$cgfb3l#Ynb3ZZ+$2cXwGr(tX8-S*F2%GSR&ATu$B72 zj*AIGeHhj-q4|q?R77Y#P>MP};_Abt?nlK|ItHU%B?$Equ!ae~miRu{N@=v?1QGdQ zO<6?p8l|Hp?(TIQgsg2k@%$06m5!o#{zwo}RIFiw+k&5Sw$gF_0GWrLAk>Fp4HJ4@ z!E>ASp+tanP^2{tO8s^1&J=cn1kTDlSFs+qh5UQum``E8JzG4zSuSK}1oph6zo{jV0%w zR6P%^l zXsIWkCfG`Q7w(qICs@OTU%ECYuAc{NrF|P$%W?_(RD^m)O);UP1g;X!gZ6V?JI`zN zd5;6XblHk`5J(VOx`s7O@E!-A55qe}@Xi#x3g0K#iucPXpI{9WJWBXJ*oyc4NDxuZ zS;ItP^a;wU4=y*3){lyjky`Cot zwqjWcIcZGxnOra5Cirft?(|7=uf_iOo?#ymw`W|oo|cAprZIo9U9){Jw~=S}Vvc6_in z{I1`WBFyEz?1ADCGk$qquQ5xyzg2*;>Sy|ST$YYoojAHU#0+eo_^9ztn~#Rg|CeSBWF@#ZjrpKQh189$%$XIx zy~+}5)%2d8;qF_C!--!%SmYB2Hvh%?`2PCqZJndnqBX>ceXXR~&Qnr5@7nLor(SEF zXo;ZF5-}(JgQ>-#TLsbe*Ar~cKWkOwl`hX*_lX~u=Gyw$(6M=%HB2Ei95#@(AjZs})xi=g zcORK%4HLZv^bXffC=TaNo+QLuZ=Ihy?u0R|9-LX<5{L?E@p==VXuZ6X^|Ae=L({Bb z0`jb}5|ylJF{a}s-7N9h<^$5KVPeaw-eH}g#o_CBJRro{FRo0Tb=c@u-yL1i5;iJH zi&sAQ#NMK7t&e~1*;T?CCLlNITO49FkL*=E`9@2uzWhA^x~6l1krOu z&s2w9BU?Sud7~u|71H9h89p(nppW%YXZxxW)-VCNZ^z;gYe9_psc@hrK6-av32T^G zb8(+=PF`_%MjnXA#tcf0+B2-x`TNbX1foJ(yiUU>)=e91ee`bda0zRefV}*e;t*?E zWIupHcV1DIs>4cH!^Er+eZrEe#bNFqtpB)V-O$uyvu|nDW6rgfKvYPJSBdz<(>b@> zs5Uk^r-U_3K%V_ukI=0#`QXx#AcAn|Ps`XUzA7a_7$sE01myV(dxR@w6^!fzy?d1P z@mOB9H`pq^ZYDt(B~-%%KK`lsb{n>eujWY*MhVq00r{O%dW2Y^ zWX$r{huM5Q^7MrTY{hGg$|Q^unidm~um9@C(5;WE{MF6Y$Jo~%DPXJkimC)*lu!*5 zkdMFb#tVu1xlUta**~aec|20=9~; zL`x7x3DqzG`R6Zg2(hkEcA&ZXBJ1PiBkQKviq{O5Nf;$GEhZp;HRguUtx>$XYk~E# zvRRW9Tk$E; zaNy5aIf+%|ElM73fq&WR-PNyU)~qfFv2NQZo~Yz}bP$3yaRRjS@#>v}>^;Mv#Y61< zmEK2TiKnjVJIHFr(BFwIu+m6PQYs$l~1kno%kD>aSztf+$ZvHI_;(rgu9 z+gU!L8YUq3tJf~X`cY$E-~K@f^6|(4z0zzIUvXMKp&BM2kL%MetYugIPCxZ&>!a(l zgVJmjUng8Xp&BM2|N2_H5bKhSS$f@d*2i~ChNjsnzLL3oLN!c44lA_}v0B=gopra{ z9Z$YIWn`MI;_Iu+Cse}(>Z&T(g}_)72c3DqzGdCvIuAy$^l ziG`Ut*nuY4RdZCDt>SCZ6NFJhHB3Oh?#=cg*1Jo;Xq!Sm50;F)JOw#TPf!vy5p zCg+51&FG-|9W62JqXsF~F!A?^>oZ?Y%L&Id#u~+K4K7NT%seFjy&-iifv9+uDONK2 z#L>Ghu|AgUt(jsCuYH6(b7oHH)oSXG=Y+YSnPTtBw2jcV`KHw#$91mqc?<%C$H zDrY-ge3K;>eE(trYnXU)@Y>AG-*UpAMm!?Kupu|6OM4xfpOSsB*oxP|`o!OZ-M6y3 zeJ2&Lh6%`TRmu&qQdjmD-QwQ$Ej@5R0c)7(am?DxKMixkF$+L!DIS)-?T>18gcF3_Ig8U`0`h5t zazm^#melEF(zq4!gxy-oB!Jp=!kU)SO0=1uYiW7!%pHK}G zkf-g+4c&eje@T5HqE4GTm#~%AAXa++--M>c1mvOZ^Fq+Z6iZ8lj|H-G7F%hn#QO99 zo6xkFfPCQeyb!c8XGkA}kG`^V7F%hr#Y*`9o6xkFfPDSdywI(q4`lR#kB5v&vz3ll zSgZek6PgwikRNW>G6XI6)H3eEhm5;v&nmkkknRmoKA{>N+btpVoF`j`kmYnPx#GYF zcFtlezN+E(@(I;2!PiIozTNu3`*xo33mN?bZ|HfJu6=u+9>3vjthBI%TJb(SK7l>9 z8a_Y5zSCz76E&;v$c*Tf6aHAgx8xjm0B_#ZU;*BqvlZ_rjNtjPh-&3e(nKoFxr%=y{8@9Qo5UoCKucwB3QE?=^vzg3cxnNs!e3y_fCeaRN zh!<vV8prM##Qx;u$HV>-SfiS z9*4z<84H%@y)36-wyK)~Oz3%#CbrC@S2OzYu^`wt@NZ=v@4(3F#4k0&%{SHiHbE$_^ss9My(eY zi;q#_gRS%|TeM@Jc<8Oya~FvZIV;{9shQvw>c&Hi4j2;=6~3$4IlFWhrfc7EQkNs{ zX!m(DCG=j6@8Ns`BTse&virTl2hxfYr~ci{{tjCcWas;&bXE{{Z`IjCnB}Xplkj_- z*f(ce=PD%$Iqk;Y@8YzZHl}%!!=>%n8Ahiv>V8X)}4=Y!ho|u1ncFr8@6h_ zOZMB@R%p+zDU&ctXj)7_#_#TYoWnlrY<*N{RU^$-_neiF##FB zyYq22ZR~D+bi8;=30pOIsWh{&dRu#TO__vILepXbGJbdGF##FByYq3r+;pq;@#5gSOW11uXX(tjXP;%yt|^l+N@!Y4K*sOx ze4M%qhFc$_*EA|&t9s9+Gt<96%bs0RCSjD&w3vX5-`)8*HJ=(~eVozi%4KYYy=7L7 zKikf^E0ZuvXj)9@&NP^RCtpmeH%wptPpkYna^lo&%a&X3IG5_@mdi6M*QCNhHv~o8 z3uMkjk7I3A&wqDLI&QVSLZLlz$|uU}QLs{i`;9Rr<0_}?P0r8XfA!_*f(9|$h$5QsJEuZ*us{7{kV#f=;oWn{9&Yv-x zc79%R%pEQBd&((e-|c?OMuoG;UMhYo)8d#^_{g%+MI5a$4;21{?>NCx-(8=MTg`5l zvZsvs#D*6P@?mbi_-Zfbuu_8aXUu8WO}0M9b-E?Je~Xp&+a^w7n|!#F@tqUDqb;~I z+?tGhvZTe$d-E#Szd6lTyT-qr3BD@`_sfeDC6~QevUy}~{#H4|jniU+OGMsuwO(SQ zI^xs*>A2Oxy#@9RH=merm)lkTiuZbXr3))1xD1V%G{l|4cbA;PcU;BQncasrvuE{< zn)+_$*}bRPZ?us2eXo_%>ugjwy^hO@^K{VQRhDpP>ct5yMOZUmPr^8tceq7 zSLs%$!S5b?qTsH+w{%n(y0sMjzy8jj29;oQy ziGB5P;p0yfG=6-*($CtsoNJkIS#kc1S-1C@f}%(Fw)~~ZAX^_=2RAo)Kht7*v#`!J zV~Tv@#!V9nTHUi?$@gvjvSNZu0VgT%w)yx{&SZUXyE~C1N?czl`=;zA=Lq zq;1ZZ|F56d+T(wqw;|l&BBwP4ZQj{rt(oWt&cCKTx#na;~-i_oY>b& z5Rv-}>1u`=1yB0y#YgAc;TRWl8IBoh)DQe%KuU!SvsQH|t zUJV}`dZ#9Sdi?8gk_JQQV)*@S}j0p9~%iUR)&7Djw!(@bJG3sK<-sazicTk+Y#qw@~-hQaoWrRT}G3u|5hb zq;-udWZmyT%nBXx*E@&Vo$=U8S7hTWfKSMmrSu^q|822V{^c^k%5t3binm`pqRI?9 zv8*_5XbXI|Wh-9qo+OYDd?jN|oWQqK_f~DASborVcrM;8FIsl~DD9(xtj2gvAy zclqayX}kd6pV^9Y?h~*ay}fV&N|!ZEaQ@s|LF5D9pW{}zilVH10#Sj$zpR10kJz`z zfjkxMJ-I|8N}c}wY4Wabs#x6`Ry0o*?Ol%6ertHcL5pJ}L-j0ih7fGUSI&4#3=oz5 z(^9~Ln~RDsuDJB)K==DMFuiz5VF4O$Ic|KCH~yt zDmw$4t#ob!c1Qf&M5Tnb zUDTk<2Z*bM_(=%1f?V3Io~=Qxb4Rol;(Q?vk#nk9!^EF^r(_PU($Lbjtg`|A*x1NK=jYn1S#Vk_R6okt9x;HbDQG3^s<#pPBeA!v|h z4HM-@#a3LR3BraJFI~Sx%jh2g2)6S3T^WSU2j`p#zi(ESy9(jeU1B|OUc!Z%v^qXNDHj&$9y%mf{gPY z@SW2qT7GhcooOg{uU-u%39XMKdT!6TT5>)v>qFDkb1ZO@1m{oY8WgQOqpX}W!KIFz z@4F*IBs!9*jC?@m(I+B;xRple6E!6d@br=71N~gbD17I}S8MDj#{J(ICfG{9j3)`C zFL|+kuWIM3cxr_`@07-Fc95ezWg~*q#onlzZuvgg zO6R@eZpkO~%t@Re$r>hfj|+E4ro^kqG+e}1e0Sy(C@C!~)-a*FNkk`YLHl{nFxF;5Qnn-nPd=BPpTLPmG2yQVxfzj>vjaM:WfBSN(sYU3!tO?rYNF z51gR@A3cUWZQo3ATI|Co;6wAl8Ya+o^?okOxqaG>Tj_}E6WQk|%=d}js$j1Yjnc)ed)6?aZzpiJs}+T(b&u@EuDPxw(*&tHaL0Izhk54C`$xv_17EDYHyPX z+aV&k|>f{1*u zhKc-QN1rfbOsuTfs#fZLn~zz4-IGZWkq_1|F>H?W@xs>8F&}JI`xWP-?RR%)5=7*K zHB7wxyYq2%tGYKN{ z!5St;FL6FrA2KZFgRK@{;e32_aF9t5kq_1|aqdUX$2%|F7W2VYJ100FU$h;bNf40_ z)-Z9;7UyH-iMPaju+_x5&PQRV3i=$N5C2;)c2C&elZ_xrT$L%q)(KOh=_b}T1;pe=6}>X z=7X)Y+`^LLs6HYh^1*2_p=}|rOV5}Ow$l1PZrSxwyNZa&2dBk^w&@nX-Wc=2R@#m) z-E?i#KO!RX!D%s}ee~F=p-1>ta6GO2?J&!*0=d z6%mmSPKya0E8iY@ZOjK->G(M7;me|NHzFb*oE8&0=C@yXb<77_={W!F>z72=kBEqT za9T|0wQKINSH*m=m0qt#~Yw&`1uZa0zE4}W%R{O%}dL9vx4^E2- zy_dLV!R0X@Y^C=P?_7F*bYBt?kq=Ib3B4!!^Q&$#A8e)fLBH-jFS@^qh{y-0#f0A5 z{n07zgRS&_u0ezIqWi>%h&dVhX zYnaIY*3nT*R3C<|UTEp8(00owSi?m6VMj+jD)PZrKc>goe4r1OPq2oGk)526Xk>_d zu+{e$I3E~G$|qREM8_J=M>N7kKG^(G@51!B(lJ&IhhhiYW^Fh*m+ z-i;MCw%90(vX7u*?8ev;|Hc9cx}qXB$|!4HD~UZ8Y)R}9R2F0(cWlw9QLNF}jmF*^ zioEA{&YYRw-I)jS@=3X$J?DGRxp!_kx6C|eXsLc6n{UT5b<(gAx&ZFM}ma zcpaA4IIQLMhBZ!!$ZfEM32zJeTFr@swfy;Gt=5nTEMdaibiU@yZLpTNW2`wF5`iU5 zc;C#|&bbZN^8Sdmb3-Dqgb5#G@;!ju25b4af<1tSL|_RMK33*?8MzJC^6_y~*~@51 z1eP%2V}8CTliOe|ALp?r(~t-(VZ!IGd~YeY!CF3FVQ;A+5m>^6&%yZ~S#E>1eBQ+# zSwkYQgb9x&^1Z&?25WizfW5wkL|_RM9uwtzmbneq@;C^4mJNwKzCvD1cx;#Nz2-Jp z%i}rhy~f1LqhH0FNa61jC)7-v!YJVcYN z>6Tk|C6NDG4^8U--8?7SG+!n>ayA>ksK2_6+bC<9S1}>w(07+m4whKj2wwr9eDVc> z62V$l3o&u^ng{6{BQNwgrN$CV8{sP%JWcuLa*1HA))ZPX(d*P3)W!){99LtBrH$|v z8CqosWrDR@Q)tD+oF86L8&B>#qQ(+S8{sQU^sW%f1Z%aX(29vGf9Rnn0M8#dq{b3U z8{sQtj1nP~3D#;&p%oM3KUzg?eDK6BHI`V~2w&-Av7L}VdC4#kDQ)tD+=uHk)8xKAAX){YKZG`WHAsUdA%o4#`ttqr( z;`h%Stv0?qeO5C|ENz7E=pm|+H^WK{{HM{mRQ;d-o7DAa| zt=1G;G4b|wKsk4L$A7ik( zkH(UWXibr?k3P_fiEM-mGA7np!i0~N*rkZZ#EfW7k*|-U(29v{qz*E+*IB}ZkNMbb ziN^MfkU2{7_1OSgF_FzULFTABOPKJv3%f?q9F-BRDf0DM4O%hLVsmZy?7$&)mN4OS zFm}J>U88JvE{N6?`TFb(t(eFnfFLnLoh3|oEP-9TC}zlr))e`AlmV@n$Re2_u}_^P zOn6L$-N-2R$%xie_Yn0SKx+!En3%Md#&F^B9;eh<;_(#-kL|Fl8bU@S1!4Jm)CaAY z_^Cx>(eTv733Zk*;V~+9hvkb|MkEE%nj&A1UZE8eh^g&gQfCPh9=DqfSC`N|BU)2P zJccjQZTffhO4kPPit}Q^R~A-RQVtMWjP5*?HQ32gym~mHU`Ip%pYn4^9M_q@SPW%qcS2X2+P;BY%Yn3 zxo`bWZCrUv&pJz(@Es(ZYcnD#2+P;BY)*`czMJYdox=0aeA>YhCVVH%Vup-J3c~U= zEt}h8LgErF2jUWzFyT9T7W-sGQV^D}X<3XC6A~@iGne>^B~19vq{VOQly2xOmRQ;d-YE_tBa(t( zEsK3);=|0w6ZZ`rz!FOv;kIpUkP%5iu$IN}F+p|J%n~mL^7T5jH4fEPMp(XHyU>aW zSrzFs$2y87On6(cwOU3b1z~F(fBw*l32M8|EMdaiw5>U*?Pi3n)x5PsD<-H9HnW5Y z@0+%EraqVvw&wI+3$2)-u|&RtVJ8@cmaU3?jIlic8cQ;QwQQ{(6Er5)SmNUq^7XOO z_A+Qp%m~ZZM^R|S1dZ)AmN4OCzU|4-*q#x#m*KMkv|@ths2WR{@VU$OmS~R32(cmg z`m6@6n2_BlZM)dNVhIyI2iqQ5MkEDcdrLk$Ln|gIW~i}*36CXgua9DejIcd2k20VY z6BPT@Si*$IM7C#1u}?iV{hf4=xZyN7DwuaNA^zdPS*1x+p{y(WfYuK>PjF?Pm{C#FY zBv3b^(1N|;!)9f47eW9d#?8ApbsOX7okr-&R+ki}Yz?gX$`Q0k^?gg;x~>AhqFnu~(>d|GOw^{%)fvtvwqnM{wRdp% z;ybL*d;r7+VxzF$FVXLPf8VU@cDDyWz17 zZzWa><`vTX%*#Z%b}IP~20k*Y*e($*tl`($V)^EMMNZC@y*EO1KvO?kzvAE6xk) z7goJqc7*?;HcA9gwc(N~0<_xD)-EZz>+JpfI?315TV-h*kIMwwm3&)7wY-hlIEIpE zbrsoQEpL4d2`LB0M9T|lCh%mth3Q2(5-&%rg^|-dED