From 3354d919fc71130fe5b6b1d9997fdfc68fd6b42f Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Tue, 25 Feb 2025 15:27:29 +0100 Subject: [PATCH 01/69] LeRobotDataset v2.1 (#711) Co-authored-by: Remi Co-authored-by: Remi Cadene --- README.md | 2 +- examples/10_use_so100.md | 6 +- examples/11_use_lekiwi.md | 6 +- examples/11_use_moss.md | 6 +- examples/7_get_started_with_real_robot.md | 6 +- examples/port_datasets/pusht_zarr.py | 41 +- lerobot/common/constants.py | 15 + .../common/datasets/backward_compatibility.py | 54 ++ lerobot/common/datasets/compute_stats.py | 316 ++++++------ lerobot/common/datasets/factory.py | 4 +- lerobot/common/datasets/image_writer.py | 28 +- lerobot/common/datasets/lerobot_dataset.py | 472 ++++++++++-------- .../push_dataset_to_hub/CODEBASE_VERSION.md | 56 --- lerobot/common/datasets/utils.py | 439 +++++++++++----- .../datasets/v2/convert_dataset_v1_to_v2.py | 4 +- .../v21/_remove_language_instruction.py | 73 +++ .../v21/batch_convert_dataset_v20_to_v21.py | 54 ++ .../v21/convert_dataset_v20_to_v21.py | 100 ++++ lerobot/common/datasets/v21/convert_stats.py | 85 ++++ lerobot/common/datasets/video_utils.py | 4 +- lerobot/common/policies/normalize.py | 34 +- .../common/robot_devices/control_configs.py | 8 - lerobot/common/robot_devices/control_utils.py | 8 +- lerobot/common/utils/utils.py | 16 +- lerobot/configs/default.py | 2 +- lerobot/scripts/control_robot.py | 16 +- lerobot/scripts/visualize_dataset.py | 9 +- lerobot/scripts/visualize_dataset_html.py | 15 +- lerobot/scripts/visualize_image_transforms.py | 2 +- pyproject.toml | 1 + tests/fixtures/constants.py | 6 +- tests/fixtures/dataset_factories.py | 89 +++- tests/fixtures/files.py | 26 +- tests/fixtures/hub.py | 21 +- tests/test_cameras.py | 4 +- tests/test_compute_stats.py | 311 ++++++++++++ tests/test_control_robot.py | 63 +-- tests/test_datasets.py | 359 +++++++++---- tests/test_delta_timestamps.py | 155 +++--- tests/test_examples.py | 2 +- tests/test_image_writer.py | 50 +- tests/test_push_dataset_to_hub.py | 370 -------------- tests/test_robots.py | 7 +- 43 files changed, 2023 insertions(+), 1322 deletions(-) create mode 100644 lerobot/common/datasets/backward_compatibility.py delete mode 100644 lerobot/common/datasets/push_dataset_to_hub/CODEBASE_VERSION.md create mode 100644 lerobot/common/datasets/v21/_remove_language_instruction.py create mode 100644 lerobot/common/datasets/v21/batch_convert_dataset_v20_to_v21.py create mode 100644 lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py create mode 100644 lerobot/common/datasets/v21/convert_stats.py create mode 100644 tests/test_compute_stats.py delete mode 100644 tests/test_push_dataset_to_hub.py diff --git a/README.md b/README.md index 5125ace5..59929341 100644 --- a/README.md +++ b/README.md @@ -210,7 +210,7 @@ A `LeRobotDataset` is serialised using several widespread file formats for each - videos are stored in mp4 format to save space - metadata are stored in plain json/jsonl files -Dataset can be uploaded/downloaded from the HuggingFace hub seamlessly. To work on a local dataset, you can use the `local_files_only` argument and specify its location with the `root` argument if it's not in the default `~/.cache/huggingface/lerobot` location. +Dataset can be uploaded/downloaded from the HuggingFace hub seamlessly. To work on a local dataset, you can specify its location with the `root` argument if it's not in the default `~/.cache/huggingface/lerobot` location. ### Evaluate a pretrained policy diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index f7efcb45..b39a0239 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -335,7 +335,7 @@ python lerobot/scripts/control_robot.py \ --control.push_to_hub=true ``` -Note: You can resume recording by adding `--control.resume=true`. Also if you didn't push your dataset yet, add `--control.local_files_only=true`. +Note: You can resume recording by adding `--control.resume=true`. ## H. Visualize a dataset @@ -363,8 +363,6 @@ python lerobot/scripts/control_robot.py \ --control.episode=0 ``` -Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. - ## J. Train a policy To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command: @@ -378,8 +376,6 @@ python lerobot/scripts/train.py \ --wandb.enable=true ``` -Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. - Let's explain it: 1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/so100_test`. 2. We provided the policy with `policy.type=act`. This loads configurations from [`configuration_act.py`](../lerobot/common/policies/act/configuration_act.py). Importantly, this policy will automatically adapt to the number of motor sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. diff --git a/examples/11_use_lekiwi.md b/examples/11_use_lekiwi.md index f10a9396..a7024cc6 100644 --- a/examples/11_use_lekiwi.md +++ b/examples/11_use_lekiwi.md @@ -391,7 +391,7 @@ python lerobot/scripts/control_robot.py \ --control.push_to_hub=true ``` -Note: You can resume recording by adding `--control.resume=true`. Also if you didn't push your dataset yet, add `--control.local_files_only=true`. +Note: You can resume recording by adding `--control.resume=true`. # H. Visualize a dataset @@ -418,8 +418,6 @@ python lerobot/scripts/control_robot.py \ --control.episode=0 ``` -Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. - ## J. Train a policy To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command: @@ -433,8 +431,6 @@ python lerobot/scripts/train.py \ --wandb.enable=true ``` -Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. - Let's explain it: 1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/lekiwi_test`. 2. We provided the policy with `policy.type=act`. This loads configurations from [`configuration_act.py`](../lerobot/common/policies/act/configuration_act.py). Importantly, this policy will automatically adapt to the number of motor sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md index e35ba9b2..2bbfbb18 100644 --- a/examples/11_use_moss.md +++ b/examples/11_use_moss.md @@ -256,7 +256,7 @@ python lerobot/scripts/control_robot.py \ --control.push_to_hub=true ``` -Note: You can resume recording by adding `--control.resume=true`. Also if you didn't push your dataset yet, add `--control.local_files_only=true`. +Note: You can resume recording by adding `--control.resume=true`. ## Visualize a dataset @@ -284,8 +284,6 @@ python lerobot/scripts/control_robot.py \ --control.episode=0 ``` -Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. - ## Train a policy To train a policy to control your robot, use the [`python lerobot/scripts/train.py`](../lerobot/scripts/train.py) script. A few arguments are required. Here is an example command: @@ -299,8 +297,6 @@ python lerobot/scripts/train.py \ --wandb.enable=true ``` -Note: If you didn't push your dataset yet, add `--control.local_files_only=true`. - Let's explain it: 1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/moss_test`. 2. We provided the policy with `policy.type=act`. This loads configurations from [`configuration_act.py`](../lerobot/common/policies/act/configuration_act.py). Importantly, this policy will automatically adapt to the number of motor sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index e57d783a..638b54d3 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -768,7 +768,7 @@ You can use the `record` function from [`lerobot/scripts/control_robot.py`](../l 1. Frames from cameras are saved on disk in threads, and encoded into videos at the end of each episode recording. 2. Video streams from cameras are displayed in window so that you can verify them. 3. Data is stored with [`LeRobotDataset`](../lerobot/common/datasets/lerobot_dataset.py) format which is pushed to your Hugging Face page (unless `--control.push_to_hub=false` is provided). -4. Checkpoints are done during recording, so if any issue occurs, you can resume recording by re-running the same command again with `--control.resume=true`. You might need to add `--control.local_files_only=true` if your dataset was not uploaded to hugging face hub. Also you will need to manually delete the dataset directory to start recording from scratch. +4. Checkpoints are done during recording, so if any issue occurs, you can resume recording by re-running the same command again with `--control.resume=true`. You will need to manually delete the dataset directory if you want to start recording from scratch. 5. Set the flow of data recording using command line arguments: - `--control.warmup_time_s=10` defines the number of seconds before starting data collection. It allows the robot devices to warmup and synchronize (10 seconds by default). - `--control.episode_time_s=60` defines the number of seconds for data recording for each episode (60 seconds by default). @@ -883,8 +883,6 @@ python lerobot/scripts/control_robot.py \ --control.episode=0 ``` -Note: You might need to add `--control.local_files_only=true` if your dataset was not uploaded to hugging face hub. - Your robot should replicate movements similar to those you recorded. For example, check out [this video](https://x.com/RemiCadene/status/1793654950905680090) where we use `replay` on a Aloha robot from [Trossen Robotics](https://www.trossenrobotics.com). ## 4. Train a policy on your data @@ -902,8 +900,6 @@ python lerobot/scripts/train.py \ --wandb.enable=true ``` -Note: You might need to add `--dataset.local_files_only=true` if your dataset was not uploaded to hugging face hub. - Let's explain it: 1. We provided the dataset as argument with `--dataset.repo_id=${HF_USER}/koch_test`. 2. We provided the policy with `policy.type=act`. This loads configurations from [`configuration_act.py`](../lerobot/common/policies/act/configuration_act.py). Importantly, this policy will automatically adapt to the number of motor sates, motor actions and cameras of your robot (e.g. `laptop` and `phone`) which have been saved in your dataset. diff --git a/examples/port_datasets/pusht_zarr.py b/examples/port_datasets/pusht_zarr.py index 1506f427..eac6f63d 100644 --- a/examples/port_datasets/pusht_zarr.py +++ b/examples/port_datasets/pusht_zarr.py @@ -2,9 +2,10 @@ import shutil from pathlib import Path import numpy as np -import torch +from huggingface_hub import HfApi -from lerobot.common.datasets.lerobot_dataset import LEROBOT_HOME, LeRobotDataset +from lerobot.common.constants import HF_LEROBOT_HOME +from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION, LeRobotDataset from lerobot.common.datasets.push_dataset_to_hub._download_raw import download_raw PUSHT_TASK = "Push the T-shaped blue block onto the T-shaped green target surface." @@ -89,9 +90,9 @@ def calculate_coverage(zarr_data): num_frames = len(block_pos) - coverage = np.zeros((num_frames,)) + coverage = np.zeros((num_frames,), dtype=np.float32) # 8 keypoints with 2 coords each - keypoints = np.zeros((num_frames, 16)) + keypoints = np.zeros((num_frames, 16), dtype=np.float32) # Set x, y, theta (in radians) goal_pos_angle = np.array([256, 256, np.pi / 4]) @@ -117,7 +118,7 @@ def calculate_coverage(zarr_data): intersection_area = goal_geom.intersection(block_geom).area goal_area = goal_geom.area coverage[i] = intersection_area / goal_area - keypoints[i] = torch.from_numpy(PushTEnv.get_keypoints(block_shapes).flatten()) + keypoints[i] = PushTEnv.get_keypoints(block_shapes).flatten() return coverage, keypoints @@ -134,8 +135,8 @@ def main(raw_dir: Path, repo_id: str, mode: str = "video", push_to_hub: bool = T if mode not in ["video", "image", "keypoints"]: raise ValueError(mode) - if (LEROBOT_HOME / repo_id).exists(): - shutil.rmtree(LEROBOT_HOME / repo_id) + if (HF_LEROBOT_HOME / repo_id).exists(): + shutil.rmtree(HF_LEROBOT_HOME / repo_id) if not raw_dir.exists(): download_raw(raw_dir, repo_id="lerobot-raw/pusht_raw") @@ -148,6 +149,10 @@ def main(raw_dir: Path, repo_id: str, mode: str = "video", push_to_hub: bool = T action = zarr_data["action"][:] image = zarr_data["img"] # (b, h, w, c) + if image.dtype == np.float32 and image.max() == np.float32(255): + # HACK: images are loaded as float32 but they actually encode uint8 data + image = image.astype(np.uint8) + episode_data_index = { "from": np.concatenate(([0], zarr_data.meta["episode_ends"][:-1])), "to": zarr_data.meta["episode_ends"], @@ -175,28 +180,30 @@ def main(raw_dir: Path, repo_id: str, mode: str = "video", push_to_hub: bool = T for frame_idx in range(num_frames): i = from_idx + frame_idx + idx = i + (frame_idx < num_frames - 1) frame = { - "action": torch.from_numpy(action[i]), + "action": action[i], # Shift reward and success by +1 until the last item of the episode - "next.reward": reward[i + (frame_idx < num_frames - 1)], - "next.success": success[i + (frame_idx < num_frames - 1)], + "next.reward": reward[idx : idx + 1], + "next.success": success[idx : idx + 1], + "task": PUSHT_TASK, } - frame["observation.state"] = torch.from_numpy(agent_pos[i]) + frame["observation.state"] = agent_pos[i] if mode == "keypoints": - frame["observation.environment_state"] = torch.from_numpy(keypoints[i]) + frame["observation.environment_state"] = keypoints[i] else: - frame["observation.image"] = torch.from_numpy(image[i]) + frame["observation.image"] = image[i] dataset.add_frame(frame) - dataset.save_episode(task=PUSHT_TASK) - - dataset.consolidate() + dataset.save_episode() if push_to_hub: dataset.push_to_hub() + hub_api = HfApi() + hub_api.create_tag(repo_id, tag=CODEBASE_VERSION, repo_type="dataset") if __name__ == "__main__": @@ -218,5 +225,5 @@ if __name__ == "__main__": main(raw_dir, repo_id=repo_id, mode=mode) # Uncomment if you want to load the local dataset and explore it - # dataset = LeRobotDataset(repo_id=repo_id, local_files_only=True) + # dataset = LeRobotDataset(repo_id=repo_id) # breakpoint() diff --git a/lerobot/common/constants.py b/lerobot/common/constants.py index 34da4ac0..d0c9845a 100644 --- a/lerobot/common/constants.py +++ b/lerobot/common/constants.py @@ -1,4 +1,9 @@ # keys +import os +from pathlib import Path + +from huggingface_hub.constants import HF_HOME + OBS_ENV = "observation.environment_state" OBS_ROBOT = "observation.state" OBS_IMAGE = "observation.image" @@ -15,3 +20,13 @@ TRAINING_STEP = "training_step.json" OPTIMIZER_STATE = "optimizer_state.safetensors" OPTIMIZER_PARAM_GROUPS = "optimizer_param_groups.json" SCHEDULER_STATE = "scheduler_state.json" + +# cache dir +default_cache_path = Path(HF_HOME) / "lerobot" +HF_LEROBOT_HOME = Path(os.getenv("HF_LEROBOT_HOME", default_cache_path)).expanduser() + +if "LEROBOT_HOME" in os.environ: + raise ValueError( + f"You have a 'LEROBOT_HOME' environment variable set to '{os.getenv('LEROBOT_HOME')}'.\n" + "'LEROBOT_HOME' is deprecated, please use 'HF_LEROBOT_HOME' instead." + ) diff --git a/lerobot/common/datasets/backward_compatibility.py b/lerobot/common/datasets/backward_compatibility.py new file mode 100644 index 00000000..d1b8926a --- /dev/null +++ b/lerobot/common/datasets/backward_compatibility.py @@ -0,0 +1,54 @@ +import packaging.version + +V2_MESSAGE = """ +The dataset you requested ({repo_id}) is in {version} format. + +We introduced a new format since v2.0 which is not backward compatible with v1.x. +Please, use our conversion script. Modify the following command with your own task description: +``` +python lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py \\ + --repo-id {repo_id} \\ + --single-task "TASK DESCRIPTION." # <---- /!\\ Replace TASK DESCRIPTION /!\\ +``` + +A few examples to replace TASK DESCRIPTION: "Pick up the blue cube and place it into the bin.", "Insert the +peg into the socket.", "Slide open the ziploc bag.", "Take the elevator to the 1st floor.", "Open the top +cabinet, store the pot inside it then close the cabinet.", "Push the T-shaped block onto the T-shaped +target.", "Grab the spray paint on the shelf and place it in the bin on top of the robot dog.", "Fold the +sweatshirt.", ... + +If you encounter a problem, contact LeRobot maintainers on [Discord](https://discord.com/invite/s3KuuzsPFb) +or open an [issue on GitHub](https://github.com/huggingface/lerobot/issues/new/choose). +""" + +V21_MESSAGE = """ +The dataset you requested ({repo_id}) is in {version} format. +While current version of LeRobot is backward-compatible with it, the version of your dataset still uses global +stats instead of per-episode stats. Update your dataset stats to the new format using this command: +``` +python lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py --repo-id={repo_id} +``` + +If you encounter a problem, contact LeRobot maintainers on [Discord](https://discord.com/invite/s3KuuzsPFb) +or open an [issue on GitHub](https://github.com/huggingface/lerobot/issues/new/choose). +""" + +FUTURE_MESSAGE = """ +The dataset you requested ({repo_id}) is only available in {version} format. +As we cannot ensure forward compatibility with it, please update your current version of lerobot. +""" + + +class CompatibilityError(Exception): ... + + +class BackwardCompatibilityError(CompatibilityError): + def __init__(self, repo_id: str, version: packaging.version.Version): + message = V2_MESSAGE.format(repo_id=repo_id, version=version) + super().__init__(message) + + +class ForwardCompatibilityError(CompatibilityError): + def __init__(self, repo_id: str, version: packaging.version.Version): + message = FUTURE_MESSAGE.format(repo_id=repo_id, version=version) + super().__init__(message) diff --git a/lerobot/common/datasets/compute_stats.py b/lerobot/common/datasets/compute_stats.py index c6211699..a029f892 100644 --- a/lerobot/common/datasets/compute_stats.py +++ b/lerobot/common/datasets/compute_stats.py @@ -13,202 +13,164 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. -from copy import deepcopy -from math import ceil +import numpy as np -import einops -import torch -import tqdm +from lerobot.common.datasets.utils import load_image_as_numpy -def get_stats_einops_patterns(dataset, num_workers=0): - """These einops patterns will be used to aggregate batches and compute statistics. +def estimate_num_samples( + dataset_len: int, min_num_samples: int = 100, max_num_samples: int = 10_000, power: float = 0.75 +) -> int: + """Heuristic to estimate the number of samples based on dataset size. + The power controls the sample growth relative to dataset size. + Lower the power for less number of samples. - Note: We assume the images are in channel first format + For default arguments, we have: + - from 1 to ~500, num_samples=100 + - at 1000, num_samples=177 + - at 2000, num_samples=299 + - at 5000, num_samples=594 + - at 10000, num_samples=1000 + - at 20000, num_samples=1681 """ + if dataset_len < min_num_samples: + min_num_samples = dataset_len + return max(min_num_samples, min(int(dataset_len**power), max_num_samples)) - dataloader = torch.utils.data.DataLoader( - dataset, - num_workers=num_workers, - batch_size=2, - shuffle=False, - ) - batch = next(iter(dataloader)) - stats_patterns = {} +def sample_indices(data_len: int) -> list[int]: + num_samples = estimate_num_samples(data_len) + return np.round(np.linspace(0, data_len - 1, num_samples)).astype(int).tolist() - for key in dataset.features: - # sanity check that tensors are not float64 - assert batch[key].dtype != torch.float64 - # if isinstance(feats_type, (VideoFrame, Image)): - if key in dataset.meta.camera_keys: - # sanity check that images are channel first - _, c, h, w = batch[key].shape - assert c < h and c < w, f"expect channel first images, but instead {batch[key].shape}" +def auto_downsample_height_width(img: np.ndarray, target_size: int = 150, max_size_threshold: int = 300): + _, height, width = img.shape - # sanity check that images are float32 in range [0,1] - assert batch[key].dtype == torch.float32, f"expect torch.float32, but instead {batch[key].dtype=}" - assert batch[key].max() <= 1, f"expect pixels lower than 1, but instead {batch[key].max()=}" - assert batch[key].min() >= 0, f"expect pixels greater than 1, but instead {batch[key].min()=}" + if max(width, height) < max_size_threshold: + # no downsampling needed + return img - stats_patterns[key] = "b c h w -> c 1 1" - elif batch[key].ndim == 2: - stats_patterns[key] = "b c -> c " - elif batch[key].ndim == 1: - stats_patterns[key] = "b -> 1" + downsample_factor = int(width / target_size) if width > height else int(height / target_size) + return img[:, ::downsample_factor, ::downsample_factor] + + +def sample_images(image_paths: list[str]) -> np.ndarray: + sampled_indices = sample_indices(len(image_paths)) + + images = None + for i, idx in enumerate(sampled_indices): + path = image_paths[idx] + # we load as uint8 to reduce memory usage + img = load_image_as_numpy(path, dtype=np.uint8, channel_first=True) + img = auto_downsample_height_width(img) + + if images is None: + images = np.empty((len(sampled_indices), *img.shape), dtype=np.uint8) + + images[i] = img + + return images + + +def get_feature_stats(array: np.ndarray, axis: tuple, keepdims: bool) -> dict[str, np.ndarray]: + return { + "min": np.min(array, axis=axis, keepdims=keepdims), + "max": np.max(array, axis=axis, keepdims=keepdims), + "mean": np.mean(array, axis=axis, keepdims=keepdims), + "std": np.std(array, axis=axis, keepdims=keepdims), + "count": np.array([len(array)]), + } + + +def compute_episode_stats(episode_data: dict[str, list[str] | np.ndarray], features: dict) -> dict: + ep_stats = {} + for key, data in episode_data.items(): + if features[key]["dtype"] == "string": + continue # HACK: we should receive np.arrays of strings + elif features[key]["dtype"] in ["image", "video"]: + ep_ft_array = sample_images(data) # data is a list of image paths + axes_to_reduce = (0, 2, 3) # keep channel dim + keepdims = True else: - raise ValueError(f"{key}, {batch[key].shape}") + ep_ft_array = data # data is alreay a np.ndarray + axes_to_reduce = 0 # compute stats over the first axis + keepdims = data.ndim == 1 # keep as np.array - return stats_patterns + ep_stats[key] = get_feature_stats(ep_ft_array, axis=axes_to_reduce, keepdims=keepdims) + + # finally, we normalize and remove batch dim for images + if features[key]["dtype"] in ["image", "video"]: + ep_stats[key] = { + k: v if k == "count" else np.squeeze(v / 255.0, axis=0) for k, v in ep_stats[key].items() + } + + return ep_stats -def compute_stats(dataset, batch_size=8, num_workers=8, max_num_samples=None): - """Compute mean/std and min/max statistics of all data keys in a LeRobotDataset.""" - if max_num_samples is None: - max_num_samples = len(dataset) - - # for more info on why we need to set the same number of workers, see `load_from_videos` - stats_patterns = get_stats_einops_patterns(dataset, num_workers) - - # mean and std will be computed incrementally while max and min will track the running value. - mean, std, max, min = {}, {}, {}, {} - for key in stats_patterns: - mean[key] = torch.tensor(0.0).float() - std[key] = torch.tensor(0.0).float() - max[key] = torch.tensor(-float("inf")).float() - min[key] = torch.tensor(float("inf")).float() - - def create_seeded_dataloader(dataset, batch_size, seed): - generator = torch.Generator() - generator.manual_seed(seed) - dataloader = torch.utils.data.DataLoader( - dataset, - num_workers=num_workers, - batch_size=batch_size, - shuffle=True, - drop_last=False, - generator=generator, - ) - return dataloader - - # Note: Due to be refactored soon. The point of storing `first_batch` is to make sure we don't get - # surprises when rerunning the sampler. - first_batch = None - running_item_count = 0 # for online mean computation - dataloader = create_seeded_dataloader(dataset, batch_size, seed=1337) - for i, batch in enumerate( - tqdm.tqdm(dataloader, total=ceil(max_num_samples / batch_size), desc="Compute mean, min, max") - ): - this_batch_size = len(batch["index"]) - running_item_count += this_batch_size - if first_batch is None: - first_batch = deepcopy(batch) - for key, pattern in stats_patterns.items(): - batch[key] = batch[key].float() - # Numerically stable update step for mean computation. - batch_mean = einops.reduce(batch[key], pattern, "mean") - # Hint: to update the mean we need x̄ₙ = (Nₙ₋₁x̄ₙ₋₁ + Bₙxₙ) / Nₙ, where the subscript represents - # the update step, N is the running item count, B is this batch size, x̄ is the running mean, - # and x is the current batch mean. Some rearrangement is then required to avoid risking - # numerical overflow. Another hint: Nₙ₋₁ = Nₙ - Bₙ. Rearrangement yields - # x̄ₙ = x̄ₙ₋₁ + Bₙ * (xₙ - x̄ₙ₋₁) / Nₙ - mean[key] = mean[key] + this_batch_size * (batch_mean - mean[key]) / running_item_count - max[key] = torch.maximum(max[key], einops.reduce(batch[key], pattern, "max")) - min[key] = torch.minimum(min[key], einops.reduce(batch[key], pattern, "min")) - - if i == ceil(max_num_samples / batch_size) - 1: - break - - first_batch_ = None - running_item_count = 0 # for online std computation - dataloader = create_seeded_dataloader(dataset, batch_size, seed=1337) - for i, batch in enumerate( - tqdm.tqdm(dataloader, total=ceil(max_num_samples / batch_size), desc="Compute std") - ): - this_batch_size = len(batch["index"]) - running_item_count += this_batch_size - # Sanity check to make sure the batches are still in the same order as before. - if first_batch_ is None: - first_batch_ = deepcopy(batch) - for key in stats_patterns: - assert torch.equal(first_batch_[key], first_batch[key]) - for key, pattern in stats_patterns.items(): - batch[key] = batch[key].float() - # Numerically stable update step for mean computation (where the mean is over squared - # residuals).See notes in the mean computation loop above. - batch_std = einops.reduce((batch[key] - mean[key]) ** 2, pattern, "mean") - std[key] = std[key] + this_batch_size * (batch_std - std[key]) / running_item_count - - if i == ceil(max_num_samples / batch_size) - 1: - break - - for key in stats_patterns: - std[key] = torch.sqrt(std[key]) - - stats = {} - for key in stats_patterns: - stats[key] = { - "mean": mean[key], - "std": std[key], - "max": max[key], - "min": min[key], - } - return stats +def _assert_type_and_shape(stats_list: list[dict[str, dict]]): + for i in range(len(stats_list)): + for fkey in stats_list[i]: + for k, v in stats_list[i][fkey].items(): + if not isinstance(v, np.ndarray): + raise ValueError( + f"Stats must be composed of numpy array, but key '{k}' of feature '{fkey}' is of type '{type(v)}' instead." + ) + if v.ndim == 0: + raise ValueError("Number of dimensions must be at least 1, and is 0 instead.") + if k == "count" and v.shape != (1,): + raise ValueError(f"Shape of 'count' must be (1), but is {v.shape} instead.") + if "image" in fkey and k != "count" and v.shape != (3, 1, 1): + raise ValueError(f"Shape of '{k}' must be (3,1,1), but is {v.shape} instead.") -def aggregate_stats(ls_datasets) -> dict[str, torch.Tensor]: - """Aggregate stats of multiple LeRobot datasets into one set of stats without recomputing from scratch. +def aggregate_feature_stats(stats_ft_list: list[dict[str, dict]]) -> dict[str, dict[str, np.ndarray]]: + """Aggregates stats for a single feature.""" + means = np.stack([s["mean"] for s in stats_ft_list]) + variances = np.stack([s["std"] ** 2 for s in stats_ft_list]) + counts = np.stack([s["count"] for s in stats_ft_list]) + total_count = counts.sum(axis=0) - The final stats will have the union of all data keys from each of the datasets. + # Prepare weighted mean by matching number of dimensions + while counts.ndim < means.ndim: + counts = np.expand_dims(counts, axis=-1) - The final stats will have the union of all data keys from each of the datasets. For instance: - - new_max = max(max_dataset_0, max_dataset_1, ...) + # Compute the weighted mean + weighted_means = means * counts + total_mean = weighted_means.sum(axis=0) / total_count + + # Compute the variance using the parallel algorithm + delta_means = means - total_mean + weighted_variances = (variances + delta_means**2) * counts + total_variance = weighted_variances.sum(axis=0) / total_count + + return { + "min": np.min(np.stack([s["min"] for s in stats_ft_list]), axis=0), + "max": np.max(np.stack([s["max"] for s in stats_ft_list]), axis=0), + "mean": total_mean, + "std": np.sqrt(total_variance), + "count": total_count, + } + + +def aggregate_stats(stats_list: list[dict[str, dict]]) -> dict[str, dict[str, np.ndarray]]: + """Aggregate stats from multiple compute_stats outputs into a single set of stats. + + The final stats will have the union of all data keys from each of the stats dicts. + + For instance: - new_min = min(min_dataset_0, min_dataset_1, ...) - - new_mean = (mean of all data) + - new_max = max(max_dataset_0, max_dataset_1, ...) + - new_mean = (mean of all data, weighted by counts) - new_std = (std of all data) """ - data_keys = set() - for dataset in ls_datasets: - data_keys.update(dataset.meta.stats.keys()) - stats = {k: {} for k in data_keys} - for data_key in data_keys: - for stat_key in ["min", "max"]: - # compute `max(dataset_0["max"], dataset_1["max"], ...)` - stats[data_key][stat_key] = einops.reduce( - torch.stack( - [ds.meta.stats[data_key][stat_key] for ds in ls_datasets if data_key in ds.meta.stats], - dim=0, - ), - "n ... -> ...", - stat_key, - ) - total_samples = sum(d.num_frames for d in ls_datasets if data_key in d.meta.stats) - # Compute the "sum" statistic by multiplying each mean by the number of samples in the respective - # dataset, then divide by total_samples to get the overall "mean". - # NOTE: the brackets around (d.num_frames / total_samples) are needed tor minimize the risk of - # numerical overflow! - stats[data_key]["mean"] = sum( - d.meta.stats[data_key]["mean"] * (d.num_frames / total_samples) - for d in ls_datasets - if data_key in d.meta.stats - ) - # The derivation for standard deviation is a little more involved but is much in the same spirit as - # the computation of the mean. - # Given two sets of data where the statistics are known: - # σ_combined = sqrt[ (n1 * (σ1^2 + d1^2) + n2 * (σ2^2 + d2^2)) / (n1 + n2) ] - # where d1 = μ1 - μ_combined, d2 = μ2 - μ_combined - # NOTE: the brackets around (d.num_frames / total_samples) are needed tor minimize the risk of - # numerical overflow! - stats[data_key]["std"] = torch.sqrt( - sum( - ( - d.meta.stats[data_key]["std"] ** 2 - + (d.meta.stats[data_key]["mean"] - stats[data_key]["mean"]) ** 2 - ) - * (d.num_frames / total_samples) - for d in ls_datasets - if data_key in d.meta.stats - ) - ) - return stats + + _assert_type_and_shape(stats_list) + + data_keys = {key for stats in stats_list for key in stats} + aggregated_stats = {key: {} for key in data_keys} + + for key in data_keys: + stats_with_key = [stats[key] for stats in stats_list if key in stats] + aggregated_stats[key] = aggregate_feature_stats(stats_with_key) + + return aggregated_stats diff --git a/lerobot/common/datasets/factory.py b/lerobot/common/datasets/factory.py index 95ba76b8..fb1fe6d6 100644 --- a/lerobot/common/datasets/factory.py +++ b/lerobot/common/datasets/factory.py @@ -83,15 +83,15 @@ def make_dataset(cfg: TrainPipelineConfig) -> LeRobotDataset | MultiLeRobotDatas ) if isinstance(cfg.dataset.repo_id, str): - ds_meta = LeRobotDatasetMetadata(cfg.dataset.repo_id, local_files_only=cfg.dataset.local_files_only) + ds_meta = LeRobotDatasetMetadata(cfg.dataset.repo_id, revision=cfg.dataset.revision) delta_timestamps = resolve_delta_timestamps(cfg.policy, ds_meta) dataset = LeRobotDataset( cfg.dataset.repo_id, episodes=cfg.dataset.episodes, delta_timestamps=delta_timestamps, image_transforms=image_transforms, + revision=cfg.dataset.revision, video_backend=cfg.dataset.video_backend, - local_files_only=cfg.dataset.local_files_only, ) else: raise NotImplementedError("The MultiLeRobotDataset isn't supported for now.") diff --git a/lerobot/common/datasets/image_writer.py b/lerobot/common/datasets/image_writer.py index 85dd6830..6fc0ee2f 100644 --- a/lerobot/common/datasets/image_writer.py +++ b/lerobot/common/datasets/image_writer.py @@ -38,22 +38,40 @@ def safe_stop_image_writer(func): return wrapper -def image_array_to_image(image_array: np.ndarray) -> PIL.Image.Image: +def image_array_to_pil_image(image_array: np.ndarray, range_check: bool = True) -> PIL.Image.Image: # TODO(aliberts): handle 1 channel and 4 for depth images - if image_array.ndim == 3 and image_array.shape[0] in [1, 3]: + if image_array.ndim != 3: + raise ValueError(f"The array has {image_array.ndim} dimensions, but 3 is expected for an image.") + + if image_array.shape[0] == 3: # Transpose from pytorch convention (C, H, W) to (H, W, C) image_array = image_array.transpose(1, 2, 0) + + elif image_array.shape[-1] != 3: + raise NotImplementedError( + f"The image has {image_array.shape[-1]} channels, but 3 is required for now." + ) + if image_array.dtype != np.uint8: - # Assume the image is in [0, 1] range for floating-point data - image_array = np.clip(image_array, 0, 1) + if range_check: + max_ = image_array.max().item() + min_ = image_array.min().item() + if max_ > 1.0 or min_ < 0.0: + raise ValueError( + "The image data type is float, which requires values in the range [0.0, 1.0]. " + f"However, the provided range is [{min_}, {max_}]. Please adjust the range or " + "provide a uint8 image with values in the range [0, 255]." + ) + image_array = (image_array * 255).astype(np.uint8) + return PIL.Image.fromarray(image_array) def write_image(image: np.ndarray | PIL.Image.Image, fpath: Path): try: if isinstance(image, np.ndarray): - img = image_array_to_image(image) + img = image_array_to_pil_image(image) elif isinstance(image, PIL.Image.Image): img = image else: diff --git a/lerobot/common/datasets/lerobot_dataset.py b/lerobot/common/datasets/lerobot_dataset.py index 9483bf0a..f1eb11a0 100644 --- a/lerobot/common/datasets/lerobot_dataset.py +++ b/lerobot/common/datasets/lerobot_dataset.py @@ -14,49 +14,54 @@ # See the License for the specific language governing permissions and # limitations under the License. import logging -import os import shutil -from functools import cached_property from pathlib import Path from typing import Callable import datasets import numpy as np +import packaging.version import PIL.Image import torch import torch.utils -from datasets import load_dataset -from huggingface_hub import create_repo, snapshot_download, upload_folder +from datasets import concatenate_datasets, load_dataset +from huggingface_hub import HfApi, snapshot_download +from huggingface_hub.constants import REPOCARD_NAME -from lerobot.common.datasets.compute_stats import aggregate_stats, compute_stats +from lerobot.common.constants import HF_LEROBOT_HOME +from lerobot.common.datasets.compute_stats import aggregate_stats, compute_episode_stats from lerobot.common.datasets.image_writer import AsyncImageWriter, write_image from lerobot.common.datasets.utils import ( DEFAULT_FEATURES, DEFAULT_IMAGE_PATH, - EPISODES_PATH, INFO_PATH, - STATS_PATH, TASKS_PATH, append_jsonlines, + backward_compatible_episodes_stats, check_delta_timestamps, check_timestamps_sync, check_version_compatibility, - create_branch, create_empty_dataset_info, create_lerobot_dataset_card, + embed_images, get_delta_indices, get_episode_data_index, get_features_from_robot, get_hf_features_from_features, - get_hub_safe_version, + get_safe_version, hf_transform_to_torch, + is_valid_version, load_episodes, + load_episodes_stats, load_info, load_stats, load_tasks, - serialize_dict, + validate_episode_buffer, + validate_frame, + write_episode, + write_episode_stats, + write_info, write_json, - write_parquet, ) from lerobot.common.datasets.video_utils import ( VideoFrame, @@ -66,9 +71,7 @@ from lerobot.common.datasets.video_utils import ( ) from lerobot.common.robot_devices.robots.utils import Robot -# For maintainers, see lerobot/common/datasets/push_dataset_to_hub/CODEBASE_VERSION.md -CODEBASE_VERSION = "v2.0" -LEROBOT_HOME = Path(os.getenv("LEROBOT_HOME", "~/.cache/huggingface/lerobot")).expanduser() +CODEBASE_VERSION = "v2.1" class LeRobotDatasetMetadata: @@ -76,19 +79,36 @@ class LeRobotDatasetMetadata: self, repo_id: str, root: str | Path | None = None, - local_files_only: bool = False, + revision: str | None = None, + force_cache_sync: bool = False, ): self.repo_id = repo_id - self.root = Path(root) if root is not None else LEROBOT_HOME / repo_id - self.local_files_only = local_files_only + self.revision = revision if revision else CODEBASE_VERSION + self.root = Path(root) if root is not None else HF_LEROBOT_HOME / repo_id - # Load metadata - (self.root / "meta").mkdir(exist_ok=True, parents=True) - self.pull_from_repo(allow_patterns="meta/") + try: + if force_cache_sync: + raise FileNotFoundError + self.load_metadata() + except (FileNotFoundError, NotADirectoryError): + if is_valid_version(self.revision): + self.revision = get_safe_version(self.repo_id, self.revision) + + (self.root / "meta").mkdir(exist_ok=True, parents=True) + self.pull_from_repo(allow_patterns="meta/") + self.load_metadata() + + def load_metadata(self): self.info = load_info(self.root) - self.stats = load_stats(self.root) - self.tasks = load_tasks(self.root) + check_version_compatibility(self.repo_id, self._version, CODEBASE_VERSION) + self.tasks, self.task_to_task_index = load_tasks(self.root) self.episodes = load_episodes(self.root) + if self._version < packaging.version.parse("v2.1"): + self.stats = load_stats(self.root) + self.episodes_stats = backward_compatible_episodes_stats(self.stats, self.episodes) + else: + self.episodes_stats = load_episodes_stats(self.root) + self.stats = aggregate_stats(list(self.episodes_stats.values())) def pull_from_repo( self, @@ -98,21 +118,16 @@ class LeRobotDatasetMetadata: snapshot_download( self.repo_id, repo_type="dataset", - revision=self._hub_version, + revision=self.revision, local_dir=self.root, allow_patterns=allow_patterns, ignore_patterns=ignore_patterns, - local_files_only=self.local_files_only, ) - @cached_property - def _hub_version(self) -> str | None: - return None if self.local_files_only else get_hub_safe_version(self.repo_id, CODEBASE_VERSION) - @property - def _version(self) -> str: + def _version(self) -> packaging.version.Version: """Codebase version used to create this dataset.""" - return self.info["codebase_version"] + return packaging.version.parse(self.info["codebase_version"]) def get_data_file_path(self, ep_index: int) -> Path: ep_chunk = self.get_episode_chunk(ep_index) @@ -202,54 +217,65 @@ class LeRobotDatasetMetadata: """Max number of episodes per chunk.""" return self.info["chunks_size"] - @property - def task_to_task_index(self) -> dict: - return {task: task_idx for task_idx, task in self.tasks.items()} - - def get_task_index(self, task: str) -> int: + def get_task_index(self, task: str) -> int | None: """ Given a task in natural language, returns its task_index if the task already exists in the dataset, - otherwise creates a new task_index. + otherwise return None. """ - task_index = self.task_to_task_index.get(task, None) - return task_index if task_index is not None else self.total_tasks + return self.task_to_task_index.get(task, None) - def save_episode(self, episode_index: int, episode_length: int, task: str, task_index: int) -> None: + def add_task(self, task: str): + """ + Given a task in natural language, add it to the dictionnary of tasks. + """ + if task in self.task_to_task_index: + raise ValueError(f"The task '{task}' already exists and can't be added twice.") + + task_index = self.info["total_tasks"] + self.task_to_task_index[task] = task_index + self.tasks[task_index] = task + self.info["total_tasks"] += 1 + + task_dict = { + "task_index": task_index, + "task": task, + } + append_jsonlines(task_dict, self.root / TASKS_PATH) + + def save_episode( + self, + episode_index: int, + episode_length: int, + episode_tasks: list[str], + episode_stats: dict[str, dict], + ) -> None: self.info["total_episodes"] += 1 self.info["total_frames"] += episode_length - if task_index not in self.tasks: - self.info["total_tasks"] += 1 - self.tasks[task_index] = task - task_dict = { - "task_index": task_index, - "task": task, - } - append_jsonlines(task_dict, self.root / TASKS_PATH) - chunk = self.get_episode_chunk(episode_index) if chunk >= self.total_chunks: self.info["total_chunks"] += 1 self.info["splits"] = {"train": f"0:{self.info['total_episodes']}"} self.info["total_videos"] += len(self.video_keys) - write_json(self.info, self.root / INFO_PATH) + if len(self.video_keys) > 0: + self.update_video_info() + + write_info(self.info, self.root) episode_dict = { "episode_index": episode_index, - "tasks": [task], + "tasks": episode_tasks, "length": episode_length, } - self.episodes.append(episode_dict) - append_jsonlines(episode_dict, self.root / EPISODES_PATH) + self.episodes[episode_index] = episode_dict + write_episode(episode_dict, self.root) - # TODO(aliberts): refactor stats in save_episodes - # image_sampling = int(self.fps / 2) # sample 2 img/s for the stats - # ep_stats = compute_episode_stats(episode_buffer, self.features, episode_length, image_sampling=image_sampling) - # ep_stats = serialize_dict(ep_stats) - # append_jsonlines(ep_stats, self.root / STATS_PATH) + self.episodes_stats[episode_index] = episode_stats + self.stats = aggregate_stats([self.stats, episode_stats]) if self.stats else episode_stats + write_episode_stats(episode_index, episode_stats, self.root) - def write_video_info(self) -> None: + def update_video_info(self) -> None: """ Warning: this function writes info from first episode videos, implicitly assuming that all videos have been encoded the same way. Also, this means it assumes the first episode exists. @@ -259,8 +285,6 @@ class LeRobotDatasetMetadata: video_path = self.root / self.get_video_file_path(ep_index=0, vid_key=key) self.info["features"][key]["info"] = get_video_info(video_path) - write_json(self.info, self.root / INFO_PATH) - def __repr__(self): feature_keys = list(self.features) return ( @@ -286,7 +310,7 @@ class LeRobotDatasetMetadata: """Creates metadata for a LeRobotDataset.""" obj = cls.__new__(cls) obj.repo_id = repo_id - obj.root = Path(root) if root is not None else LEROBOT_HOME / repo_id + obj.root = Path(root) if root is not None else HF_LEROBOT_HOME / repo_id obj.root.mkdir(parents=True, exist_ok=False) @@ -304,6 +328,7 @@ class LeRobotDatasetMetadata: ) else: # TODO(aliberts, rcadene): implement sanity check for features + features = {**features, **DEFAULT_FEATURES} # check if none of the features contains a "/" in their names, # as this would break the dict flattening in the stats computation, which uses '/' as separator @@ -313,12 +338,13 @@ class LeRobotDatasetMetadata: features = {**features, **DEFAULT_FEATURES} - obj.tasks, obj.stats, obj.episodes = {}, {}, [] + obj.tasks, obj.task_to_task_index = {}, {} + obj.episodes_stats, obj.stats, obj.episodes = {}, {}, {} obj.info = create_empty_dataset_info(CODEBASE_VERSION, fps, robot_type, features, use_videos) if len(obj.video_keys) > 0 and not use_videos: raise ValueError() write_json(obj.info, obj.root / INFO_PATH) - obj.local_files_only = True + obj.revision = None return obj @@ -331,8 +357,9 @@ class LeRobotDataset(torch.utils.data.Dataset): image_transforms: Callable | None = None, delta_timestamps: dict[list[float]] | None = None, tolerance_s: float = 1e-4, + revision: str | None = None, + force_cache_sync: bool = False, download_videos: bool = True, - local_files_only: bool = False, video_backend: str | None = None, ): """ @@ -342,7 +369,7 @@ class LeRobotDataset(torch.utils.data.Dataset): - On your local disk in the 'root' folder. This is typically the case when you recorded your dataset locally and you may or may not have pushed it to the hub yet. Instantiating this class with 'root' will load your dataset directly from disk. This can happen while you're offline (no - internet connection), in that case, use local_files_only=True. + internet connection). - On the Hugging Face Hub at the address https://huggingface.co/datasets/{repo_id} and not on your local disk in the 'root' folder. Instantiating this class with this 'repo_id' will download @@ -424,24 +451,28 @@ class LeRobotDataset(torch.utils.data.Dataset): timestamps is separated to the next by 1/fps +/- tolerance_s. This also applies to frames decoded from video files. It is also used to check that `delta_timestamps` (when provided) are multiples of 1/fps. Defaults to 1e-4. + revision (str, optional): An optional Git revision id which can be a branch name, a tag, or a + commit hash. Defaults to current codebase version tag. + sync_cache_first (bool, optional): Flag to sync and refresh local files first. If True and files + are already present in the local cache, this will be faster. However, files loaded might not + be in sync with the version on the hub, especially if you specified 'revision'. Defaults to + False. download_videos (bool, optional): Flag to download the videos. Note that when set to True but the video files are already present on local disk, they won't be downloaded again. Defaults to True. - local_files_only (bool, optional): Flag to use local files only. If True, no requests to the hub - will be made. Defaults to False. video_backend (str | None, optional): Video backend to use for decoding videos. There is currently a single option which is the pyav decoder used by Torchvision. Defaults to pyav. """ super().__init__() self.repo_id = repo_id - self.root = Path(root) if root else LEROBOT_HOME / repo_id + self.root = Path(root) if root else HF_LEROBOT_HOME / repo_id self.image_transforms = image_transforms self.delta_timestamps = delta_timestamps self.episodes = episodes self.tolerance_s = tolerance_s + self.revision = revision if revision else CODEBASE_VERSION self.video_backend = video_backend if video_backend else "pyav" self.delta_indices = None - self.local_files_only = local_files_only # Unused attributes self.image_writer = None @@ -450,64 +481,86 @@ class LeRobotDataset(torch.utils.data.Dataset): self.root.mkdir(exist_ok=True, parents=True) # Load metadata - self.meta = LeRobotDatasetMetadata(self.repo_id, self.root, self.local_files_only) - - # Check version - check_version_compatibility(self.repo_id, self.meta._version, CODEBASE_VERSION) + self.meta = LeRobotDatasetMetadata( + self.repo_id, self.root, self.revision, force_cache_sync=force_cache_sync + ) + if self.episodes is not None and self.meta._version >= packaging.version.parse("v2.1"): + episodes_stats = [self.meta.episodes_stats[ep_idx] for ep_idx in self.episodes] + self.stats = aggregate_stats(episodes_stats) # Load actual data - self.download_episodes(download_videos) - self.hf_dataset = self.load_hf_dataset() + try: + if force_cache_sync: + raise FileNotFoundError + assert all((self.root / fpath).is_file() for fpath in self.get_episodes_file_paths()) + self.hf_dataset = self.load_hf_dataset() + except (AssertionError, FileNotFoundError, NotADirectoryError): + self.revision = get_safe_version(self.repo_id, self.revision) + self.download_episodes(download_videos) + self.hf_dataset = self.load_hf_dataset() + self.episode_data_index = get_episode_data_index(self.meta.episodes, self.episodes) # Check timestamps - check_timestamps_sync(self.hf_dataset, self.episode_data_index, self.fps, self.tolerance_s) + timestamps = torch.stack(self.hf_dataset["timestamp"]).numpy() + episode_indices = torch.stack(self.hf_dataset["episode_index"]).numpy() + ep_data_index_np = {k: t.numpy() for k, t in self.episode_data_index.items()} + check_timestamps_sync(timestamps, episode_indices, ep_data_index_np, self.fps, self.tolerance_s) # Setup delta_indices if self.delta_timestamps is not None: check_delta_timestamps(self.delta_timestamps, self.fps, self.tolerance_s) self.delta_indices = get_delta_indices(self.delta_timestamps, self.fps) - # Available stats implies all videos have been encoded and dataset is iterable - self.consolidated = self.meta.stats is not None - def push_to_hub( self, + branch: str | None = None, tags: list | None = None, license: str | None = "apache-2.0", push_videos: bool = True, private: bool = False, + allow_patterns: list[str] | str | None = None, + upload_large_folder: bool = False, **card_kwargs, ) -> None: - if not self.consolidated: - logging.warning( - "You are trying to upload to the hub a LeRobotDataset that has not been consolidated yet. " - "Consolidating first." - ) - self.consolidate() - ignore_patterns = ["images/"] if not push_videos: ignore_patterns.append("videos/") - create_repo( + hub_api = HfApi() + hub_api.create_repo( repo_id=self.repo_id, private=private, repo_type="dataset", exist_ok=True, ) + if branch: + hub_api.create_branch( + repo_id=self.repo_id, + branch=branch, + revision=self.revision, + repo_type="dataset", + exist_ok=True, + ) - upload_folder( - repo_id=self.repo_id, - folder_path=self.root, - repo_type="dataset", - ignore_patterns=ignore_patterns, - ) - card = create_lerobot_dataset_card( - tags=tags, dataset_info=self.meta.info, license=license, **card_kwargs - ) - card.push_to_hub(repo_id=self.repo_id, repo_type="dataset") - create_branch(repo_id=self.repo_id, branch=CODEBASE_VERSION, repo_type="dataset") + upload_kwargs = { + "repo_id": self.repo_id, + "folder_path": self.root, + "repo_type": "dataset", + "revision": branch, + "allow_patterns": allow_patterns, + "ignore_patterns": ignore_patterns, + } + if upload_large_folder: + hub_api.upload_large_folder(**upload_kwargs) + else: + hub_api.upload_folder(**upload_kwargs) + + if not hub_api.file_exists(self.repo_id, REPOCARD_NAME, repo_type="dataset", revision=branch): + card = create_lerobot_dataset_card( + tags=tags, dataset_info=self.meta.info, license=license, **card_kwargs + ) + card.push_to_hub(repo_id=self.repo_id, repo_type="dataset", revision=branch) def pull_from_repo( self, @@ -517,11 +570,10 @@ class LeRobotDataset(torch.utils.data.Dataset): snapshot_download( self.repo_id, repo_type="dataset", - revision=self.meta._hub_version, + revision=self.revision, local_dir=self.root, allow_patterns=allow_patterns, ignore_patterns=ignore_patterns, - local_files_only=self.local_files_only, ) def download_episodes(self, download_videos: bool = True) -> None: @@ -535,17 +587,23 @@ class LeRobotDataset(torch.utils.data.Dataset): files = None ignore_patterns = None if download_videos else "videos/" if self.episodes is not None: - files = [str(self.meta.get_data_file_path(ep_idx)) for ep_idx in self.episodes] - if len(self.meta.video_keys) > 0 and download_videos: - video_files = [ - str(self.meta.get_video_file_path(ep_idx, vid_key)) - for vid_key in self.meta.video_keys - for ep_idx in self.episodes - ] - files += video_files + files = self.get_episodes_file_paths() self.pull_from_repo(allow_patterns=files, ignore_patterns=ignore_patterns) + def get_episodes_file_paths(self) -> list[Path]: + episodes = self.episodes if self.episodes is not None else list(range(self.meta.total_episodes)) + fpaths = [str(self.meta.get_data_file_path(ep_idx)) for ep_idx in episodes] + if len(self.meta.video_keys) > 0: + video_files = [ + str(self.meta.get_video_file_path(ep_idx, vid_key)) + for vid_key in self.meta.video_keys + for ep_idx in episodes + ] + fpaths += video_files + + return fpaths + def load_hf_dataset(self) -> datasets.Dataset: """hf_dataset contains all the observations, states, actions, rewards, etc.""" if self.episodes is None: @@ -557,7 +615,15 @@ class LeRobotDataset(torch.utils.data.Dataset): # TODO(aliberts): hf_dataset.set_format("torch") hf_dataset.set_transform(hf_transform_to_torch) + return hf_dataset + def create_hf_dataset(self) -> datasets.Dataset: + features = get_hf_features_from_features(self.features) + ft_dict = {col: [] for col in features} + hf_dataset = datasets.Dataset.from_dict(ft_dict, features=features, split="train") + + # TODO(aliberts): hf_dataset.set_format("torch") + hf_dataset.set_transform(hf_transform_to_torch) return hf_dataset @property @@ -624,7 +690,7 @@ class LeRobotDataset(torch.utils.data.Dataset): if key not in self.meta.video_keys } - def _query_videos(self, query_timestamps: dict[str, list[float]], ep_idx: int) -> dict: + def _query_videos(self, query_timestamps: dict[str, list[float]], ep_idx: int) -> dict[str, torch.Tensor]: """Note: When using data workers (e.g. DataLoader with num_workers>0), do not call this function in the main process (e.g. by using a second Dataloader with num_workers=0). It will result in a Segmentation Fault. This probably happens because a memory reference to the video loader is created in @@ -654,8 +720,7 @@ class LeRobotDataset(torch.utils.data.Dataset): query_indices = None if self.delta_indices is not None: - current_ep_idx = self.episodes.index(ep_idx) if self.episodes is not None else ep_idx - query_indices, padding = self._get_query_indices(idx, current_ep_idx) + query_indices, padding = self._get_query_indices(idx, ep_idx) query_result = self._query_hf_dataset(query_indices) item = {**item, **padding} for key, val in query_result.items(): @@ -691,10 +756,13 @@ class LeRobotDataset(torch.utils.data.Dataset): def create_episode_buffer(self, episode_index: int | None = None) -> dict: current_ep_idx = self.meta.total_episodes if episode_index is None else episode_index - return { - "size": 0, - **{key: current_ep_idx if key == "episode_index" else [] for key in self.features}, - } + ep_buffer = {} + # size and task are special cases that are not in self.features + ep_buffer["size"] = 0 + ep_buffer["task"] = [] + for key in self.features: + ep_buffer[key] = current_ep_idx if key == "episode_index" else [] + return ep_buffer def _get_image_file_path(self, episode_index: int, image_key: str, frame_index: int) -> Path: fpath = DEFAULT_IMAGE_PATH.format( @@ -716,25 +784,35 @@ class LeRobotDataset(torch.utils.data.Dataset): temporary directory — nothing is written to disk. To save those frames, the 'save_episode()' method then needs to be called. """ - # TODO(aliberts, rcadene): Add sanity check for the input, check it's numpy or torch, - # check the dtype and shape matches, etc. + # Convert torch to numpy if needed + for name in frame: + if isinstance(frame[name], torch.Tensor): + frame[name] = frame[name].numpy() + + validate_frame(frame, self.features) if self.episode_buffer is None: self.episode_buffer = self.create_episode_buffer() + # Automatically add frame_index and timestamp to episode buffer frame_index = self.episode_buffer["size"] timestamp = frame.pop("timestamp") if "timestamp" in frame else frame_index / self.fps self.episode_buffer["frame_index"].append(frame_index) self.episode_buffer["timestamp"].append(timestamp) + # Add frame features to episode_buffer for key in frame: - if key not in self.features: - raise ValueError(key) + if key == "task": + # Note: we associate the task in natural language to its task index during `save_episode` + self.episode_buffer["task"].append(frame["task"]) + continue - if self.features[key]["dtype"] not in ["image", "video"]: - item = frame[key].numpy() if isinstance(frame[key], torch.Tensor) else frame[key] - self.episode_buffer[key].append(item) - elif self.features[key]["dtype"] in ["image", "video"]: + if key not in self.features: + raise ValueError( + f"An element of the frame is not in the features. '{key}' not in '{self.features.keys()}'." + ) + + if self.features[key]["dtype"] in ["image", "video"]: img_path = self._get_image_file_path( episode_index=self.episode_buffer["episode_index"], image_key=key, frame_index=frame_index ) @@ -742,80 +820,95 @@ class LeRobotDataset(torch.utils.data.Dataset): img_path.parent.mkdir(parents=True, exist_ok=True) self._save_image(frame[key], img_path) self.episode_buffer[key].append(str(img_path)) + else: + self.episode_buffer[key].append(frame[key]) self.episode_buffer["size"] += 1 - def save_episode(self, task: str, encode_videos: bool = True, episode_data: dict | None = None) -> None: + def save_episode(self, episode_data: dict | None = None) -> None: """ - This will save to disk the current episode in self.episode_buffer. Note that since it affects files on - disk, it sets self.consolidated to False to ensure proper consolidation later on before uploading to - the hub. + This will save to disk the current episode in self.episode_buffer. - Use 'encode_videos' if you want to encode videos during the saving of this episode. Otherwise, - you can do it later with dataset.consolidate(). This is to give more flexibility on when to spend - time for video encoding. + Args: + episode_data (dict | None, optional): Dict containing the episode data to save. If None, this will + save the current episode in self.episode_buffer, which is filled with 'add_frame'. Defaults to + None. """ if not episode_data: episode_buffer = self.episode_buffer + validate_episode_buffer(episode_buffer, self.meta.total_episodes, self.features) + + # size and task are special cases that won't be added to hf_dataset episode_length = episode_buffer.pop("size") + tasks = episode_buffer.pop("task") + episode_tasks = list(set(tasks)) episode_index = episode_buffer["episode_index"] - if episode_index != self.meta.total_episodes: - # TODO(aliberts): Add option to use existing episode_index - raise NotImplementedError( - "You might have manually provided the episode_buffer with an episode_index that doesn't " - "match the total number of episodes in the dataset. This is not supported for now." - ) - if episode_length == 0: - raise ValueError( - "You must add one or several frames with `add_frame` before calling `add_episode`." - ) + episode_buffer["index"] = np.arange(self.meta.total_frames, self.meta.total_frames + episode_length) + episode_buffer["episode_index"] = np.full((episode_length,), episode_index) - task_index = self.meta.get_task_index(task) + # Add new tasks to the tasks dictionnary + for task in episode_tasks: + task_index = self.meta.get_task_index(task) + if task_index is None: + self.meta.add_task(task) - if not set(episode_buffer.keys()) == set(self.features): - raise ValueError() + # Given tasks in natural language, find their corresponding task indices + episode_buffer["task_index"] = np.array([self.meta.get_task_index(task) for task in tasks]) for key, ft in self.features.items(): - if key == "index": - episode_buffer[key] = np.arange( - self.meta.total_frames, self.meta.total_frames + episode_length - ) - elif key == "episode_index": - episode_buffer[key] = np.full((episode_length,), episode_index) - elif key == "task_index": - episode_buffer[key] = np.full((episode_length,), task_index) - elif ft["dtype"] in ["image", "video"]: + # index, episode_index, task_index are already processed above, and image and video + # are processed separately by storing image path and frame info as meta data + if key in ["index", "episode_index", "task_index"] or ft["dtype"] in ["image", "video"]: continue - elif len(ft["shape"]) == 1 and ft["shape"][0] == 1: - episode_buffer[key] = np.array(episode_buffer[key], dtype=ft["dtype"]) - elif len(ft["shape"]) == 1 and ft["shape"][0] > 1: - episode_buffer[key] = np.stack(episode_buffer[key]) - else: - raise ValueError(key) + episode_buffer[key] = np.stack(episode_buffer[key]) self._wait_image_writer() self._save_episode_table(episode_buffer, episode_index) + ep_stats = compute_episode_stats(episode_buffer, self.features) - self.meta.save_episode(episode_index, episode_length, task, task_index) - - if encode_videos and len(self.meta.video_keys) > 0: + if len(self.meta.video_keys) > 0: video_paths = self.encode_episode_videos(episode_index) for key in self.meta.video_keys: episode_buffer[key] = video_paths[key] + # `meta.save_episode` be executed after encoding the videos + self.meta.save_episode(episode_index, episode_length, episode_tasks, ep_stats) + + ep_data_index = get_episode_data_index(self.meta.episodes, [episode_index]) + ep_data_index_np = {k: t.numpy() for k, t in ep_data_index.items()} + check_timestamps_sync( + episode_buffer["timestamp"], + episode_buffer["episode_index"], + ep_data_index_np, + self.fps, + self.tolerance_s, + ) + + video_files = list(self.root.rglob("*.mp4")) + assert len(video_files) == self.num_episodes * len(self.meta.video_keys) + + parquet_files = list(self.root.rglob("*.parquet")) + assert len(parquet_files) == self.num_episodes + + # delete images + img_dir = self.root / "images" + if img_dir.is_dir(): + shutil.rmtree(self.root / "images") + if not episode_data: # Reset the buffer self.episode_buffer = self.create_episode_buffer() - self.consolidated = False - def _save_episode_table(self, episode_buffer: dict, episode_index: int) -> None: episode_dict = {key: episode_buffer[key] for key in self.hf_features} ep_dataset = datasets.Dataset.from_dict(episode_dict, features=self.hf_features, split="train") + ep_dataset = embed_images(ep_dataset) + self.hf_dataset = concatenate_datasets([self.hf_dataset, ep_dataset]) + self.hf_dataset.set_transform(hf_transform_to_torch) ep_data_path = self.root / self.meta.get_data_file_path(ep_index=episode_index) ep_data_path.parent.mkdir(parents=True, exist_ok=True) - write_parquet(ep_dataset, ep_data_path) + ep_dataset.to_parquet(ep_data_path) def clear_episode_buffer(self) -> None: episode_index = self.episode_buffer["episode_index"] @@ -884,38 +977,6 @@ class LeRobotDataset(torch.utils.data.Dataset): return video_paths - def consolidate(self, run_compute_stats: bool = True, keep_image_files: bool = False) -> None: - self.hf_dataset = self.load_hf_dataset() - self.episode_data_index = get_episode_data_index(self.meta.episodes, self.episodes) - check_timestamps_sync(self.hf_dataset, self.episode_data_index, self.fps, self.tolerance_s) - - if len(self.meta.video_keys) > 0: - self.encode_videos() - self.meta.write_video_info() - - if not keep_image_files: - img_dir = self.root / "images" - if img_dir.is_dir(): - shutil.rmtree(self.root / "images") - - video_files = list(self.root.rglob("*.mp4")) - assert len(video_files) == self.num_episodes * len(self.meta.video_keys) - - parquet_files = list(self.root.rglob("*.parquet")) - assert len(parquet_files) == self.num_episodes - - if run_compute_stats: - self.stop_image_writer() - # TODO(aliberts): refactor stats in save_episodes - self.meta.stats = compute_stats(self) - serialized_stats = serialize_dict(self.meta.stats) - write_json(serialized_stats, self.root / STATS_PATH) - self.consolidated = True - else: - logging.warning( - "Skipping computation of the dataset statistics, dataset is not fully consolidated." - ) - @classmethod def create( cls, @@ -944,7 +1005,7 @@ class LeRobotDataset(torch.utils.data.Dataset): ) obj.repo_id = obj.meta.repo_id obj.root = obj.meta.root - obj.local_files_only = obj.meta.local_files_only + obj.revision = None obj.tolerance_s = tolerance_s obj.image_writer = None @@ -954,14 +1015,8 @@ class LeRobotDataset(torch.utils.data.Dataset): # TODO(aliberts, rcadene, alexander-soare): Merge this with OnlineBuffer/DataBuffer obj.episode_buffer = obj.create_episode_buffer() - # This bool indicates that the current LeRobotDataset instance is in sync with the files on disk. It - # is used to know when certain operations are need (for instance, computing dataset statistics). In - # order to be able to push the dataset to the hub, it needs to be consolidated first by calling - # self.consolidate(). - obj.consolidated = True - obj.episodes = None - obj.hf_dataset = None + obj.hf_dataset = obj.create_hf_dataset() obj.image_transforms = None obj.delta_timestamps = None obj.delta_indices = None @@ -986,12 +1041,11 @@ class MultiLeRobotDataset(torch.utils.data.Dataset): delta_timestamps: dict[list[float]] | None = None, tolerances_s: dict | None = None, download_videos: bool = True, - local_files_only: bool = False, video_backend: str | None = None, ): super().__init__() self.repo_ids = repo_ids - self.root = Path(root) if root else LEROBOT_HOME + self.root = Path(root) if root else HF_LEROBOT_HOME self.tolerances_s = tolerances_s if tolerances_s else {repo_id: 1e-4 for repo_id in repo_ids} # Construct the underlying datasets passing everything but `transform` and `delta_timestamps` which # are handled by this class. @@ -1004,7 +1058,6 @@ class MultiLeRobotDataset(torch.utils.data.Dataset): delta_timestamps=delta_timestamps, tolerance_s=self.tolerances_s[repo_id], download_videos=download_videos, - local_files_only=local_files_only, video_backend=video_backend, ) for repo_id in repo_ids @@ -1032,7 +1085,10 @@ class MultiLeRobotDataset(torch.utils.data.Dataset): self.image_transforms = image_transforms self.delta_timestamps = delta_timestamps - self.stats = aggregate_stats(self._datasets) + # TODO(rcadene, aliberts): We should not perform this aggregation for datasets + # with multiple robots of different ranges. Instead we should have one normalization + # per robot. + self.stats = aggregate_stats([dataset.meta.stats for dataset in self._datasets]) @property def repo_id_to_index(self): diff --git a/lerobot/common/datasets/push_dataset_to_hub/CODEBASE_VERSION.md b/lerobot/common/datasets/push_dataset_to_hub/CODEBASE_VERSION.md deleted file mode 100644 index 8fcc8bbe..00000000 --- a/lerobot/common/datasets/push_dataset_to_hub/CODEBASE_VERSION.md +++ /dev/null @@ -1,56 +0,0 @@ -## Using / Updating `CODEBASE_VERSION` (for maintainers) - -Since our dataset pushed to the hub are decoupled with the evolution of this repo, we ensure compatibility of -the datasets with our code, we use a `CODEBASE_VERSION` (defined in -lerobot/common/datasets/lerobot_dataset.py) variable. - -For instance, [`lerobot/pusht`](https://huggingface.co/datasets/lerobot/pusht) has many versions to maintain backward compatibility between LeRobot codebase versions: -- [v1.0](https://huggingface.co/datasets/lerobot/pusht/tree/v1.0) -- [v1.1](https://huggingface.co/datasets/lerobot/pusht/tree/v1.1) -- [v1.2](https://huggingface.co/datasets/lerobot/pusht/tree/v1.2) -- [v1.3](https://huggingface.co/datasets/lerobot/pusht/tree/v1.3) -- [v1.4](https://huggingface.co/datasets/lerobot/pusht/tree/v1.4) -- [v1.5](https://huggingface.co/datasets/lerobot/pusht/tree/v1.5) -- [v1.6](https://huggingface.co/datasets/lerobot/pusht/tree/v1.6) <-- last version -- [main](https://huggingface.co/datasets/lerobot/pusht/tree/main) <-- points to the last version - -Starting with v1.6, every dataset pushed to the hub or saved locally also have this version number in their -`info.json` metadata. - -### Uploading a new dataset -If you are pushing a new dataset, you don't need to worry about any of the instructions below, nor to be -compatible with previous codebase versions. The `push_dataset_to_hub.py` script will automatically tag your -dataset with the current `CODEBASE_VERSION`. - -### Updating an existing dataset -If you want to update an existing dataset, you need to change the `CODEBASE_VERSION` from `lerobot_dataset.py` -before running `push_dataset_to_hub.py`. This is especially useful if you introduce a breaking change -intentionally or not (i.e. something not backward compatible such as modifying the reward functions used, -deleting some frames at the end of an episode, etc.). That way, people running a previous version of the -codebase won't be affected by your change and backward compatibility is maintained. - -However, you will need to update the version of ALL the other datasets so that they have the new -`CODEBASE_VERSION` as a branch in their hugging face dataset repository. Don't worry, there is an easy way -that doesn't require to run `push_dataset_to_hub.py`. You can just "branch-out" from the `main` branch on HF -dataset repo by running this script which corresponds to a `git checkout -b` (so no copy or upload needed): - -```python -from huggingface_hub import HfApi - -from lerobot import available_datasets -from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION - -api = HfApi() - -for repo_id in available_datasets: - dataset_info = api.list_repo_refs(repo_id, repo_type="dataset") - branches = [b.name for b in dataset_info.branches] - if CODEBASE_VERSION in branches: - print(f"{repo_id} already @{CODEBASE_VERSION}, skipping.") - continue - else: - # Now create a branch named after the new version by branching out from "main" - # which is expected to be the preceding version - api.create_branch(repo_id, repo_type="dataset", branch=CODEBASE_VERSION, revision="main") - print(f"{repo_id} successfully updated @{CODEBASE_VERSION}") -``` diff --git a/lerobot/common/datasets/utils.py b/lerobot/common/datasets/utils.py index 612bac39..2d90798f 100644 --- a/lerobot/common/datasets/utils.py +++ b/lerobot/common/datasets/utils.py @@ -13,10 +13,10 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. +import contextlib import importlib.resources import json import logging -import textwrap from collections.abc import Iterator from itertools import accumulate from pathlib import Path @@ -27,14 +27,20 @@ from typing import Any import datasets import jsonlines import numpy as np -import pyarrow.compute as pc +import packaging.version import torch from datasets.table import embed_table_storage from huggingface_hub import DatasetCard, DatasetCardData, HfApi from PIL import Image as PILImage from torchvision import transforms +from lerobot.common.datasets.backward_compatibility import ( + V21_MESSAGE, + BackwardCompatibilityError, + ForwardCompatibilityError, +) from lerobot.common.robot_devices.robots.utils import Robot +from lerobot.common.utils.utils import is_valid_numpy_dtype_string from lerobot.configs.types import DictLike, FeatureType, PolicyFeature DEFAULT_CHUNK_SIZE = 1000 # Max number of episodes per chunk @@ -42,6 +48,7 @@ DEFAULT_CHUNK_SIZE = 1000 # Max number of episodes per chunk INFO_PATH = "meta/info.json" EPISODES_PATH = "meta/episodes.jsonl" STATS_PATH = "meta/stats.json" +EPISODES_STATS_PATH = "meta/episodes_stats.jsonl" TASKS_PATH = "meta/tasks.jsonl" DEFAULT_VIDEO_PATH = "videos/chunk-{episode_chunk:03d}/{video_key}/episode_{episode_index:06d}.mp4" @@ -112,17 +119,26 @@ def get_nested_item(obj: DictLike, flattened_key: str, sep: str = "/") -> Any: def serialize_dict(stats: dict[str, torch.Tensor | np.ndarray | dict]) -> dict: - serialized_dict = {key: value.tolist() for key, value in flatten_dict(stats).items()} + serialized_dict = {} + for key, value in flatten_dict(stats).items(): + if isinstance(value, (torch.Tensor, np.ndarray)): + serialized_dict[key] = value.tolist() + elif isinstance(value, np.generic): + serialized_dict[key] = value.item() + elif isinstance(value, (int, float)): + serialized_dict[key] = value + else: + raise NotImplementedError(f"The value '{value}' of type '{type(value)}' is not supported.") return unflatten_dict(serialized_dict) -def write_parquet(dataset: datasets.Dataset, fpath: Path) -> None: +def embed_images(dataset: datasets.Dataset) -> datasets.Dataset: # Embed image bytes into the table before saving to parquet format = dataset.format dataset = dataset.with_format("arrow") dataset = dataset.map(embed_table_storage, batched=False) dataset = dataset.with_format(**format) - dataset.to_parquet(fpath) + return dataset def load_json(fpath: Path) -> Any: @@ -153,6 +169,10 @@ def append_jsonlines(data: dict, fpath: Path) -> None: writer.write(data) +def write_info(info: dict, local_dir: Path): + write_json(info, local_dir / INFO_PATH) + + def load_info(local_dir: Path) -> dict: info = load_json(local_dir / INFO_PATH) for ft in info["features"].values(): @@ -160,29 +180,76 @@ def load_info(local_dir: Path) -> dict: return info -def load_stats(local_dir: Path) -> dict: - if not (local_dir / STATS_PATH).exists(): - return None - stats = load_json(local_dir / STATS_PATH) - stats = {key: torch.tensor(value) for key, value in flatten_dict(stats).items()} +def write_stats(stats: dict, local_dir: Path): + serialized_stats = serialize_dict(stats) + write_json(serialized_stats, local_dir / STATS_PATH) + + +def cast_stats_to_numpy(stats) -> dict[str, dict[str, np.ndarray]]: + stats = {key: np.array(value) for key, value in flatten_dict(stats).items()} return unflatten_dict(stats) -def load_tasks(local_dir: Path) -> dict: +def load_stats(local_dir: Path) -> dict[str, dict[str, np.ndarray]]: + if not (local_dir / STATS_PATH).exists(): + return None + stats = load_json(local_dir / STATS_PATH) + return cast_stats_to_numpy(stats) + + +def write_task(task_index: int, task: dict, local_dir: Path): + task_dict = { + "task_index": task_index, + "task": task, + } + append_jsonlines(task_dict, local_dir / TASKS_PATH) + + +def load_tasks(local_dir: Path) -> tuple[dict, dict]: tasks = load_jsonlines(local_dir / TASKS_PATH) - return {item["task_index"]: item["task"] for item in sorted(tasks, key=lambda x: x["task_index"])} + tasks = {item["task_index"]: item["task"] for item in sorted(tasks, key=lambda x: x["task_index"])} + task_to_task_index = {task: task_index for task_index, task in tasks.items()} + return tasks, task_to_task_index + + +def write_episode(episode: dict, local_dir: Path): + append_jsonlines(episode, local_dir / EPISODES_PATH) def load_episodes(local_dir: Path) -> dict: - return load_jsonlines(local_dir / EPISODES_PATH) + episodes = load_jsonlines(local_dir / EPISODES_PATH) + return {item["episode_index"]: item for item in sorted(episodes, key=lambda x: x["episode_index"])} -def load_image_as_numpy(fpath: str | Path, dtype="float32", channel_first: bool = True) -> np.ndarray: +def write_episode_stats(episode_index: int, episode_stats: dict, local_dir: Path): + # We wrap episode_stats in a dictionnary since `episode_stats["episode_index"]` + # is a dictionary of stats and not an integer. + episode_stats = {"episode_index": episode_index, "stats": serialize_dict(episode_stats)} + append_jsonlines(episode_stats, local_dir / EPISODES_STATS_PATH) + + +def load_episodes_stats(local_dir: Path) -> dict: + episodes_stats = load_jsonlines(local_dir / EPISODES_STATS_PATH) + return { + item["episode_index"]: cast_stats_to_numpy(item["stats"]) + for item in sorted(episodes_stats, key=lambda x: x["episode_index"]) + } + + +def backward_compatible_episodes_stats( + stats: dict[str, dict[str, np.ndarray]], episodes: list[int] +) -> dict[str, dict[str, np.ndarray]]: + return {ep_idx: stats for ep_idx in episodes} + + +def load_image_as_numpy( + fpath: str | Path, dtype: np.dtype = np.float32, channel_first: bool = True +) -> np.ndarray: img = PILImage.open(fpath).convert("RGB") img_array = np.array(img, dtype=dtype) if channel_first: # (H, W, C) -> (C, H, W) img_array = np.transpose(img_array, (2, 0, 1)) - if "float" in dtype: + if np.issubdtype(dtype, np.floating): img_array /= 255.0 return img_array @@ -201,77 +268,82 @@ def hf_transform_to_torch(items_dict: dict[torch.Tensor | None]): elif first_item is None: pass else: - items_dict[key] = [torch.tensor(x) for x in items_dict[key]] + items_dict[key] = [x if isinstance(x, str) else torch.tensor(x) for x in items_dict[key]] return items_dict -def _get_major_minor(version: str) -> tuple[int]: - split = version.strip("v").split(".") - return int(split[0]), int(split[1]) - - -class BackwardCompatibilityError(Exception): - def __init__(self, repo_id, version): - message = textwrap.dedent(f""" - BackwardCompatibilityError: The dataset you requested ({repo_id}) is in {version} format. - - We introduced a new format since v2.0 which is not backward compatible with v1.x. - Please, use our conversion script. Modify the following command with your own task description: - ``` - python lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py \\ - --repo-id {repo_id} \\ - --single-task "TASK DESCRIPTION." # <---- /!\\ Replace TASK DESCRIPTION /!\\ - ``` - - A few examples to replace TASK DESCRIPTION: "Pick up the blue cube and place it into the bin.", - "Insert the peg into the socket.", "Slide open the ziploc bag.", "Take the elevator to the 1st floor.", - "Open the top cabinet, store the pot inside it then close the cabinet.", "Push the T-shaped block onto the T-shaped target.", - "Grab the spray paint on the shelf and place it in the bin on top of the robot dog.", "Fold the sweatshirt.", ... - - If you encounter a problem, contact LeRobot maintainers on [Discord](https://discord.com/invite/s3KuuzsPFb) - or open an [issue on GitHub](https://github.com/huggingface/lerobot/issues/new/choose). - """) - super().__init__(message) +def is_valid_version(version: str) -> bool: + try: + packaging.version.parse(version) + return True + except packaging.version.InvalidVersion: + return False def check_version_compatibility( - repo_id: str, version_to_check: str, current_version: str, enforce_breaking_major: bool = True + repo_id: str, + version_to_check: str | packaging.version.Version, + current_version: str | packaging.version.Version, + enforce_breaking_major: bool = True, ) -> None: - current_major, _ = _get_major_minor(current_version) - major_to_check, _ = _get_major_minor(version_to_check) - if major_to_check < current_major and enforce_breaking_major: - raise BackwardCompatibilityError(repo_id, version_to_check) - elif float(version_to_check.strip("v")) < float(current_version.strip("v")): - logging.warning( - f"""The dataset you requested ({repo_id}) was created with a previous version ({version_to_check}) of the - codebase. The current codebase version is {current_version}. You should be fine since - backward compatibility is maintained. If you encounter a problem, contact LeRobot maintainers on - Discord ('https://discord.com/invite/s3KuuzsPFb') or open an issue on github.""", - ) + v_check = ( + packaging.version.parse(version_to_check) + if not isinstance(version_to_check, packaging.version.Version) + else version_to_check + ) + v_current = ( + packaging.version.parse(current_version) + if not isinstance(current_version, packaging.version.Version) + else current_version + ) + if v_check.major < v_current.major and enforce_breaking_major: + raise BackwardCompatibilityError(repo_id, v_check) + elif v_check.minor < v_current.minor: + logging.warning(V21_MESSAGE.format(repo_id=repo_id, version=v_check)) -def get_hub_safe_version(repo_id: str, version: str) -> str: +def get_repo_versions(repo_id: str) -> list[packaging.version.Version]: + """Returns available valid versions (branches and tags) on given repo.""" api = HfApi() - dataset_info = api.list_repo_refs(repo_id, repo_type="dataset") - branches = [b.name for b in dataset_info.branches] - if version not in branches: - num_version = float(version.strip("v")) - hub_num_versions = [float(v.strip("v")) for v in branches if v.startswith("v")] - if num_version >= 2.0 and all(v < 2.0 for v in hub_num_versions): - raise BackwardCompatibilityError(repo_id, version) + repo_refs = api.list_repo_refs(repo_id, repo_type="dataset") + repo_refs = [b.name for b in repo_refs.branches + repo_refs.tags] + repo_versions = [] + for ref in repo_refs: + with contextlib.suppress(packaging.version.InvalidVersion): + repo_versions.append(packaging.version.parse(ref)) - logging.warning( - f"""You are trying to load a dataset from {repo_id} created with a previous version of the - codebase. The following versions are available: {branches}. - The requested version ('{version}') is not found. You should be fine since - backward compatibility is maintained. If you encounter a problem, contact LeRobot maintainers on - Discord ('https://discord.com/invite/s3KuuzsPFb') or open an issue on github.""", - ) - if "main" not in branches: - raise ValueError(f"Version 'main' not found on {repo_id}") - return "main" - else: - return version + return repo_versions + + +def get_safe_version(repo_id: str, version: str | packaging.version.Version) -> str: + """ + Returns the version if available on repo or the latest compatible one. + Otherwise, will throw a `CompatibilityError`. + """ + target_version = ( + packaging.version.parse(version) if not isinstance(version, packaging.version.Version) else version + ) + hub_versions = get_repo_versions(repo_id) + + if target_version in hub_versions: + return f"v{target_version}" + + compatibles = [ + v for v in hub_versions if v.major == target_version.major and v.minor <= target_version.minor + ] + if compatibles: + return_version = max(compatibles) + if return_version < target_version: + logging.warning(f"Revision {version} for {repo_id} not found, using version v{return_version}") + return f"v{return_version}" + + lower_major = [v for v in hub_versions if v.major < target_version.major] + if lower_major: + raise BackwardCompatibilityError(repo_id, max(lower_major)) + + upper_versions = [v for v in hub_versions if v > target_version] + assert len(upper_versions) > 0 + raise ForwardCompatibilityError(repo_id, min(upper_versions)) def get_hf_features_from_features(features: dict) -> datasets.Features: @@ -283,11 +355,20 @@ def get_hf_features_from_features(features: dict) -> datasets.Features: hf_features[key] = datasets.Image() elif ft["shape"] == (1,): hf_features[key] = datasets.Value(dtype=ft["dtype"]) - else: - assert len(ft["shape"]) == 1 + elif len(ft["shape"]) == 1: hf_features[key] = datasets.Sequence( length=ft["shape"][0], feature=datasets.Value(dtype=ft["dtype"]) ) + elif len(ft["shape"]) == 2: + hf_features[key] = datasets.Array2D(shape=ft["shape"], dtype=ft["dtype"]) + elif len(ft["shape"]) == 3: + hf_features[key] = datasets.Array3D(shape=ft["shape"], dtype=ft["dtype"]) + elif len(ft["shape"]) == 4: + hf_features[key] = datasets.Array4D(shape=ft["shape"], dtype=ft["dtype"]) + elif len(ft["shape"]) == 5: + hf_features[key] = datasets.Array5D(shape=ft["shape"], dtype=ft["dtype"]) + else: + raise ValueError(f"Corresponding feature is not valid: {ft}") return datasets.Features(hf_features) @@ -358,9 +439,9 @@ def create_empty_dataset_info( def get_episode_data_index( - episode_dicts: list[dict], episodes: list[int] | None = None + episode_dicts: dict[dict], episodes: list[int] | None = None ) -> dict[str, torch.Tensor]: - episode_lengths = {ep_idx: ep_dict["length"] for ep_idx, ep_dict in enumerate(episode_dicts)} + episode_lengths = {ep_idx: ep_dict["length"] for ep_idx, ep_dict in episode_dicts.items()} if episodes is not None: episode_lengths = {ep_idx: episode_lengths[ep_idx] for ep_idx in episodes} @@ -371,75 +452,72 @@ def get_episode_data_index( } -def calculate_total_episode( - hf_dataset: datasets.Dataset, raise_if_not_contiguous: bool = True -) -> dict[str, torch.Tensor]: - episode_indices = sorted(hf_dataset.unique("episode_index")) - total_episodes = len(episode_indices) - if raise_if_not_contiguous and episode_indices != list(range(total_episodes)): - raise ValueError("episode_index values are not sorted and contiguous.") - return total_episodes - - -def calculate_episode_data_index(hf_dataset: datasets.Dataset) -> dict[str, torch.Tensor]: - episode_lengths = [] - table = hf_dataset.data.table - total_episodes = calculate_total_episode(hf_dataset) - for ep_idx in range(total_episodes): - ep_table = table.filter(pc.equal(table["episode_index"], ep_idx)) - episode_lengths.insert(ep_idx, len(ep_table)) - - cumulative_lenghts = list(accumulate(episode_lengths)) - return { - "from": torch.LongTensor([0] + cumulative_lenghts[:-1]), - "to": torch.LongTensor(cumulative_lenghts), - } - - def check_timestamps_sync( - hf_dataset: datasets.Dataset, - episode_data_index: dict[str, torch.Tensor], + timestamps: np.ndarray, + episode_indices: np.ndarray, + episode_data_index: dict[str, np.ndarray], fps: int, tolerance_s: float, raise_value_error: bool = True, ) -> bool: """ - This check is to make sure that each timestamps is separated to the next by 1/fps +/- tolerance to - account for possible numerical error. - """ - timestamps = torch.stack(hf_dataset["timestamp"]) - diffs = torch.diff(timestamps) - within_tolerance = torch.abs(diffs - 1 / fps) <= tolerance_s + This check is to make sure that each timestamp is separated from the next by (1/fps) +/- tolerance + to account for possible numerical error. - # We mask differences between the timestamp at the end of an episode - # and the one at the start of the next episode since these are expected - # to be outside tolerance. - mask = torch.ones(len(diffs), dtype=torch.bool) - ignored_diffs = episode_data_index["to"][:-1] - 1 + Args: + timestamps (np.ndarray): Array of timestamps in seconds. + episode_indices (np.ndarray): Array indicating the episode index for each timestamp. + episode_data_index (dict[str, np.ndarray]): A dictionary that includes 'to', + which identifies indices for the end of each episode. + fps (int): Frames per second. Used to check the expected difference between consecutive timestamps. + tolerance_s (float): Allowed deviation from the expected (1/fps) difference. + raise_value_error (bool): Whether to raise a ValueError if the check fails. + + Returns: + bool: True if all checked timestamp differences lie within tolerance, False otherwise. + + Raises: + ValueError: If the check fails and `raise_value_error` is True. + """ + if timestamps.shape != episode_indices.shape: + raise ValueError( + "timestamps and episode_indices should have the same shape. " + f"Found {timestamps.shape=} and {episode_indices.shape=}." + ) + + # Consecutive differences + diffs = np.diff(timestamps) + within_tolerance = np.abs(diffs - (1.0 / fps)) <= tolerance_s + + # Mask to ignore differences at the boundaries between episodes + mask = np.ones(len(diffs), dtype=bool) + ignored_diffs = episode_data_index["to"][:-1] - 1 # indices at the end of each episode mask[ignored_diffs] = False filtered_within_tolerance = within_tolerance[mask] - if not torch.all(filtered_within_tolerance): + # Check if all remaining diffs are within tolerance + if not np.all(filtered_within_tolerance): # Track original indices before masking - original_indices = torch.arange(len(diffs)) + original_indices = np.arange(len(diffs)) filtered_indices = original_indices[mask] - outside_tolerance_filtered_indices = torch.nonzero(~filtered_within_tolerance) # .squeeze() + outside_tolerance_filtered_indices = np.nonzero(~filtered_within_tolerance)[0] outside_tolerance_indices = filtered_indices[outside_tolerance_filtered_indices] - episode_indices = torch.stack(hf_dataset["episode_index"]) outside_tolerances = [] for idx in outside_tolerance_indices: entry = { "timestamps": [timestamps[idx], timestamps[idx + 1]], "diff": diffs[idx], - "episode_index": episode_indices[idx].item(), + "episode_index": episode_indices[idx].item() + if hasattr(episode_indices[idx], "item") + else episode_indices[idx], } outside_tolerances.append(entry) if raise_value_error: raise ValueError( f"""One or several timestamps unexpectedly violate the tolerance inside episode range. - This might be due to synchronization issues with timestamps during data collection. + This might be due to synchronization issues during data collection. \n{pformat(outside_tolerances)}""" ) return False @@ -604,3 +682,118 @@ class IterableNamespace(SimpleNamespace): def keys(self): return vars(self).keys() + + +def validate_frame(frame: dict, features: dict): + optional_features = {"timestamp"} + expected_features = (set(features) - set(DEFAULT_FEATURES.keys())) | {"task"} + actual_features = set(frame.keys()) + + error_message = validate_features_presence(actual_features, expected_features, optional_features) + + if "task" in frame: + error_message += validate_feature_string("task", frame["task"]) + + common_features = actual_features & (expected_features | optional_features) + for name in common_features - {"task"}: + error_message += validate_feature_dtype_and_shape(name, features[name], frame[name]) + + if error_message: + raise ValueError(error_message) + + +def validate_features_presence( + actual_features: set[str], expected_features: set[str], optional_features: set[str] +): + error_message = "" + missing_features = expected_features - actual_features + extra_features = actual_features - (expected_features | optional_features) + + if missing_features or extra_features: + error_message += "Feature mismatch in `frame` dictionary:\n" + if missing_features: + error_message += f"Missing features: {missing_features}\n" + if extra_features: + error_message += f"Extra features: {extra_features}\n" + + return error_message + + +def validate_feature_dtype_and_shape(name: str, feature: dict, value: np.ndarray | PILImage.Image | str): + expected_dtype = feature["dtype"] + expected_shape = feature["shape"] + if is_valid_numpy_dtype_string(expected_dtype): + return validate_feature_numpy_array(name, expected_dtype, expected_shape, value) + elif expected_dtype in ["image", "video"]: + return validate_feature_image_or_video(name, expected_shape, value) + elif expected_dtype == "string": + return validate_feature_string(name, value) + else: + raise NotImplementedError(f"The feature dtype '{expected_dtype}' is not implemented yet.") + + +def validate_feature_numpy_array( + name: str, expected_dtype: str, expected_shape: list[int], value: np.ndarray +): + error_message = "" + if isinstance(value, np.ndarray): + actual_dtype = value.dtype + actual_shape = value.shape + + if actual_dtype != np.dtype(expected_dtype): + error_message += f"The feature '{name}' of dtype '{actual_dtype}' is not of the expected dtype '{expected_dtype}'.\n" + + if actual_shape != expected_shape: + error_message += f"The feature '{name}' of shape '{actual_shape}' does not have the expected shape '{expected_shape}'.\n" + else: + error_message += f"The feature '{name}' is not a 'np.ndarray'. Expected type is '{expected_dtype}', but type '{type(value)}' provided instead.\n" + + return error_message + + +def validate_feature_image_or_video(name: str, expected_shape: list[str], value: np.ndarray | PILImage.Image): + # Note: The check of pixels range ([0,1] for float and [0,255] for uint8) is done by the image writer threads. + error_message = "" + if isinstance(value, np.ndarray): + actual_shape = value.shape + c, h, w = expected_shape + if len(actual_shape) != 3 or (actual_shape != (c, h, w) and actual_shape != (h, w, c)): + error_message += f"The feature '{name}' of shape '{actual_shape}' does not have the expected shape '{(c, h, w)}' or '{(h, w, c)}'.\n" + elif isinstance(value, PILImage.Image): + pass + else: + error_message += f"The feature '{name}' is expected to be of type 'PIL.Image' or 'np.ndarray' channel first or channel last, but type '{type(value)}' provided instead.\n" + + return error_message + + +def validate_feature_string(name: str, value: str): + if not isinstance(value, str): + return f"The feature '{name}' is expected to be of type 'str', but type '{type(value)}' provided instead.\n" + return "" + + +def validate_episode_buffer(episode_buffer: dict, total_episodes: int, features: dict): + if "size" not in episode_buffer: + raise ValueError("size key not found in episode_buffer") + + if "task" not in episode_buffer: + raise ValueError("task key not found in episode_buffer") + + if episode_buffer["episode_index"] != total_episodes: + # TODO(aliberts): Add option to use existing episode_index + raise NotImplementedError( + "You might have manually provided the episode_buffer with an episode_index that doesn't " + "match the total number of episodes already in the dataset. This is not supported for now." + ) + + if episode_buffer["size"] == 0: + raise ValueError("You must add one or several frames with `add_frame` before calling `add_episode`.") + + buffer_keys = set(episode_buffer.keys()) - {"task", "size"} + if not buffer_keys == set(features): + raise ValueError( + f"Features from `episode_buffer` don't match the ones in `features`." + f"In episode_buffer not in features: {buffer_keys - set(features)}" + f"In features not in episode_buffer: {set(features) - buffer_keys}" + ) diff --git a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py index 62ca9932..99864e3b 100644 --- a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py @@ -130,7 +130,7 @@ from lerobot.common.datasets.utils import ( create_branch, create_lerobot_dataset_card, flatten_dict, - get_hub_safe_version, + get_safe_version, load_json, unflatten_dict, write_json, @@ -443,7 +443,7 @@ def convert_dataset( test_branch: str | None = None, **card_kwargs, ): - v1 = get_hub_safe_version(repo_id, V16) + v1 = get_safe_version(repo_id, V16) v1x_dir = local_dir / V16 / repo_id v20_dir = local_dir / V20 / repo_id v1x_dir.mkdir(parents=True, exist_ok=True) diff --git a/lerobot/common/datasets/v21/_remove_language_instruction.py b/lerobot/common/datasets/v21/_remove_language_instruction.py new file mode 100644 index 00000000..dd4604cf --- /dev/null +++ b/lerobot/common/datasets/v21/_remove_language_instruction.py @@ -0,0 +1,73 @@ +import logging +import traceback +from pathlib import Path + +from datasets import get_dataset_config_info +from huggingface_hub import HfApi + +from lerobot import available_datasets +from lerobot.common.datasets.lerobot_dataset import LeRobotDatasetMetadata +from lerobot.common.datasets.utils import INFO_PATH, write_info +from lerobot.common.datasets.v21.convert_dataset_v20_to_v21 import V20, SuppressWarnings + +LOCAL_DIR = Path("data/") + +hub_api = HfApi() + + +def fix_dataset(repo_id: str) -> str: + if not hub_api.revision_exists(repo_id, V20, repo_type="dataset"): + return f"{repo_id}: skipped (not in {V20})." + + dataset_info = get_dataset_config_info(repo_id, "default") + with SuppressWarnings(): + lerobot_metadata = LeRobotDatasetMetadata(repo_id, revision=V20, force_cache_sync=True) + + meta_features = {key for key, ft in lerobot_metadata.features.items() if ft["dtype"] != "video"} + parquet_features = set(dataset_info.features) + + diff_parquet_meta = parquet_features - meta_features + diff_meta_parquet = meta_features - parquet_features + + if diff_parquet_meta: + raise ValueError(f"In parquet not in info.json: {parquet_features - meta_features}") + + if not diff_meta_parquet: + return f"{repo_id}: skipped (no diff)" + + if diff_meta_parquet: + logging.warning(f"In info.json not in parquet: {meta_features - parquet_features}") + assert diff_meta_parquet == {"language_instruction"} + lerobot_metadata.features.pop("language_instruction") + write_info(lerobot_metadata.info, lerobot_metadata.root) + commit_info = hub_api.upload_file( + path_or_fileobj=lerobot_metadata.root / INFO_PATH, + path_in_repo=INFO_PATH, + repo_id=repo_id, + repo_type="dataset", + revision=V20, + commit_message="Remove 'language_instruction'", + create_pr=True, + ) + return f"{repo_id}: success - PR: {commit_info.pr_url}" + + +def batch_fix(): + status = {} + LOCAL_DIR.mkdir(parents=True, exist_ok=True) + logfile = LOCAL_DIR / "fix_features_v20.txt" + for num, repo_id in enumerate(available_datasets): + print(f"\nConverting {repo_id} ({num}/{len(available_datasets)})") + print("---------------------------------------------------------") + try: + status = fix_dataset(repo_id) + except Exception: + status = f"{repo_id}: failed\n {traceback.format_exc()}" + + logging.info(status) + with open(logfile, "a") as file: + file.write(status + "\n") + + +if __name__ == "__main__": + batch_fix() diff --git a/lerobot/common/datasets/v21/batch_convert_dataset_v20_to_v21.py b/lerobot/common/datasets/v21/batch_convert_dataset_v20_to_v21.py new file mode 100644 index 00000000..cc9272a8 --- /dev/null +++ b/lerobot/common/datasets/v21/batch_convert_dataset_v20_to_v21.py @@ -0,0 +1,54 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +""" +This script is for internal use to convert all datasets under the 'lerobot' hub user account to v2.1. +""" + +import traceback +from pathlib import Path + +from huggingface_hub import HfApi + +from lerobot import available_datasets +from lerobot.common.datasets.v21.convert_dataset_v20_to_v21 import V21, convert_dataset + +LOCAL_DIR = Path("data/") + + +def batch_convert(): + status = {} + LOCAL_DIR.mkdir(parents=True, exist_ok=True) + logfile = LOCAL_DIR / "conversion_log_v21.txt" + hub_api = HfApi() + for num, repo_id in enumerate(available_datasets): + print(f"\nConverting {repo_id} ({num}/{len(available_datasets)})") + print("---------------------------------------------------------") + try: + if hub_api.revision_exists(repo_id, V21, repo_type="dataset"): + status = f"{repo_id}: success (already in {V21})." + else: + convert_dataset(repo_id) + status = f"{repo_id}: success." + except Exception: + status = f"{repo_id}: failed\n {traceback.format_exc()}" + + with open(logfile, "a") as file: + file.write(status + "\n") + + +if __name__ == "__main__": + batch_convert() diff --git a/lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py b/lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py new file mode 100644 index 00000000..20bda75b --- /dev/null +++ b/lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py @@ -0,0 +1,100 @@ +""" +This script will help you convert any LeRobot dataset already pushed to the hub from codebase version 2.0 to +2.1. It will: + +- Generate per-episodes stats and writes them in `episodes_stats.jsonl` +- Check consistency between these new stats and the old ones. +- Remove the deprecated `stats.json`. +- Update codebase_version in `info.json`. +- Push this new version to the hub on the 'main' branch and tags it with "v2.1". + +Usage: + +```bash +python lerobot/common/datasets/v21/convert_dataset_v20_to_v21.py \ + --repo-id=aliberts/koch_tutorial +``` + +""" + +import argparse +import logging + +from huggingface_hub import HfApi + +from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION, LeRobotDataset +from lerobot.common.datasets.utils import EPISODES_STATS_PATH, STATS_PATH, load_stats, write_info +from lerobot.common.datasets.v21.convert_stats import check_aggregate_stats, convert_stats + +V20 = "v2.0" +V21 = "v2.1" + + +class SuppressWarnings: + def __enter__(self): + self.previous_level = logging.getLogger().getEffectiveLevel() + logging.getLogger().setLevel(logging.ERROR) + + def __exit__(self, exc_type, exc_val, exc_tb): + logging.getLogger().setLevel(self.previous_level) + + +def convert_dataset( + repo_id: str, + branch: str | None = None, + num_workers: int = 4, +): + with SuppressWarnings(): + dataset = LeRobotDataset(repo_id, revision=V20, force_cache_sync=True) + + if (dataset.root / EPISODES_STATS_PATH).is_file(): + (dataset.root / EPISODES_STATS_PATH).unlink() + + convert_stats(dataset, num_workers=num_workers) + ref_stats = load_stats(dataset.root) + check_aggregate_stats(dataset, ref_stats) + + dataset.meta.info["codebase_version"] = CODEBASE_VERSION + write_info(dataset.meta.info, dataset.root) + + dataset.push_to_hub(branch=branch, allow_patterns="meta/") + + # delete old stats.json file + if (dataset.root / STATS_PATH).is_file: + (dataset.root / STATS_PATH).unlink() + + hub_api = HfApi() + if hub_api.file_exists( + repo_id=dataset.repo_id, filename=STATS_PATH, revision=branch, repo_type="dataset" + ): + hub_api.delete_file( + path_in_repo=STATS_PATH, repo_id=dataset.repo_id, revision=branch, repo_type="dataset" + ) + + hub_api.create_tag(repo_id, tag=CODEBASE_VERSION, revision=branch, repo_type="dataset") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument( + "--repo-id", + type=str, + required=True, + help="Repository identifier on Hugging Face: a community or a user name `/` the name of the dataset " + "(e.g. `lerobot/pusht`, `cadene/aloha_sim_insertion_human`).", + ) + parser.add_argument( + "--branch", + type=str, + default=None, + help="Repo branch to push your dataset. Defaults to the main branch.", + ) + parser.add_argument( + "--num-workers", + type=int, + default=4, + help="Number of workers for parallelizing stats compute. Defaults to 4.", + ) + + args = parser.parse_args() + convert_dataset(**vars(args)) diff --git a/lerobot/common/datasets/v21/convert_stats.py b/lerobot/common/datasets/v21/convert_stats.py new file mode 100644 index 00000000..cbf584b7 --- /dev/null +++ b/lerobot/common/datasets/v21/convert_stats.py @@ -0,0 +1,85 @@ +from concurrent.futures import ThreadPoolExecutor, as_completed + +import numpy as np +from tqdm import tqdm + +from lerobot.common.datasets.compute_stats import aggregate_stats, get_feature_stats, sample_indices +from lerobot.common.datasets.lerobot_dataset import LeRobotDataset +from lerobot.common.datasets.utils import write_episode_stats + + +def sample_episode_video_frames(dataset: LeRobotDataset, episode_index: int, ft_key: str) -> np.ndarray: + ep_len = dataset.meta.episodes[episode_index]["length"] + sampled_indices = sample_indices(ep_len) + query_timestamps = dataset._get_query_timestamps(0.0, {ft_key: sampled_indices}) + video_frames = dataset._query_videos(query_timestamps, episode_index) + return video_frames[ft_key].numpy() + + +def convert_episode_stats(dataset: LeRobotDataset, ep_idx: int): + ep_start_idx = dataset.episode_data_index["from"][ep_idx] + ep_end_idx = dataset.episode_data_index["to"][ep_idx] + ep_data = dataset.hf_dataset.select(range(ep_start_idx, ep_end_idx)) + + ep_stats = {} + for key, ft in dataset.features.items(): + if ft["dtype"] == "video": + # We sample only for videos + ep_ft_data = sample_episode_video_frames(dataset, ep_idx, key) + else: + ep_ft_data = np.array(ep_data[key]) + + axes_to_reduce = (0, 2, 3) if ft["dtype"] in ["image", "video"] else 0 + keepdims = True if ft["dtype"] in ["image", "video"] else ep_ft_data.ndim == 1 + ep_stats[key] = get_feature_stats(ep_ft_data, axis=axes_to_reduce, keepdims=keepdims) + + if ft["dtype"] in ["image", "video"]: # remove batch dim + ep_stats[key] = { + k: v if k == "count" else np.squeeze(v, axis=0) for k, v in ep_stats[key].items() + } + + dataset.meta.episodes_stats[ep_idx] = ep_stats + + +def convert_stats(dataset: LeRobotDataset, num_workers: int = 0): + assert dataset.episodes is None + print("Computing episodes stats") + total_episodes = dataset.meta.total_episodes + if num_workers > 0: + with ThreadPoolExecutor(max_workers=num_workers) as executor: + futures = { + executor.submit(convert_episode_stats, dataset, ep_idx): ep_idx + for ep_idx in range(total_episodes) + } + for future in tqdm(as_completed(futures), total=total_episodes): + future.result() + else: + for ep_idx in tqdm(range(total_episodes)): + convert_episode_stats(dataset, ep_idx) + + for ep_idx in tqdm(range(total_episodes)): + write_episode_stats(ep_idx, dataset.meta.episodes_stats[ep_idx], dataset.root) + + +def check_aggregate_stats( + dataset: LeRobotDataset, + reference_stats: dict[str, dict[str, np.ndarray]], + video_rtol_atol: tuple[float] = (1e-2, 1e-2), + default_rtol_atol: tuple[float] = (5e-6, 6e-5), +): + """Verifies that the aggregated stats from episodes_stats are close to reference stats.""" + agg_stats = aggregate_stats(list(dataset.meta.episodes_stats.values())) + for key, ft in dataset.features.items(): + # These values might need some fine-tuning + if ft["dtype"] == "video": + # to account for image sub-sampling + rtol, atol = video_rtol_atol + else: + rtol, atol = default_rtol_atol + + for stat, val in agg_stats[key].items(): + if key in reference_stats and stat in reference_stats[key]: + err_msg = f"feature='{key}' stats='{stat}'" + np.testing.assert_allclose( + val, reference_stats[key][stat], rtol=rtol, atol=atol, err_msg=err_msg + ) diff --git a/lerobot/common/datasets/video_utils.py b/lerobot/common/datasets/video_utils.py index 8ed3318d..8be53483 100644 --- a/lerobot/common/datasets/video_utils.py +++ b/lerobot/common/datasets/video_utils.py @@ -69,8 +69,8 @@ def decode_video_frames_torchvision( # set the first and last requested timestamps # Note: previous timestamps are usually loaded, since we need to access the previous key frame - first_ts = timestamps[0] - last_ts = timestamps[-1] + first_ts = min(timestamps) + last_ts = max(timestamps) # access closest key frame of the first requested frame # Note: closest key frame timestamp is usally smaller than `first_ts` (e.g. key frame can be the first frame of the video) diff --git a/lerobot/common/policies/normalize.py b/lerobot/common/policies/normalize.py index 95219273..b3255ec1 100644 --- a/lerobot/common/policies/normalize.py +++ b/lerobot/common/policies/normalize.py @@ -13,6 +13,7 @@ # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. +import numpy as np import torch from torch import Tensor, nn @@ -77,17 +78,29 @@ def create_stats_buffers( } ) + # TODO(aliberts, rcadene): harmonize this to only use one framework (np or torch) if stats: - # Note: The clone is needed to make sure that the logic in save_pretrained doesn't see duplicated - # tensors anywhere (for example, when we use the same stats for normalization and - # unnormalization). See the logic here - # https://github.com/huggingface/safetensors/blob/079781fd0dc455ba0fe851e2b4507c33d0c0d407/bindings/python/py_src/safetensors/torch.py#L97. - if norm_mode is NormalizationMode.MEAN_STD: - buffer["mean"].data = stats[key]["mean"].clone() - buffer["std"].data = stats[key]["std"].clone() - elif norm_mode is NormalizationMode.MIN_MAX: - buffer["min"].data = stats[key]["min"].clone() - buffer["max"].data = stats[key]["max"].clone() + if isinstance(stats[key]["mean"], np.ndarray): + if norm_mode is NormalizationMode.MEAN_STD: + buffer["mean"].data = torch.from_numpy(stats[key]["mean"]).to(dtype=torch.float32) + buffer["std"].data = torch.from_numpy(stats[key]["std"]).to(dtype=torch.float32) + elif norm_mode is NormalizationMode.MIN_MAX: + buffer["min"].data = torch.from_numpy(stats[key]["min"]).to(dtype=torch.float32) + buffer["max"].data = torch.from_numpy(stats[key]["max"]).to(dtype=torch.float32) + elif isinstance(stats[key]["mean"], torch.Tensor): + # Note: The clone is needed to make sure that the logic in save_pretrained doesn't see duplicated + # tensors anywhere (for example, when we use the same stats for normalization and + # unnormalization). See the logic here + # https://github.com/huggingface/safetensors/blob/079781fd0dc455ba0fe851e2b4507c33d0c0d407/bindings/python/py_src/safetensors/torch.py#L97. + if norm_mode is NormalizationMode.MEAN_STD: + buffer["mean"].data = stats[key]["mean"].clone().to(dtype=torch.float32) + buffer["std"].data = stats[key]["std"].clone().to(dtype=torch.float32) + elif norm_mode is NormalizationMode.MIN_MAX: + buffer["min"].data = stats[key]["min"].clone().to(dtype=torch.float32) + buffer["max"].data = stats[key]["max"].clone().to(dtype=torch.float32) + else: + type_ = type(stats[key]["mean"]) + raise ValueError(f"np.ndarray or torch.Tensor expected, but type is '{type_}' instead.") stats_buffers[key] = buffer return stats_buffers @@ -141,6 +154,7 @@ class Normalize(nn.Module): batch = dict(batch) # shallow copy avoids mutating the input batch for key, ft in self.features.items(): if key not in batch: + # FIXME(aliberts, rcadene): This might lead to silent fail! continue norm_mode = self.norm_map.get(ft.type, NormalizationMode.IDENTITY) diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index 6dae8cb6..c3e920b1 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -60,8 +60,6 @@ class RecordControlConfig(ControlConfig): num_episodes: int = 50 # Encode frames in the dataset into video video: bool = True - # By default, run the computation of the data statistics at the end of data collection. Compute intensive and not required to just replay an episode. - run_compute_stats: bool = True # Upload dataset to Hugging Face hub. push_to_hub: bool = True # Upload on private repository on the Hugging Face hub. @@ -83,9 +81,6 @@ class RecordControlConfig(ControlConfig): play_sounds: bool = True # Resume recording on an existing dataset. resume: bool = False - # TODO(rcadene, aliberts): remove local_files_only when refactor with dataset as argument - # Use local files only. By default, this script will try to fetch the dataset from the hub if it exists. - local_files_only: bool = False def __post_init__(self): # HACK: We parse again the cli args here to get the pretrained path if there was one. @@ -130,9 +125,6 @@ class ReplayControlConfig(ControlConfig): fps: int | None = None # Use vocal synthesis to read events. play_sounds: bool = True - # TODO(rcadene, aliberts): remove local_files_only when refactor with dataset as argument - # Use local files only. By default, this script will try to fetch the dataset from the hub if it exists. - local_files_only: bool = False @ControlConfig.register_subclass("remote_robot") diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/robot_devices/control_utils.py index 7264f078..6c97d0cb 100644 --- a/lerobot/common/robot_devices/control_utils.py +++ b/lerobot/common/robot_devices/control_utils.py @@ -183,6 +183,7 @@ def record_episode( device, use_amp, fps, + single_task, ): control_loop( robot=robot, @@ -195,6 +196,7 @@ def record_episode( use_amp=use_amp, fps=fps, teleoperate=policy is None, + single_task=single_task, ) @@ -210,6 +212,7 @@ def control_loop( device: torch.device | str | None = None, use_amp: bool | None = None, fps: int | None = None, + single_task: str | None = None, ): # TODO(rcadene): Add option to record logs if not robot.is_connected: @@ -224,6 +227,9 @@ def control_loop( if teleoperate and policy is not None: raise ValueError("When `teleoperate` is True, `policy` should be None.") + if dataset is not None and single_task is None: + raise ValueError("You need to provide a task as argument in `single_task`.") + if dataset is not None and fps is not None and dataset.fps != fps: raise ValueError(f"The dataset fps should be equal to requested fps ({dataset['fps']} != {fps}).") @@ -248,7 +254,7 @@ def control_loop( action = {"action": action} if dataset is not None: - frame = {**observation, **action} + frame = {**observation, **action, "task": single_task} dataset.add_frame(frame) if display_cameras and not is_headless(): diff --git a/lerobot/common/utils/utils.py b/lerobot/common/utils/utils.py index 015d1ede..d0c12b30 100644 --- a/lerobot/common/utils/utils.py +++ b/lerobot/common/utils/utils.py @@ -21,6 +21,7 @@ from copy import copy from datetime import datetime, timezone from pathlib import Path +import numpy as np import torch @@ -200,5 +201,18 @@ def get_channel_first_image_shape(image_shape: tuple) -> tuple: return shape -def has_method(cls: object, method_name: str): +def has_method(cls: object, method_name: str) -> bool: return hasattr(cls, method_name) and callable(getattr(cls, method_name)) + + +def is_valid_numpy_dtype_string(dtype_str: str) -> bool: + """ + Return True if a given string can be converted to a numpy dtype. + """ + try: + # Attempt to convert the string to a numpy dtype + np.dtype(dtype_str) + return True + except TypeError: + # If a TypeError is raised, the string is not a valid dtype + return False diff --git a/lerobot/configs/default.py b/lerobot/configs/default.py index 5dd2f898..a5013431 100644 --- a/lerobot/configs/default.py +++ b/lerobot/configs/default.py @@ -31,7 +31,7 @@ class DatasetConfig: repo_id: str episodes: list[int] | None = None image_transforms: ImageTransformsConfig = field(default_factory=ImageTransformsConfig) - local_files_only: bool = False + revision: str | None = None use_imagenet_stats: bool = True video_backend: str = "pyav" diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 9129c9e3..32f3b181 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -92,7 +92,6 @@ python lerobot/scripts/control_robot.py \ This might require a sudo permission to allow your terminal to monitor keyboard events. **NOTE**: You can resume/continue data recording by running the same data recording command and adding `--control.resume=true`. -If the dataset you want to extend is not on the hub, you also need to add `--control.local_files_only=true`. - Train on this dataset with the ACT policy: ```bash @@ -234,7 +233,6 @@ def record( dataset = LeRobotDataset( cfg.repo_id, root=cfg.root, - local_files_only=cfg.local_files_only, ) if len(robot.cameras) > 0: dataset.start_image_writer( @@ -281,8 +279,8 @@ def record( log_say(f"Recording episode {dataset.num_episodes}", cfg.play_sounds) record_episode( - dataset=dataset, robot=robot, + dataset=dataset, events=events, episode_time_s=cfg.episode_time_s, display_cameras=cfg.display_cameras, @@ -290,6 +288,7 @@ def record( device=cfg.device, use_amp=cfg.use_amp, fps=cfg.fps, + single_task=cfg.single_task, ) # Execute a few seconds without recording to give time to manually reset the environment @@ -309,7 +308,7 @@ def record( dataset.clear_episode_buffer() continue - dataset.save_episode(cfg.single_task) + dataset.save_episode() recorded_episodes += 1 if events["stop_recording"]: @@ -318,11 +317,6 @@ def record( log_say("Stop recording", cfg.play_sounds, blocking=True) stop_recording(robot, listener, cfg.display_cameras) - if cfg.run_compute_stats: - logging.info("Computing dataset statistics") - - dataset.consolidate(cfg.run_compute_stats) - if cfg.push_to_hub: dataset.push_to_hub(tags=cfg.tags, private=cfg.private) @@ -338,9 +332,7 @@ def replay( # TODO(rcadene, aliberts): refactor with control_loop, once `dataset` is an instance of LeRobotDataset # TODO(rcadene): Add option to record logs - dataset = LeRobotDataset( - cfg.repo_id, root=cfg.root, episodes=[cfg.episode], local_files_only=cfg.local_files_only - ) + dataset = LeRobotDataset(cfg.repo_id, root=cfg.root, episodes=[cfg.episode]) actions = dataset.hf_dataset.select_columns("action") if not robot.is_connected: diff --git a/lerobot/scripts/visualize_dataset.py b/lerobot/scripts/visualize_dataset.py index 626b0bde..11feb1af 100644 --- a/lerobot/scripts/visualize_dataset.py +++ b/lerobot/scripts/visualize_dataset.py @@ -207,12 +207,6 @@ def main(): required=True, help="Episode to visualize.", ) - parser.add_argument( - "--local-files-only", - type=int, - default=0, - help="Use local files only. By default, this script will try to fetch the dataset from the hub if it exists.", - ) parser.add_argument( "--root", type=Path, @@ -275,10 +269,9 @@ def main(): kwargs = vars(args) repo_id = kwargs.pop("repo_id") root = kwargs.pop("root") - local_files_only = kwargs.pop("local_files_only") logging.info("Loading dataset") - dataset = LeRobotDataset(repo_id, root=root, local_files_only=local_files_only) + dataset = LeRobotDataset(repo_id, root=root) visualize_dataset(dataset, **vars(args)) diff --git a/lerobot/scripts/visualize_dataset_html.py b/lerobot/scripts/visualize_dataset_html.py index cc3f3930..ed748c9a 100644 --- a/lerobot/scripts/visualize_dataset_html.py +++ b/lerobot/scripts/visualize_dataset_html.py @@ -150,7 +150,7 @@ def run_server( 400, ) dataset_version = ( - dataset.meta._version if isinstance(dataset, LeRobotDataset) else dataset.codebase_version + str(dataset.meta._version) if isinstance(dataset, LeRobotDataset) else dataset.codebase_version ) match = re.search(r"v(\d+)\.", dataset_version) if match: @@ -384,12 +384,6 @@ def main(): default=None, help="Name of hugging face repositery containing a LeRobotDataset dataset (e.g. `lerobot/pusht` for https://huggingface.co/datasets/lerobot/pusht).", ) - parser.add_argument( - "--local-files-only", - type=int, - default=0, - help="Use local files only. By default, this script will try to fetch the dataset from the hub if it exists.", - ) parser.add_argument( "--root", type=Path, @@ -445,15 +439,10 @@ def main(): repo_id = kwargs.pop("repo_id") load_from_hf_hub = kwargs.pop("load_from_hf_hub") root = kwargs.pop("root") - local_files_only = kwargs.pop("local_files_only") dataset = None if repo_id: - dataset = ( - LeRobotDataset(repo_id, root=root, local_files_only=local_files_only) - if not load_from_hf_hub - else get_dataset_info(repo_id) - ) + dataset = LeRobotDataset(repo_id, root=root) if not load_from_hf_hub else get_dataset_info(repo_id) visualize_dataset_html(dataset, **vars(args)) diff --git a/lerobot/scripts/visualize_image_transforms.py b/lerobot/scripts/visualize_image_transforms.py index 727fe178..80935d32 100644 --- a/lerobot/scripts/visualize_image_transforms.py +++ b/lerobot/scripts/visualize_image_transforms.py @@ -109,7 +109,7 @@ def visualize_image_transforms(cfg: DatasetConfig, output_dir: Path = OUTPUT_DIR dataset = LeRobotDataset( repo_id=cfg.repo_id, episodes=cfg.episodes, - local_files_only=cfg.local_files_only, + revision=cfg.revision, video_backend=cfg.video_backend, ) diff --git a/pyproject.toml b/pyproject.toml index 21c3fc78..25cadb3e 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -47,6 +47,7 @@ dependencies = [ "numba>=0.59.0", "omegaconf>=2.3.0", "opencv-python>=4.9.0", + "packaging>=24.2", "pyav>=12.0.5", "pymunk>=6.6.0", "pynput>=1.7.7", diff --git a/tests/fixtures/constants.py b/tests/fixtures/constants.py index bfe6c339..3201dcf2 100644 --- a/tests/fixtures/constants.py +++ b/tests/fixtures/constants.py @@ -1,6 +1,6 @@ -from lerobot.common.datasets.lerobot_dataset import LEROBOT_HOME +from lerobot.common.constants import HF_LEROBOT_HOME -LEROBOT_TEST_DIR = LEROBOT_HOME / "_testing" +LEROBOT_TEST_DIR = HF_LEROBOT_HOME / "_testing" DUMMY_REPO_ID = "dummy/repo" DUMMY_ROBOT_TYPE = "dummy_robot" DUMMY_MOTOR_FEATURES = { @@ -27,3 +27,5 @@ DUMMY_VIDEO_INFO = { "video.is_depth_map": False, "has_audio": False, } +DUMMY_CHW = (3, 96, 128) +DUMMY_HWC = (96, 128, 3) diff --git a/tests/fixtures/dataset_factories.py b/tests/fixtures/dataset_factories.py index c28a1165..2259e0e6 100644 --- a/tests/fixtures/dataset_factories.py +++ b/tests/fixtures/dataset_factories.py @@ -1,5 +1,7 @@ import random +from functools import partial from pathlib import Path +from typing import Protocol from unittest.mock import patch import datasets @@ -27,8 +29,12 @@ from tests.fixtures.constants import ( ) +class LeRobotDatasetFactory(Protocol): + def __call__(self, *args, **kwargs) -> LeRobotDataset: ... + + def get_task_index(task_dicts: dict, task: str) -> int: - tasks = {d["task_index"]: d["task"] for d in task_dicts} + tasks = {d["task_index"]: d["task"] for d in task_dicts.values()} task_to_task_index = {task: task_idx for task_idx, task in tasks.items()} return task_to_task_index[task] @@ -141,6 +147,7 @@ def stats_factory(): "mean": np.full((3, 1, 1), 0.5, dtype=np.float32).tolist(), "min": np.full((3, 1, 1), 0, dtype=np.float32).tolist(), "std": np.full((3, 1, 1), 0.25, dtype=np.float32).tolist(), + "count": [10], } else: stats[key] = { @@ -148,20 +155,38 @@ def stats_factory(): "mean": np.full(shape, 0.5, dtype=dtype).tolist(), "min": np.full(shape, 0, dtype=dtype).tolist(), "std": np.full(shape, 0.25, dtype=dtype).tolist(), + "count": [10], } return stats return _create_stats +@pytest.fixture(scope="session") +def episodes_stats_factory(stats_factory): + def _create_episodes_stats( + features: dict[str], + total_episodes: int = 3, + ) -> dict: + episodes_stats = {} + for episode_index in range(total_episodes): + episodes_stats[episode_index] = { + "episode_index": episode_index, + "stats": stats_factory(features), + } + return episodes_stats + + return _create_episodes_stats + + @pytest.fixture(scope="session") def tasks_factory(): def _create_tasks(total_tasks: int = 3) -> int: - tasks_list = [] - for i in range(total_tasks): - task_dict = {"task_index": i, "task": f"Perform action {i}."} - tasks_list.append(task_dict) - return tasks_list + tasks = {} + for task_index in range(total_tasks): + task_dict = {"task_index": task_index, "task": f"Perform action {task_index}."} + tasks[task_index] = task_dict + return tasks return _create_tasks @@ -190,10 +215,10 @@ def episodes_factory(tasks_factory): # Generate random lengths that sum up to total_length lengths = np.random.multinomial(total_frames, [1 / total_episodes] * total_episodes).tolist() - tasks_list = [task_dict["task"] for task_dict in tasks] + tasks_list = [task_dict["task"] for task_dict in tasks.values()] num_tasks_available = len(tasks_list) - episodes_list = [] + episodes = {} remaining_tasks = tasks_list.copy() for ep_idx in range(total_episodes): num_tasks_in_episode = random.randint(1, min(3, num_tasks_available)) if multi_task else 1 @@ -203,15 +228,13 @@ def episodes_factory(tasks_factory): for task in episode_tasks: remaining_tasks.remove(task) - episodes_list.append( - { - "episode_index": ep_idx, - "tasks": episode_tasks, - "length": lengths[ep_idx], - } - ) + episodes[ep_idx] = { + "episode_index": ep_idx, + "tasks": episode_tasks, + "length": lengths[ep_idx], + } - return episodes_list + return episodes return _create_episodes @@ -235,7 +258,7 @@ def hf_dataset_factory(features_factory, tasks_factory, episodes_factory, img_ar frame_index_col = np.array([], dtype=np.int64) episode_index_col = np.array([], dtype=np.int64) task_index = np.array([], dtype=np.int64) - for ep_dict in episodes: + for ep_dict in episodes.values(): timestamp_col = np.concatenate((timestamp_col, np.arange(ep_dict["length"]) / fps)) frame_index_col = np.concatenate((frame_index_col, np.arange(ep_dict["length"], dtype=int))) episode_index_col = np.concatenate( @@ -278,6 +301,7 @@ def hf_dataset_factory(features_factory, tasks_factory, episodes_factory, img_ar def lerobot_dataset_metadata_factory( info_factory, stats_factory, + episodes_stats_factory, tasks_factory, episodes_factory, mock_snapshot_download_factory, @@ -287,14 +311,18 @@ def lerobot_dataset_metadata_factory( repo_id: str = DUMMY_REPO_ID, info: dict | None = None, stats: dict | None = None, + episodes_stats: list[dict] | None = None, tasks: list[dict] | None = None, episodes: list[dict] | None = None, - local_files_only: bool = False, ) -> LeRobotDatasetMetadata: if not info: info = info_factory() if not stats: stats = stats_factory(features=info["features"]) + if not episodes_stats: + episodes_stats = episodes_stats_factory( + features=info["features"], total_episodes=info["total_episodes"] + ) if not tasks: tasks = tasks_factory(total_tasks=info["total_tasks"]) if not episodes: @@ -305,21 +333,20 @@ def lerobot_dataset_metadata_factory( mock_snapshot_download = mock_snapshot_download_factory( info=info, stats=stats, + episodes_stats=episodes_stats, tasks=tasks, episodes=episodes, ) with ( - patch( - "lerobot.common.datasets.lerobot_dataset.get_hub_safe_version" - ) as mock_get_hub_safe_version_patch, + patch("lerobot.common.datasets.lerobot_dataset.get_safe_version") as mock_get_safe_version_patch, patch( "lerobot.common.datasets.lerobot_dataset.snapshot_download" ) as mock_snapshot_download_patch, ): - mock_get_hub_safe_version_patch.side_effect = lambda repo_id, version: version + mock_get_safe_version_patch.side_effect = lambda repo_id, version: version mock_snapshot_download_patch.side_effect = mock_snapshot_download - return LeRobotDatasetMetadata(repo_id=repo_id, root=root, local_files_only=local_files_only) + return LeRobotDatasetMetadata(repo_id=repo_id, root=root) return _create_lerobot_dataset_metadata @@ -328,12 +355,13 @@ def lerobot_dataset_metadata_factory( def lerobot_dataset_factory( info_factory, stats_factory, + episodes_stats_factory, tasks_factory, episodes_factory, hf_dataset_factory, mock_snapshot_download_factory, lerobot_dataset_metadata_factory, -): +) -> LeRobotDatasetFactory: def _create_lerobot_dataset( root: Path, repo_id: str = DUMMY_REPO_ID, @@ -343,6 +371,7 @@ def lerobot_dataset_factory( multi_task: bool = False, info: dict | None = None, stats: dict | None = None, + episodes_stats: list[dict] | None = None, tasks: list[dict] | None = None, episode_dicts: list[dict] | None = None, hf_dataset: datasets.Dataset | None = None, @@ -354,6 +383,8 @@ def lerobot_dataset_factory( ) if not stats: stats = stats_factory(features=info["features"]) + if not episodes_stats: + episodes_stats = episodes_stats_factory(features=info["features"], total_episodes=total_episodes) if not tasks: tasks = tasks_factory(total_tasks=info["total_tasks"]) if not episode_dicts: @@ -369,6 +400,7 @@ def lerobot_dataset_factory( mock_snapshot_download = mock_snapshot_download_factory( info=info, stats=stats, + episodes_stats=episodes_stats, tasks=tasks, episodes=episode_dicts, hf_dataset=hf_dataset, @@ -378,19 +410,26 @@ def lerobot_dataset_factory( repo_id=repo_id, info=info, stats=stats, + episodes_stats=episodes_stats, tasks=tasks, episodes=episode_dicts, - local_files_only=kwargs.get("local_files_only", False), ) with ( patch("lerobot.common.datasets.lerobot_dataset.LeRobotDatasetMetadata") as mock_metadata_patch, + patch("lerobot.common.datasets.lerobot_dataset.get_safe_version") as mock_get_safe_version_patch, patch( "lerobot.common.datasets.lerobot_dataset.snapshot_download" ) as mock_snapshot_download_patch, ): mock_metadata_patch.return_value = mock_metadata + mock_get_safe_version_patch.side_effect = lambda repo_id, version: version mock_snapshot_download_patch.side_effect = mock_snapshot_download return LeRobotDataset(repo_id=repo_id, root=root, **kwargs) return _create_lerobot_dataset + + +@pytest.fixture(scope="session") +def empty_lerobot_dataset_factory() -> LeRobotDatasetFactory: + return partial(LeRobotDataset.create, repo_id=DUMMY_REPO_ID, fps=DEFAULT_FPS) diff --git a/tests/fixtures/files.py b/tests/fixtures/files.py index 5fe8a314..4ef12e49 100644 --- a/tests/fixtures/files.py +++ b/tests/fixtures/files.py @@ -7,7 +7,13 @@ import pyarrow.compute as pc import pyarrow.parquet as pq import pytest -from lerobot.common.datasets.utils import EPISODES_PATH, INFO_PATH, STATS_PATH, TASKS_PATH +from lerobot.common.datasets.utils import ( + EPISODES_PATH, + EPISODES_STATS_PATH, + INFO_PATH, + STATS_PATH, + TASKS_PATH, +) @pytest.fixture(scope="session") @@ -38,6 +44,20 @@ def stats_path(stats_factory): return _create_stats_json_file +@pytest.fixture(scope="session") +def episodes_stats_path(episodes_stats_factory): + def _create_episodes_stats_jsonl_file(dir: Path, episodes_stats: list[dict] | None = None) -> Path: + if not episodes_stats: + episodes_stats = episodes_stats_factory() + fpath = dir / EPISODES_STATS_PATH + fpath.parent.mkdir(parents=True, exist_ok=True) + with jsonlines.open(fpath, "w") as writer: + writer.write_all(episodes_stats.values()) + return fpath + + return _create_episodes_stats_jsonl_file + + @pytest.fixture(scope="session") def tasks_path(tasks_factory): def _create_tasks_jsonl_file(dir: Path, tasks: list | None = None) -> Path: @@ -46,7 +66,7 @@ def tasks_path(tasks_factory): fpath = dir / TASKS_PATH fpath.parent.mkdir(parents=True, exist_ok=True) with jsonlines.open(fpath, "w") as writer: - writer.write_all(tasks) + writer.write_all(tasks.values()) return fpath return _create_tasks_jsonl_file @@ -60,7 +80,7 @@ def episode_path(episodes_factory): fpath = dir / EPISODES_PATH fpath.parent.mkdir(parents=True, exist_ok=True) with jsonlines.open(fpath, "w") as writer: - writer.write_all(episodes) + writer.write_all(episodes.values()) return fpath return _create_episodes_jsonl_file diff --git a/tests/fixtures/hub.py b/tests/fixtures/hub.py index 351768c0..ae309cb4 100644 --- a/tests/fixtures/hub.py +++ b/tests/fixtures/hub.py @@ -4,7 +4,13 @@ import datasets import pytest from huggingface_hub.utils import filter_repo_objects -from lerobot.common.datasets.utils import EPISODES_PATH, INFO_PATH, STATS_PATH, TASKS_PATH +from lerobot.common.datasets.utils import ( + EPISODES_PATH, + EPISODES_STATS_PATH, + INFO_PATH, + STATS_PATH, + TASKS_PATH, +) from tests.fixtures.constants import LEROBOT_TEST_DIR @@ -14,6 +20,8 @@ def mock_snapshot_download_factory( info_path, stats_factory, stats_path, + episodes_stats_factory, + episodes_stats_path, tasks_factory, tasks_path, episodes_factory, @@ -29,6 +37,7 @@ def mock_snapshot_download_factory( def _mock_snapshot_download_func( info: dict | None = None, stats: dict | None = None, + episodes_stats: list[dict] | None = None, tasks: list[dict] | None = None, episodes: list[dict] | None = None, hf_dataset: datasets.Dataset | None = None, @@ -37,6 +46,10 @@ def mock_snapshot_download_factory( info = info_factory() if not stats: stats = stats_factory(features=info["features"]) + if not episodes_stats: + episodes_stats = episodes_stats_factory( + features=info["features"], total_episodes=info["total_episodes"] + ) if not tasks: tasks = tasks_factory(total_tasks=info["total_tasks"]) if not episodes: @@ -67,11 +80,11 @@ def mock_snapshot_download_factory( # List all possible files all_files = [] - meta_files = [INFO_PATH, STATS_PATH, TASKS_PATH, EPISODES_PATH] + meta_files = [INFO_PATH, STATS_PATH, EPISODES_STATS_PATH, TASKS_PATH, EPISODES_PATH] all_files.extend(meta_files) data_files = [] - for episode_dict in episodes: + for episode_dict in episodes.values(): ep_idx = episode_dict["episode_index"] ep_chunk = ep_idx // info["chunks_size"] data_path = info["data_path"].format(episode_chunk=ep_chunk, episode_index=ep_idx) @@ -92,6 +105,8 @@ def mock_snapshot_download_factory( _ = info_path(local_dir, info) elif rel_path == STATS_PATH: _ = stats_path(local_dir, stats) + elif rel_path == EPISODES_STATS_PATH: + _ = episodes_stats_path(local_dir, episodes_stats) elif rel_path == TASKS_PATH: _ = tasks_path(local_dir, tasks) elif rel_path == EPISODES_PATH: diff --git a/tests/test_cameras.py b/tests/test_cameras.py index 1a1812f7..7c043c25 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -182,7 +182,7 @@ def test_camera(request, camera_type, mock): @pytest.mark.parametrize("camera_type, mock", TEST_CAMERA_TYPES) @require_camera -def test_save_images_from_cameras(tmpdir, request, camera_type, mock): +def test_save_images_from_cameras(tmp_path, request, camera_type, mock): # TODO(rcadene): refactor if camera_type == "opencv": from lerobot.common.robot_devices.cameras.opencv import save_images_from_cameras @@ -190,4 +190,4 @@ def test_save_images_from_cameras(tmpdir, request, camera_type, mock): from lerobot.common.robot_devices.cameras.intelrealsense import save_images_from_cameras # Small `record_time_s` to speedup unit tests - save_images_from_cameras(tmpdir, record_time_s=0.02, mock=mock) + save_images_from_cameras(tmp_path, record_time_s=0.02, mock=mock) diff --git a/tests/test_compute_stats.py b/tests/test_compute_stats.py new file mode 100644 index 00000000..d9032c8a --- /dev/null +++ b/tests/test_compute_stats.py @@ -0,0 +1,311 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. +from unittest.mock import patch + +import numpy as np +import pytest + +from lerobot.common.datasets.compute_stats import ( + _assert_type_and_shape, + aggregate_feature_stats, + aggregate_stats, + compute_episode_stats, + estimate_num_samples, + get_feature_stats, + sample_images, + sample_indices, +) + + +def mock_load_image_as_numpy(path, dtype, channel_first): + return np.ones((3, 32, 32), dtype=dtype) if channel_first else np.ones((32, 32, 3), dtype=dtype) + + +@pytest.fixture +def sample_array(): + return np.array([[1, 2, 3], [4, 5, 6], [7, 8, 9]]) + + +def test_estimate_num_samples(): + assert estimate_num_samples(1) == 1 + assert estimate_num_samples(10) == 10 + assert estimate_num_samples(100) == 100 + assert estimate_num_samples(200) == 100 + assert estimate_num_samples(1000) == 177 + assert estimate_num_samples(2000) == 299 + assert estimate_num_samples(5000) == 594 + assert estimate_num_samples(10_000) == 1000 + assert estimate_num_samples(20_000) == 1681 + assert estimate_num_samples(50_000) == 3343 + assert estimate_num_samples(500_000) == 10_000 + + +def test_sample_indices(): + indices = sample_indices(10) + assert len(indices) > 0 + assert indices[0] == 0 + assert indices[-1] == 9 + assert len(indices) == estimate_num_samples(10) + + +@patch("lerobot.common.datasets.compute_stats.load_image_as_numpy", side_effect=mock_load_image_as_numpy) +def test_sample_images(mock_load): + image_paths = [f"image_{i}.jpg" for i in range(100)] + images = sample_images(image_paths) + assert isinstance(images, np.ndarray) + assert images.shape[1:] == (3, 32, 32) + assert images.dtype == np.uint8 + assert len(images) == estimate_num_samples(100) + + +def test_get_feature_stats_images(): + data = np.random.rand(100, 3, 32, 32) + stats = get_feature_stats(data, axis=(0, 2, 3), keepdims=True) + assert "min" in stats and "max" in stats and "mean" in stats and "std" in stats and "count" in stats + np.testing.assert_equal(stats["count"], np.array([100])) + assert stats["min"].shape == stats["max"].shape == stats["mean"].shape == stats["std"].shape + + +def test_get_feature_stats_axis_0_keepdims(sample_array): + expected = { + "min": np.array([[1, 2, 3]]), + "max": np.array([[7, 8, 9]]), + "mean": np.array([[4.0, 5.0, 6.0]]), + "std": np.array([[2.44948974, 2.44948974, 2.44948974]]), + "count": np.array([3]), + } + result = get_feature_stats(sample_array, axis=(0,), keepdims=True) + for key in expected: + np.testing.assert_allclose(result[key], expected[key]) + + +def test_get_feature_stats_axis_1(sample_array): + expected = { + "min": np.array([1, 4, 7]), + "max": np.array([3, 6, 9]), + "mean": np.array([2.0, 5.0, 8.0]), + "std": np.array([0.81649658, 0.81649658, 0.81649658]), + "count": np.array([3]), + } + result = get_feature_stats(sample_array, axis=(1,), keepdims=False) + for key in expected: + np.testing.assert_allclose(result[key], expected[key]) + + +def test_get_feature_stats_no_axis(sample_array): + expected = { + "min": np.array(1), + "max": np.array(9), + "mean": np.array(5.0), + "std": np.array(2.5819889), + "count": np.array([3]), + } + result = get_feature_stats(sample_array, axis=None, keepdims=False) + for key in expected: + np.testing.assert_allclose(result[key], expected[key]) + + +def test_get_feature_stats_empty_array(): + array = np.array([]) + with pytest.raises(ValueError): + get_feature_stats(array, axis=(0,), keepdims=True) + + +def test_get_feature_stats_single_value(): + array = np.array([[1337]]) + result = get_feature_stats(array, axis=None, keepdims=True) + np.testing.assert_equal(result["min"], np.array(1337)) + np.testing.assert_equal(result["max"], np.array(1337)) + np.testing.assert_equal(result["mean"], np.array(1337.0)) + np.testing.assert_equal(result["std"], np.array(0.0)) + np.testing.assert_equal(result["count"], np.array([1])) + + +def test_compute_episode_stats(): + episode_data = { + "observation.image": [f"image_{i}.jpg" for i in range(100)], + "observation.state": np.random.rand(100, 10), + } + features = { + "observation.image": {"dtype": "image"}, + "observation.state": {"dtype": "numeric"}, + } + + with patch( + "lerobot.common.datasets.compute_stats.load_image_as_numpy", side_effect=mock_load_image_as_numpy + ): + stats = compute_episode_stats(episode_data, features) + + assert "observation.image" in stats and "observation.state" in stats + assert stats["observation.image"]["count"].item() == 100 + assert stats["observation.state"]["count"].item() == 100 + assert stats["observation.image"]["mean"].shape == (3, 1, 1) + + +def test_assert_type_and_shape_valid(): + valid_stats = [ + { + "feature1": { + "min": np.array([1.0]), + "max": np.array([10.0]), + "mean": np.array([5.0]), + "std": np.array([2.0]), + "count": np.array([1]), + } + } + ] + _assert_type_and_shape(valid_stats) + + +def test_assert_type_and_shape_invalid_type(): + invalid_stats = [ + { + "feature1": { + "min": [1.0], # Not a numpy array + "max": np.array([10.0]), + "mean": np.array([5.0]), + "std": np.array([2.0]), + "count": np.array([1]), + } + } + ] + with pytest.raises(ValueError, match="Stats must be composed of numpy array"): + _assert_type_and_shape(invalid_stats) + + +def test_assert_type_and_shape_invalid_shape(): + invalid_stats = [ + { + "feature1": { + "count": np.array([1, 2]), # Wrong shape + } + } + ] + with pytest.raises(ValueError, match=r"Shape of 'count' must be \(1\)"): + _assert_type_and_shape(invalid_stats) + + +def test_aggregate_feature_stats(): + stats_ft_list = [ + { + "min": np.array([1.0]), + "max": np.array([10.0]), + "mean": np.array([5.0]), + "std": np.array([2.0]), + "count": np.array([1]), + }, + { + "min": np.array([2.0]), + "max": np.array([12.0]), + "mean": np.array([6.0]), + "std": np.array([2.5]), + "count": np.array([1]), + }, + ] + result = aggregate_feature_stats(stats_ft_list) + np.testing.assert_allclose(result["min"], np.array([1.0])) + np.testing.assert_allclose(result["max"], np.array([12.0])) + np.testing.assert_allclose(result["mean"], np.array([5.5])) + np.testing.assert_allclose(result["std"], np.array([2.318405]), atol=1e-6) + np.testing.assert_allclose(result["count"], np.array([2])) + + +def test_aggregate_stats(): + all_stats = [ + { + "observation.image": { + "min": [1, 2, 3], + "max": [10, 20, 30], + "mean": [5.5, 10.5, 15.5], + "std": [2.87, 5.87, 8.87], + "count": 10, + }, + "observation.state": {"min": 1, "max": 10, "mean": 5.5, "std": 2.87, "count": 10}, + "extra_key_0": {"min": 5, "max": 25, "mean": 15, "std": 6, "count": 6}, + }, + { + "observation.image": { + "min": [2, 1, 0], + "max": [15, 10, 5], + "mean": [8.5, 5.5, 2.5], + "std": [3.42, 2.42, 1.42], + "count": 15, + }, + "observation.state": {"min": 2, "max": 15, "mean": 8.5, "std": 3.42, "count": 15}, + "extra_key_1": {"min": 0, "max": 20, "mean": 10, "std": 5, "count": 5}, + }, + ] + + expected_agg_stats = { + "observation.image": { + "min": [1, 1, 0], + "max": [15, 20, 30], + "mean": [7.3, 7.5, 7.7], + "std": [3.5317, 4.8267, 8.5581], + "count": 25, + }, + "observation.state": { + "min": 1, + "max": 15, + "mean": 7.3, + "std": 3.5317, + "count": 25, + }, + "extra_key_0": { + "min": 5, + "max": 25, + "mean": 15.0, + "std": 6.0, + "count": 6, + }, + "extra_key_1": { + "min": 0, + "max": 20, + "mean": 10.0, + "std": 5.0, + "count": 5, + }, + } + + # cast to numpy + for ep_stats in all_stats: + for fkey, stats in ep_stats.items(): + for k in stats: + stats[k] = np.array(stats[k], dtype=np.int64 if k == "count" else np.float32) + if fkey == "observation.image" and k != "count": + stats[k] = stats[k].reshape(3, 1, 1) # for normalization on image channels + else: + stats[k] = stats[k].reshape(1) + + # cast to numpy + for fkey, stats in expected_agg_stats.items(): + for k in stats: + stats[k] = np.array(stats[k], dtype=np.int64 if k == "count" else np.float32) + if fkey == "observation.image" and k != "count": + stats[k] = stats[k].reshape(3, 1, 1) # for normalization on image channels + else: + stats[k] = stats[k].reshape(1) + + results = aggregate_stats(all_stats) + + for fkey in expected_agg_stats: + np.testing.assert_allclose(results[fkey]["min"], expected_agg_stats[fkey]["min"]) + np.testing.assert_allclose(results[fkey]["max"], expected_agg_stats[fkey]["max"]) + np.testing.assert_allclose(results[fkey]["mean"], expected_agg_stats[fkey]["mean"]) + np.testing.assert_allclose( + results[fkey]["std"], expected_agg_stats[fkey]["std"], atol=1e-04, rtol=1e-04 + ) + np.testing.assert_allclose(results[fkey]["count"], expected_agg_stats[fkey]["count"]) diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 36ee096f..12b68641 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -24,7 +24,6 @@ pytest -sx 'tests/test_control_robot.py::test_teleoperate[aloha-True]' """ import multiprocessing -from pathlib import Path from unittest.mock import patch import pytest @@ -45,7 +44,7 @@ from tests.utils import DEVICE, TEST_ROBOT_TYPES, mock_calibration_dir, require_ @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_teleoperate(tmpdir, request, robot_type, mock): +def test_teleoperate(tmp_path, request, robot_type, mock): robot_kwargs = {"robot_type": robot_type, "mock": mock} if mock and robot_type != "aloha": @@ -53,8 +52,7 @@ def test_teleoperate(tmpdir, request, robot_type, mock): # Create an empty calibration directory to trigger manual calibration # and avoid writing calibration files in user .cache/calibration folder - tmpdir = Path(tmpdir) - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir else: @@ -70,15 +68,14 @@ def test_teleoperate(tmpdir, request, robot_type, mock): @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_calibrate(tmpdir, request, robot_type, mock): +def test_calibrate(tmp_path, request, robot_type, mock): robot_kwargs = {"robot_type": robot_type, "mock": mock} if mock: request.getfixturevalue("patch_builtins_input") # Create an empty calibration directory to trigger manual calibration - tmpdir = Path(tmpdir) - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type robot_kwargs["calibration_dir"] = calibration_dir robot = make_robot(**robot_kwargs) @@ -89,7 +86,7 @@ def test_calibrate(tmpdir, request, robot_type, mock): @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_record_without_cameras(tmpdir, request, robot_type, mock): +def test_record_without_cameras(tmp_path, request, robot_type, mock): robot_kwargs = {"robot_type": robot_type, "mock": mock} # Avoid using cameras @@ -100,7 +97,7 @@ def test_record_without_cameras(tmpdir, request, robot_type, mock): # Create an empty calibration directory to trigger manual calibration # and avoid writing calibration files in user .cache/calibration folder - calibration_dir = Path(tmpdir) / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir else: @@ -108,7 +105,7 @@ def test_record_without_cameras(tmpdir, request, robot_type, mock): pass repo_id = "lerobot/debug" - root = Path(tmpdir) / "data" / repo_id + root = tmp_path / "data" / repo_id single_task = "Do something." robot = make_robot(**robot_kwargs) @@ -121,7 +118,6 @@ def test_record_without_cameras(tmpdir, request, robot_type, mock): episode_time_s=1, reset_time_s=0.1, num_episodes=2, - run_compute_stats=False, push_to_hub=False, video=False, play_sounds=False, @@ -131,8 +127,7 @@ def test_record_without_cameras(tmpdir, request, robot_type, mock): @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): - tmpdir = Path(tmpdir) +def test_record_and_replay_and_policy(tmp_path, request, robot_type, mock): robot_kwargs = {"robot_type": robot_type, "mock": mock} if mock and robot_type != "aloha": @@ -140,7 +135,7 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): # Create an empty calibration directory to trigger manual calibration # and avoid writing calibration files in user .cache/calibration folder - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir else: @@ -148,7 +143,7 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): pass repo_id = "lerobot_test/debug" - root = tmpdir / "data" / repo_id + root = tmp_path / "data" / repo_id single_task = "Do something." robot = make_robot(**robot_kwargs) @@ -172,15 +167,13 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): assert dataset.meta.total_episodes == 2 assert len(dataset) == 2 - replay_cfg = ReplayControlConfig( - episode=0, fps=1, root=root, repo_id=repo_id, play_sounds=False, local_files_only=True - ) + replay_cfg = ReplayControlConfig(episode=0, fps=1, root=root, repo_id=repo_id, play_sounds=False) replay(robot, replay_cfg) policy_cfg = ACTConfig() policy = make_policy(policy_cfg, ds_meta=dataset.meta, device=DEVICE) - out_dir = tmpdir / "logger" + out_dir = tmp_path / "logger" pretrained_policy_path = out_dir / "checkpoints/last/pretrained_model" policy.save_pretrained(pretrained_policy_path) @@ -207,7 +200,7 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): num_image_writer_processes = 0 eval_repo_id = "lerobot/eval_debug" - eval_root = tmpdir / "data" / eval_repo_id + eval_root = tmp_path / "data" / eval_repo_id rec_eval_cfg = RecordControlConfig( repo_id=eval_repo_id, @@ -218,7 +211,6 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): episode_time_s=1, reset_time_s=0.1, num_episodes=2, - run_compute_stats=False, push_to_hub=False, video=False, display_cameras=False, @@ -240,7 +232,7 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): @pytest.mark.parametrize("robot_type, mock", [("koch", True)]) @require_robot -def test_resume_record(tmpdir, request, robot_type, mock): +def test_resume_record(tmp_path, request, robot_type, mock): robot_kwargs = {"robot_type": robot_type, "mock": mock} if mock and robot_type != "aloha": @@ -248,7 +240,7 @@ def test_resume_record(tmpdir, request, robot_type, mock): # Create an empty calibration directory to trigger manual calibration # and avoid writing calibration files in user .cache/calibration folder - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir else: @@ -258,7 +250,7 @@ def test_resume_record(tmpdir, request, robot_type, mock): robot = make_robot(**robot_kwargs) repo_id = "lerobot/debug" - root = Path(tmpdir) / "data" / repo_id + root = tmp_path / "data" / repo_id single_task = "Do something." rec_cfg = RecordControlConfig( @@ -272,8 +264,6 @@ def test_resume_record(tmpdir, request, robot_type, mock): video=False, display_cameras=False, play_sounds=False, - run_compute_stats=False, - local_files_only=True, num_episodes=1, ) @@ -291,7 +281,7 @@ def test_resume_record(tmpdir, request, robot_type, mock): @pytest.mark.parametrize("robot_type, mock", [("koch", True)]) @require_robot -def test_record_with_event_rerecord_episode(tmpdir, request, robot_type, mock): +def test_record_with_event_rerecord_episode(tmp_path, request, robot_type, mock): robot_kwargs = {"robot_type": robot_type, "mock": mock} if mock and robot_type != "aloha": @@ -299,7 +289,7 @@ def test_record_with_event_rerecord_episode(tmpdir, request, robot_type, mock): # Create an empty calibration directory to trigger manual calibration # and avoid writing calibration files in user .cache/calibration folder - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir else: @@ -316,7 +306,7 @@ def test_record_with_event_rerecord_episode(tmpdir, request, robot_type, mock): mock_listener.return_value = (None, mock_events) repo_id = "lerobot/debug" - root = Path(tmpdir) / "data" / repo_id + root = tmp_path / "data" / repo_id single_task = "Do something." rec_cfg = RecordControlConfig( @@ -331,7 +321,6 @@ def test_record_with_event_rerecord_episode(tmpdir, request, robot_type, mock): video=False, display_cameras=False, play_sounds=False, - run_compute_stats=False, ) dataset = record(robot, rec_cfg) @@ -342,7 +331,7 @@ def test_record_with_event_rerecord_episode(tmpdir, request, robot_type, mock): @pytest.mark.parametrize("robot_type, mock", [("koch", True)]) @require_robot -def test_record_with_event_exit_early(tmpdir, request, robot_type, mock): +def test_record_with_event_exit_early(tmp_path, request, robot_type, mock): robot_kwargs = {"robot_type": robot_type, "mock": mock} if mock: @@ -350,7 +339,7 @@ def test_record_with_event_exit_early(tmpdir, request, robot_type, mock): # Create an empty calibration directory to trigger manual calibration # and avoid writing calibration files in user .cache/calibration folder - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir else: @@ -367,7 +356,7 @@ def test_record_with_event_exit_early(tmpdir, request, robot_type, mock): mock_listener.return_value = (None, mock_events) repo_id = "lerobot/debug" - root = Path(tmpdir) / "data" / repo_id + root = tmp_path / "data" / repo_id single_task = "Do something." rec_cfg = RecordControlConfig( @@ -382,7 +371,6 @@ def test_record_with_event_exit_early(tmpdir, request, robot_type, mock): video=False, display_cameras=False, play_sounds=False, - run_compute_stats=False, ) dataset = record(robot, rec_cfg) @@ -395,7 +383,7 @@ def test_record_with_event_exit_early(tmpdir, request, robot_type, mock): "robot_type, mock, num_image_writer_processes", [("koch", True, 0), ("koch", True, 1)] ) @require_robot -def test_record_with_event_stop_recording(tmpdir, request, robot_type, mock, num_image_writer_processes): +def test_record_with_event_stop_recording(tmp_path, request, robot_type, mock, num_image_writer_processes): robot_kwargs = {"robot_type": robot_type, "mock": mock} if mock: @@ -403,7 +391,7 @@ def test_record_with_event_stop_recording(tmpdir, request, robot_type, mock, num # Create an empty calibration directory to trigger manual calibration # and avoid writing calibration files in user .cache/calibration folder - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir else: @@ -420,7 +408,7 @@ def test_record_with_event_stop_recording(tmpdir, request, robot_type, mock, num mock_listener.return_value = (None, mock_events) repo_id = "lerobot/debug" - root = Path(tmpdir) / "data" / repo_id + root = tmp_path / "data" / repo_id single_task = "Do something." rec_cfg = RecordControlConfig( @@ -436,7 +424,6 @@ def test_record_with_event_stop_recording(tmpdir, request, robot_type, mock, num video=False, display_cameras=False, play_sounds=False, - run_compute_stats=False, num_image_writer_processes=num_image_writer_processes, ) diff --git a/tests/test_datasets.py b/tests/test_datasets.py index 8664d33e..61b68aa8 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -15,24 +15,21 @@ # limitations under the License. import json import logging +import re from copy import deepcopy from itertools import chain from pathlib import Path -import einops +import numpy as np import pytest import torch -from datasets import Dataset from huggingface_hub import HfApi +from PIL import Image from safetensors.torch import load_file import lerobot -from lerobot.common.datasets.compute_stats import ( - aggregate_stats, - compute_stats, - get_stats_einops_patterns, -) from lerobot.common.datasets.factory import make_dataset +from lerobot.common.datasets.image_writer import image_array_to_pil_image from lerobot.common.datasets.lerobot_dataset import ( LeRobotDataset, MultiLeRobotDataset, @@ -40,20 +37,34 @@ from lerobot.common.datasets.lerobot_dataset import ( from lerobot.common.datasets.utils import ( create_branch, flatten_dict, - hf_transform_to_torch, unflatten_dict, ) from lerobot.common.envs.factory import make_env_config from lerobot.common.policies.factory import make_policy_config from lerobot.common.robot_devices.robots.utils import make_robot -from lerobot.common.utils.random_utils import seeded_context from lerobot.configs.default import DatasetConfig from lerobot.configs.train import TrainPipelineConfig -from tests.fixtures.constants import DUMMY_REPO_ID +from tests.fixtures.constants import DUMMY_CHW, DUMMY_HWC, DUMMY_REPO_ID from tests.utils import DEVICE, require_x86_64_kernel -def test_same_attributes_defined(lerobot_dataset_factory, tmp_path): +@pytest.fixture +def image_dataset(tmp_path, empty_lerobot_dataset_factory): + features = { + "image": { + "dtype": "image", + "shape": DUMMY_CHW, + "names": [ + "channels", + "height", + "width", + ], + } + } + return empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + + +def test_same_attributes_defined(tmp_path, lerobot_dataset_factory): """ Instantiate a LeRobotDataset both ways with '__init__()' and 'create()' and verify that instantiated objects have the same sets of attributes defined. @@ -66,24 +77,20 @@ def test_same_attributes_defined(lerobot_dataset_factory, tmp_path): root_init = tmp_path / "init" dataset_init = lerobot_dataset_factory(root=root_init) - # Access the '_hub_version' cached_property in both instances to force its creation - _ = dataset_init.meta._hub_version - _ = dataset_create.meta._hub_version - init_attr = set(vars(dataset_init).keys()) create_attr = set(vars(dataset_create).keys()) assert init_attr == create_attr -def test_dataset_initialization(lerobot_dataset_factory, tmp_path): +def test_dataset_initialization(tmp_path, lerobot_dataset_factory): kwargs = { "repo_id": DUMMY_REPO_ID, "total_episodes": 10, "total_frames": 400, "episodes": [2, 5, 6], } - dataset = lerobot_dataset_factory(root=tmp_path, **kwargs) + dataset = lerobot_dataset_factory(root=tmp_path / "test", **kwargs) assert dataset.repo_id == kwargs["repo_id"] assert dataset.meta.total_episodes == kwargs["total_episodes"] @@ -93,12 +100,232 @@ def test_dataset_initialization(lerobot_dataset_factory, tmp_path): assert dataset.num_frames == len(dataset) +def test_add_frame_missing_task(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, match="Feature mismatch in `frame` dictionary:\nMissing features: {'task'}\n" + ): + dataset.add_frame({"state": torch.randn(1)}) + + +def test_add_frame_missing_feature(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, match="Feature mismatch in `frame` dictionary:\nMissing features: {'state'}\n" + ): + dataset.add_frame({"task": "Dummy task"}) + + +def test_add_frame_extra_feature(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, match="Feature mismatch in `frame` dictionary:\nExtra features: {'extra'}\n" + ): + dataset.add_frame({"state": torch.randn(1), "task": "Dummy task", "extra": "dummy_extra"}) + + +def test_add_frame_wrong_type(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, match="The feature 'state' of dtype 'float16' is not of the expected dtype 'float32'.\n" + ): + dataset.add_frame({"state": torch.randn(1, dtype=torch.float16), "task": "Dummy task"}) + + +def test_add_frame_wrong_shape(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (2,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, + match=re.escape("The feature 'state' of shape '(1,)' does not have the expected shape '(2,)'.\n"), + ): + dataset.add_frame({"state": torch.randn(1), "task": "Dummy task"}) + + +def test_add_frame_wrong_shape_python_float(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, + match=re.escape( + "The feature 'state' is not a 'np.ndarray'. Expected type is 'float32', but type '' provided instead.\n" + ), + ): + dataset.add_frame({"state": 1.0, "task": "Dummy task"}) + + +def test_add_frame_wrong_shape_torch_ndim_0(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, + match=re.escape("The feature 'state' of shape '()' does not have the expected shape '(1,)'.\n"), + ): + dataset.add_frame({"state": torch.tensor(1.0), "task": "Dummy task"}) + + +def test_add_frame_wrong_shape_numpy_ndim_0(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + with pytest.raises( + ValueError, + match=re.escape( + "The feature 'state' is not a 'np.ndarray'. Expected type is 'float32', but type '' provided instead.\n" + ), + ): + dataset.add_frame({"state": np.float32(1.0), "task": "Dummy task"}) + + +def test_add_frame(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"state": torch.randn(1), "task": "Dummy task"}) + dataset.save_episode() + + assert len(dataset) == 1 + assert dataset[0]["task"] == "Dummy task" + assert dataset[0]["task_index"] == 0 + assert dataset[0]["state"].ndim == 0 + + +def test_add_frame_state_1d(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (2,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"state": torch.randn(2), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["state"].shape == torch.Size([2]) + + +def test_add_frame_state_2d(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (2, 4), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"state": torch.randn(2, 4), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["state"].shape == torch.Size([2, 4]) + + +def test_add_frame_state_3d(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (2, 4, 3), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"state": torch.randn(2, 4, 3), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["state"].shape == torch.Size([2, 4, 3]) + + +def test_add_frame_state_4d(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (2, 4, 3, 5), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"state": torch.randn(2, 4, 3, 5), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["state"].shape == torch.Size([2, 4, 3, 5]) + + +def test_add_frame_state_5d(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (2, 4, 3, 5, 1), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"state": torch.randn(2, 4, 3, 5, 1), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["state"].shape == torch.Size([2, 4, 3, 5, 1]) + + +def test_add_frame_state_numpy(tmp_path, empty_lerobot_dataset_factory): + features = {"state": {"dtype": "float32", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"state": np.array([1], dtype=np.float32), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["state"].ndim == 0 + + +def test_add_frame_string(tmp_path, empty_lerobot_dataset_factory): + features = {"caption": {"dtype": "string", "shape": (1,), "names": None}} + dataset = empty_lerobot_dataset_factory(root=tmp_path / "test", features=features) + dataset.add_frame({"caption": "Dummy caption", "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["caption"] == "Dummy caption" + + +def test_add_frame_image_wrong_shape(image_dataset): + dataset = image_dataset + with pytest.raises( + ValueError, + match=re.escape( + "The feature 'image' of shape '(3, 128, 96)' does not have the expected shape '(3, 96, 128)' or '(96, 128, 3)'.\n" + ), + ): + c, h, w = DUMMY_CHW + dataset.add_frame({"image": torch.randn(c, w, h), "task": "Dummy task"}) + + +def test_add_frame_image_wrong_range(image_dataset): + """This test will display the following error message from a thread: + ``` + Error writing image ...test_add_frame_image_wrong_ran0/test/images/image/episode_000000/frame_000000.png: + The image data type is float, which requires values in the range [0.0, 1.0]. However, the provided range is [0.009678772038470007, 254.9776492089887]. + Please adjust the range or provide a uint8 image with values in the range [0, 255] + ``` + Hence the image won't be saved on disk and save_episode will raise `FileNotFoundError`. + """ + dataset = image_dataset + dataset.add_frame({"image": np.random.rand(*DUMMY_CHW) * 255, "task": "Dummy task"}) + with pytest.raises(FileNotFoundError): + dataset.save_episode() + + +def test_add_frame_image(image_dataset): + dataset = image_dataset + dataset.add_frame({"image": np.random.rand(*DUMMY_CHW), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["image"].shape == torch.Size(DUMMY_CHW) + + +def test_add_frame_image_h_w_c(image_dataset): + dataset = image_dataset + dataset.add_frame({"image": np.random.rand(*DUMMY_HWC), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["image"].shape == torch.Size(DUMMY_CHW) + + +def test_add_frame_image_uint8(image_dataset): + dataset = image_dataset + image = np.random.randint(0, 256, DUMMY_HWC, dtype=np.uint8) + dataset.add_frame({"image": image, "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["image"].shape == torch.Size(DUMMY_CHW) + + +def test_add_frame_image_pil(image_dataset): + dataset = image_dataset + image = np.random.randint(0, 256, DUMMY_HWC, dtype=np.uint8) + dataset.add_frame({"image": Image.fromarray(image), "task": "Dummy task"}) + dataset.save_episode() + + assert dataset[0]["image"].shape == torch.Size(DUMMY_CHW) + + +def test_image_array_to_pil_image_wrong_range_float_0_255(): + image = np.random.rand(*DUMMY_HWC) * 255 + with pytest.raises(ValueError): + image_array_to_pil_image(image) + + # TODO(aliberts): # - [ ] test various attributes & state from init and create # - [ ] test init with episodes and check num_frames -# - [ ] test add_frame # - [ ] test add_episode -# - [ ] test consolidate # - [ ] test push_to_hub # - [ ] test smaller methods @@ -210,67 +437,6 @@ def test_multidataset_frames(): assert torch.equal(sub_dataset_item[k], dataset_item[k]) -# TODO(aliberts, rcadene): Refactor and move this to a tests/test_compute_stats.py -def test_compute_stats_on_xarm(): - """Check that the statistics are computed correctly according to the stats_patterns property. - - We compare with taking a straight min, mean, max, std of all the data in one pass (which we can do - because we are working with a small dataset). - """ - # TODO(rcadene, aliberts): remove dataset download - dataset = LeRobotDataset("lerobot/xarm_lift_medium", episodes=[0]) - - # reduce size of dataset sample on which stats compute is tested to 10 frames - dataset.hf_dataset = dataset.hf_dataset.select(range(10)) - - # Note: we set the batch size to be smaller than the whole dataset to make sure we are testing batched - # computation of the statistics. While doing this, we also make sure it works when we don't divide the - # dataset into even batches. - computed_stats = compute_stats(dataset, batch_size=int(len(dataset) * 0.25), num_workers=0) - - # get einops patterns to aggregate batches and compute statistics - stats_patterns = get_stats_einops_patterns(dataset) - - # get all frames from the dataset in the same dtype and range as during compute_stats - dataloader = torch.utils.data.DataLoader( - dataset, - num_workers=0, - batch_size=len(dataset), - shuffle=False, - ) - full_batch = next(iter(dataloader)) - - # compute stats based on all frames from the dataset without any batching - expected_stats = {} - for k, pattern in stats_patterns.items(): - full_batch[k] = full_batch[k].float() - expected_stats[k] = {} - expected_stats[k]["mean"] = einops.reduce(full_batch[k], pattern, "mean") - expected_stats[k]["std"] = torch.sqrt( - einops.reduce((full_batch[k] - expected_stats[k]["mean"]) ** 2, pattern, "mean") - ) - expected_stats[k]["min"] = einops.reduce(full_batch[k], pattern, "min") - expected_stats[k]["max"] = einops.reduce(full_batch[k], pattern, "max") - - # test computed stats match expected stats - for k in stats_patterns: - assert torch.allclose(computed_stats[k]["mean"], expected_stats[k]["mean"]) - assert torch.allclose(computed_stats[k]["std"], expected_stats[k]["std"]) - assert torch.allclose(computed_stats[k]["min"], expected_stats[k]["min"]) - assert torch.allclose(computed_stats[k]["max"], expected_stats[k]["max"]) - - # load stats used during training which are expected to match the ones returned by computed_stats - loaded_stats = dataset.meta.stats # noqa: F841 - - # TODO(rcadene): we can't test this because expected_stats is computed on a subset - # # test loaded stats match expected stats - # for k in stats_patterns: - # assert torch.allclose(loaded_stats[k]["mean"], expected_stats[k]["mean"]) - # assert torch.allclose(loaded_stats[k]["std"], expected_stats[k]["std"]) - # assert torch.allclose(loaded_stats[k]["min"], expected_stats[k]["min"]) - # assert torch.allclose(loaded_stats[k]["max"], expected_stats[k]["max"]) - - # TODO(aliberts): Move to more appropriate location def test_flatten_unflatten_dict(): d = { @@ -374,35 +540,6 @@ def test_backward_compatibility(repo_id): # load_and_compare(i - 1) -@pytest.mark.skip("TODO after fix multidataset") -def test_multidataset_aggregate_stats(): - """Makes 3 basic datasets and checks that aggregate stats are computed correctly.""" - with seeded_context(0): - data_a = torch.rand(30, dtype=torch.float32) - data_b = torch.rand(20, dtype=torch.float32) - data_c = torch.rand(20, dtype=torch.float32) - - hf_dataset_1 = Dataset.from_dict( - {"a": data_a[:10], "b": data_b[:10], "c": data_c[:10], "index": torch.arange(10)} - ) - hf_dataset_1.set_transform(hf_transform_to_torch) - hf_dataset_2 = Dataset.from_dict({"a": data_a[10:20], "b": data_b[10:], "index": torch.arange(10)}) - hf_dataset_2.set_transform(hf_transform_to_torch) - hf_dataset_3 = Dataset.from_dict({"a": data_a[20:], "c": data_c[10:], "index": torch.arange(10)}) - hf_dataset_3.set_transform(hf_transform_to_torch) - dataset_1 = LeRobotDataset.from_preloaded("d1", hf_dataset=hf_dataset_1) - dataset_1.stats = compute_stats(dataset_1, batch_size=len(hf_dataset_1), num_workers=0) - dataset_2 = LeRobotDataset.from_preloaded("d2", hf_dataset=hf_dataset_2) - dataset_2.stats = compute_stats(dataset_2, batch_size=len(hf_dataset_2), num_workers=0) - dataset_3 = LeRobotDataset.from_preloaded("d3", hf_dataset=hf_dataset_3) - dataset_3.stats = compute_stats(dataset_3, batch_size=len(hf_dataset_3), num_workers=0) - stats = aggregate_stats([dataset_1, dataset_2, dataset_3]) - for data_key, data in zip(["a", "b", "c"], [data_a, data_b, data_c], strict=True): - for agg_fn in ["mean", "min", "max"]: - assert torch.allclose(stats[data_key][agg_fn], einops.reduce(data, "n -> 1", agg_fn)) - assert torch.allclose(stats[data_key]["std"], torch.std(data, correction=0)) - - @pytest.mark.skip("Requires internet access") def test_create_branch(): api = HfApi() @@ -431,9 +568,9 @@ def test_create_branch(): def test_dataset_feature_with_forward_slash_raises_error(): # make sure dir does not exist - from lerobot.common.datasets.lerobot_dataset import LEROBOT_HOME + from lerobot.common.constants import HF_LEROBOT_HOME - dataset_dir = LEROBOT_HOME / "lerobot/test/with/slash" + dataset_dir = HF_LEROBOT_HOME / "lerobot/test/with/slash" # make sure does not exist if dataset_dir.exists(): dataset_dir.rmdir() diff --git a/tests/test_delta_timestamps.py b/tests/test_delta_timestamps.py index 3516583d..3e3b83ac 100644 --- a/tests/test_delta_timestamps.py +++ b/tests/test_delta_timestamps.py @@ -1,55 +1,78 @@ +from itertools import accumulate + +import datasets +import numpy as np +import pyarrow.compute as pc import pytest import torch -from datasets import Dataset from lerobot.common.datasets.utils import ( - calculate_episode_data_index, check_delta_timestamps, check_timestamps_sync, get_delta_indices, - hf_transform_to_torch, ) from tests.fixtures.constants import DUMMY_MOTOR_FEATURES -@pytest.fixture(scope="module") -def synced_hf_dataset_factory(hf_dataset_factory): - def _create_synced_hf_dataset(fps: int = 30) -> Dataset: - return hf_dataset_factory(fps=fps) +def calculate_total_episode( + hf_dataset: datasets.Dataset, raise_if_not_contiguous: bool = True +) -> dict[str, torch.Tensor]: + episode_indices = sorted(hf_dataset.unique("episode_index")) + total_episodes = len(episode_indices) + if raise_if_not_contiguous and episode_indices != list(range(total_episodes)): + raise ValueError("episode_index values are not sorted and contiguous.") + return total_episodes - return _create_synced_hf_dataset + +def calculate_episode_data_index(hf_dataset: datasets.Dataset) -> dict[str, np.ndarray]: + episode_lengths = [] + table = hf_dataset.data.table + total_episodes = calculate_total_episode(hf_dataset) + for ep_idx in range(total_episodes): + ep_table = table.filter(pc.equal(table["episode_index"], ep_idx)) + episode_lengths.insert(ep_idx, len(ep_table)) + + cumulative_lenghts = list(accumulate(episode_lengths)) + return { + "from": np.array([0] + cumulative_lenghts[:-1], dtype=np.int64), + "to": np.array(cumulative_lenghts, dtype=np.int64), + } @pytest.fixture(scope="module") -def unsynced_hf_dataset_factory(synced_hf_dataset_factory): - def _create_unsynced_hf_dataset(fps: int = 30, tolerance_s: float = 1e-4) -> Dataset: - hf_dataset = synced_hf_dataset_factory(fps=fps) - features = hf_dataset.features - df = hf_dataset.to_pandas() - dtype = df["timestamp"].dtype # This is to avoid pandas type warning - # Modify a single timestamp just outside tolerance - df.at[30, "timestamp"] = dtype.type(df.at[30, "timestamp"] + (tolerance_s * 1.1)) - unsynced_hf_dataset = Dataset.from_pandas(df, features=features) - unsynced_hf_dataset.set_transform(hf_transform_to_torch) - return unsynced_hf_dataset +def synced_timestamps_factory(hf_dataset_factory): + def _create_synced_timestamps(fps: int = 30) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + hf_dataset = hf_dataset_factory(fps=fps) + timestamps = torch.stack(hf_dataset["timestamp"]).numpy() + episode_indices = torch.stack(hf_dataset["episode_index"]).numpy() + episode_data_index = calculate_episode_data_index(hf_dataset) + return timestamps, episode_indices, episode_data_index - return _create_unsynced_hf_dataset + return _create_synced_timestamps @pytest.fixture(scope="module") -def slightly_off_hf_dataset_factory(synced_hf_dataset_factory): - def _create_slightly_off_hf_dataset(fps: int = 30, tolerance_s: float = 1e-4) -> Dataset: - hf_dataset = synced_hf_dataset_factory(fps=fps) - features = hf_dataset.features - df = hf_dataset.to_pandas() - dtype = df["timestamp"].dtype # This is to avoid pandas type warning - # Modify a single timestamp just inside tolerance - df.at[30, "timestamp"] = dtype.type(df.at[30, "timestamp"] + (tolerance_s * 0.9)) - unsynced_hf_dataset = Dataset.from_pandas(df, features=features) - unsynced_hf_dataset.set_transform(hf_transform_to_torch) - return unsynced_hf_dataset +def unsynced_timestamps_factory(synced_timestamps_factory): + def _create_unsynced_timestamps( + fps: int = 30, tolerance_s: float = 1e-4 + ) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + timestamps, episode_indices, episode_data_index = synced_timestamps_factory(fps=fps) + timestamps[30] += tolerance_s * 1.1 # Modify a single timestamp just outside tolerance + return timestamps, episode_indices, episode_data_index - return _create_slightly_off_hf_dataset + return _create_unsynced_timestamps + + +@pytest.fixture(scope="module") +def slightly_off_timestamps_factory(synced_timestamps_factory): + def _create_slightly_off_timestamps( + fps: int = 30, tolerance_s: float = 1e-4 + ) -> tuple[np.ndarray, np.ndarray, np.ndarray]: + timestamps, episode_indices, episode_data_index = synced_timestamps_factory(fps=fps) + timestamps[30] += tolerance_s * 0.9 # Modify a single timestamp just inside tolerance + return timestamps, episode_indices, episode_data_index + + return _create_slightly_off_timestamps @pytest.fixture(scope="module") @@ -100,42 +123,42 @@ def delta_indices_factory(): return _delta_indices -def test_check_timestamps_sync_synced(synced_hf_dataset_factory): +def test_check_timestamps_sync_synced(synced_timestamps_factory): fps = 30 tolerance_s = 1e-4 - synced_hf_dataset = synced_hf_dataset_factory(fps) - episode_data_index = calculate_episode_data_index(synced_hf_dataset) + timestamps, ep_idx, ep_data_index = synced_timestamps_factory(fps) result = check_timestamps_sync( - hf_dataset=synced_hf_dataset, - episode_data_index=episode_data_index, + timestamps=timestamps, + episode_indices=ep_idx, + episode_data_index=ep_data_index, fps=fps, tolerance_s=tolerance_s, ) assert result is True -def test_check_timestamps_sync_unsynced(unsynced_hf_dataset_factory): +def test_check_timestamps_sync_unsynced(unsynced_timestamps_factory): fps = 30 tolerance_s = 1e-4 - unsynced_hf_dataset = unsynced_hf_dataset_factory(fps, tolerance_s) - episode_data_index = calculate_episode_data_index(unsynced_hf_dataset) + timestamps, ep_idx, ep_data_index = unsynced_timestamps_factory(fps, tolerance_s) with pytest.raises(ValueError): check_timestamps_sync( - hf_dataset=unsynced_hf_dataset, - episode_data_index=episode_data_index, + timestamps=timestamps, + episode_indices=ep_idx, + episode_data_index=ep_data_index, fps=fps, tolerance_s=tolerance_s, ) -def test_check_timestamps_sync_unsynced_no_exception(unsynced_hf_dataset_factory): +def test_check_timestamps_sync_unsynced_no_exception(unsynced_timestamps_factory): fps = 30 tolerance_s = 1e-4 - unsynced_hf_dataset = unsynced_hf_dataset_factory(fps, tolerance_s) - episode_data_index = calculate_episode_data_index(unsynced_hf_dataset) + timestamps, ep_idx, ep_data_index = unsynced_timestamps_factory(fps, tolerance_s) result = check_timestamps_sync( - hf_dataset=unsynced_hf_dataset, - episode_data_index=episode_data_index, + timestamps=timestamps, + episode_indices=ep_idx, + episode_data_index=ep_data_index, fps=fps, tolerance_s=tolerance_s, raise_value_error=False, @@ -143,14 +166,14 @@ def test_check_timestamps_sync_unsynced_no_exception(unsynced_hf_dataset_factory assert result is False -def test_check_timestamps_sync_slightly_off(slightly_off_hf_dataset_factory): +def test_check_timestamps_sync_slightly_off(slightly_off_timestamps_factory): fps = 30 tolerance_s = 1e-4 - slightly_off_hf_dataset = slightly_off_hf_dataset_factory(fps, tolerance_s) - episode_data_index = calculate_episode_data_index(slightly_off_hf_dataset) + timestamps, ep_idx, ep_data_index = slightly_off_timestamps_factory(fps, tolerance_s) result = check_timestamps_sync( - hf_dataset=slightly_off_hf_dataset, - episode_data_index=episode_data_index, + timestamps=timestamps, + episode_indices=ep_idx, + episode_data_index=ep_data_index, fps=fps, tolerance_s=tolerance_s, ) @@ -158,33 +181,13 @@ def test_check_timestamps_sync_slightly_off(slightly_off_hf_dataset_factory): def test_check_timestamps_sync_single_timestamp(): - single_timestamp_hf_dataset = Dataset.from_dict({"timestamp": [0.0], "episode_index": [0]}) - single_timestamp_hf_dataset.set_transform(hf_transform_to_torch) - episode_data_index = {"to": torch.tensor([1]), "from": torch.tensor([0])} fps = 30 tolerance_s = 1e-4 + timestamps, ep_idx = np.array([0.0]), np.array([0]) + episode_data_index = {"to": np.array([1]), "from": np.array([0])} result = check_timestamps_sync( - hf_dataset=single_timestamp_hf_dataset, - episode_data_index=episode_data_index, - fps=fps, - tolerance_s=tolerance_s, - ) - assert result is True - - -# TODO(aliberts): Change behavior of hf_transform_to_torch so that it can work with empty dataset -@pytest.mark.skip("TODO: fix") -def test_check_timestamps_sync_empty_dataset(): - fps = 30 - tolerance_s = 1e-4 - empty_hf_dataset = Dataset.from_dict({"timestamp": [], "episode_index": []}) - empty_hf_dataset.set_transform(hf_transform_to_torch) - episode_data_index = { - "to": torch.tensor([], dtype=torch.int64), - "from": torch.tensor([], dtype=torch.int64), - } - result = check_timestamps_sync( - hf_dataset=empty_hf_dataset, + timestamps=timestamps, + episode_indices=ep_idx, episode_data_index=episode_data_index, fps=fps, tolerance_s=tolerance_s, diff --git a/tests/test_examples.py b/tests/test_examples.py index f3b7948c..aabec69a 100644 --- a/tests/test_examples.py +++ b/tests/test_examples.py @@ -53,7 +53,7 @@ def test_example_1(tmp_path, lerobot_dataset_factory): ('repo_id = "lerobot/pusht"', f'repo_id = "{DUMMY_REPO_ID}"'), ( "LeRobotDataset(repo_id", - f"LeRobotDataset(repo_id, root='{str(tmp_path)}', local_files_only=True", + f"LeRobotDataset(repo_id, root='{str(tmp_path)}'", ), ], ) diff --git a/tests/test_image_writer.py b/tests/test_image_writer.py index f51e86b4..c7fc11f2 100644 --- a/tests/test_image_writer.py +++ b/tests/test_image_writer.py @@ -9,10 +9,11 @@ from PIL import Image from lerobot.common.datasets.image_writer import ( AsyncImageWriter, - image_array_to_image, + image_array_to_pil_image, safe_stop_image_writer, write_image, ) +from tests.fixtures.constants import DUMMY_HWC DUMMY_IMAGE = "test_image.png" @@ -48,49 +49,62 @@ def test_zero_threads(): AsyncImageWriter(num_processes=0, num_threads=0) -def test_image_array_to_image_rgb(img_array_factory): +def test_image_array_to_pil_image_float_array_wrong_range_0_255(): + image = np.random.rand(*DUMMY_HWC) * 255 + with pytest.raises(ValueError): + image_array_to_pil_image(image) + + +def test_image_array_to_pil_image_float_array_wrong_range_neg_1_1(): + image = np.random.rand(*DUMMY_HWC) * 2 - 1 + with pytest.raises(ValueError): + image_array_to_pil_image(image) + + +def test_image_array_to_pil_image_rgb(img_array_factory): img_array = img_array_factory(100, 100) - result_image = image_array_to_image(img_array) + result_image = image_array_to_pil_image(img_array) assert isinstance(result_image, Image.Image) assert result_image.size == (100, 100) assert result_image.mode == "RGB" -def test_image_array_to_image_pytorch_format(img_array_factory): +def test_image_array_to_pil_image_pytorch_format(img_array_factory): img_array = img_array_factory(100, 100).transpose(2, 0, 1) - result_image = image_array_to_image(img_array) + result_image = image_array_to_pil_image(img_array) assert isinstance(result_image, Image.Image) assert result_image.size == (100, 100) assert result_image.mode == "RGB" -@pytest.mark.skip("TODO: implement") -def test_image_array_to_image_single_channel(img_array_factory): +def test_image_array_to_pil_image_single_channel(img_array_factory): img_array = img_array_factory(channels=1) - result_image = image_array_to_image(img_array) - assert isinstance(result_image, Image.Image) - assert result_image.size == (100, 100) - assert result_image.mode == "L" + with pytest.raises(NotImplementedError): + image_array_to_pil_image(img_array) -def test_image_array_to_image_float_array(img_array_factory): +def test_image_array_to_pil_image_4_channels(img_array_factory): + img_array = img_array_factory(channels=4) + with pytest.raises(NotImplementedError): + image_array_to_pil_image(img_array) + + +def test_image_array_to_pil_image_float_array(img_array_factory): img_array = img_array_factory(dtype=np.float32) - result_image = image_array_to_image(img_array) + result_image = image_array_to_pil_image(img_array) assert isinstance(result_image, Image.Image) assert result_image.size == (100, 100) assert result_image.mode == "RGB" assert np.array(result_image).dtype == np.uint8 -def test_image_array_to_image_out_of_bounds_float(): - # Float array with values out of [0, 1] - img_array = np.random.uniform(-1, 2, size=(100, 100, 3)).astype(np.float32) - result_image = image_array_to_image(img_array) +def test_image_array_to_pil_image_uint8_array(img_array_factory): + img_array = img_array_factory(dtype=np.float32) + result_image = image_array_to_pil_image(img_array) assert isinstance(result_image, Image.Image) assert result_image.size == (100, 100) assert result_image.mode == "RGB" assert np.array(result_image).dtype == np.uint8 - assert np.array(result_image).min() >= 0 and np.array(result_image).max() <= 255 def test_write_image_numpy(tmp_path, img_array_factory): diff --git a/tests/test_push_dataset_to_hub.py b/tests/test_push_dataset_to_hub.py deleted file mode 100644 index a0c8d908..00000000 --- a/tests/test_push_dataset_to_hub.py +++ /dev/null @@ -1,370 +0,0 @@ -""" -This file contains generic tests to ensure that nothing breaks if we modify the push_dataset_to_hub API. -Also, this file contains backward compatibility tests. Because they are slow and require to download the raw datasets, -we skip them for now in our CI. - -Example to run backward compatiblity tests locally: -``` -python -m pytest --run-skipped tests/test_push_dataset_to_hub.py::test_push_dataset_to_hub_pusht_backward_compatibility -``` -""" - -from pathlib import Path - -import numpy as np -import pytest -import torch - -from lerobot.common.datasets.lerobot_dataset import LeRobotDataset -from lerobot.common.datasets.push_dataset_to_hub.utils import save_images_concurrently -from lerobot.common.datasets.video_utils import encode_video_frames -from lerobot.scripts.push_dataset_to_hub import push_dataset_to_hub -from tests.utils import require_package_arg - - -def _mock_download_raw_pusht(raw_dir, num_frames=4, num_episodes=3): - import zarr - - raw_dir.mkdir(parents=True, exist_ok=True) - zarr_path = raw_dir / "pusht_cchi_v7_replay.zarr" - store = zarr.DirectoryStore(zarr_path) - zarr_data = zarr.group(store=store) - - zarr_data.create_dataset( - "data/action", shape=(num_frames, 1), chunks=(num_frames, 1), dtype=np.float32, overwrite=True - ) - zarr_data.create_dataset( - "data/img", - shape=(num_frames, 96, 96, 3), - chunks=(num_frames, 96, 96, 3), - dtype=np.uint8, - overwrite=True, - ) - zarr_data.create_dataset( - "data/n_contacts", shape=(num_frames, 2), chunks=(num_frames, 2), dtype=np.float32, overwrite=True - ) - zarr_data.create_dataset( - "data/state", shape=(num_frames, 5), chunks=(num_frames, 5), dtype=np.float32, overwrite=True - ) - zarr_data.create_dataset( - "data/keypoint", shape=(num_frames, 9, 2), chunks=(num_frames, 9, 2), dtype=np.float32, overwrite=True - ) - zarr_data.create_dataset( - "meta/episode_ends", shape=(num_episodes,), chunks=(num_episodes,), dtype=np.int32, overwrite=True - ) - - zarr_data["data/action"][:] = np.random.randn(num_frames, 1) - zarr_data["data/img"][:] = np.random.randint(0, 255, size=(num_frames, 96, 96, 3), dtype=np.uint8) - zarr_data["data/n_contacts"][:] = np.random.randn(num_frames, 2) - zarr_data["data/state"][:] = np.random.randn(num_frames, 5) - zarr_data["data/keypoint"][:] = np.random.randn(num_frames, 9, 2) - zarr_data["meta/episode_ends"][:] = np.array([1, 3, 4]) - - store.close() - - -def _mock_download_raw_umi(raw_dir, num_frames=4, num_episodes=3): - import zarr - - raw_dir.mkdir(parents=True, exist_ok=True) - zarr_path = raw_dir / "cup_in_the_wild.zarr" - store = zarr.DirectoryStore(zarr_path) - zarr_data = zarr.group(store=store) - - zarr_data.create_dataset( - "data/camera0_rgb", - shape=(num_frames, 96, 96, 3), - chunks=(num_frames, 96, 96, 3), - dtype=np.uint8, - overwrite=True, - ) - zarr_data.create_dataset( - "data/robot0_demo_end_pose", - shape=(num_frames, 5), - chunks=(num_frames, 5), - dtype=np.float32, - overwrite=True, - ) - zarr_data.create_dataset( - "data/robot0_demo_start_pose", - shape=(num_frames, 5), - chunks=(num_frames, 5), - dtype=np.float32, - overwrite=True, - ) - zarr_data.create_dataset( - "data/robot0_eef_pos", shape=(num_frames, 5), chunks=(num_frames, 5), dtype=np.float32, overwrite=True - ) - zarr_data.create_dataset( - "data/robot0_eef_rot_axis_angle", - shape=(num_frames, 5), - chunks=(num_frames, 5), - dtype=np.float32, - overwrite=True, - ) - zarr_data.create_dataset( - "data/robot0_gripper_width", - shape=(num_frames, 5), - chunks=(num_frames, 5), - dtype=np.float32, - overwrite=True, - ) - zarr_data.create_dataset( - "meta/episode_ends", shape=(num_episodes,), chunks=(num_episodes,), dtype=np.int32, overwrite=True - ) - - zarr_data["data/camera0_rgb"][:] = np.random.randint(0, 255, size=(num_frames, 96, 96, 3), dtype=np.uint8) - zarr_data["data/robot0_demo_end_pose"][:] = np.random.randn(num_frames, 5) - zarr_data["data/robot0_demo_start_pose"][:] = np.random.randn(num_frames, 5) - zarr_data["data/robot0_eef_pos"][:] = np.random.randn(num_frames, 5) - zarr_data["data/robot0_eef_rot_axis_angle"][:] = np.random.randn(num_frames, 5) - zarr_data["data/robot0_gripper_width"][:] = np.random.randn(num_frames, 5) - zarr_data["meta/episode_ends"][:] = np.array([1, 3, 4]) - - store.close() - - -def _mock_download_raw_xarm(raw_dir, num_frames=4): - import pickle - - dataset_dict = { - "observations": { - "rgb": np.random.randint(0, 255, size=(num_frames, 3, 84, 84), dtype=np.uint8), - "state": np.random.randn(num_frames, 4), - }, - "actions": np.random.randn(num_frames, 3), - "rewards": np.random.randn(num_frames), - "masks": np.random.randn(num_frames), - "dones": np.array([False, True, True, True]), - } - - raw_dir.mkdir(parents=True, exist_ok=True) - pkl_path = raw_dir / "buffer.pkl" - with open(pkl_path, "wb") as f: - pickle.dump(dataset_dict, f) - - -def _mock_download_raw_aloha(raw_dir, num_frames=6, num_episodes=3): - import h5py - - for ep_idx in range(num_episodes): - raw_dir.mkdir(parents=True, exist_ok=True) - path_h5 = raw_dir / f"episode_{ep_idx}.hdf5" - with h5py.File(str(path_h5), "w") as f: - f.create_dataset("action", data=np.random.randn(num_frames // num_episodes, 14)) - f.create_dataset("observations/qpos", data=np.random.randn(num_frames // num_episodes, 14)) - f.create_dataset("observations/qvel", data=np.random.randn(num_frames // num_episodes, 14)) - f.create_dataset( - "observations/images/top", - data=np.random.randint( - 0, 255, size=(num_frames // num_episodes, 480, 640, 3), dtype=np.uint8 - ), - ) - - -def _mock_download_raw_dora(raw_dir, num_frames=6, num_episodes=3, fps=30): - from datetime import datetime, timedelta, timezone - - import pandas - - def write_parquet(key, timestamps, values): - data = { - "timestamp_utc": timestamps, - key: values, - } - df = pandas.DataFrame(data) - raw_dir.mkdir(parents=True, exist_ok=True) - df.to_parquet(raw_dir / f"{key}.parquet", engine="pyarrow") - - episode_indices = [None, None, -1, None, None, -1, None, None, -1] - episode_indices_mapping = [0, 0, 0, 1, 1, 1, 2, 2, 2] - frame_indices = [0, 1, -1, 0, 1, -1, 0, 1, -1] - - cam_key = "observation.images.cam_high" - timestamps = [] - actions = [] - states = [] - frames = [] - # `+ num_episodes`` for buffer frames associated to episode_index=-1 - for i, frame_idx in enumerate(frame_indices): - t_utc = datetime.now(timezone.utc) + timedelta(seconds=i / fps) - action = np.random.randn(21).tolist() - state = np.random.randn(21).tolist() - ep_idx = episode_indices_mapping[i] - frame = [{"path": f"videos/{cam_key}_episode_{ep_idx:06d}.mp4", "timestamp": frame_idx / fps}] - timestamps.append(t_utc) - actions.append(action) - states.append(state) - frames.append(frame) - - write_parquet(cam_key, timestamps, frames) - write_parquet("observation.state", timestamps, states) - write_parquet("action", timestamps, actions) - write_parquet("episode_index", timestamps, episode_indices) - - # write fake mp4 file for each episode - for ep_idx in range(num_episodes): - imgs_array = np.random.randint(0, 255, size=(num_frames // num_episodes, 480, 640, 3), dtype=np.uint8) - - tmp_imgs_dir = raw_dir / "tmp_images" - save_images_concurrently(imgs_array, tmp_imgs_dir) - - fname = f"{cam_key}_episode_{ep_idx:06d}.mp4" - video_path = raw_dir / "videos" / fname - encode_video_frames(tmp_imgs_dir, video_path, fps, vcodec="libx264") - - -def _mock_download_raw(raw_dir, repo_id): - if "wrist_gripper" in repo_id: - _mock_download_raw_dora(raw_dir) - elif "aloha" in repo_id: - _mock_download_raw_aloha(raw_dir) - elif "pusht" in repo_id: - _mock_download_raw_pusht(raw_dir) - elif "xarm" in repo_id: - _mock_download_raw_xarm(raw_dir) - elif "umi" in repo_id: - _mock_download_raw_umi(raw_dir) - else: - raise ValueError(repo_id) - - -@pytest.mark.skip("push_dataset_to_hub is deprecated") -def test_push_dataset_to_hub_invalid_repo_id(tmpdir): - with pytest.raises(ValueError): - push_dataset_to_hub(Path(tmpdir), "raw_format", "invalid_repo_id") - - -@pytest.mark.skip("push_dataset_to_hub is deprecated") -def test_push_dataset_to_hub_out_dir_force_override_false(tmpdir): - tmpdir = Path(tmpdir) - out_dir = tmpdir / "out" - raw_dir = tmpdir / "raw" - # mkdir to skip download - raw_dir.mkdir(parents=True, exist_ok=True) - with pytest.raises(ValueError): - push_dataset_to_hub( - raw_dir=raw_dir, - raw_format="some_format", - repo_id="user/dataset", - local_dir=out_dir, - force_override=False, - ) - - -@pytest.mark.skip("push_dataset_to_hub is deprecated") -@pytest.mark.parametrize( - "required_packages, raw_format, repo_id, make_test_data", - [ - (["gym_pusht"], "pusht_zarr", "lerobot/pusht", False), - (["gym_pusht"], "pusht_zarr", "lerobot/pusht", True), - (None, "xarm_pkl", "lerobot/xarm_lift_medium", False), - (None, "aloha_hdf5", "lerobot/aloha_sim_insertion_scripted", False), - (["imagecodecs"], "umi_zarr", "lerobot/umi_cup_in_the_wild", False), - (None, "dora_parquet", "cadene/wrist_gripper", False), - ], -) -@require_package_arg -def test_push_dataset_to_hub_format(required_packages, tmpdir, raw_format, repo_id, make_test_data): - num_episodes = 3 - tmpdir = Path(tmpdir) - - raw_dir = tmpdir / f"{repo_id}_raw" - _mock_download_raw(raw_dir, repo_id) - - local_dir = tmpdir / repo_id - - lerobot_dataset = push_dataset_to_hub( - raw_dir=raw_dir, - raw_format=raw_format, - repo_id=repo_id, - push_to_hub=False, - local_dir=local_dir, - force_override=False, - cache_dir=tmpdir / "cache", - tests_data_dir=tmpdir / "tests/data" if make_test_data else None, - encoding={"vcodec": "libx264"}, - ) - - # minimal generic tests on the local directory containing LeRobotDataset - assert (local_dir / "meta_data" / "info.json").exists() - assert (local_dir / "meta_data" / "stats.safetensors").exists() - assert (local_dir / "meta_data" / "episode_data_index.safetensors").exists() - for i in range(num_episodes): - for cam_key in lerobot_dataset.camera_keys: - assert (local_dir / "videos" / f"{cam_key}_episode_{i:06d}.mp4").exists() - assert (local_dir / "train" / "dataset_info.json").exists() - assert (local_dir / "train" / "state.json").exists() - assert len(list((local_dir / "train").glob("*.arrow"))) > 0 - - # minimal generic tests on the item - item = lerobot_dataset[0] - assert "index" in item - assert "episode_index" in item - assert "timestamp" in item - for cam_key in lerobot_dataset.camera_keys: - assert cam_key in item - - if make_test_data: - # Check that only the first episode is selected. - test_dataset = LeRobotDataset(repo_id=repo_id, root=tmpdir / "tests/data") - num_frames = sum( - i == lerobot_dataset.hf_dataset["episode_index"][0] - for i in lerobot_dataset.hf_dataset["episode_index"] - ).item() - assert ( - test_dataset.hf_dataset["episode_index"] - == lerobot_dataset.hf_dataset["episode_index"][:num_frames] - ) - for k in ["from", "to"]: - assert torch.equal(test_dataset.episode_data_index[k], lerobot_dataset.episode_data_index[k][:1]) - - -@pytest.mark.skip("push_dataset_to_hub is deprecated") -@pytest.mark.parametrize( - "raw_format, repo_id", - [ - # TODO(rcadene): add raw dataset test artifacts - ("pusht_zarr", "lerobot/pusht"), - ("xarm_pkl", "lerobot/xarm_lift_medium"), - ("aloha_hdf5", "lerobot/aloha_sim_insertion_scripted"), - ("umi_zarr", "lerobot/umi_cup_in_the_wild"), - ("dora_parquet", "cadene/wrist_gripper"), - ], -) -def test_push_dataset_to_hub_pusht_backward_compatibility(tmpdir, raw_format, repo_id): - _, dataset_id = repo_id.split("/") - - tmpdir = Path(tmpdir) - raw_dir = tmpdir / f"{dataset_id}_raw" - local_dir = tmpdir / repo_id - - push_dataset_to_hub( - raw_dir=raw_dir, - raw_format=raw_format, - repo_id=repo_id, - push_to_hub=False, - local_dir=local_dir, - force_override=False, - cache_dir=tmpdir / "cache", - episodes=[0], - ) - - ds_actual = LeRobotDataset(repo_id, root=tmpdir) - ds_reference = LeRobotDataset(repo_id) - - assert len(ds_reference.hf_dataset) == len(ds_actual.hf_dataset) - - def check_same_items(item1, item2): - assert item1.keys() == item2.keys(), "Keys mismatch" - - for key in item1: - if isinstance(item1[key], torch.Tensor) and isinstance(item2[key], torch.Tensor): - assert torch.equal(item1[key], item2[key]), f"Mismatch found in key: {key}" - else: - assert item1[key] == item2[key], f"Mismatch found in key: {key}" - - for i in range(len(ds_reference.hf_dataset)): - item_reference = ds_reference.hf_dataset[i] - item_actual = ds_actual.hf_dataset[i] - check_same_items(item_reference, item_actual) diff --git a/tests/test_robots.py b/tests/test_robots.py index e03b5f78..6c300b71 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -23,8 +23,6 @@ pytest -sx 'tests/test_robots.py::test_robot[aloha-True]' ``` """ -from pathlib import Path - import pytest import torch @@ -35,7 +33,7 @@ from tests.utils import TEST_ROBOT_TYPES, mock_calibration_dir, require_robot @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_robot(tmpdir, request, robot_type, mock): +def test_robot(tmp_path, request, robot_type, mock): # TODO(rcadene): measure fps in nightly? # TODO(rcadene): test logs # TODO(rcadene): add compatibility with other robots @@ -50,8 +48,7 @@ def test_robot(tmpdir, request, robot_type, mock): request.getfixturevalue("patch_builtins_input") # Create an empty calibration directory to trigger manual calibration - tmpdir = Path(tmpdir) - calibration_dir = tmpdir / robot_type + calibration_dir = tmp_path / robot_type mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir From eecf32e77a73c3e4ad243021719a41adaa3b0f82 Mon Sep 17 00:00:00 2001 From: Haskely Date: Wed, 26 Feb 2025 00:27:36 +0800 Subject: [PATCH 02/69] feat: Add root directory option for dataset configuration (#765) Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- lerobot/common/datasets/factory.py | 5 ++++- lerobot/configs/default.py | 2 ++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/lerobot/common/datasets/factory.py b/lerobot/common/datasets/factory.py index fb1fe6d6..38c01b42 100644 --- a/lerobot/common/datasets/factory.py +++ b/lerobot/common/datasets/factory.py @@ -83,10 +83,13 @@ def make_dataset(cfg: TrainPipelineConfig) -> LeRobotDataset | MultiLeRobotDatas ) if isinstance(cfg.dataset.repo_id, str): - ds_meta = LeRobotDatasetMetadata(cfg.dataset.repo_id, revision=cfg.dataset.revision) + ds_meta = LeRobotDatasetMetadata( + cfg.dataset.repo_id, root=cfg.dataset.root, revision=cfg.dataset.revision + ) delta_timestamps = resolve_delta_timestamps(cfg.policy, ds_meta) dataset = LeRobotDataset( cfg.dataset.repo_id, + root=cfg.dataset.root, episodes=cfg.dataset.episodes, delta_timestamps=delta_timestamps, image_transforms=image_transforms, diff --git a/lerobot/configs/default.py b/lerobot/configs/default.py index a5013431..0dc7f4c7 100644 --- a/lerobot/configs/default.py +++ b/lerobot/configs/default.py @@ -29,6 +29,8 @@ class DatasetConfig: # "dataset_index" into the returned item. The index mapping is made according to the order in which the # datsets are provided. repo_id: str + # Root directory where the dataset will be stored (e.g. 'dataset/path'). + root: str | None = None episodes: list[int] | None = None image_transforms: ImageTransformsConfig = field(default_factory=ImageTransformsConfig) revision: str | None = None From e64fad2224ba01e21ed698b1a07a8ead81252177 Mon Sep 17 00:00:00 2001 From: Yongjin Cho Date: Wed, 26 Feb 2025 02:33:32 +0900 Subject: [PATCH 03/69] Fix the URL to setup hardware Aloha Stationary in the example document (#766) --- examples/9_use_aloha.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md index d74c8b7a..5d2843fa 100644 --- a/examples/9_use_aloha.md +++ b/examples/9_use_aloha.md @@ -2,7 +2,7 @@ This tutorial explains how to use [Aloha and Aloha 2 stationary](https://www.tro ## Setup -Follow the [documentation from Trossen Robotics](https://docs.trossenrobotics.com/aloha_docs/getting_started/stationary/hardware_setup.html) for setting up the hardware and plugging the 4 arms and 4 cameras to your computer. +Follow the [documentation from Trossen Robotics](https://docs.trossenrobotics.com/aloha_docs/2.0/getting_started/stationary/hardware_setup.html) for setting up the hardware and plugging the 4 arms and 4 cameras to your computer. ## Install LeRobot From 75d5fa4604bb2e812a869a2d4f3dc805e56faec6 Mon Sep 17 00:00:00 2001 From: Youssef Bayouli <75679079+YoussefBayouli@users.noreply.github.com> Date: Tue, 25 Feb 2025 18:42:35 +0100 Subject: [PATCH 04/69] Optimizing Dockerfile (#751) --- docker/lerobot-gpu/Dockerfile | 34 ++++++++++++++-------------------- 1 file changed, 14 insertions(+), 20 deletions(-) diff --git a/docker/lerobot-gpu/Dockerfile b/docker/lerobot-gpu/Dockerfile index 65ca4377..b2898b97 100644 --- a/docker/lerobot-gpu/Dockerfile +++ b/docker/lerobot-gpu/Dockerfile @@ -1,31 +1,25 @@ FROM nvidia/cuda:12.4.1-base-ubuntu22.04 -# Configure image +# Configure environment variables ARG PYTHON_VERSION=3.10 -ARG DEBIAN_FRONTEND=noninteractive +ENV DEBIAN_FRONTEND=noninteractive +ENV MUJOCO_GL="egl" +ENV PATH="/opt/venv/bin:$PATH" - -# Install apt dependencies +# Install dependencies and set up Python in a single layer RUN apt-get update && apt-get install -y --no-install-recommends \ build-essential cmake git git-lfs \ libglib2.0-0 libgl1-mesa-glx libegl1-mesa ffmpeg \ speech-dispatcher libgeos-dev \ python${PYTHON_VERSION}-dev python${PYTHON_VERSION}-venv \ - && apt-get clean && rm -rf /var/lib/apt/lists/* + && ln -s /usr/bin/python${PYTHON_VERSION} /usr/bin/python \ + && python -m venv /opt/venv \ + && apt-get clean && rm -rf /var/lib/apt/lists/* \ + && echo "source /opt/venv/bin/activate" >> /root/.bashrc - -# Create virtual environment -RUN ln -s /usr/bin/python${PYTHON_VERSION} /usr/bin/python -RUN python -m venv /opt/venv -ENV PATH="/opt/venv/bin:$PATH" -RUN echo "source /opt/venv/bin/activate" >> /root/.bashrc - -# Install LeRobot -RUN git lfs install -RUN git clone https://github.com/huggingface/lerobot.git /lerobot +# Clone repository and install LeRobot in a single layer WORKDIR /lerobot -RUN pip install --upgrade --no-cache-dir pip -RUN pip install --no-cache-dir ".[test, aloha, xarm, pusht, dynamixel]" - -# Set EGL as the rendering backend for MuJoCo -ENV MUJOCO_GL="egl" +RUN git lfs install \ + && git clone https://github.com/huggingface/lerobot.git . \ + && /opt/venv/bin/pip install --upgrade --no-cache-dir pip \ + && /opt/venv/bin/pip install --no-cache-dir ".[test, aloha, xarm, pusht, dynamixel]" From 65db5afe1c4664ce27503fc982d65ee83b23db66 Mon Sep 17 00:00:00 2001 From: Raul Garreta Date: Tue, 25 Feb 2025 10:03:29 -0800 Subject: [PATCH 05/69] fixes in 7_get_started_with_real_robot.md (#677) --- examples/7_get_started_with_real_robot.md | 20 +++++++++++--------- 1 file changed, 11 insertions(+), 9 deletions(-) diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index 638b54d3..be22d4a5 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -626,7 +626,7 @@ Finally, run this code to instantiate and connectyour camera: from lerobot.common.robot_devices.cameras.configs import OpenCVCameraConfig from lerobot.common.robot_devices.cameras.opencv import OpenCVCamera -camera_config = OpenCVCameraConfig(camera_index=0) +config = OpenCVCameraConfig(camera_index=0) camera = OpenCVCamera(config) camera.connect() color_image = camera.read() @@ -668,13 +668,15 @@ Additionaly, you can set up your robot to work with your cameras. Modify the following Python code with the appropriate camera names and configurations: ```python robot = ManipulatorRobot( - leader_arms={"main": leader_arm}, - follower_arms={"main": follower_arm}, - calibration_dir=".cache/calibration/koch", - cameras={ - "laptop": OpenCVCameraConfig(0, fps=30, width=640, height=480), - "phone": OpenCVCameraConfig(1, fps=30, width=640, height=480), - }, + KochRobotConfig( + leader_arms={"main": leader_arm}, + follower_arms={"main": follower_arm}, + calibration_dir=".cache/calibration/koch", + cameras={ + "laptop": OpenCVCameraConfig(0, fps=30, width=640, height=480), + "phone": OpenCVCameraConfig(1, fps=30, width=640, height=480), + }, + ) ) robot.connect() ``` @@ -711,7 +713,7 @@ python lerobot/scripts/control_robot.py \ You will see a lot of lines appearing like this one: ``` -INFO 2024-08-10 11:15:03 ol_robot.py:209 dt: 5.12 (195.1hz) dtRlead: 4.93 (203.0hz) dtRfoll: 0.19 (5239.0hz) +INFO 2024-08-10 11:15:03 ol_robot.py:209 dt: 5.12 (195.1hz) dtRlead: 4.93 (203.0hz) dtWfoll: 0.19 (5239.0hz) ``` It contains From 8699a28be0c0db33120c35ce85c9c72f5783f2a1 Mon Sep 17 00:00:00 2001 From: Jannik Grothusen <56967823+J4nn1K@users.noreply.github.com> Date: Tue, 25 Feb 2025 19:28:26 +0100 Subject: [PATCH 06/69] [QOL] Enable teleoperation during environment reset (#725) --- lerobot/common/robot_devices/control_utils.py | 23 +++++++------------ lerobot/scripts/control_robot.py | 2 +- 2 files changed, 9 insertions(+), 16 deletions(-) diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/robot_devices/control_utils.py index 6c97d0cb..d2361a64 100644 --- a/lerobot/common/robot_devices/control_utils.py +++ b/lerobot/common/robot_devices/control_utils.py @@ -12,7 +12,6 @@ from functools import cache import cv2 import torch -import tqdm from deepdiff import DeepDiff from termcolor import colored @@ -276,24 +275,18 @@ def control_loop( break -def reset_environment(robot, events, reset_time_s): +def reset_environment(robot, events, reset_time_s, fps): # TODO(rcadene): refactor warmup_record and reset_environment - # TODO(alibets): allow for teleop during reset if has_method(robot, "teleop_safety_stop"): robot.teleop_safety_stop() - timestamp = 0 - start_vencod_t = time.perf_counter() - - # Wait if necessary - with tqdm.tqdm(total=reset_time_s, desc="Waiting") as pbar: - while timestamp < reset_time_s: - time.sleep(1) - timestamp = time.perf_counter() - start_vencod_t - pbar.update(1) - if events["exit_early"]: - events["exit_early"] = False - break + control_loop( + robot=robot, + control_time_s=reset_time_s, + events=events, + fps=fps, + teleoperate=True, + ) def stop_recording(robot, listener, display_cameras): diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 32f3b181..ab5d0e8a 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -299,7 +299,7 @@ def record( (recorded_episodes < cfg.num_episodes - 1) or events["rerecord_episode"] ): log_say("Reset the environment", cfg.play_sounds) - reset_environment(robot, events, cfg.reset_time_s) + reset_environment(robot, events, cfg.reset_time_s, cfg.fps) if events["rerecord_episode"]: log_say("Re-record episode", cfg.play_sounds) From a1809ad3de96c6989acd33c0650849bf4f631929 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Tue, 25 Feb 2025 23:51:15 +0100 Subject: [PATCH 07/69] Add typos checks (#770) --- .github/workflows/quality.yml | 12 ++++++++++++ .pre-commit-config.yaml | 5 +++++ CONTRIBUTING.md | 2 +- benchmarks/video/README.md | 2 +- examples/11_use_lekiwi.md | 4 ++-- examples/11_use_moss.md | 2 +- examples/7_get_started_with_real_robot.md | 10 +++++----- examples/8_use_stretch.md | 2 +- examples/9_use_aloha.md | 4 ++-- lerobot/common/datasets/compute_stats.py | 2 +- lerobot/common/datasets/lerobot_dataset.py | 6 +++--- .../datasets/push_dataset_to_hub/_download_raw.py | 2 +- .../push_dataset_to_hub/dora_parquet_format.py | 8 ++++---- .../push_dataset_to_hub/openx_rlds_format.py | 2 +- lerobot/common/datasets/utils.py | 8 ++++---- .../datasets/v2/batch_convert_dataset_v1_to_v2.py | 2 ++ .../common/datasets/v2/convert_dataset_v1_to_v2.py | 2 +- lerobot/common/datasets/video_utils.py | 2 +- lerobot/common/envs/factory.py | 4 ++-- lerobot/common/policies/act/configuration_act.py | 2 +- .../policies/diffusion/configuration_diffusion.py | 4 ++-- .../conversion_scripts/convert_pi0_to_hf_lerobot.py | 2 +- .../common/policies/tdmpc/configuration_tdmpc.py | 4 ++-- .../common/policies/vqbet/configuration_vqbet.py | 2 +- lerobot/common/policies/vqbet/modeling_vqbet.py | 4 ++-- lerobot/common/policies/vqbet/vqbet_utils.py | 10 +++++----- lerobot/common/robot_devices/control_configs.py | 2 +- lerobot/common/robot_devices/motors/dynamixel.py | 4 ++-- lerobot/common/robot_devices/motors/feetech.py | 6 +++--- .../robot_devices/robots/dynamixel_calibration.py | 4 ++-- .../robot_devices/robots/feetech_calibration.py | 2 +- lerobot/common/robot_devices/robots/manipulator.py | 12 ++++++------ lerobot/common/robot_devices/robots/stretch.py | 4 ++-- lerobot/configs/default.py | 2 +- lerobot/configs/train.py | 2 +- lerobot/scripts/control_sim_robot.py | 8 ++++---- lerobot/scripts/push_dataset_to_hub.py | 2 +- lerobot/scripts/train.py | 2 +- lerobot/scripts/visualize_dataset_html.py | 2 +- pyproject.toml | 13 +++++++++++++ tests/mock_cv2.py | 6 +++--- tests/test_cameras.py | 2 +- tests/test_control_robot.py | 2 +- tests/test_datasets.py | 2 +- tests/test_delta_timestamps.py | 6 +++--- tests/test_motors.py | 2 +- tests/test_robots.py | 2 +- 47 files changed, 114 insertions(+), 82 deletions(-) diff --git a/.github/workflows/quality.yml b/.github/workflows/quality.yml index b42539e6..4cf8e0df 100644 --- a/.github/workflows/quality.yml +++ b/.github/workflows/quality.yml @@ -42,3 +42,15 @@ jobs: - name: Ruff format run: ruff format --diff + + typos: + name: Typos + runs-on: ubuntu-latest + steps: + - name: Checkout Repository + uses: actions/checkout@v4 + with: + persist-credentials: false + + - name: typos-action + uses: crate-ci/typos@v1.29.10 diff --git a/.pre-commit-config.yaml b/.pre-commit-config.yaml index 00b538e8..b921f4e1 100644 --- a/.pre-commit-config.yaml +++ b/.pre-commit-config.yaml @@ -13,6 +13,11 @@ repos: - id: check-toml - id: end-of-file-fixer - id: trailing-whitespace + - repo: https://github.com/crate-ci/typos + rev: v1.29.10 + hooks: + - id: typos + args: [--force-exclude] - repo: https://github.com/asottile/pyupgrade rev: v3.19.1 hooks: diff --git a/CONTRIBUTING.md b/CONTRIBUTING.md index 61fa2eb9..8aff26d8 100644 --- a/CONTRIBUTING.md +++ b/CONTRIBUTING.md @@ -228,7 +228,7 @@ Follow these steps to start contributing: git commit ``` - Note, if you already commited some changes that have a wrong formatting, you can use: + Note, if you already committed some changes that have a wrong formatting, you can use: ```bash pre-commit run --all-files ``` diff --git a/benchmarks/video/README.md b/benchmarks/video/README.md index 56cd1d1e..49e49811 100644 --- a/benchmarks/video/README.md +++ b/benchmarks/video/README.md @@ -114,7 +114,7 @@ We tried to measure the most impactful parameters for both encoding and decoding Additional encoding parameters exist that are not included in this benchmark. In particular: - `-preset` which allows for selecting encoding presets. This represents a collection of options that will provide a certain encoding speed to compression ratio. By leaving this parameter unspecified, it is considered to be `medium` for libx264 and libx265 and `8` for libsvtav1. -- `-tune` which allows to optimize the encoding for certains aspects (e.g. film quality, fast decoding, etc.). +- `-tune` which allows to optimize the encoding for certain aspects (e.g. film quality, fast decoding, etc.). See the documentation mentioned above for more detailed info on these settings and for a more comprehensive list of other parameters. diff --git a/examples/11_use_lekiwi.md b/examples/11_use_lekiwi.md index a7024cc6..224a1854 100644 --- a/examples/11_use_lekiwi.md +++ b/examples/11_use_lekiwi.md @@ -185,7 +185,7 @@ sudo chmod 666 /dev/ttyACM1 #### d. Update config file -IMPORTANTLY: Now that you have your ports of leader and follower arm and ip adress of the mobile-so100, update the **ip** in Network configuration, **port** in leader_arms and **port** in lekiwi. In the [`LeKiwiRobotConfig`](../lerobot/common/robot_devices/robots/configs.py) file. Where you will find something like: +IMPORTANTLY: Now that you have your ports of leader and follower arm and ip address of the mobile-so100, update the **ip** in Network configuration, **port** in leader_arms and **port** in lekiwi. In the [`LeKiwiRobotConfig`](../lerobot/common/robot_devices/robots/configs.py) file. Where you will find something like: ```python @RobotConfig.register_subclass("lekiwi") @dataclass @@ -324,7 +324,7 @@ You should see on your laptop something like this: ```[INFO] Connected to remote | F | Decrease speed | > [!TIP] -> If you use a different keyboard you can change the keys for each commmand in the [`LeKiwiRobotConfig`](../lerobot/common/robot_devices/robots/configs.py). +> If you use a different keyboard you can change the keys for each command in the [`LeKiwiRobotConfig`](../lerobot/common/robot_devices/robots/configs.py). ## Troubleshoot communication diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md index 2bbfbb18..67f8157e 100644 --- a/examples/11_use_moss.md +++ b/examples/11_use_moss.md @@ -2,7 +2,7 @@ This tutorial explains how to use [Moss v1](https://github.com/jess-moss/moss-ro ## Source the parts -Follow this [README](https://github.com/jess-moss/moss-robot-arms). It contains the bill of materials, with link to source the parts, as well as the instructions to 3D print the parts, and advices if it's your first time printing or if you don't own a 3D printer already. +Follow this [README](https://github.com/jess-moss/moss-robot-arms). It contains the bill of materials with link to source the parts, as well as the instructions to 3D print the parts and advice if it's your first time printing or if you don't own a 3D printer already. **Important**: Before assembling, you will first need to configure your motors. To this end, we provide a nice script, so let's first install LeRobot. After configuration, we will also guide you through assembly. diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index be22d4a5..f4bef69c 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -398,7 +398,7 @@ And here are the corresponding positions for the leader arm: You can watch a [video tutorial of the calibration procedure](https://youtu.be/8drnU9uRY24) for more details. -During calibration, we count the number of full 360-degree rotations your motors have made since they were first used. That's why we ask yo to move to this arbitrary "zero" position. We don't actually "set" the zero position, so you don't need to be accurate. After calculating these "offsets" to shift the motor values around 0, we need to assess the rotation direction of each motor, which might differ. That's why we ask you to rotate all motors to roughly 90 degrees, to mesure if the values changed negatively or positively. +During calibration, we count the number of full 360-degree rotations your motors have made since they were first used. That's why we ask yo to move to this arbitrary "zero" position. We don't actually "set" the zero position, so you don't need to be accurate. After calculating these "offsets" to shift the motor values around 0, we need to assess the rotation direction of each motor, which might differ. That's why we ask you to rotate all motors to roughly 90 degrees, to measure if the values changed negatively or positively. Finally, the rest position ensures that the follower and leader arms are roughly aligned after calibration, preventing sudden movements that could damage the motors when starting teleoperation. @@ -663,7 +663,7 @@ camera.disconnect() **Instantiate your robot with cameras** -Additionaly, you can set up your robot to work with your cameras. +Additionally, you can set up your robot to work with your cameras. Modify the following Python code with the appropriate camera names and configurations: ```python @@ -825,8 +825,8 @@ It contains: - `dtRlead: 5.06 (197.5hz)` which is the delta time of reading the present position of the leader arm. - `dtWfoll: 0.25 (3963.7hz)` which is the delta time of writing the goal position on the follower arm ; writing is asynchronous so it takes less time than reading. - `dtRfoll: 6.22 (160.7hz)` which is the delta time of reading the present position on the follower arm. -- `dtRlaptop:32.57 (30.7hz) ` which is the delta time of capturing an image from the laptop camera in the thread running asynchrously. -- `dtRphone:33.84 (29.5hz)` which is the delta time of capturing an image from the phone camera in the thread running asynchrously. +- `dtRlaptop:32.57 (30.7hz) ` which is the delta time of capturing an image from the laptop camera in the thread running asynchronously. +- `dtRphone:33.84 (29.5hz)` which is the delta time of capturing an image from the phone camera in the thread running asynchronously. Troubleshooting: - On Linux, if you encounter a hanging issue when using cameras, uninstall opencv and re-install it with conda: @@ -846,7 +846,7 @@ At the end of data recording, your dataset will be uploaded on your Hugging Face echo https://huggingface.co/datasets/${HF_USER}/koch_test ``` -### b. Advices for recording dataset +### b. Advice for recording dataset Once you're comfortable with data recording, it's time to create a larger dataset for training. A good starting task is grasping an object at different locations and placing it in a bin. We suggest recording at least 50 episodes, with 10 episodes per location. Keep the cameras fixed and maintain consistent grasping behavior throughout the recordings. diff --git a/examples/8_use_stretch.md b/examples/8_use_stretch.md index 2f8c0ffb..802ea718 100644 --- a/examples/8_use_stretch.md +++ b/examples/8_use_stretch.md @@ -98,7 +98,7 @@ python lerobot/scripts/control_robot.py \ ``` This is equivalent to running `stretch_robot_home.py` -> **Note:** If you run any of the LeRobot scripts below and Stretch is not poperly homed, it will automatically home/calibrate first. +> **Note:** If you run any of the LeRobot scripts below and Stretch is not properly homed, it will automatically home/calibrate first. **Teleoperate** Before trying teleoperation, you need activate the gamepad controller by pressing the middle button. For more info, see Stretch's [doc](https://docs.hello-robot.com/0.3/getting_started/hello_robot/#gamepad-teleoperation). diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md index 5d2843fa..055551f0 100644 --- a/examples/9_use_aloha.md +++ b/examples/9_use_aloha.md @@ -172,10 +172,10 @@ python lerobot/scripts/control_robot.py \ As you can see, it's almost the same command as previously used to record your training dataset. Two things changed: 1. There is an additional `--control.policy.path` argument which indicates the path to your policy checkpoint with (e.g. `outputs/train/eval_act_aloha_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `${HF_USER}/act_aloha_test`). 2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `${HF_USER}/eval_act_aloha_test`). -3. We use `--control.num_image_writer_processes=1` instead of the default value (`0`). On our computer, using a dedicated process to write images from the 4 cameras on disk allows to reach constent 30 fps during inference. Feel free to explore different values for `--control.num_image_writer_processes`. +3. We use `--control.num_image_writer_processes=1` instead of the default value (`0`). On our computer, using a dedicated process to write images from the 4 cameras on disk allows to reach constant 30 fps during inference. Feel free to explore different values for `--control.num_image_writer_processes`. ## More -Follow this [previous tutorial](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#4-train-a-policy-on-your-data) for a more in-depth explaination. +Follow this [previous tutorial](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#4-train-a-policy-on-your-data) for a more in-depth explanation. If you have any question or need help, please reach out on Discord in the channel `#aloha-arm`. diff --git a/lerobot/common/datasets/compute_stats.py b/lerobot/common/datasets/compute_stats.py index a029f892..1149ec83 100644 --- a/lerobot/common/datasets/compute_stats.py +++ b/lerobot/common/datasets/compute_stats.py @@ -92,7 +92,7 @@ def compute_episode_stats(episode_data: dict[str, list[str] | np.ndarray], featu axes_to_reduce = (0, 2, 3) # keep channel dim keepdims = True else: - ep_ft_array = data # data is alreay a np.ndarray + ep_ft_array = data # data is already a np.ndarray axes_to_reduce = 0 # compute stats over the first axis keepdims = data.ndim == 1 # keep as np.array diff --git a/lerobot/common/datasets/lerobot_dataset.py b/lerobot/common/datasets/lerobot_dataset.py index f1eb11a0..086411b4 100644 --- a/lerobot/common/datasets/lerobot_dataset.py +++ b/lerobot/common/datasets/lerobot_dataset.py @@ -226,7 +226,7 @@ class LeRobotDatasetMetadata: def add_task(self, task: str): """ - Given a task in natural language, add it to the dictionnary of tasks. + Given a task in natural language, add it to the dictionary of tasks. """ if task in self.task_to_task_index: raise ValueError(f"The task '{task}' already exists and can't be added twice.") @@ -389,7 +389,7 @@ class LeRobotDataset(torch.utils.data.Dataset): - info contains various information about the dataset like shapes, keys, fps etc. - stats stores the dataset statistics of the different modalities for normalization - tasks contains the prompts for each task of the dataset, which can be used for - task-conditionned training. + task-conditioned training. - hf_dataset (from datasets.Dataset), which will read any values from parquet files. - videos (optional) from which frames are loaded to be synchronous with data from parquet files. @@ -848,7 +848,7 @@ class LeRobotDataset(torch.utils.data.Dataset): episode_buffer["index"] = np.arange(self.meta.total_frames, self.meta.total_frames + episode_length) episode_buffer["episode_index"] = np.full((episode_length,), episode_index) - # Add new tasks to the tasks dictionnary + # Add new tasks to the tasks dictionary for task in episode_tasks: task_index = self.meta.get_task_index(task) if task_index is None: diff --git a/lerobot/common/datasets/push_dataset_to_hub/_download_raw.py b/lerobot/common/datasets/push_dataset_to_hub/_download_raw.py index edeaf093..cc291cea 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/_download_raw.py +++ b/lerobot/common/datasets/push_dataset_to_hub/_download_raw.py @@ -152,7 +152,7 @@ def download_raw(raw_dir: Path, repo_id: str): stacklevel=1, ) - # Send warning if raw_dir isn't well formated + # Send warning if raw_dir isn't well formatted if raw_dir.parts[-2] != user_id or raw_dir.parts[-1] != dataset_id: warnings.warn( f"""`raw_dir` ({raw_dir}) doesn't contain a community or user id `/` the name of the dataset that diff --git a/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py b/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py index 4968e002..acf820bf 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/dora_parquet_format.py @@ -68,9 +68,9 @@ def load_from_raw(raw_dir: Path, videos_dir: Path, fps: int, video: bool, episod modality_df, on="timestamp_utc", # "nearest" is the best option over "backward", since the latter can desynchronizes camera timestamps by - # matching timestamps that are too far appart, in order to fit the backward constraints. It's not the case for "nearest". + # matching timestamps that are too far apart, in order to fit the backward constraints. It's not the case for "nearest". # However, note that "nearest" might synchronize the reference camera with other cameras on slightly future timestamps. - # are too far appart. + # are too far apart. direction="nearest", tolerance=pd.Timedelta(f"{1 / fps} seconds"), ) @@ -126,7 +126,7 @@ def load_from_raw(raw_dir: Path, videos_dir: Path, fps: int, video: bool, episod videos_dir.parent.mkdir(parents=True, exist_ok=True) videos_dir.symlink_to((raw_dir / "videos").absolute()) - # sanity check the video paths are well formated + # sanity check the video paths are well formatted for key in df: if "observation.images." not in key: continue @@ -143,7 +143,7 @@ def load_from_raw(raw_dir: Path, videos_dir: Path, fps: int, video: bool, episod # it is the case for video_frame dictionary = [{"path": ..., "timestamp": ...}] data_dict[key] = [video_frame[0] for video_frame in df[key].values] - # sanity check the video path is well formated + # sanity check the video path is well formatted video_path = videos_dir.parent / data_dict[key][0]["path"] if not video_path.exists(): raise ValueError(f"Video file not found in {video_path}") diff --git a/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py b/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py index 1f8a5d14..2ffb8369 100644 --- a/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py +++ b/lerobot/common/datasets/push_dataset_to_hub/openx_rlds_format.py @@ -17,7 +17,7 @@ For all datasets in the RLDS format. For https://github.com/google-deepmind/open_x_embodiment (OPENX) datasets. -NOTE: You need to install tensorflow and tensorflow_datsets before running this script. +NOTE: You need to install tensorflow and tensorflow_datasets before running this script. Example: python lerobot/scripts/push_dataset_to_hub.py \ diff --git a/lerobot/common/datasets/utils.py b/lerobot/common/datasets/utils.py index 2d90798f..89adb163 100644 --- a/lerobot/common/datasets/utils.py +++ b/lerobot/common/datasets/utils.py @@ -222,7 +222,7 @@ def load_episodes(local_dir: Path) -> dict: def write_episode_stats(episode_index: int, episode_stats: dict, local_dir: Path): - # We wrap episode_stats in a dictionnary since `episode_stats["episode_index"]` + # We wrap episode_stats in a dictionary since `episode_stats["episode_index"]` # is a dictionary of stats and not an integer. episode_stats = {"episode_index": episode_index, "stats": serialize_dict(episode_stats)} append_jsonlines(episode_stats, local_dir / EPISODES_STATS_PATH) @@ -445,10 +445,10 @@ def get_episode_data_index( if episodes is not None: episode_lengths = {ep_idx: episode_lengths[ep_idx] for ep_idx in episodes} - cumulative_lenghts = list(accumulate(episode_lengths.values())) + cumulative_lengths = list(accumulate(episode_lengths.values())) return { - "from": torch.LongTensor([0] + cumulative_lenghts[:-1]), - "to": torch.LongTensor(cumulative_lenghts), + "from": torch.LongTensor([0] + cumulative_lengths[:-1]), + "to": torch.LongTensor(cumulative_lengths), } diff --git a/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py index 4cd93a2d..99ab2cbf 100644 --- a/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py @@ -31,6 +31,7 @@ from lerobot.common.robot_devices.robots.configs import AlohaRobotConfig LOCAL_DIR = Path("data/") +# spellchecker:off ALOHA_MOBILE_INFO = { "robot_config": AlohaRobotConfig(), "license": "mit", @@ -856,6 +857,7 @@ DATASETS = { }""").lstrip(), }, } +# spellchecker:on def batch_convert(): diff --git a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py index 99864e3b..acf0282f 100644 --- a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py @@ -17,7 +17,7 @@ """ This script will help you convert any LeRobot dataset already pushed to the hub from codebase version 1.6 to 2.0. You will be required to provide the 'tasks', which is a short but accurate description in plain English -for each of the task performed in the dataset. This will allow to easily train models with task-conditionning. +for each of the task performed in the dataset. This will allow to easily train models with task-conditioning. We support 3 different scenarios for these tasks (see instructions below): 1. Single task dataset: all episodes of your dataset have the same single task. diff --git a/lerobot/common/datasets/video_utils.py b/lerobot/common/datasets/video_utils.py index 8be53483..9f043f96 100644 --- a/lerobot/common/datasets/video_utils.py +++ b/lerobot/common/datasets/video_utils.py @@ -73,7 +73,7 @@ def decode_video_frames_torchvision( last_ts = max(timestamps) # access closest key frame of the first requested frame - # Note: closest key frame timestamp is usally smaller than `first_ts` (e.g. key frame can be the first frame of the video) + # Note: closest key frame timestamp is usually smaller than `first_ts` (e.g. key frame can be the first frame of the video) # for details on what `seek` is doing see: https://pyav.basswood-io.com/docs/stable/api/container.html?highlight=inputcontainer#av.container.InputContainer.seek reader.seek(first_ts, keyframes_only=keyframes_only) diff --git a/lerobot/common/envs/factory.py b/lerobot/common/envs/factory.py index 49239363..8450f84b 100644 --- a/lerobot/common/envs/factory.py +++ b/lerobot/common/envs/factory.py @@ -37,12 +37,12 @@ def make_env(cfg: EnvConfig, n_envs: int = 1, use_async_envs: bool = False) -> g Args: cfg (EnvConfig): the config of the environment to instantiate. n_envs (int, optional): The number of parallelized env to return. Defaults to 1. - use_async_envs (bool, optional): Wether to return an AsyncVectorEnv or a SyncVectorEnv. Defaults to + use_async_envs (bool, optional): Whether to return an AsyncVectorEnv or a SyncVectorEnv. Defaults to False. Raises: ValueError: if n_envs < 1 - ModuleNotFoundError: If the requested env package is not intalled + ModuleNotFoundError: If the requested env package is not installed Returns: gym.vector.VectorEnv: The parallelized gym.env instance. diff --git a/lerobot/common/policies/act/configuration_act.py b/lerobot/common/policies/act/configuration_act.py index 4f724c12..7a5819b7 100644 --- a/lerobot/common/policies/act/configuration_act.py +++ b/lerobot/common/policies/act/configuration_act.py @@ -64,7 +64,7 @@ class ACTConfig(PreTrainedConfig): output_normalization_modes: Similar dictionary as `normalize_input_modes`, but to unnormalize to the original scale. Note that this is also used for normalizing the training targets. vision_backbone: Name of the torchvision resnet backbone to use for encoding images. - pretrained_backbone_weights: Pretrained weights from torchvision to initalize the backbone. + pretrained_backbone_weights: Pretrained weights from torchvision to initialize the backbone. `None` means no pretrained weights. replace_final_stride_with_dilation: Whether to replace the ResNet's final 2x2 stride with a dilated convolution. diff --git a/lerobot/common/policies/diffusion/configuration_diffusion.py b/lerobot/common/policies/diffusion/configuration_diffusion.py index d571e152..e73c65fe 100644 --- a/lerobot/common/policies/diffusion/configuration_diffusion.py +++ b/lerobot/common/policies/diffusion/configuration_diffusion.py @@ -68,7 +68,7 @@ class DiffusionConfig(PreTrainedConfig): within the image size. If None, no cropping is done. crop_is_random: Whether the crop should be random at training time (it's always a center crop in eval mode). - pretrained_backbone_weights: Pretrained weights from torchvision to initalize the backbone. + pretrained_backbone_weights: Pretrained weights from torchvision to initialize the backbone. `None` means no pretrained weights. use_group_norm: Whether to replace batch normalization with group normalization in the backbone. The group sizes are set to be about 16 (to be precise, feature_dim // 16). @@ -99,7 +99,7 @@ class DiffusionConfig(PreTrainedConfig): num_inference_steps: Number of reverse diffusion steps to use at inference time (steps are evenly spaced). If not provided, this defaults to be the same as `num_train_timesteps`. do_mask_loss_for_padding: Whether to mask the loss when there are copy-padded actions. See - `LeRobotDataset` and `load_previous_and_future_frames` for mor information. Note, this defaults + `LeRobotDataset` and `load_previous_and_future_frames` for more information. Note, this defaults to False as the original Diffusion Policy implementation does the same. """ diff --git a/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py b/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py index f85437a5..dd8622dd 100644 --- a/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py +++ b/lerobot/common/policies/pi0/conversion_scripts/convert_pi0_to_hf_lerobot.py @@ -2,7 +2,7 @@ Convert pi0 parameters from Jax to Pytorch Follow [README of openpi](https://github.com/Physical-Intelligence/openpi) to create a new environment -and install the required librairies. +and install the required libraries. ```bash cd ~/code/openpi diff --git a/lerobot/common/policies/tdmpc/configuration_tdmpc.py b/lerobot/common/policies/tdmpc/configuration_tdmpc.py index c3e8aee6..3fce01df 100644 --- a/lerobot/common/policies/tdmpc/configuration_tdmpc.py +++ b/lerobot/common/policies/tdmpc/configuration_tdmpc.py @@ -76,7 +76,7 @@ class TDMPCConfig(PreTrainedConfig): n_pi_samples: Number of samples to draw from the policy / world model rollout every CEM iteration. Can be zero. uncertainty_regularizer_coeff: Coefficient for the uncertainty regularization used when estimating - trajectory values (this is the λ coeffiecient in eqn 4 of FOWM). + trajectory values (this is the λ coefficient in eqn 4 of FOWM). n_elites: The number of elite samples to use for updating the gaussian parameters every CEM iteration. elite_weighting_temperature: The temperature to use for softmax weighting (by trajectory value) of the elites, when updating the gaussian parameters for CEM. @@ -165,7 +165,7 @@ class TDMPCConfig(PreTrainedConfig): """Input validation (not exhaustive).""" if self.n_gaussian_samples <= 0: raise ValueError( - f"The number of guassian samples for CEM should be non-zero. Got `{self.n_gaussian_samples=}`" + f"The number of gaussian samples for CEM should be non-zero. Got `{self.n_gaussian_samples=}`" ) if self.normalization_mapping["ACTION"] is not NormalizationMode.MIN_MAX: raise ValueError( diff --git a/lerobot/common/policies/vqbet/configuration_vqbet.py b/lerobot/common/policies/vqbet/configuration_vqbet.py index 59389d6e..28e9c433 100644 --- a/lerobot/common/policies/vqbet/configuration_vqbet.py +++ b/lerobot/common/policies/vqbet/configuration_vqbet.py @@ -66,7 +66,7 @@ class VQBeTConfig(PreTrainedConfig): within the image size. If None, no cropping is done. crop_is_random: Whether the crop should be random at training time (it's always a center crop in eval mode). - pretrained_backbone_weights: Pretrained weights from torchvision to initalize the backbone. + pretrained_backbone_weights: Pretrained weights from torchvision to initialize the backbone. `None` means no pretrained weights. use_group_norm: Whether to replace batch normalization with group normalization in the backbone. The group sizes are set to be about 16 (to be precise, feature_dim // 16). diff --git a/lerobot/common/policies/vqbet/modeling_vqbet.py b/lerobot/common/policies/vqbet/modeling_vqbet.py index 1f70b186..97a08e2f 100644 --- a/lerobot/common/policies/vqbet/modeling_vqbet.py +++ b/lerobot/common/policies/vqbet/modeling_vqbet.py @@ -485,7 +485,7 @@ class VQBeTHead(nn.Module): def forward(self, x, **kwargs) -> dict: # N is the batch size, and T is number of action query tokens, which are process through same GPT N, T, _ = x.shape - # we calculate N and T side parallely. Thus, the dimensions would be + # we calculate N and T side parallelly. Thus, the dimensions would be # (batch size * number of action query tokens, action chunk size, action dimension) x = einops.rearrange(x, "N T WA -> (N T) WA") @@ -772,7 +772,7 @@ class VqVae(nn.Module): Encoder and decoder are MLPs consisting of an input, output layer, and hidden layer, respectively. The vq_layer uses residual VQs. - This class contains functions for training the encoder and decoder along with the residual VQ layer (for trainign phase 1), + This class contains functions for training the encoder and decoder along with the residual VQ layer (for training phase 1), as well as functions to help BeT training part in training phase 2. """ diff --git a/lerobot/common/policies/vqbet/vqbet_utils.py b/lerobot/common/policies/vqbet/vqbet_utils.py index a2bd2df3..139d119e 100644 --- a/lerobot/common/policies/vqbet/vqbet_utils.py +++ b/lerobot/common/policies/vqbet/vqbet_utils.py @@ -38,7 +38,7 @@ from lerobot.common.policies.vqbet.configuration_vqbet import VQBeTConfig This file is part of a VQ-BeT that utilizes code from the following repositories: - Vector Quantize PyTorch code is licensed under the MIT License: - Origianl source: https://github.com/lucidrains/vector-quantize-pytorch + Original source: https://github.com/lucidrains/vector-quantize-pytorch - nanoGPT part is an adaptation of Andrej Karpathy's nanoGPT implementation in PyTorch. Original source: https://github.com/karpathy/nanoGPT @@ -289,7 +289,7 @@ class GPT(nn.Module): This file is a part for Residual Vector Quantization that utilizes code from the following repository: - Phil Wang's vector-quantize-pytorch implementation in PyTorch. - Origianl source: https://github.com/lucidrains/vector-quantize-pytorch + Original source: https://github.com/lucidrains/vector-quantize-pytorch - The vector-quantize-pytorch code is licensed under the MIT License: @@ -1349,9 +1349,9 @@ class EuclideanCodebook(nn.Module): # calculate distributed variance - variance_numer = reduce((data - batch_mean) ** 2, "h n d -> h 1 d", "sum") - distributed.all_reduce(variance_numer) - batch_variance = variance_numer / num_vectors + variance_number = reduce((data - batch_mean) ** 2, "h n d -> h 1 d", "sum") + distributed.all_reduce(variance_number) + batch_variance = variance_number / num_vectors self.update_with_decay("batch_variance", batch_variance, self.affine_param_batch_decay) diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/common/robot_devices/control_configs.py index c3e920b1..2ef1b44b 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/common/robot_devices/control_configs.py @@ -66,7 +66,7 @@ class RecordControlConfig(ControlConfig): private: bool = False # Add tags to your dataset on the hub. tags: list[str] | None = None - # Number of subprocesses handling the saving of frames as PNGs. Set to 0 to use threads only; + # Number of subprocesses handling the saving of frames as PNG. Set to 0 to use threads only; # set to ≥1 to use subprocesses, each using threads to write images. The best number of processes # and threads depends on your system. We recommend 4 threads per camera with 0 processes. # If fps is unstable, adjust the thread count. If still unstable, try using 1 or more subprocesses. diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/robot_devices/motors/dynamixel.py index 54836d8e..17ea933d 100644 --- a/lerobot/common/robot_devices/motors/dynamixel.py +++ b/lerobot/common/robot_devices/motors/dynamixel.py @@ -242,7 +242,7 @@ class DriveMode(enum.Enum): class CalibrationMode(enum.Enum): # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180] DEGREE = 0 - # Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100] + # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100] LINEAR = 1 @@ -610,7 +610,7 @@ class DynamixelMotorsBus: # 0-centered resolution range (e.g. [-2048, 2048] for resolution=4096) values[i] = values[i] / HALF_TURN_DEGREE * (resolution // 2) - # Substract the homing offsets to come back to actual motor range of values + # Subtract the homing offsets to come back to actual motor range of values # which can be arbitrary. values[i] -= homing_offset diff --git a/lerobot/common/robot_devices/motors/feetech.py b/lerobot/common/robot_devices/motors/feetech.py index a59db7df..cec36d37 100644 --- a/lerobot/common/robot_devices/motors/feetech.py +++ b/lerobot/common/robot_devices/motors/feetech.py @@ -221,7 +221,7 @@ class DriveMode(enum.Enum): class CalibrationMode(enum.Enum): # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180] DEGREE = 0 - # Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100] + # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100] LINEAR = 1 @@ -591,7 +591,7 @@ class FeetechMotorsBus: # 0-centered resolution range (e.g. [-2048, 2048] for resolution=4096) values[i] = values[i] / HALF_TURN_DEGREE * (resolution // 2) - # Substract the homing offsets to come back to actual motor range of values + # Subtract the homing offsets to come back to actual motor range of values # which can be arbitrary. values[i] -= homing_offset @@ -632,7 +632,7 @@ class FeetechMotorsBus: track["prev"][idx] = values[i] continue - # Detect a full rotation occured + # Detect a full rotation occurred if abs(track["prev"][idx] - values[i]) > 2048: # Position went below 0 and got reset to 4095 if track["prev"][idx] < values[i]: diff --git a/lerobot/common/robot_devices/robots/dynamixel_calibration.py b/lerobot/common/robot_devices/robots/dynamixel_calibration.py index 5c4932d2..142d5794 100644 --- a/lerobot/common/robot_devices/robots/dynamixel_calibration.py +++ b/lerobot/common/robot_devices/robots/dynamixel_calibration.py @@ -87,7 +87,7 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type # For instance, if the motor rotates 90 degree, and its value is -90 after applying the homing offset, then we know its rotation direction # is inverted. However, for the calibration being successful, we need everyone to follow the same target position. # Sometimes, there is only one possible rotation direction. For instance, if the gripper is closed, there is only one direction which - # corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarely rotate clockwise from the point of view + # corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarily rotate clockwise from the point of view # of the previous motor in the kinetic chain. print("\nMove arm to rotated target position") print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated")) @@ -115,7 +115,7 @@ def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type # TODO(rcadene): make type of joints (DEGREE or LINEAR) configurable from yaml? if robot_type in ["aloha"] and "gripper" in arm.motor_names: - # Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100] + # Joints with linear motions (like gripper of Aloha) are expressed in nominal range of [0, 100] calib_idx = arm.motor_names.index("gripper") calib_mode[calib_idx] = CalibrationMode.LINEAR.name diff --git a/lerobot/common/robot_devices/robots/feetech_calibration.py b/lerobot/common/robot_devices/robots/feetech_calibration.py index b015951a..d779cd44 100644 --- a/lerobot/common/robot_devices/robots/feetech_calibration.py +++ b/lerobot/common/robot_devices/robots/feetech_calibration.py @@ -443,7 +443,7 @@ def run_arm_manual_calibration(arm: MotorsBus, robot_type: str, arm_name: str, a # For instance, if the motor rotates 90 degree, and its value is -90 after applying the homing offset, then we know its rotation direction # is inverted. However, for the calibration being successful, we need everyone to follow the same target position. # Sometimes, there is only one possible rotation direction. For instance, if the gripper is closed, there is only one direction which - # corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarely rotate clockwise from the point of view + # corresponds to opening the gripper. When the rotation direction is ambiguous, we arbitrarily rotate clockwise from the point of view # of the previous motor in the kinetic chain. print("\nMove arm to rotated target position") print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated")) diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index 9c82d069..62e5416e 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -44,7 +44,7 @@ class ManipulatorRobot: # TODO(rcadene): Implement force feedback """This class allows to control any manipulator robot of various number of motors. - Non exaustive list of robots: + Non exhaustive list of robots: - [Koch v1.0](https://github.com/AlexanderKoch-Koch/low_cost_robot), with and without the wrist-to-elbow expansion, developed by Alexander Koch from [Tau Robotics](https://tau-robotics.com) - [Koch v1.1](https://github.com/jess-moss/koch-v1-1) developed by Jess Moss @@ -55,7 +55,7 @@ class ManipulatorRobot: robot = ManipulatorRobot(KochRobotConfig()) ``` - Example of overwritting motors during instantiation: + Example of overwriting motors during instantiation: ```python # Defines how to communicate with the motors of the leader and follower arms leader_arms = { @@ -90,7 +90,7 @@ class ManipulatorRobot: robot = ManipulatorRobot(robot_config) ``` - Example of overwritting cameras during instantiation: + Example of overwriting cameras during instantiation: ```python # Defines how to communicate with 2 cameras connected to the computer. # Here, the webcam of the laptop and the phone (connected in USB to the laptop) @@ -348,7 +348,7 @@ class ManipulatorRobot: set_operating_mode_(self.follower_arms[name]) # Set better PID values to close the gap between recorded states and actions - # TODO(rcadene): Implement an automatic procedure to set optimial PID values for each motor + # TODO(rcadene): Implement an automatic procedure to set optimal PID values for each motor self.follower_arms[name].write("Position_P_Gain", 1500, "elbow_flex") self.follower_arms[name].write("Position_I_Gain", 0, "elbow_flex") self.follower_arms[name].write("Position_D_Gain", 600, "elbow_flex") @@ -500,7 +500,7 @@ class ManipulatorRobot: self.logs[f"read_camera_{name}_dt_s"] = self.cameras[name].logs["delta_timestamp_s"] self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t - # Populate output dictionnaries + # Populate output dictionaries obs_dict, action_dict = {}, {} obs_dict["observation.state"] = state action_dict["action"] = action @@ -540,7 +540,7 @@ class ManipulatorRobot: self.logs[f"read_camera_{name}_dt_s"] = self.cameras[name].logs["delta_timestamp_s"] self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t - # Populate output dictionnaries and format to pytorch + # Populate output dictionaries and format to pytorch obs_dict = {} obs_dict["observation.state"] = state for name in self.cameras: diff --git a/lerobot/common/robot_devices/robots/stretch.py b/lerobot/common/robot_devices/robots/stretch.py index b63bf941..9cfe6e49 100644 --- a/lerobot/common/robot_devices/robots/stretch.py +++ b/lerobot/common/robot_devices/robots/stretch.py @@ -108,7 +108,7 @@ class StretchRobot(StretchAPI): self.logs[f"read_camera_{name}_dt_s"] = self.cameras[name].logs["delta_timestamp_s"] self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t - # Populate output dictionnaries + # Populate output dictionaries obs_dict, action_dict = {}, {} obs_dict["observation.state"] = state action_dict["action"] = action @@ -153,7 +153,7 @@ class StretchRobot(StretchAPI): self.logs[f"read_camera_{name}_dt_s"] = self.cameras[name].logs["delta_timestamp_s"] self.logs[f"async_read_camera_{name}_dt_s"] = time.perf_counter() - before_camread_t - # Populate output dictionnaries + # Populate output dictionaries obs_dict = {} obs_dict["observation.state"] = state for name in self.cameras: diff --git a/lerobot/configs/default.py b/lerobot/configs/default.py index 0dc7f4c7..1e7f5819 100644 --- a/lerobot/configs/default.py +++ b/lerobot/configs/default.py @@ -27,7 +27,7 @@ class DatasetConfig: # You may provide a list of datasets here. `train.py` creates them all and concatenates them. Note: only data # keys common between the datasets are kept. Each dataset gets and additional transform that inserts the # "dataset_index" into the returned item. The index mapping is made according to the order in which the - # datsets are provided. + # datasets are provided. repo_id: str # Root directory where the dataset will be stored (e.g. 'dataset/path'). root: str | None = None diff --git a/lerobot/configs/train.py b/lerobot/configs/train.py index 93f6e2a4..464c11f9 100644 --- a/lerobot/configs/train.py +++ b/lerobot/configs/train.py @@ -102,7 +102,7 @@ class TrainPipelineConfig(HubMixin): if not self.resume and isinstance(self.output_dir, Path) and self.output_dir.is_dir(): raise FileExistsError( - f"Output directory {self.output_dir} alreay exists and resume is {self.resume}. " + f"Output directory {self.output_dir} already exists and resume is {self.resume}. " f"Please change your output directory so that {self.output_dir} is not overwritten." ) elif not self.output_dir: diff --git a/lerobot/scripts/control_sim_robot.py b/lerobot/scripts/control_sim_robot.py index 8d69bf31..49a88d14 100644 --- a/lerobot/scripts/control_sim_robot.py +++ b/lerobot/scripts/control_sim_robot.py @@ -59,8 +59,8 @@ python lerobot/scripts/control_sim_robot.py record \ ``` **NOTE**: You can use your keyboard to control data recording flow. -- Tap right arrow key '->' to early exit while recording an episode and go to reseting the environment. -- Tap right arrow key '->' to early exit while reseting the environment and got to recording the next episode. +- Tap right arrow key '->' to early exit while recording an episode and go to resetting the environment. +- Tap right arrow key '->' to early exit while resetting the environment and got to recording the next episode. - Tap left arrow key '<-' to early exit and re-record the current episode. - Tap escape key 'esc' to stop the data recording. This might require a sudo permission to allow your terminal to monitor keyboard events. @@ -131,7 +131,7 @@ def none_or_int(value): def init_sim_calibration(robot, cfg): # Constants necessary for transforming the joint pos of the real robot to the sim - # depending on the robot discription used in that sim. + # depending on the robot description used in that sim. start_pos = np.array(robot.leader_arms.main.calibration["start_pos"]) axis_directions = np.array(cfg.get("axis_directions", [1])) offsets = np.array(cfg.get("offsets", [0])) * np.pi @@ -445,7 +445,7 @@ if __name__ == "__main__": type=int, default=0, help=( - "Number of subprocesses handling the saving of frames as PNGs. Set to 0 to use threads only; " + "Number of subprocesses handling the saving of frames as PNG. Set to 0 to use threads only; " "set to ≥1 to use subprocesses, each using threads to write images. The best number of processes " "and threads depends on your system. We recommend 4 threads per camera with 0 processes. " "If fps is unstable, adjust the thread count. If still unstable, try using 1 or more subprocesses." diff --git a/lerobot/scripts/push_dataset_to_hub.py b/lerobot/scripts/push_dataset_to_hub.py index 0233ede6..3de2462b 100644 --- a/lerobot/scripts/push_dataset_to_hub.py +++ b/lerobot/scripts/push_dataset_to_hub.py @@ -175,7 +175,7 @@ def push_dataset_to_hub( # Robustify when `local_dir` is str instead of Path local_dir = Path(local_dir) - # Send warning if local_dir isn't well formated + # Send warning if local_dir isn't well formatted if local_dir.parts[-2] != user_id or local_dir.parts[-1] != dataset_id: warnings.warn( f"`local_dir` ({local_dir}) doesn't contain a community or user id `/` the name of the dataset that match the `repo_id` (e.g. 'data/lerobot/pusht'). Following this naming convention is advised, but not mandatory.", diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index f3c57fe2..e36c697a 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -72,7 +72,7 @@ def update_policy( # TODO(rcadene): policy.unnormalize_outputs(out_dict) grad_scaler.scale(loss).backward() - # Unscale the graident of the optimzer's assigned params in-place **prior to gradient clipping**. + # Unscale the gradient of the optimizer's assigned params in-place **prior to gradient clipping**. grad_scaler.unscale_(optimizer) grad_norm = torch.nn.utils.clip_grad_norm_( diff --git a/lerobot/scripts/visualize_dataset_html.py b/lerobot/scripts/visualize_dataset_html.py index ed748c9a..ac91f0c8 100644 --- a/lerobot/scripts/visualize_dataset_html.py +++ b/lerobot/scripts/visualize_dataset_html.py @@ -364,7 +364,7 @@ def visualize_dataset_html( template_folder=template_dir, ) else: - # Create a simlink from the dataset video folder containg mp4 files to the output directory + # Create a simlink from the dataset video folder containing mp4 files to the output directory # so that the http server can get access to the mp4 files. if isinstance(dataset, LeRobotDataset): ln_videos_dir = static_dir / "videos" diff --git a/pyproject.toml b/pyproject.toml index 25cadb3e..0bd3c029 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -116,6 +116,19 @@ exclude = [ select = ["E4", "E7", "E9", "F", "I", "N", "B", "C4", "SIM"] +[tool.typos] +default.extend-ignore-re = [ + "(?Rm)^.*(#|//)\\s*spellchecker:disable-line$", # spellchecker:disable-line + "(?s)(#|//)\\s*spellchecker:off.*?\\n\\s*(#|//)\\s*spellchecker:on" # spellchecker: +] +default.extend-ignore-identifiers-re = [ + # Add individual words here to ignore them + "2nd", + "pn", + "ser", + "ein", +] + [build-system] requires = ["poetry-core"] build-backend = "poetry.core.masonry.api" diff --git a/tests/mock_cv2.py b/tests/mock_cv2.py index 3f3f9e34..806e35ed 100644 --- a/tests/mock_cv2.py +++ b/tests/mock_cv2.py @@ -18,11 +18,11 @@ def _generate_image(width: int, height: int): return np.random.randint(0, 256, size=(height, width, 3), dtype=np.uint8) -def cvtColor(color_image, color_convertion): # noqa: N802 - if color_convertion in [COLOR_RGB2BGR, COLOR_BGR2RGB]: +def cvtColor(color_image, color_conversion): # noqa: N802 + if color_conversion in [COLOR_RGB2BGR, COLOR_BGR2RGB]: return color_image[:, :, [2, 1, 0]] else: - raise NotImplementedError(color_convertion) + raise NotImplementedError(color_conversion) def rotate(color_image, rotation): diff --git a/tests/test_cameras.py b/tests/test_cameras.py index 7c043c25..cfefc215 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -27,7 +27,7 @@ import pytest from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from tests.utils import TEST_CAMERA_TYPES, make_camera, require_camera -# Maximum absolute difference between two consecutive images recored by a camera. +# Maximum absolute difference between two consecutive images recorded by a camera. # This value differs with respect to the camera. MAX_PIXEL_DIFFERENCE = 25 diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 12b68641..1796291f 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -179,7 +179,7 @@ def test_record_and_replay_and_policy(tmp_path, request, robot_type, mock): policy.save_pretrained(pretrained_policy_path) # In `examples/9_use_aloha.md`, we advise using `num_image_writer_processes=1` - # during inference, to reach constent fps, so we test this here. + # during inference, to reach constant fps, so we test this here. if robot_type == "aloha": num_image_writer_processes = 1 diff --git a/tests/test_datasets.py b/tests/test_datasets.py index 61b68aa8..003a60c9 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -486,7 +486,7 @@ def test_backward_compatibility(repo_id): old_frame = load_file(test_dir / f"frame_{i}.safetensors") # noqa: B023 # ignore language instructions (if exists) in language conditioned datasets - # TODO (michel-aractingi): transform language obs to langauge embeddings via tokenizer + # TODO (michel-aractingi): transform language obs to language embeddings via tokenizer new_frame.pop("language_instruction", None) old_frame.pop("language_instruction", None) new_frame.pop("task", None) diff --git a/tests/test_delta_timestamps.py b/tests/test_delta_timestamps.py index 3e3b83ac..b27cc1eb 100644 --- a/tests/test_delta_timestamps.py +++ b/tests/test_delta_timestamps.py @@ -32,10 +32,10 @@ def calculate_episode_data_index(hf_dataset: datasets.Dataset) -> dict[str, np.n ep_table = table.filter(pc.equal(table["episode_index"], ep_idx)) episode_lengths.insert(ep_idx, len(ep_table)) - cumulative_lenghts = list(accumulate(episode_lengths)) + cumulative_lengths = list(accumulate(episode_lengths)) return { - "from": np.array([0] + cumulative_lenghts[:-1], dtype=np.int64), - "to": np.array(cumulative_lenghts, dtype=np.int64), + "from": np.array([0] + cumulative_lengths[:-1], dtype=np.int64), + "to": np.array(cumulative_lengths, dtype=np.int64), } diff --git a/tests/test_motors.py b/tests/test_motors.py index 2f668926..75793636 100644 --- a/tests/test_motors.py +++ b/tests/test_motors.py @@ -88,7 +88,7 @@ def test_motors_bus(request, motor_type, mock): motors_bus = make_motors_bus(motor_type, mock=mock) - # Test reading and writting before connecting raises an error + # Test reading and writing before connecting raises an error with pytest.raises(RobotDeviceNotConnectedError): motors_bus.read("Torque_Enable") with pytest.raises(RobotDeviceNotConnectedError): diff --git a/tests/test_robots.py b/tests/test_robots.py index 6c300b71..fe440da8 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -86,7 +86,7 @@ def test_robot(tmp_path, request, robot_type, mock): robot.connect() robot.teleop_step() - # Test data recorded during teleop are well formated + # Test data recorded during teleop are well formatted observation, action = robot.teleop_step(record_data=True) # State assert "observation.state" in observation From da265ca92000cfc40a8baaadb481cd2375a85044 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Tue, 25 Feb 2025 23:52:25 +0100 Subject: [PATCH 08/69] Add pr style bot (#772) --- .github/workflows/pr_style_bot.yml | 125 +++++++++++++++++++++++++++++ .github/workflows/quality.yml | 6 +- 2 files changed, 129 insertions(+), 2 deletions(-) create mode 100644 .github/workflows/pr_style_bot.yml diff --git a/.github/workflows/pr_style_bot.yml b/.github/workflows/pr_style_bot.yml new file mode 100644 index 00000000..a34042c4 --- /dev/null +++ b/.github/workflows/pr_style_bot.yml @@ -0,0 +1,125 @@ +# Adapted from https://github.com/huggingface/diffusers/blob/main/.github/workflows/pr_style_bot.yml +name: PR Style Bot + +on: + issue_comment: + types: [created] + +permissions: + contents: write + pull-requests: write + +jobs: + run-style-bot: + if: > + contains(github.event.comment.body, '@bot /style') && + github.event.issue.pull_request != null + runs-on: ubuntu-latest + + steps: + - name: Extract PR details + id: pr_info + uses: actions/github-script@v6 + with: + script: | + const prNumber = context.payload.issue.number; + const { data: pr } = await github.rest.pulls.get({ + owner: context.repo.owner, + repo: context.repo.repo, + pull_number: prNumber + }); + + // We capture both the branch ref and the "full_name" of the head repo + // so that we can check out the correct repository & branch (including forks). + core.setOutput("prNumber", prNumber); + core.setOutput("headRef", pr.head.ref); + core.setOutput("headRepoFullName", pr.head.repo.full_name); + + - name: Check out PR branch + uses: actions/checkout@v4 + env: + HEADREPOFULLNAME: ${{ steps.pr_info.outputs.headRepoFullName }} + HEADREF: ${{ steps.pr_info.outputs.headRef }} + with: + persist-credentials: false + # Instead of checking out the base repo, use the contributor's repo name + repository: ${{ env.HEADREPOFULLNAME }} + ref: ${{ env.HEADREF }} + # You may need fetch-depth: 0 for being able to push + fetch-depth: 0 + token: ${{ secrets.GITHUB_TOKEN }} + + - name: Debug + env: + HEADREPOFULLNAME: ${{ steps.pr_info.outputs.headRepoFullName }} + HEADREF: ${{ steps.pr_info.outputs.headRef }} + PRNUMBER: ${{ steps.pr_info.outputs.prNumber }} + run: | + echo "PR number: $PRNUMBER" + echo "Head Ref: $HEADREF" + echo "Head Repo Full Name: $HEADREPOFULLNAME" + + - name: Set up Python + uses: actions/setup-python@v4 + + - name: Get Ruff Version from pre-commit-config.yaml + id: get-ruff-version + run: | + RUFF_VERSION=$(awk '/repo: https:\/\/github.com\/astral-sh\/ruff-pre-commit/{flag=1;next}/rev:/{if(flag){print $2;exit}}' .pre-commit-config.yaml) + echo "ruff_version=${RUFF_VERSION}" >> $GITHUB_OUTPUT + + - name: Install Ruff + env: + RUFF_VERSION: ${{ steps.get-ruff-version.outputs.ruff_version }} + run: python -m pip install "ruff==${RUFF_VERSION}" + + - name: Ruff check + run: ruff check --fix + + - name: Ruff format + run: ruff format + + - name: Commit and push changes + id: commit_and_push + env: + HEADREPOFULLNAME: ${{ steps.pr_info.outputs.headRepoFullName }} + HEADREF: ${{ steps.pr_info.outputs.headRef }} + PRNUMBER: ${{ steps.pr_info.outputs.prNumber }} + GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} + run: | + echo "HEADREPOFULLNAME: $HEADREPOFULLNAME, HEADREF: $HEADREF" + # Configure git with the Actions bot user + git config user.name "github-actions[bot]" + git config user.email "github-actions[bot]@users.noreply.github.com" + + # Make sure your 'origin' remote is set to the contributor's fork + git remote set-url origin "https://x-access-token:${GITHUB_TOKEN}@github.com/$HEADREPOFULLNAME.git" + + # If there are changes after running style/quality, commit them + if [ -n "$(git status --porcelain)" ]; then + git add . + git commit -m "Apply style fixes" + # Push to the original contributor's forked branch + git push origin HEAD:$HEADREF + echo "changes_pushed=true" >> $GITHUB_OUTPUT + else + echo "No changes to commit." + echo "changes_pushed=false" >> $GITHUB_OUTPUT + fi + + - name: Comment on PR with workflow run link + if: steps.commit_and_push.outputs.changes_pushed == 'true' + uses: actions/github-script@v6 + with: + script: | + const prNumber = parseInt(process.env.prNumber, 10); + const runUrl = `${process.env.GITHUB_SERVER_URL}/${process.env.GITHUB_REPOSITORY}/actions/runs/${process.env.GITHUB_RUN_ID}` + + await github.rest.issues.createComment({ + owner: context.repo.owner, + repo: context.repo.repo, + issue_number: prNumber, + body: `Style fixes have been applied. [View the workflow run here](${runUrl}).` + }); + env: + prNumber: ${{ steps.pr_info.outputs.prNumber }} diff --git a/.github/workflows/quality.yml b/.github/workflows/quality.yml index 4cf8e0df..f785d52f 100644 --- a/.github/workflows/quality.yml +++ b/.github/workflows/quality.yml @@ -32,10 +32,12 @@ jobs: id: get-ruff-version run: | RUFF_VERSION=$(awk '/repo: https:\/\/github.com\/astral-sh\/ruff-pre-commit/{flag=1;next}/rev:/{if(flag){print $2;exit}}' .pre-commit-config.yaml) - echo "RUFF_VERSION=${RUFF_VERSION}" >> $GITHUB_ENV + echo "ruff_version=${RUFF_VERSION}" >> $GITHUB_OUTPUT - name: Install Ruff - run: python -m pip install "ruff==${{ env.RUFF_VERSION }}" + env: + RUFF_VERSION: ${{ steps.get-ruff-version.outputs.ruff_version }} + run: python -m pip install "ruff==${RUFF_VERSION}" - name: Ruff check run: ruff check --output-format=github From 659ec4434d4aa9cf633477be3b1cbf1dd6f4c2bf Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Wed, 26 Feb 2025 16:36:03 +0100 Subject: [PATCH 09/69] Fix nightly (#775) --- .github/workflows/test-docker-build.yml | 2 +- docker/lerobot-cpu/Dockerfile | 38 +++++------ docker/lerobot-gpu/Dockerfile | 7 +- .../aloha_act/actions.safetensors | 3 - .../aloha_act/grad_stats.safetensors | 3 - .../aloha_act/output_dict.safetensors | 3 - .../aloha_act/param_stats.safetensors | 3 - .../aloha_act_1000_steps/actions.safetensors | 3 - .../grad_stats.safetensors | 3 - .../output_dict.safetensors | 3 - .../param_stats.safetensors | 3 - .../actions.safetensors | 3 + .../grad_stats.safetensors | 3 + .../output_dict.safetensors | 3 + .../param_stats.safetensors | 3 + .../actions.safetensors | 3 + .../grad_stats.safetensors | 3 + .../output_dict.safetensors | 3 + .../param_stats.safetensors | 3 + .../actions.safetensors | 3 - .../grad_stats.safetensors | 3 - .../output_dict.safetensors | 3 - .../param_stats.safetensors | 3 - .../pusht_diffusion/actions.safetensors | 3 - .../pusht_diffusion/grad_stats.safetensors | 3 - .../pusht_diffusion/output_dict.safetensors | 3 - .../pusht_diffusion/param_stats.safetensors | 3 - .../pusht_diffusion_/actions.safetensors | 3 + .../pusht_diffusion_/grad_stats.safetensors | 3 + .../pusht_diffusion_/output_dict.safetensors | 3 + .../pusht_diffusion_/param_stats.safetensors | 3 + .../actions.safetensors | 3 + .../grad_stats.safetensors | 3 + .../output_dict.safetensors | 3 + .../param_stats.safetensors | 3 + .../actions.safetensors | 3 + .../grad_stats.safetensors | 3 + .../output_dict.safetensors | 3 + .../param_stats.safetensors | 3 + .../xarm_tdmpcuse_mpc/actions.safetensors | 3 - .../xarm_tdmpcuse_mpc/grad_stats.safetensors | 3 - .../xarm_tdmpcuse_mpc/output_dict.safetensors | 3 - .../xarm_tdmpcuse_mpc/param_stats.safetensors | 3 - .../xarm_tdmpcuse_policy/actions.safetensors | 3 - .../grad_stats.safetensors | 3 - .../output_dict.safetensors | 3 - .../param_stats.safetensors | 3 - tests/scripts/save_policy_to_safetensors.py | 60 ++++++++--------- tests/test_online_buffer.py | 10 +-- tests/test_policies.py | 66 +++++++++---------- tests/test_robots.py | 2 +- 51 files changed, 145 insertions(+), 172 deletions(-) delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act/actions.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act/grad_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act/output_dict.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act/param_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act_1000_steps/actions.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act_1000_steps/grad_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act_1000_steps/output_dict.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/aloha_act_1000_steps/param_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/actions.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/grad_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/output_dict.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/param_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/actions.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/grad_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/output_dict.safetensors create mode 100644 tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/param_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/actions.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/grad_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/output_dict.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/param_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion/actions.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion/grad_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion/output_dict.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion/param_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion_/actions.safetensors create mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion_/grad_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion_/output_dict.safetensors create mode 100644 tests/data/save_policy_to_safetensors/pusht_diffusion_/param_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/actions.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/grad_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/output_dict.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/param_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/actions.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/grad_stats.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/output_dict.safetensors create mode 100644 tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/param_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/actions.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/grad_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/output_dict.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/param_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/actions.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/grad_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/output_dict.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/param_stats.safetensors diff --git a/.github/workflows/test-docker-build.yml b/.github/workflows/test-docker-build.yml index 4d6e9ce5..3ee84a27 100644 --- a/.github/workflows/test-docker-build.yml +++ b/.github/workflows/test-docker-build.yml @@ -43,7 +43,7 @@ jobs: needs: get_changed_files runs-on: group: aws-general-8-plus - if: ${{ needs.get_changed_files.outputs.matrix }} != '' + if: needs.get_changed_files.outputs.matrix != '' strategy: fail-fast: false matrix: diff --git a/docker/lerobot-cpu/Dockerfile b/docker/lerobot-cpu/Dockerfile index 06673092..13a45d24 100644 --- a/docker/lerobot-cpu/Dockerfile +++ b/docker/lerobot-cpu/Dockerfile @@ -1,33 +1,29 @@ # Configure image ARG PYTHON_VERSION=3.10 - FROM python:${PYTHON_VERSION}-slim -ARG PYTHON_VERSION -ARG DEBIAN_FRONTEND=noninteractive -# Install apt dependencies +# Configure environment variables +ARG PYTHON_VERSION +ENV DEBIAN_FRONTEND=noninteractive +ENV MUJOCO_GL="egl" +ENV PATH="/opt/venv/bin:$PATH" + +# Install dependencies and set up Python in a single layer RUN apt-get update && apt-get install -y --no-install-recommends \ - build-essential cmake git git-lfs \ + build-essential cmake git \ libglib2.0-0 libgl1-mesa-glx libegl1-mesa ffmpeg \ speech-dispatcher libgeos-dev \ - && apt-get clean && rm -rf /var/lib/apt/lists/* + && ln -s /usr/bin/python${PYTHON_VERSION} /usr/bin/python \ + && python -m venv /opt/venv \ + && apt-get clean && rm -rf /var/lib/apt/lists/* \ + && echo "source /opt/venv/bin/activate" >> /root/.bashrc -# Create virtual environment -RUN ln -s /usr/bin/python${PYTHON_VERSION} /usr/bin/python -RUN python -m venv /opt/venv -ENV PATH="/opt/venv/bin:$PATH" -RUN echo "source /opt/venv/bin/activate" >> /root/.bashrc - -# Install LeRobot -RUN git lfs install -RUN git clone https://github.com/huggingface/lerobot.git /lerobot +# Clone repository and install LeRobot in a single layer +COPY . /lerobot WORKDIR /lerobot -RUN pip install --upgrade --no-cache-dir pip -RUN pip install --no-cache-dir ".[test, aloha, xarm, pusht, dynamixel]" \ - --extra-index-url https://download.pytorch.org/whl/cpu - -# Set EGL as the rendering backend for MuJoCo -ENV MUJOCO_GL="egl" +RUN /opt/venv/bin/pip install --upgrade --no-cache-dir pip \ + && /opt/venv/bin/pip install --no-cache-dir ".[test, aloha, xarm, pusht, dynamixel]" \ + --extra-index-url https://download.pytorch.org/whl/cpu # Execute in bash shell rather than python CMD ["/bin/bash"] diff --git a/docker/lerobot-gpu/Dockerfile b/docker/lerobot-gpu/Dockerfile index b2898b97..642a8ded 100644 --- a/docker/lerobot-gpu/Dockerfile +++ b/docker/lerobot-gpu/Dockerfile @@ -8,7 +8,7 @@ ENV PATH="/opt/venv/bin:$PATH" # Install dependencies and set up Python in a single layer RUN apt-get update && apt-get install -y --no-install-recommends \ - build-essential cmake git git-lfs \ + build-essential cmake git \ libglib2.0-0 libgl1-mesa-glx libegl1-mesa ffmpeg \ speech-dispatcher libgeos-dev \ python${PYTHON_VERSION}-dev python${PYTHON_VERSION}-venv \ @@ -18,8 +18,7 @@ RUN apt-get update && apt-get install -y --no-install-recommends \ && echo "source /opt/venv/bin/activate" >> /root/.bashrc # Clone repository and install LeRobot in a single layer +COPY . /lerobot WORKDIR /lerobot -RUN git lfs install \ - && git clone https://github.com/huggingface/lerobot.git . \ - && /opt/venv/bin/pip install --upgrade --no-cache-dir pip \ +RUN /opt/venv/bin/pip install --upgrade --no-cache-dir pip \ && /opt/venv/bin/pip install --no-cache-dir ".[test, aloha, xarm, pusht, dynamixel]" diff --git a/tests/data/save_policy_to_safetensors/aloha_act/actions.safetensors b/tests/data/save_policy_to_safetensors/aloha_act/actions.safetensors deleted file mode 100644 index 2dd4dda3..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act/actions.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:eb7b74f919adf8d4478585f65c54997e6f3bccab67eadb4048300108586a4163 -size 5104 diff --git a/tests/data/save_policy_to_safetensors/aloha_act/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_act/grad_stats.safetensors deleted file mode 100644 index cd966518..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act/grad_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:dfbc3b1ad5e3b94311edda0f04db002b26117b0719b73dfdb56dd483dc9c409d -size 31672 diff --git a/tests/data/save_policy_to_safetensors/aloha_act/output_dict.safetensors b/tests/data/save_policy_to_safetensors/aloha_act/output_dict.safetensors deleted file mode 100644 index e957acb8..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act/output_dict.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:e39afdf1f3db8a72a1095a5a0ffdb7e67f478a28bd73e59cda197687da8d236c -size 68 diff --git a/tests/data/save_policy_to_safetensors/aloha_act/param_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_act/param_stats.safetensors deleted file mode 100644 index 35ba61bd..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act/param_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:5dd39a554c9c3db537e98c9ceade024d172c46c4fa7ce9e27601b94116445417 -size 33400 diff --git a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/actions.safetensors b/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/actions.safetensors deleted file mode 100644 index ababdedf..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/actions.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:a5ec46abc5a3c85675a5ee4a1bb362eecb3ff4c546082ff309c89fc7821f38bd -size 515400 diff --git a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/grad_stats.safetensors deleted file mode 100644 index e0b2f54a..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/grad_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:50303d05caea725c4a240f1389424d6c2361961f2cee729a0010e909ebffed81 -size 31672 diff --git a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/output_dict.safetensors b/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/output_dict.safetensors deleted file mode 100644 index 3c5d3b93..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/output_dict.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:9bb9b195d32e05550af0edd5df88fcc761c829ab8c4b129ba970a723f39b46ee -size 68 diff --git a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/param_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/param_stats.safetensors deleted file mode 100644 index 88d3106e..00000000 --- a/tests/data/save_policy_to_safetensors/aloha_act_1000_steps/param_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:683a2038185f3d070e7d7c0c31e4aa75067c11bf798daa41c9fab336f4183fda -size 33400 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/actions.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/actions.safetensors new file mode 100644 index 00000000..6fec6b22 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/actions.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:cc67af1d60f95d84c98d6c9ebd648990e0f0705368bd6b72d2b39533950b0179 +size 5104 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/grad_stats.safetensors new file mode 100644 index 00000000..7136a69f --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/grad_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:64518cf652105d15f5fd2cfc13d0681f66a4ec4797dc5d5dc2f7b0d91fe5dfd6 +size 31672 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/output_dict.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/output_dict.safetensors new file mode 100644 index 00000000..864feebe --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/output_dict.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:32b6d14fab4244b5140adb345e47f662b6739c04974e04b21c3127caa988abbb +size 68 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/param_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/param_stats.safetensors new file mode 100644 index 00000000..bbabade6 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_/param_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:e1904ef0338f7b6efdec70ec235ee931b5751008bf4eb433edb0b3fa0838a4f1 +size 33400 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/actions.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/actions.safetensors new file mode 100644 index 00000000..1093b45d --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/actions.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:fa544a97f00bf46393a09b006b44c2499bbf7d177782360a8c21cacbf200c07a +size 515400 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/grad_stats.safetensors new file mode 100644 index 00000000..092e0040 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/grad_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:83c7a8ae912300b5cedba31904f7ba22542059fd60dd86548a95e415713f719e +size 31672 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/output_dict.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/output_dict.safetensors new file mode 100644 index 00000000..6561116c --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/output_dict.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5a010633237b3a1141603c65174c551daa9e7b4c474af5a1376d73e5425bfb5d +size 68 diff --git a/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/param_stats.safetensors b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/param_stats.safetensors new file mode 100644 index 00000000..09772ea3 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/aloha_sim_insertion_human_act_1000_steps/param_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:ec8b5c440e9fcec190c9be48b28ebb79f82ae63626afe7c811e4bb0c3dd08842 +size 33400 diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/actions.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/actions.safetensors deleted file mode 100644 index 40434950..00000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/actions.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:e56a5d30778395534a06ad1742843700424614168fc26d1098558012a5df90c6 -size 5104 diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/grad_stats.safetensors deleted file mode 100644 index a8c15716..00000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/grad_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:c9007dd51c748db4ecd6d75e70bdcabf8c312454ac97bf6710895a12e7288557 -size 31672 diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/output_dict.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/output_dict.safetensors deleted file mode 100644 index 95c598c7..00000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/output_dict.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:170bd8365dfd1e36e8f56814bf8bc2057aa0d035c41212b7ddd7e4b9feee1633 -size 68 diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/param_stats.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/param_stats.safetensors deleted file mode 100644 index 09a11d73..00000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/param_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:11884346b41ca102c672bb0f361ea9699d2f8b33bb503038b53cc7e7fafd281b -size 34920 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion/actions.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion/actions.safetensors deleted file mode 100644 index b021f63c..00000000 --- a/tests/data/save_policy_to_safetensors/pusht_diffusion/actions.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:0c259ea9c40aab3841ca35b2a2e708d8829b0a9163b2f9e5efd28f1c65848293 -size 4600 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion/grad_stats.safetensors deleted file mode 100644 index ad0300ca..00000000 --- a/tests/data/save_policy_to_safetensors/pusht_diffusion/grad_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:77cd4127a45ded2f75d85ca9c17537808517614ef16fb3035cebb1b45547acbf -size 47424 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion/output_dict.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion/output_dict.safetensors deleted file mode 100644 index 9c7143e5..00000000 --- a/tests/data/save_policy_to_safetensors/pusht_diffusion/output_dict.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:fcff4b736e95d685d56830b501f4542b081f4334f72d28a7415809f4d9d15d0f -size 68 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion/param_stats.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion/param_stats.safetensors deleted file mode 100644 index 1efb0765..00000000 --- a/tests/data/save_policy_to_safetensors/pusht_diffusion/param_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:60775e91ed550aae66cb0547ee4b0e38917f29172e942671e9361b3812364df6 -size 49120 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion_/actions.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion_/actions.safetensors new file mode 100644 index 00000000..84e14b97 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/pusht_diffusion_/actions.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a32376dde65a1562403afd1db3e56c7e6b987ebaf6c3c601336e77155b9e608c +size 992 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion_/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion_/grad_stats.safetensors new file mode 100644 index 00000000..54229791 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/pusht_diffusion_/grad_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:12ee532c53173d0361ebb979f087b229cc045aa3d9e6b94cfd4290af54fd1201 +size 47424 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion_/output_dict.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion_/output_dict.safetensors new file mode 100644 index 00000000..f2930399 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/pusht_diffusion_/output_dict.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:271b00cb2f0cd5fd26b1d53463638e3d1a6e92692ec625fcffb420ca190869e5 +size 68 diff --git a/tests/data/save_policy_to_safetensors/pusht_diffusion_/param_stats.safetensors b/tests/data/save_policy_to_safetensors/pusht_diffusion_/param_stats.safetensors new file mode 100644 index 00000000..e91cd08b --- /dev/null +++ b/tests/data/save_policy_to_safetensors/pusht_diffusion_/param_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:010c01181b95625051276d69cb4209423c21f2e30a3fa9464ae67064a2ba4c22 +size 49120 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/actions.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/actions.safetensors new file mode 100644 index 00000000..fa9bf06a --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/actions.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c5edc5600d7206f027cb696a597bc99fcdd9073a15fa130b8031c52c0a7c134b +size 200 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/grad_stats.safetensors new file mode 100644 index 00000000..8d90a671 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/grad_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a70e29263afdbff3a49d7041ff2d5065df75472b7c030cc8a5d12ab20d24cc10 +size 16904 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/output_dict.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/output_dict.safetensors new file mode 100644 index 00000000..cde6c6dc --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/output_dict.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c49a5b4d4df92c9564009780f5e286ddfca84ca2b1753557024057b3b36afb8b +size 164 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/param_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/param_stats.safetensors new file mode 100644 index 00000000..692377d1 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_mpc/param_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5f8d19a86065937cffdd3ca49caef87c59e67d419b28f40f2817bad892dc3170 +size 36312 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/actions.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/actions.safetensors new file mode 100644 index 00000000..7a0b165e --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/actions.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a9c08753ddc43b6c02a176418b81eb784146e59f4fc914591cbd3582ade392bb +size 200 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/grad_stats.safetensors new file mode 100644 index 00000000..8d90a671 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/grad_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:a70e29263afdbff3a49d7041ff2d5065df75472b7c030cc8a5d12ab20d24cc10 +size 16904 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/output_dict.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/output_dict.safetensors new file mode 100644 index 00000000..cde6c6dc --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/output_dict.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:c49a5b4d4df92c9564009780f5e286ddfca84ca2b1753557024057b3b36afb8b +size 164 diff --git a/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/param_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/param_stats.safetensors new file mode 100644 index 00000000..692377d1 --- /dev/null +++ b/tests/data/save_policy_to_safetensors/xarm_lift_medium_tdmpc_use_policy/param_stats.safetensors @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:5f8d19a86065937cffdd3ca49caef87c59e67d419b28f40f2817bad892dc3170 +size 36312 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/actions.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/actions.safetensors deleted file mode 100644 index e2fb68ac..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/actions.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:81457cfd193d9d46b6871071a3971c2901fefa544ab225576132772087b4cf3a -size 472 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/grad_stats.safetensors deleted file mode 100644 index cf756229..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/grad_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d796577863740e8fd643a056e9eff891e51a858ff66019eba11f0a982cb9e9c0 -size 16904 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/output_dict.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/output_dict.safetensors deleted file mode 100644 index f8863cfb..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/output_dict.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:4636751d82103a268ac7cf36f1e69f6356f356b9c40561a9fe8557bb9255e2ee -size 240 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/param_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/param_stats.safetensors deleted file mode 100644 index 8ce3c4f3..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_mpc/param_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b7d08c9518f1f15226e4efc6f2a8542d0f3e620c91421c7cacea07d9bd9025d6 -size 36312 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/actions.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/actions.safetensors deleted file mode 100644 index 1b3912ed..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/actions.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:6cdb181ba6acc4aa1209a9ea5dd783f077ff87760257de1026c33f8e2fb2b2b1 -size 472 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/grad_stats.safetensors deleted file mode 100644 index cf756229..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/grad_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:d796577863740e8fd643a056e9eff891e51a858ff66019eba11f0a982cb9e9c0 -size 16904 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/output_dict.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/output_dict.safetensors deleted file mode 100644 index f8863cfb..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/output_dict.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:4636751d82103a268ac7cf36f1e69f6356f356b9c40561a9fe8557bb9255e2ee -size 240 diff --git a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/param_stats.safetensors b/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/param_stats.safetensors deleted file mode 100644 index 8ce3c4f3..00000000 --- a/tests/data/save_policy_to_safetensors/xarm_tdmpcuse_policy/param_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b7d08c9518f1f15226e4efc6f2a8542d0f3e620c91421c7cacea07d9bd9025d6 -size 36312 diff --git a/tests/scripts/save_policy_to_safetensors.py b/tests/scripts/save_policy_to_safetensors.py index de784db3..03726163 100644 --- a/tests/scripts/save_policy_to_safetensors.py +++ b/tests/scripts/save_policy_to_safetensors.py @@ -27,16 +27,13 @@ from lerobot.configs.default import DatasetConfig from lerobot.configs.train import TrainPipelineConfig -def get_policy_stats(ds_repo_id, env_name, policy_name, policy_kwargs, train_kwargs): - # TODO(rcadene, aliberts): env_name? +def get_policy_stats(ds_repo_id: str, policy_name: str, policy_kwargs: dict): set_seed(1337) - train_cfg = TrainPipelineConfig( # TODO(rcadene, aliberts): remove dataset download dataset=DatasetConfig(repo_id=ds_repo_id, episodes=[0]), policy=make_policy_config(policy_name, **policy_kwargs), device="cpu", - **train_kwargs, ) train_cfg.validate() # Needed for auto-setting some parameters @@ -54,8 +51,11 @@ def get_policy_stats(ds_repo_id, env_name, policy_name, policy_kwargs, train_kwa batch = next(iter(dataloader)) loss, output_dict = policy.forward(batch) - output_dict = {k: v for k, v in output_dict.items() if isinstance(v, torch.Tensor)} - output_dict["loss"] = loss + if output_dict is not None: + output_dict = {k: v for k, v in output_dict.items() if isinstance(v, torch.Tensor)} + output_dict["loss"] = loss + else: + output_dict = {"loss": loss} loss.backward() grad_stats = {} @@ -101,30 +101,27 @@ def get_policy_stats(ds_repo_id, env_name, policy_name, policy_kwargs, train_kwa return output_dict, grad_stats, param_stats, actions -def save_policy_to_safetensors(output_dir, env_name, policy_name, policy_kwargs, file_name_extra): - env_policy_dir = Path(output_dir) / f"{env_name}_{policy_name}{file_name_extra}" +def save_policy_to_safetensors(output_dir: Path, ds_repo_id: str, policy_name: str, policy_kwargs: dict): + if output_dir.exists(): + print(f"Overwrite existing safetensors in '{output_dir}':") + print(f" - Validate with: `git add {output_dir}`") + print(f" - Revert with: `git checkout -- {output_dir}`") + shutil.rmtree(output_dir) - if env_policy_dir.exists(): - print(f"Overwrite existing safetensors in '{env_policy_dir}':") - print(f" - Validate with: `git add {env_policy_dir}`") - print(f" - Revert with: `git checkout -- {env_policy_dir}`") - shutil.rmtree(env_policy_dir) - - env_policy_dir.mkdir(parents=True, exist_ok=True) - output_dict, grad_stats, param_stats, actions = get_policy_stats(env_name, policy_name, policy_kwargs) - save_file(output_dict, env_policy_dir / "output_dict.safetensors") - save_file(grad_stats, env_policy_dir / "grad_stats.safetensors") - save_file(param_stats, env_policy_dir / "param_stats.safetensors") - save_file(actions, env_policy_dir / "actions.safetensors") + output_dir.mkdir(parents=True, exist_ok=True) + output_dict, grad_stats, param_stats, actions = get_policy_stats(ds_repo_id, policy_name, policy_kwargs) + save_file(output_dict, output_dir / "output_dict.safetensors") + save_file(grad_stats, output_dir / "grad_stats.safetensors") + save_file(param_stats, output_dir / "param_stats.safetensors") + save_file(actions, output_dir / "actions.safetensors") if __name__ == "__main__": - env_policies = [ - ("lerobot/xarm_lift_medium", "xarm", "tdmpc", {"use_mpc": False}, "use_policy"), - ("lerobot/xarm_lift_medium", "xarm", "tdmpc", {"use_mpc": True}, "use_mpc"), + artifacts_cfg = [ + ("lerobot/xarm_lift_medium", "tdmpc", {"use_mpc": False}, "use_policy"), + ("lerobot/xarm_lift_medium", "tdmpc", {"use_mpc": True}, "use_mpc"), ( "lerobot/pusht", - "pusht", "diffusion", { "n_action_steps": 8, @@ -133,18 +130,17 @@ if __name__ == "__main__": }, "", ), - ("lerobot/aloha_sim_insertion_human", "aloha", "act", {"n_action_steps": 10}, ""), + ("lerobot/aloha_sim_insertion_human", "act", {"n_action_steps": 10}, ""), ( "lerobot/aloha_sim_insertion_human", - "aloha", "act", {"n_action_steps": 1000, "chunk_size": 1000}, - "_1000_steps", + "1000_steps", ), ] - if len(env_policies) == 0: + if len(artifacts_cfg) == 0: raise RuntimeError("No policies were provided!") - for ds_repo_id, env, policy, policy_kwargs, file_name_extra in env_policies: - save_policy_to_safetensors( - "tests/data/save_policy_to_safetensors", ds_repo_id, env, policy, policy_kwargs, file_name_extra - ) + for ds_repo_id, policy, policy_kwargs, file_name_extra in artifacts_cfg: + ds_name = ds_repo_id.split("/")[-1] + output_dir = Path("tests/data/save_policy_to_safetensors") / f"{ds_name}_{policy}_{file_name_extra}" + save_policy_to_safetensors(output_dir, ds_repo_id, policy, policy_kwargs) diff --git a/tests/test_online_buffer.py b/tests/test_online_buffer.py index db53808d..339f6848 100644 --- a/tests/test_online_buffer.py +++ b/tests/test_online_buffer.py @@ -166,7 +166,7 @@ def test_delta_timestamps_within_tolerance(): buffer.tolerance_s = 0.04 item = buffer[2] data, is_pad = item["index"], item[f"index{OnlineBuffer.IS_PAD_POSTFIX}"] - assert torch.allclose(data, torch.tensor([0, 2, 3])), "Data does not match expected values" + torch.testing.assert_close(data, torch.tensor([0, 2, 3]), msg="Data does not match expected values") assert not is_pad.any(), "Unexpected padding detected" @@ -236,7 +236,7 @@ def test_compute_sampler_weights_trivial( elif online_sampling_ratio == 1: expected_weights = torch.cat([torch.zeros(offline_dataset_size), torch.ones(online_dataset_size)]) expected_weights /= expected_weights.sum() - assert torch.allclose(weights, expected_weights) + torch.testing.assert_close(weights, expected_weights) def test_compute_sampler_weights_nontrivial_ratio(lerobot_dataset_factory, tmp_path): @@ -248,7 +248,7 @@ def test_compute_sampler_weights_nontrivial_ratio(lerobot_dataset_factory, tmp_p weights = compute_sampler_weights( offline_dataset, online_dataset=online_dataset, online_sampling_ratio=online_sampling_ratio ) - assert torch.allclose( + torch.testing.assert_close( weights, torch.tensor([0.05, 0.05, 0.05, 0.05, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1, 0.1]) ) @@ -261,7 +261,7 @@ def test_compute_sampler_weights_nontrivial_ratio_and_drop_last_n(lerobot_datase weights = compute_sampler_weights( offline_dataset, online_dataset=online_dataset, online_sampling_ratio=0.8, online_drop_n_last_frames=1 ) - assert torch.allclose( + torch.testing.assert_close( weights, torch.tensor([0.05, 0.05, 0.05, 0.05, 0.2, 0.0, 0.2, 0.0, 0.2, 0.0, 0.2, 0.0]) ) @@ -279,4 +279,4 @@ def test_compute_sampler_weights_drop_n_last_frames(lerobot_dataset_factory, tmp online_sampling_ratio=0.5, online_drop_n_last_frames=1, ) - assert torch.allclose(weights, torch.tensor([0.5, 0, 0.125, 0, 0.125, 0, 0.125, 0, 0.125, 0])) + torch.testing.assert_close(weights, torch.tensor([0.5, 0, 0.125, 0, 0.125, 0, 0.125, 0, 0.125, 0])) diff --git a/tests/test_policies.py b/tests/test_policies.py index 27cf49f8..9dab6176 100644 --- a/tests/test_policies.py +++ b/tests/test_policies.py @@ -363,37 +363,33 @@ def test_normalize(insert_temporal_dim): @pytest.mark.parametrize( - "ds_repo_id, env_name, policy_name, policy_kwargs, train_kwargs, file_name_extra", + "ds_repo_id, policy_name, policy_kwargs, file_name_extra", [ # TODO(alexander-soare): `policy.use_mpc=false` was previously the default in the config yaml but it # was changed to true. For some reason, tests would pass locally, but not in CI. So here we override # to test with `policy.use_mpc=false`. - ("lerobot/xarm_lift_medium", "xarm", "tdmpc", {"use_mpc": False}, {"batch_size": 25}, "use_policy"), - # ("lerobot/xarm_lift_medium", "xarm", "tdmpc", {"use_mpc": True}, {}, "use_mpc"), + ("lerobot/xarm_lift_medium", "tdmpc", {"use_mpc": False}, "use_policy"), + ("lerobot/xarm_lift_medium", "tdmpc", {"use_mpc": True}, "use_mpc"), # TODO(rcadene): the diffusion model was normalizing the image in mean=0.5 std=0.5 which is a hack supposed to # to normalize the image at all. In our current codebase we dont normalize at all. But there is still a minor difference # that fails the test. However, by testing to normalize the image with 0.5 0.5 in the current codebase, the test pass. # Thus, we deactivate this test for now. - # ( - # "lerobot/pusht", - # "pusht", - # "diffusion", - # { - # "n_action_steps": 8, - # "num_inference_steps": 10, - # "down_dims": [128, 256, 512], - # }, - # {"batch_size": 64}, - # "", - # ), - ("lerobot/aloha_sim_insertion_human", "aloha", "act", {"n_action_steps": 10}, {}, ""), + ( + "lerobot/pusht", + "diffusion", + { + "n_action_steps": 8, + "num_inference_steps": 10, + "down_dims": [128, 256, 512], + }, + "", + ), + ("lerobot/aloha_sim_insertion_human", "act", {"n_action_steps": 10}, ""), ( "lerobot/aloha_sim_insertion_human", - "aloha", "act", {"n_action_steps": 1000, "chunk_size": 1000}, - {}, - "_1000_steps", + "1000_steps", ), ], ) @@ -401,9 +397,7 @@ def test_normalize(insert_temporal_dim): # pass if it's run on another platform due to floating point errors @require_x86_64_kernel @require_cpu -def test_backward_compatibility( - ds_repo_id, env_name, policy_name, policy_kwargs, train_kwargs, file_name_extra -): +def test_backward_compatibility(ds_repo_id: str, policy_name: str, policy_kwargs: dict, file_name_extra: str): """ NOTE: If this test does not pass, and you have intentionally changed something in the policy: 1. Inspect the differences in policy outputs and make sure you can account for them. Your PR should @@ -416,26 +410,26 @@ def test_backward_compatibility( 5. Remember to restore `tests/scripts/save_policy_to_safetensors.py` to its original state. 6. Remember to stage and commit the resulting changes to `tests/data`. """ - env_policy_dir = ( - Path("tests/data/save_policy_to_safetensors") / f"{env_name}_{policy_name}{file_name_extra}" + ds_name = ds_repo_id.split("/")[-1] + artifact_dir = ( + Path("tests/data/save_policy_to_safetensors") / f"{ds_name}_{policy_name}_{file_name_extra}" ) - saved_output_dict = load_file(env_policy_dir / "output_dict.safetensors") - saved_grad_stats = load_file(env_policy_dir / "grad_stats.safetensors") - saved_param_stats = load_file(env_policy_dir / "param_stats.safetensors") - saved_actions = load_file(env_policy_dir / "actions.safetensors") + saved_output_dict = load_file(artifact_dir / "output_dict.safetensors") + saved_grad_stats = load_file(artifact_dir / "grad_stats.safetensors") + saved_param_stats = load_file(artifact_dir / "param_stats.safetensors") + saved_actions = load_file(artifact_dir / "actions.safetensors") - output_dict, grad_stats, param_stats, actions = get_policy_stats( - ds_repo_id, env_name, policy_name, policy_kwargs, train_kwargs - ) + output_dict, grad_stats, param_stats, actions = get_policy_stats(ds_repo_id, policy_name, policy_kwargs) for key in saved_output_dict: - assert torch.allclose(output_dict[key], saved_output_dict[key], rtol=0.1, atol=1e-7) + torch.testing.assert_close(output_dict[key], saved_output_dict[key]) for key in saved_grad_stats: - assert torch.allclose(grad_stats[key], saved_grad_stats[key], rtol=0.1, atol=1e-7) + torch.testing.assert_close(grad_stats[key], saved_grad_stats[key]) for key in saved_param_stats: - assert torch.allclose(param_stats[key], saved_param_stats[key], rtol=0.1, atol=1e-7) + torch.testing.assert_close(param_stats[key], saved_param_stats[key]) for key in saved_actions: - assert torch.allclose(actions[key], saved_actions[key], rtol=0.1, atol=1e-7) + rtol, atol = (2e-3, 5e-6) if policy_name == "diffusion" else (None, None) # HACK + torch.testing.assert_close(actions[key], saved_actions[key], rtol=rtol, atol=atol) def test_act_temporal_ensembler(): @@ -490,4 +484,4 @@ def test_act_temporal_ensembler(): assert torch.all(einops.reduce(seq_slice, "b s 1 -> b 1", "min") <= offline_avg) assert torch.all(offline_avg <= einops.reduce(seq_slice, "b s 1 -> b 1", "max")) # Selected atol=1e-4 keeping in mind actions in [-1, 1] and excepting 0.01% error. - assert torch.allclose(online_avg, offline_avg, atol=1e-4) + torch.testing.assert_close(online_avg, offline_avg, rtol=1e-4, atol=1e-4) diff --git a/tests/test_robots.py b/tests/test_robots.py index fe440da8..c5734a4c 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -114,7 +114,7 @@ def test_robot(tmp_path, request, robot_type, mock): if "image" in name: # TODO(rcadene): skipping image for now as it's challenging to assess equality between two consecutive frames continue - assert torch.allclose(captured_observation[name], observation[name], atol=1) + torch.testing.assert_close(captured_observation[name], observation[name], rtol=1e-4, atol=1) assert captured_observation[name].shape == observation[name].shape # Test send_action can run From 8d60ac3ffcaa94b4e9aef77655fc7297a7ce47a2 Mon Sep 17 00:00:00 2001 From: Mishig Date: Wed, 26 Feb 2025 19:23:37 +0100 Subject: [PATCH 10/69] [vizualisation] Add pagination for many episodes (#776) --- .../templates/visualize_dataset_template.html | 144 ++++++++++++++---- 1 file changed, 111 insertions(+), 33 deletions(-) diff --git a/lerobot/templates/visualize_dataset_template.html b/lerobot/templates/visualize_dataset_template.html index 08de3e3d..e5a2f82c 100644 --- a/lerobot/templates/visualize_dataset_template.html +++ b/lerobot/templates/visualize_dataset_template.html @@ -14,21 +14,7 @@ - +
- + + -
- {% for episode in episodes %} -

- - {{ episode }} - -

- {% endfor %} +
+ +
+ +
+
@@ -452,6 +468,68 @@ } }; } + + document.addEventListener('alpine:init', () => { + // Episode pagination component + Alpine.data('episodePagination', () => ({ + episodes: {{ episodes }}, + pageSize: 100, + page: 1, + + init() { + // Find which page contains the current episode_id + const currentEpisodeId = {{ episode_id }}; + const episodeIndex = this.episodes.indexOf(currentEpisodeId); + if (episodeIndex !== -1) { + this.page = Math.floor(episodeIndex / this.pageSize) + 1; + } + }, + + get totalPages() { + return Math.ceil(this.episodes.length / this.pageSize); + }, + + get paginatedEpisodes() { + const start = (this.page - 1) * this.pageSize; + const end = start + this.pageSize; + return this.episodes.slice(start, end); + }, + + nextPage() { + if (this.page < this.totalPages) { + this.page++; + } + }, + + prevPage() { + if (this.page > 1) { + this.page--; + } + } + })); + }); + + + From 68b369e321b2124050f04212b99c236845682d81 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Thu, 27 Feb 2025 12:13:36 +0100 Subject: [PATCH 11/69] Fix pr_style_bot (#781) --- .github/workflows/pr_style_bot.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/pr_style_bot.yml b/.github/workflows/pr_style_bot.yml index a34042c4..e0a5c774 100644 --- a/.github/workflows/pr_style_bot.yml +++ b/.github/workflows/pr_style_bot.yml @@ -41,7 +41,7 @@ jobs: HEADREPOFULLNAME: ${{ steps.pr_info.outputs.headRepoFullName }} HEADREF: ${{ steps.pr_info.outputs.headRef }} with: - persist-credentials: false + persist-credentials: true # Instead of checking out the base repo, use the contributor's repo name repository: ${{ env.HEADREPOFULLNAME }} ref: ${{ env.HEADREF }} From bba8c4c0d436a85193e9f0e402c13c71b7ed2dc0 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Thu, 27 Feb 2025 13:09:12 +0100 Subject: [PATCH 12/69] Fix pr_style bot (#782) --- .github/workflows/pr_style_bot.yml | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/workflows/pr_style_bot.yml b/.github/workflows/pr_style_bot.yml index e0a5c774..f62f10c8 100644 --- a/.github/workflows/pr_style_bot.yml +++ b/.github/workflows/pr_style_bot.yml @@ -55,9 +55,9 @@ jobs: HEADREF: ${{ steps.pr_info.outputs.headRef }} PRNUMBER: ${{ steps.pr_info.outputs.prNumber }} run: | - echo "PR number: $PRNUMBER" - echo "Head Ref: $HEADREF" - echo "Head Repo Full Name: $HEADREPOFULLNAME" + echo "PR number: ${PRNUMBER}" + echo "Head Ref: ${HEADREF}" + echo "Head Repo Full Name: ${HEADREPOFULLNAME}" - name: Set up Python uses: actions/setup-python@v4 @@ -87,20 +87,20 @@ jobs: PRNUMBER: ${{ steps.pr_info.outputs.prNumber }} GITHUB_TOKEN: ${{ secrets.GITHUB_TOKEN }} run: | - echo "HEADREPOFULLNAME: $HEADREPOFULLNAME, HEADREF: $HEADREF" + echo "HEADREPOFULLNAME: ${HEADREPOFULLNAME}, HEADREF: ${HEADREF}" # Configure git with the Actions bot user git config user.name "github-actions[bot]" git config user.email "github-actions[bot]@users.noreply.github.com" # Make sure your 'origin' remote is set to the contributor's fork - git remote set-url origin "https://x-access-token:${GITHUB_TOKEN}@github.com/$HEADREPOFULLNAME.git" + git remote set-url origin "https://x-access-token:${GITHUB_TOKEN}@github.com/${HEADREPOFULLNAME}.git" # If there are changes after running style/quality, commit them if [ -n "$(git status --porcelain)" ]; then git add . git commit -m "Apply style fixes" # Push to the original contributor's forked branch - git push origin HEAD:$HEADREF + git push origin HEAD:${HEADREF} echo "changes_pushed=true" >> $GITHUB_OUTPUT else echo "No changes to commit." From 800c4a847f1b4055624d19995e5917193e157123 Mon Sep 17 00:00:00 2001 From: Mishig Date: Thu, 27 Feb 2025 14:47:18 +0100 Subject: [PATCH 13/69] [Vizualisation] independent column names (#783) --- lerobot/scripts/visualize_dataset_html.py | 5 +++-- lerobot/templates/visualize_dataset_template.html | 11 ++++++----- 2 files changed, 9 insertions(+), 7 deletions(-) diff --git a/lerobot/scripts/visualize_dataset_html.py b/lerobot/scripts/visualize_dataset_html.py index ac91f0c8..a0da0869 100644 --- a/lerobot/scripts/visualize_dataset_html.py +++ b/lerobot/scripts/visualize_dataset_html.py @@ -245,16 +245,17 @@ def get_episode_data(dataset: LeRobotDataset | IterableNamespace, episode_index) if isinstance(dataset, LeRobotDataset) else dataset.features[column_name].shape[0] ) - header += [f"{column_name}_{i}" for i in range(dim_state)] if "names" in dataset.features[column_name] and dataset.features[column_name]["names"]: column_names = dataset.features[column_name]["names"] while not isinstance(column_names, list): column_names = list(column_names.values())[0] else: - column_names = [f"motor_{i}" for i in range(dim_state)] + column_names = [f"{column_name}_{i}" for i in range(dim_state)] columns.append({"key": column_name, "value": column_names}) + header += column_names + selected_columns.insert(0, "timestamp") if isinstance(dataset, LeRobotDataset): diff --git a/lerobot/templates/visualize_dataset_template.html b/lerobot/templates/visualize_dataset_template.html index e5a2f82c..d81ce630 100644 --- a/lerobot/templates/visualize_dataset_template.html +++ b/lerobot/templates/visualize_dataset_template.html @@ -246,14 +246,16 @@
-

- @@ -476,7 +476,7 @@ episodes: {{ episodes }}, pageSize: 100, page: 1, - + init() { // Find which page contains the current episode_id const currentEpisodeId = {{ episode_id }}; @@ -485,23 +485,23 @@ this.page = Math.floor(episodeIndex / this.pageSize) + 1; } }, - + get totalPages() { return Math.ceil(this.episodes.length / this.pageSize); }, - + get paginatedEpisodes() { const start = (this.page - 1) * this.pageSize; const end = start + this.pageSize; return this.episodes.slice(start, end); }, - + nextPage() { if (this.page < this.totalPages) { this.page++; } }, - + prevPage() { if (this.page > 1) { this.page--; @@ -515,7 +515,7 @@ window.addEventListener('keydown', (e) => { // Use the space bar to play and pause, instead of default action (e.g. scrolling) const { keyCode, key } = e; - + if (keyCode === 32 || key === ' ') { e.preventDefault(); const btnPause = document.querySelector('[x-ref="btnPause"]'); diff --git a/pyproject.toml b/pyproject.toml index 7684ce48..9a7c9730 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -111,10 +111,19 @@ exclude = [ "venv", ] - [tool.ruff.lint] select = ["E4", "E7", "E9", "F", "I", "N", "B", "C4", "SIM"] +[tool.bandit] +exclude_dirs = [ + "tests", + "benchmarks", + "lerobot/common/datasets/push_dataset_to_hub", + "lerobot/common/datasets/v2/convert_dataset_v1_to_v2", + "lerobot/common/policies/pi0/conversion_scripts", + "lerobot/scripts/push_dataset_to_hub.py", +] +skips = ["B101", "B311", "B404", "B603"] [tool.typos] default.extend-ignore-re = [ From bf6f89a5b5a5526766a53ffa337d65ff13dcb5e8 Mon Sep 17 00:00:00 2001 From: Steven Palma Date: Mon, 3 Mar 2025 17:01:04 +0100 Subject: [PATCH 21/69] fix(examples): Add Tensor type check (#799) --- examples/3_train_policy.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/3_train_policy.py b/examples/3_train_policy.py index cf5d4d3e..f6eabbfa 100644 --- a/examples/3_train_policy.py +++ b/examples/3_train_policy.py @@ -85,7 +85,7 @@ def main(): done = False while not done: for batch in dataloader: - batch = {k: v.to(device, non_blocking=True) for k, v in batch.items()} + batch = {k: (v.to(device) if isinstance(v, torch.Tensor) else v) for k, v in batch.items()} loss, _ = policy.forward(batch) loss.backward() optimizer.step() From b299cfea8a2356b033d0ed46207dce2e0924fc12 Mon Sep 17 00:00:00 2001 From: Pepijn <138571049+pkooij@users.noreply.github.com> Date: Tue, 4 Mar 2025 09:57:37 +0100 Subject: [PATCH 22/69] Add step assembly tutorial (#800) --- examples/10_use_so100.md | 227 ++++++++++++++++++++++++++++++++++++--- media/tutorial/img1.jpg | Bin 0 -> 67855 bytes media/tutorial/img10.jpg | Bin 0 -> 129990 bytes media/tutorial/img11.jpg | Bin 0 -> 111488 bytes media/tutorial/img12.jpg | Bin 0 -> 81939 bytes media/tutorial/img13.jpg | Bin 0 -> 90551 bytes media/tutorial/img14.jpg | Bin 0 -> 88316 bytes media/tutorial/img15.jpg | Bin 0 -> 98726 bytes media/tutorial/img16.jpg | Bin 0 -> 86507 bytes media/tutorial/img17.jpg | Bin 0 -> 73468 bytes media/tutorial/img18.jpg | Bin 0 -> 79960 bytes media/tutorial/img19.jpg | Bin 0 -> 99177 bytes media/tutorial/img2.jpg | Bin 0 -> 90672 bytes media/tutorial/img20.jpg | Bin 0 -> 43387 bytes media/tutorial/img21.jpg | Bin 0 -> 86694 bytes media/tutorial/img22.jpg | Bin 0 -> 63458 bytes media/tutorial/img23.jpg | Bin 0 -> 55148 bytes media/tutorial/img24.jpg | Bin 0 -> 62354 bytes media/tutorial/img25.jpg | Bin 0 -> 77381 bytes media/tutorial/img26.jpg | Bin 0 -> 81866 bytes media/tutorial/img27.jpg | Bin 0 -> 49286 bytes media/tutorial/img28.jpg | Bin 0 -> 93048 bytes media/tutorial/img29.jpg | Bin 0 -> 55617 bytes media/tutorial/img3.jpg | Bin 0 -> 87554 bytes media/tutorial/img30.jpg | Bin 0 -> 58339 bytes media/tutorial/img31.jpg | Bin 0 -> 85916 bytes media/tutorial/img32.jpg | Bin 0 -> 89561 bytes media/tutorial/img4.jpg | Bin 0 -> 71612 bytes media/tutorial/img5.jpg | Bin 0 -> 67065 bytes media/tutorial/img6.jpg | Bin 0 -> 65468 bytes media/tutorial/img7.jpg | Bin 0 -> 90926 bytes media/tutorial/img8.jpg | Bin 0 -> 76325 bytes media/tutorial/img9.jpg | Bin 0 -> 83830 bytes 33 files changed, 213 insertions(+), 14 deletions(-) create mode 100644 media/tutorial/img1.jpg create mode 100644 media/tutorial/img10.jpg create mode 100644 media/tutorial/img11.jpg create mode 100644 media/tutorial/img12.jpg create mode 100644 media/tutorial/img13.jpg create mode 100644 media/tutorial/img14.jpg create mode 100644 media/tutorial/img15.jpg create mode 100644 media/tutorial/img16.jpg create mode 100644 media/tutorial/img17.jpg create mode 100644 media/tutorial/img18.jpg create mode 100644 media/tutorial/img19.jpg create mode 100644 media/tutorial/img2.jpg create mode 100644 media/tutorial/img20.jpg create mode 100644 media/tutorial/img21.jpg create mode 100644 media/tutorial/img22.jpg create mode 100644 media/tutorial/img23.jpg create mode 100644 media/tutorial/img24.jpg create mode 100644 media/tutorial/img25.jpg create mode 100644 media/tutorial/img26.jpg create mode 100644 media/tutorial/img27.jpg create mode 100644 media/tutorial/img28.jpg create mode 100644 media/tutorial/img29.jpg create mode 100644 media/tutorial/img3.jpg create mode 100644 media/tutorial/img30.jpg create mode 100644 media/tutorial/img31.jpg create mode 100644 media/tutorial/img32.jpg create mode 100644 media/tutorial/img4.jpg create mode 100644 media/tutorial/img5.jpg create mode 100644 media/tutorial/img6.jpg create mode 100644 media/tutorial/img7.jpg create mode 100644 media/tutorial/img8.jpg create mode 100644 media/tutorial/img9.jpg diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index b39a0239..23da1eab 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -4,8 +4,8 @@ - [A. Source the parts](#a-source-the-parts) - [B. Install LeRobot](#b-install-lerobot) - - [C. Configure the motors](#c-configure-the-motors) - - [D. Assemble the arms](#d-assemble-the-arms) + - [C. Configure the Motors](#c-configure-the-motors) + - [D. Step-by-Step Assembly Instructions](#d-step-by-step-assembly-instructions) - [E. Calibrate](#e-calibrate) - [F. Teleoperate](#f-teleoperate) - [G. Record a dataset](#g-record-a-dataset) @@ -70,6 +70,7 @@ conda install -y -c conda-forge "opencv>=4.10.0" ``` Great :hugs:! You are now done installing LeRobot and we can begin assembling the SO100 arms :robot:. Every time you now want to use LeRobot you can go to the `~/lerobot` folder where we installed LeRobot and run one of the commands. + ## C. Configure the motors > [!NOTE] @@ -221,19 +222,13 @@ Redo the process for all your motors until ID 6. Do the same for the 6 motors of Follow the video for removing gears. You need to remove the gear for the motors of the leader arm. As a result, you will only use the position encoding of the motor and reduce friction to more easily operate the leader arm. -#### c. Add motor horn to all 12 motors +## D. Step-by-Step Assembly Instructions -
-Video adding motor horn +**Step 1: Clean Parts** +- Remove all support material from the 3D-printed parts. +--- - - -
- -Follow the video for adding the motor horn. For SO-100, you need to align the holes on the motor horn to the motor spline to be approximately 1:30, 4:30, 7:30 and 10:30. -Try to avoid rotating the motor while doing so to keep position 2048 set during configuration. It is especially tricky for the leader motors as it is more sensible without the gears, but it's ok if it's a bit rotated. - -## D. Assemble the arms +### Additional Guidance
Video assembling arms @@ -242,7 +237,211 @@ Try to avoid rotating the motor while doing so to keep position 2048 set during
-Follow the video for assembling the arms. It is important to insert the cables into the motor that is being assembled before you assemble the motor into the arm! Inserting the cables beforehand is much easier than doing this afterward. The first arm should take a bit more than 1 hour to assemble, but once you get used to it, you can do it under 1 hour for the second arm. +**Note:** +This video provides visual guidance for assembling the arms, but it doesn't specify when or how to do the wiring. Inserting the cables beforehand is much easier than doing it afterward. The first arm may take a bit more than 1 hour to assemble, but once you get used to it, you can assemble the second arm in under 1 hour. + +--- + +### First Motor + +**Step 2: Insert Wires** +- Insert two wires into the first motor. + + + +**Step 3: Install in Base** +- Place the first motor into the base. + + + +**Step 4: Secure Motor** +- Fasten the motor with 4 screws. Two from the bottom and two from top. + +**Step 5: Attach Motor Holder** +- Slide over the first motor holder and fasten it using two screws (one on each side). + + + +**Step 6: Attach Motor Horns** +- Install both motor horns, securing the top horn with a screw. Try not to move the motor position when attaching the motor horn, especially for the leader arms, where we removed the gears. + + +
+ Video adding motor horn + +
+ +**Step 7: Attach Shoulder Part** +- Route one wire to the back of the robot and the other to the left or in photo towards you (see photo). +- Attach the shoulder part. + + + +**Step 8: Secure Shoulder** +- Tighten the shoulder part with 4 screws on top and 4 on the bottom +*(access bottom holes by turning the shoulder).* + +--- + +### Second Motor Assembly + +**Step 9: Install Motor 2** +- Slide the second motor in from the top and link the wire from motor 1 to motor 2. + + + +**Step 10: Attach Shoulder Holder** +- Add the shoulder motor holder. +- Ensure the wire from motor 1 to motor 2 goes behind the holder while the other wire is routed upward (see photo). +- This part can be tight to assemble, you can use a workbench like the image or a similar setup to push the part around the motor. + +
+ + + +
+ +**Step 11: Secure Motor 2** +- Fasten the second motor with 4 screws. + +**Step 12: Attach Motor Horn** +- Attach both motor horns to motor 2, again use the horn screw. + +**Step 13: Attach Base** +- Install the base attachment using 2 screws. + + + +**Step 14: Attach Upper Arm** +- Attach the upper arm with 4 screws on each side. + + + +--- + +### Third Motor Assembly + +**Step 15: Install Motor 3** +- Route the motor cable from motor 2 through the cable holder to motor 3, then secure motor 3 with 4 screws. + +**Step 16: Attach Motor Horn** +- Attach both motor horns to motor 3 and secure one again with a horn screw. + + + +**Step 17: Attach Forearm** +- Connect the forearm to motor 3 using 4 screws on each side. + + + +--- + +### Fourth Motor Assembly + +**Step 18: Install Motor 4** +- Slide in motor 4, attach the cable from motor 3, and secure the cable in its holder with a screw. + +
+ + +
+ +**Step 19: Attach Motor Holder 4** +- Install the fourth motor holder (a tight fit). Ensure one wire is routed upward and the wire from motor 3 is routed downward (see photo). + + + +**Step 20: Secure Motor 4 & Attach Horn** +- Fasten motor 4 with 4 screws and attach its motor horns, use for one a horn screw. + + + +--- + +### Wrist Assembly + +**Step 21: Install Motor 5** +- Insert motor 5 into the wrist holder and secure it with 2 front screws. + + + +**Step 22: Attach Wrist** +- Connect the wire from motor 4 to motor 5. And already insert the other wire for the gripper. +- Secure the wrist to motor 4 using 4 screws on both sides. + + + +**Step 23: Attach Wrist Horn** +- Install only one motor horn on the wrist motor and secure it with a horn screw. + + + +--- + +### Follower Configuration + +**Step 24: Attach Gripper** +- Attach the gripper to motor 5. + + + +**Step 25: Install Gripper Motor** +- Insert the gripper motor, connect the motor wire from motor 5 to motor 6, and secure it with 3 screws on each side. + + + +**Step 26: Attach Gripper Horn & Claw** +- Attach the motor horns and again use a horn screw. +- Install the gripper claw and secure it with 4 screws on both sides. + + + +**Step 27: Mount Controller** +- Attach the motor controller on the back. + +
+ + +
+ +*Assembly complete – proceed to Leader arm assembly.* + +--- + +### Leader Configuration + +For the leader configuration, perform **Steps 1–23**. Make sure that you removed the motor gears from the motors. + +**Step 24: Attach Leader Holder** +- Mount the leader holder onto the wrist and secure it with a screw. + + + +**Step 25: Attach Handle** +- Attach the handle to motor 5 using 4 screws. + + + +**Step 26: Install Gripper Motor** +- Insert the gripper motor, secure it with 3 screws on each side, attach a motor horn using a horn screw, and connect the motor wire. + + + +**Step 27: Attach Trigger** +- Attach the follower trigger with 4 screws. + + + +**Step 28: Mount Controller** +- Attach the motor controller on the back. + +
+ + +
+ +*Assembly complete – proceed to calibration.* + ## E. Calibrate diff --git a/media/tutorial/img1.jpg b/media/tutorial/img1.jpg new file mode 100644 index 0000000000000000000000000000000000000000..c16fbf5e9204d8a00d44434b86a289fd25344d01 GIT binary patch literal 67855 zcmb4qbyQo;7wrvR+#QO$yO$PsE$&j>T^rn?5Ttlm(d;toZF1Z#1J0>umcUiy1$ zz5m~2tt6MZ>rR-NbI#uTocRy_-zI>ss;Hs}fIt8MLcD8PWENpTd9C87AYI=eH@Ah9GK!AaYg7O&|!~h@>fRG75{|y1u0Dy!HLNwt2 zH4qXq3Mv{p2BKFPA3#C^AtNK9pdg`Ppdurq0w5#;WE6USRKnLf)@VcwUc>?s>5L_U zZ*-ykbLb?bayH%>TTIM)krzVpm%_GX`caV5X2g>y|Bdml{l8%lPx?0wqK}mT@n<9? z=1|%^;wIYRxG4#_PXT02|SV=pX=I0gnnX@wggAr~Y(JI1iL0 z5pqCN6BvaLbKUwN=_Tq5SGBQ-Xk|Mc&OLyTk+d$fIe|gmVCVymx7vCH^SF+X5|cZ& zqen{LL*p>z`k5FC=#oK)1 zKNSu#Dr-mg9d3sbhC11J6~8F!pD2Q3EuNLW-|P;j>Yuhqp2rk87`vUdySvTL?VTsK zR7IMWO&|XD@4WE${oR_{2$@W64lc^C@p`m4yfK%QUTqn0@@^j&3J%XHK2GXUi&^xV zc9&M&za0z(y#DSyjkjm{m0(#R23f?ShaJ;P_BD zAq5r|`~|!&B_@KC$fi58&r04OWNqilg(e_Eij0L1jKrsbn@+jnjfqb+z#l&~;Zx{X zk+l<8gTaZm3EthYH0jV4 z;?p-!W8};lYTAy4Y>0|@Teqw4jq#G0$WM$1%aO34o+r=jNq0p--!?7!%U6ckwR+O$ zKMt~gctk$66qN~^w@$Tp`b1M#E|v!e@OwWVd|jio7xv~|7;V<%K9|GhK36jrySVK% zk3=g^+@j=-_UPZ6KD&Jie`Qoa_G$MBheQ6AQ1wpzawF%7ND-U(6o+Im_bV#$FGk#z z0oUzLOui2DSlgj-6|D-{=lCI;Q@n z;O%=YCP~+rZ9TvJ(BW2}zBY)d!mzzJQ~V$B5f=5*NBP>ESNTelKrH||Id`<4C;fBq zS$dFiim83gR^)8|VXd)pkVdA6d}oU&q*Tj>cbzXfv7#4Vkc-}L!*EYGF2IxirZXhn zl`BE^0beEE73F6Q@ha7N8Y<3XQs0XUeD414!3coBE_$g?p3V0K0L}skD0h9O!Lce# zd7&S#G~CT|e;->iO=BUw z)g$A})Q+UR-HZl`yD)!Y2uhiu zc22Rg+wX@?4$zqlnYg4J_e@r^>8qy2wOOYF{b1bUqGHyZe(7}hoLvp8-P(B7tWXf~C8Nsdk$4xh+;7H$%xh=D z`6Ff@OsG$elg=gG$XLEFCIv+qg;cxG0Kk^R*8qr+O2A+=B!C=)3k?ZjAaqbZaxlWG z02CB#e}yI-a@2S<7E(@PfKFg8IVFOW9AMBM7!u%;1fiyDP505~>d7%kGCMP=;Hzi6 zbFSFU`e2sPOhCUv14UKD@DF zcUAQK8Sm4R0_-pC@ch>M__-6tw7~7NnMCg!y`S#O<8J zDXtGf!=5fuMZHu>w*`!DjGAJ)t(2h}<0eA;buP~E-}WJ4X76$Zgj(gV@7MQy-}a~! znv>#EDMHhDA(M|Ot5U?-qdsa$cDD1|pW&xYmzU!OwFlFyp0+A1dJDpwXr!kwcCNtU z#2cwNi({d3h+ij*pzp-7)PI1*F^~CNa+{bKqdVMLP))D8d$svc;SIaaY43F{kNu0S@f!@*#c+}f|mNR4YejRke z4*9Rm+~tXEUJTo&ENyi69PIV+zsBuOW-=;oOG~-aZM{ngKk9{`{$vh2s%6;MH-cLX zhwX;j+#vllC9wQ{X%nO^(k`tU?$~1`(*0|f>Ul!O@vqwh+ESDgLxSBMXHfTmTUEC^ ztMoSt8JBRyt5$O=u9o$|Y=f0jpD%0t_Bkw+dKm@|=d9ukWhAzT5jJT4*1VqhPXIFh z+B)b8X9lXt7`5-CZ|`4lTv=8O;nkr)uw|Z&b)Aq+mK{ z`U3MBOZRM$F`&v1HkUe2Z7A|%^1Ozv(3lZzB|fBC&;4G=aHvXZFB|k-f9_y(Xn|?< z5{8e4Q^BStCD&xZxaV|SPtzEfMZ}l z>7M0D6_mMT?bYoR-_=PnoWcm{lJVpwf_6WHTU_OM~; zs)a>-WnUgFld$xdHrVk)gSKSnSBi$Nv)Wu$i;||XyTq{AuaL%8KdB9}*Rw5qqn``- z>NItt?G|}nopn6?HqA5Xb~l?c^jQh!MR#ckbyy7k!8>^DZEI97N*%aB)F3A2X>gwQ z3Xf(d`{&wn^j&AdfFzY~p3^}VTWhzDCbjN3Gx^oZ&97(~l6j?yyAww8gPethpB^bW z_XQ6@EYiz!qh^8U-&k<7s61Y2>@En=x7G>E+Bx z++YxT#bGR9`eUW&)!tJfFVn}fa0s4n_GpMooa4u9BaXUrC%#MNBTGT4?q=ut?H${i zRN@?{Cbo*faK{ywQGTbmWzFTx@#=6AmHAq+$cf2=-Pm^SkNc>azxEp)+XtdKoE|=l z!?Bg?f<4PR(o!^Q!WG^Mo@uU5q{F(+d;YhVw$+f#H)_oino`)Km?|fVI z)IlvjHB8Jjbq#{2<32sCl(kM4rm{q-@3DOj$1Cx5qxOCDW2yNH&EN2RpkY(69VO=> zB(5;U)Z@&2N}m$t;LMz;$WCM}USEh(Z)V;t*%#CjO;s&&=7G2gOr0wo{L*NlZZSsB z@ena*S+lS|=`fvWEc~A8-ocr<;_LR=xb2QT+b+vE&zO=UTWjA%rM0RcYO0sTP(-OC zNBykv;KhMJ)j20m%2%l$JQ`3P zwo$JVHkKblyGPnPlm?2fQ_k$;99llKissptHQ8?E-VN#UKlbd(Pb0F66`(5wg$47s zAdD9P1PgQlvO;d^#5V!KXTfN(N`1?yxZ@0*aK{%o!3q5FS(lA(izrj|*!de}zsXa!w1#O)pYI{WN9 z^8)gl=Dmu%Fl@<+KNO=l}dqDt3gRq%FUmU@$r`-Ba_}DJQyQyKWK+& zSA414OIZvK^12<~nAfuNyS|b-PhuH6ciMID;n92hV{Wg8x8qF0!u?5gWz!c{nPxoa zM^(Pk!1;M+GIeJjJ23?N=37L(4Tl~{OgtJ=6VD(BkfTY6FPR01C7EQo7_1cdI+5O3 z`y+@33c!g4;E#d(UR&|uM;_6OZ~~u@hTu4;iNkg!a3gS{<7=xo>>WLGaA+rc1YuS;_-Z>{?p5ye#}TJ}z(*7JSqHvRsVf5|iU zxFJkqzDzUI(T%ommQkr&P!n-rIXw$iSol$;!yM3YK-K0@hV4f_aaN_KlMx=ov*7G@ zHUpt7cD`oVJ>aztZxD3xVr4g7UqRK^OC(M)+TLUG+#SF9=FY9r%{w5??-E=j%Ip=T z+1?sfMa#3nME9wRMAccROGfXa$jGsIkg4dEHTa>X;&PZWwlpj# zX;pc+I6m}R9`m^C=x&_4q`h<=333)I)H39H$m>pC4HWG#_?`7i&yI18Ce8fVNz7|w zb*$Fz!HJhix7>Md`&W*SlK4i5z=Um5I0Q3Q7z&@?_I6HBLz7gYjjB8<*dsCAY(3ig zalY{*>eH`r3RTvor*s`NCZ9)(Jc%%gHUAW2f$$Mq(#$K0D|?%QH9<`SXGPs?n}l80 z7-!+y(8jJ`3!IV>PRo3To6kaGEo;jlD=5 zYb@OW$NKvSpVI*}k@$B2IT%fVQIi%g`$k)%EO44eN70N24vhWm*RSHRhYMD(wrGrS01spyLqSPMJ;`{X!Ov>7x$vf zq|;$|31)|#OdI&j{z)n(O={s9@QritOV!-jp%WD@(xWMc=d;nE+n zBLV&Czj^);sU-^kUCB=M>?|6Y(UB|uoALF2iOPUSgYb3e##PWa!p#%MX8oOBh`@2X zar+}KMa_pnwLsh+=N%0!Ug?SuRNM^rTN_&}#AjMwwZQxV*qAOX{yBwNv z8TDC%ThXJnk$S<=!mv921%LkIohalqNzb|QsltO9KjqXgxuT!zYHA77D(C9_-up94 zqDTDZuEDffpR%ijtV!;|<3yDrk6tR@JCx3llJAa_7UcM>1z)IN-J})Xo@eKm)sbfw zFq?M?C4Tj;@t4jxu$^}y=09>^*Qg+Gd#e<4{P=V5sES?fWXxw|J;}mnTc$FzYK=R4 z>|vxuhijz*fl-%F^6qjt6W!}JD>ei-M$_to>i^MY+_SulRyk@X()x6P#`mO@v1J>~ z#Qs7bojDf<%Z4|2_WdtxHkj=T#eO?SE#NW zAmU$<5t4=hW!TF#t^p#D)Gb>PHOJ6w!?-==)wvR?c9@EvjD0 zm-P21Rr8s(S6#v>XI!E4svpzYuVjymjnO;0h+D;v&RzP>Q>7qPy+bpGnyI3#`|+2G z%98ade4(^b#UZKZFNxFji3hQ*)`T;=ssId@H?qN}lSl4Uz4;43H5qDH7C}fD?<}7OTAX+Z&)0AZ0)! zrNazOR*Cr#8-c;a4qs!mZAKckQ&fmWLSj!&iAmS(j*YJrdRLRtOe*xfP6I@R#ZZZ) zj#T)uGqph?Osew75oNQ6B6ktq_Kz>nodV)k<>@xx(7<0w!LZ3}FWudXMXnWHvsR~L z%Bt!acG2CLiX8X1ymE6aWn^t%??Y(wE4K@7+)37&3y8OW<|`GPz+hVDkc)M3&(it7 z?;dUfcVP3$EZGx3j;N(pEE@Hs>UAMIv%j}ea?NVzgzeI)`8StI4h>T!Dfx$69i&Aw)nx2Jv&FFEre zYpgDx4h_Q0Bx_qGyJQNngZPemV{%zdYdDo64qH<58NKV5e@hxmWG+ziPr>v*Yo^I~ z@0tAvn5cbrcF5P`(sUYmncKki&^z>OuEq4na=zzdQGSEVd(bDBuKNx{8OH}D!=-Nz z1$tkC#XQd@A*_-jN)Sd!XfM-+T!=ltrf!)lqfXge)`A${#;TWraVn3Va-x1pr+{Mg-AuHM2 z+%XAVjCQL%5L*UGNwJR@NFNuW*q?fJ&J{tLFo?x|3UzMql%?fcuwhiHSEH{N%WCsk{L=&N%gVT`%hw~99FZZ(V)nuYh?OPWP2P9xuqEYaFuu_lQ< zf8WhSe;iy7;nn<`$5RjjoZE&uh-FA8+QMqbo=%pKfK3Erz-Xn@{0de1}Rm zB(a8*+)CjV`NE{%D^LAQVXVUWrAZB|?_z)&(Y9p{_JIL_jS>Lxafj%bNaeA<@If)q zNRdD>N#G`$c#U{;D>#@PZWNJ)J8Xkb*u-cHdO)KOFDJxjZ5MD;h&iW|RUH@tX$}mb zU~|bTNYb1t_9bRm+aR&S$0ATZ7!zcCmXlYs*9937=+dNb*2=t1qjJlrEnMo1_U$z8 zId&NS%X&N`6ZBf;cgIOM--&N!X1k2(=P9lZdzPm{vCC!GJ$>;2<<^&qyZmyU78M;l z{Od=$@~r98<`wV~%Nj+tHcpWN;mw`GkSBNPjVg@u^usSSw8mc=IaDgX)%K6h+n!J4 zn=&qL88un`igmJeb1$rQh|7_bk?9fC>0eUVa`UVkkE0qFdNL005}c{Y4C%@Ueau7X z+PEJz+bld7bM$oDlwu6gJv0*Y_>Z7o&{ddidC?%p!+(H_e-1;kv(eq(#eDvX9+fll zTGy#q((jf;H_Wh3kFn%h7KQFWMWzk2hO$uv34c#eGtM^YF-dY7m^<02(e|$1zv5tq zHN-fBU7Yrm|Kn)hPv>5g(76ik#7mZRuNls^+3nFK)>LU&+1HA}HR9_2vOzb|LCH=t zk>%=C>W=ecQAgkBc~jc8vcnLo^10!|PBI9Si1c)^I@CsaeIw;l;@ZByc6`)jTzS1(%YDV z1nd(yMx3N4nC`fWhH(l`%5f6MTIJd&wW_dz^GyWy!dAATkGBHdfxy^uSK4@E2vY*k z;%sEKN0|61$v+HG0!Xp^L6r7#0yo%dJb5||dcp+bR8h#AKPeCY8r1GH@8|9?PaiDF zNFCiJab>y}7PF6ib_*$V7~vp;vUQIIQTh(2*!r1c3;5ROdv%Jpvku&d?)V2j*!~La zI2Z1ZdRkJ%E@)H2Tl<;$gC{$Vm8x(?smCY;8k@JA_=)^x+hgE{h=zMo2;+Fo8naKMTb81YlHxb^$KH zP8&ecj%9jfE39s(LLdv^ORmmHUy|vVxCxaOot`}J7>Og2olF{ z`k6C2P}pYF0U}lG5tXLXsGQ0E#j<9h4Hw>;vBl!xeVU;5m#ITsrSsSLJAVISqRjfj z4IbiJ+v3vxf18kW+xP30&m{juU~U6K@si{OZ~*+T|VE&tD`^%SV|vn7w7xYQF!r_jbMZ-1^f%og1Dd zVjfH7u1CHmVw=L`H{G^#d46X1mdqw9a}HC~@nS zpX)&PR_QqT**m)==bR)8OW5dtK*N84{A``k4#)cW(y&RW3$0K_DGb|U&UwzPP}h_gN{mkr-5RHw%%EO9U9k<6)*qm)}v zZ&Csb4b2ZX8?`MZix~5bREp*8EqsRRAifeFD0<0%AOO+#> zxK(`{VKqvhk36HTmV=YKDdBtL!9o1KevhFaOP=v26U}(AEd^=Q)F5vm@x1$*-bJp7 zWMA*4az<(1NrYm_C7Ojh-%tmx%@vsh7AHu2d5rC1+T+x9{r%J&^zJ}pt(8r2w|{)t8JjlR2%LIhykw z)0k}zy+@R7Sq|~IlQW0UivF^(UwlIg_iBab){6_jF zbel#)B=Sv-sNRF&Bb6-a{&`l}cs5l@?=K`Y*`h}BsWikhMxILBQXXj#p|nQ7Npc%; zkB^y?=j-9Z7f!!2I;_a1Aj|UsV5@d25H?T(2C!}9WckSH@Q~k7vY|!ufvspOqnI}%nIhR2ZS@A3 zPeV<2>XApYrg&%s&#nwfLl1U}ikhv)Irfab9%XnL*xH25SYQ^ap@l}8)GKY+$yn|< zV$2xpq#n81>u=q;27hQkjTzirvR2 zF=wu1CldRt({FhK3$~~4M$t1|JXrYiefMUTNxNxjk640nSZJ{&xJXQCxW53(6uy@I$h?d8(k#04L(bYR@p7uy??8(cO%2UED?RvxiYQW zgfMQymutekD929!&uX|A>ALaIOQK zo&cFM-DNG;7C5;#z1}h~ zZ>i$keN2B)(lzl5B?$IiMt)Z?nw%5|g*{0>l1yq@48AKkKtFt=+M%RqWU`vb98=ZF zRZ}TyM+Jv*>9S|i|=mmu=1{$&{w%i2(a_%dsBxMr9e~JO-UiUN6XW_U9H6{ubODeIN zo(JnEo9m%Z&ua>IgC5#ytpbHRtVb6e_^*OzlCIygTI}brW;z&6F`Noi+0%-$qTdj) zw^?v~H8<0RFQYe$-!r%FA4;d8GleIOOnO!FT1C|~c92WQK8Wx5S){s#K?A<%J?gB& zCZnbf1zg)CSA$$rzh3y{jl=u7mkw%mbSs$p#v{>aL2bqYz9{Jb|VnzVo&ZC*ZJ zv>XorudR>(D`Hf*EFgjl^8BaYfMi*KF?;}sr31}I_5tcheKr8lga;@901g0PN&!Q% zz#%z+VW&+W0Z8I|5cy%P>Bs5mSNbU*x0CO! z6~{QlybWQOfxRwX!<}~$flxLZpG>Bj#Vp@@yMUM=tsD|itHUbO{> zsVsO4>$a)nI9_z9h$PQx@fbX7E+yfSrp`OdyoZeUl!fPzVVpT3m=8oH$ij|*2VtwqN>Kj`T?_hoOpoh+6H8lY>M`0`XqMP=XLFJM>Xp=GHSN8N7QZ` zVH7On4KQ2p42Sn}Rh{tR64)j5DA+%Hb#=HijW#I6(6HRmY`@+!q!72zW~fl-`{5%= z>Wka5ZyAXd{nPw%jJ8mLX7wa0J6AdzJO&UyA;ZKRfPplG)C*8Idg22^U^DO?2tZ&E zkQFH+8H0-XVW7`67?ti1I+$VpnrI}CNfN2XM#IZqZ!jE(!Fj-GrU-qQVy`OX)UQDA z!jO%=MN#`x?9c=3MH__JWx3FA$np`v*cS5pB!^le$8wM6Oi zW}H3T&r|Y%UP={6dj~YB+18YeuVipjyGcz~zR*)2xv?;pF3L8CXaB{T_E4YNNMJ0T zaVPWIo<`KJz}?+4qlfBp03<9ld@$$&c#Z~;p+*=b@kqA-{tz-rVjmh37M)Z~32QrW z50U|)&c#c`#EATZ&7>&UD3Jpd)^>U*vj1{nB*}^XbaJ0S``rY;;5Zo5QkZslPYHczs>@2|nQua>D&l-5)nk?V_ztPqJm1!B&;!=9=-Zo+#4 z;w`G~4L>vVGLoIV-=^{eag7N2HH1Ff8bHW=G>YO>5~~jmo90bvHdv&WMw%NTS+`xm zJdoMuW6x18YBS5;D`C6&ZxoWuluomq77f8tT6>z>9`DOr4C}m;zf$b)k#nAhwnT4y z-g#15Sk^rHh0T<$p7h=>G^yITs7$Kx%%SAItXA!9b-woxt)z<}(XN)Y;ncF3!rM}g zUDsh;OsMV8C_CFVf+8&sbkfRU8G<&Is7}@I_g)=pX{;e~m0NSUf2(BPSFe@KuPHSh zKH?s+%uOEUiHb8TwI8htr((|U%no-o3cJB<9z0EXu;9^yC@Ta|AU@>}W;MMC3qL9g ziwHxt4HgkV1o~HI^!gDD07gN84LR5fBoD;W%D$EZNZbK{E(BX0bqx53%(%0jPIgC0 z5Rx9QGFt=E&q^;{il3#-LAIfEFckPi9*NlXY~cWc1 z5Co9ZW1|6p1ST$;wlM=!c0UeICp^u6r;AExGgPT6$XB;|O$KZEOPW^0B$=UGak=ov zzwSj|p~C%_yeZeOc=djBq<`aeU5>O-FH%sCn9FMaad^0uLv`xC{kJUq1+}>C(Y^8U z(cH)s!3G6?i-8Qm*5t{r%Z))(^)p8S2_;hHpC#iOjDhB(aZ`i0Hm-ZlXmLG+(!}yZVRTX(~th?dqU!p0%fqR9Dk+egKFZ za6B~tRx|)SD>QH{3l2WuiG$jN9zo~0ia)$dNz6eLiB;N3k~RilAYvsK7y(NC=~4Lr zx_??Zg5c1}CdlD2bl=mYE6f`4F~kmSD8hsIZ*Wv$M-`k^vOyk+k9ngn6x8g}Qg3MV z5VF2z*_&zHU5z!bl6A7yt5?bf-MR~x{!9}l1u2K3OHr-Pt<(p@$ z`nR%G#_1AIJBXF-&cl9ZbhV{$!SicJQJ7p#8miHjYoez5ava6c#4#^A$;6pEo2~*h z&8M6|zlQP}PQBkMuKD9!y^{Q>R<5!&P3_bC1_%G4?>E=r>8ww`GR<8D8d1B>U`G

#7=x%o{AYtk_vNZB17;u&+>Q=7<42t=bX0y8JtbQh&&>mjR>%!$CgF9 zKvV#`k^&C^0$l^LeR3eYJ^*M(1bBeW=4FHo@aBpi1pt2ZDU@=32t;aSaAN?Rnwml* z=Dr_N;se>e?)`V=S)+`ih;nFf0p)}n>X`&_LUP=KPGPt=)eG|@Ify^3$utR}>ZHuuhBUAV_ z4KL3|WxMwxEQf2|Kj%@+fbmiJun2$+#<3^8g={Va3BkC2 z{5DDYLIsgXeU&VcA9kq~0QJhRzUjJ^EY~}r7 zbTgIu{{UaViDRbx2LCV-b7}U9M@jZ*)AUBm>M8Mdy8`>($YdRU@1wOOoZY!pA?H!T zIxpd^k=+>{zuSAh1sB+DwSIZo5md2?v!K>vwuMFfjbwN7{mxH8a?RVHBH_?RrNmXq zNAzDr5>o8v)2(9uoU6&fu72umhPl?TiDz80PFNgbV{1pL zT%_e4|CV};{fYj5o5rVLT~F#(EI|3@a>nR@zhk$E`n~Qu_?vWWu_H=G+5;8ptFFeX z(d3DXO?ebLl#4Us7<*G_hyn>jM! zP-%a-N>fUu`Jnv$Y?LE=To)gn*k@-Hgb#e=M`58)g7bhQt{AF`5T$7dPb3b~2EbBa zM3FlHiU)jY<^Qb_HS~e(!zTnf;`_ufq#7Shhpv{vBP*($ls(|BufI>guI8?MM>1j1 zFt(!S{sBGx!YzFa;m$!&0GK7F1A);$py+U*VSU&|Y<4>G2%rxj4x~cl0>N~YX!KwP zWjQmzQ#Cs7eaCA9n`0BdVimDJRO!^|x+Akn2fazxTIkw7_2ohA+%vUL?_n;TPVR*( zSKksVEIXE|+NTWC*(5Ru$*{kAb~a>Fh$^0{?>p`J`tr97PbOVku!N*EZM--gBe#MJ%ZK84!Bu%~Upj7rRfAZ^A20cBl!9%Iyagj%JBvy;|Z3v6c zU)s?mna`Xo3YeAozyB2eE&CMgS}aQCGg5eW?|8t|?AhWqKgx4x%qWr(1}{5wlD^*< zO`OuP0`!r{`J#~t-h_fzNq~HkWLZ)~RKV;5TxCJBU@pX@BK64wL;sE%oXP@x00S7o zC=gZe+N4NyTnH(c7KMFWk-Hc0{7b*YMQN;{mKmzmctRWIdbc8yRvK!)kZGM!aU7bX zlfE~B5U==(zkGJ>qOI6Yb5nSpGt>R^!ATVQ`Mc4T)CzZb&q#rn;8q&so!Eufbk9Ez zZl22WB#N;rXq~p$(ZyosHBegG)vYI$yS$9x7S4j=&s5>VkLnsQ0fm6w7HHY<$f(&n zgd>;w=g2>{Dg`J-be5sz5W;^sK^OFXAEz1{=8$(0OWHahH@alny)K>CRkWp5VtGuVq+vD~tv$-4a&h7JJtO%FJ@KVfNX2r0akJB=5$wu8 zO452bJCsG|+F%E-Lji7y&_EdKZs`DEgF}Rd#D+qPbPCAgeL#4ef6l=zFl2yauL zt$b*P0wD++kLt20;@!NeiVtZhqjALcREDtr;WOv5(4R6ogxzQ)k zz-7i@KW$*Qh&6-HopW5@)<>n->|Sou)m%?4;#hF|A;?)L|urqqHh?Cp;~Sb{r!uT!N@x}v@| z%uk9GQ3!Rqrjd9E_2mC~a43e&G&?;8N=M#9jPonFamnRyiEEGc9-q@_LvpH?HjYR0 zqV3Z-zA6RCWz4rE)WgKT$!>v;L0#tXFSGnAp{f%|9qj|~Xc0LgkN_i2}$ zE+bxZB=UAlvj14R#@y+gt+L??0;%RZ5(fd^9t2^&P+b-Lu%GmYNIir-iSiX{4p381FZ2 zy7dqY+!=^%gqW|Ss>t9KJ3tnknR$IWmW9)JR1{>4M@NzC{t9X-r465jRYyx|h+TF} z#9){zpE!QWhLtLXyQ@Smn17o0T$SdDQt^Wp%a!{U(pFVDwts!IJl%F@(&?XA+EX~a z&bUS#Z#@F-ck8gO-gEyRKZH*JP3n8oWX0MCd<-O+H3zKdKB=Q)M?`73=f7DN5HLu<>m$G7xX|I1Gk80m8bWFFY47~?~R^}wVZxXYx z9ipOKP>Wq_`c9bN!NdF!K-<-h8bef^og%R992MOE2srg+9%q^$!LUU^I zODpiV6x5W}vg9_0X$JYSSIgM`L;b2ap+?43?1lOI!DfA44RL6{2iA+2ldu!*IE zkVc!s%cGC9*pQjV;>B!LOT}0BVJioGTEXIBgH`L($n$Mit#rtDb%c6TokIMrWYG*<&DZuG;dK1Y<55- z^U-VPwd^}i!)eFUTD^)L7HaNZ{WadaHg=Q02}2hVu8*9|Hrl*(W2}7tlE|dt8+1~u z+90oO_uQ%KXNn}-@oM1SK+AS=mkp$?D|}ZX+~Uyxk!o{lG@rKh5L}06I$=cz0Av|p z;NLpisYnm?#m5c-h#K4rI)FTGQ(ha}1{8zkhI*a9J9SPq-o3qF59u;bl%k@mA+|{fK_pLt%$L`9Ms+NV1G(oBXCVat z2F=0dwl_>fqZb0dHE6+VN(YC_x+;dU5GacWcRz;=&8HFD4Ys2yYD!(yRre6Mt|v)h z*R<&|Max+4T%?|%@^SRpZ;&br7FVPt62MEUir?0ZF|yL7Qt9JjtJisVkhwitew}A1 z&Z$&3=fqy2V8YGnte>XvY0lJ?^e1e8FKgnw@#vA$gVuay5qwQeZvY!iR9h$zh(DyQ9Se^K@gY1C0HA^~to|2m5HSYP zP(DSQJ@b4lCf}w@8c(TL#s>4=>&`C}5yZ;A7*X1IkkINPrwtnoI4$|j)u$>k80Uk)#|UR6+Cj$K{Z{P`;q zGJGbyx^B`_2;V_nqse4cd7m%!6((V#qG;m3R++urdzvhf>`q}49-x$iw_`CbnvzT(%vD@GQ9`acNFs)o{87uA>I}JBS#Nq z`qQ!EV!Ik{9m%g!g09Y`ne3asKL-5}G7Tv@^1n2$=-H-UC)MGDqJoD=sSqsx5YUK; zM<`bVAOL{V8=>;yKjDB4UV-|NKo2hgd22_EP6Uz$M-D{u8{s3i1QhU;9eRE<(X#sx zSivh#vK!95To+gl`K&bJxAMbHegCQDN2o*NSFx%t_`{Ntx1_biyINN>Xe(RoyPD(; z$3dKw_Qg)Yofs;9`Kv2K_+`_AWvWn2w*1l@JLEk50OEHo(9>QA8|+jHP)JHibx$M1 zp^Z{Viu!si!^>l_B4MH)>gs>peyf>GY38S-Bbbs9^ZP z`+Dbsf|^s$rmY|*)!Bc6cy!_G4e=O=>gLmNULfgQhm!pK?ticoyJWDM=s%1!9teFfp0CUx3q@ zZpl8#3JE>&qduZ2`!k7X#{%GRG#>O@fJnZTp51NiwVgc&-ToV04mVNBX6YrxQvx}+ z6nFWI^%o4vDmX02|nCMvCpU$XWO5C4Rgl-7!mu=4^9gJ+H zS8WwngwxM)8$|lnmxqU+Jc>I7$12})+8D#kzv))s0(~arEc%(jTv7mEF=v` zH6>a!t6D$57j!Hy3S{M3_$d=tbu3M5V-ABN5{Zs;J8iDk)K7IcLPv*C529Ho{!8V3N2u5Mk9ph8j^)Y1 zPD-e(LaLSC*5R_z`k>NK&#R;NjK;qS>kt1VY`&jISATeXVV4}BI%VspbJ1aDha+A&=|^yuk0=-y z^0QZ6RZ`R9PM;aebWmAoQ9Yx6VA)yOb~u65Ru#MMFdwH?UH>TIc2G#A_Rxxb$z9Xl z_M5VP-XrO^(gbueEKP4VcyN9zoBdfWi)`>uv1ATT&(mL{QAw_F%}UQp3W>G;Hk#WJ z<+2)${iR94vyNZQqzf)E`5LWB{7Sd7Atj-oS8$;3-XpDY5xX8S)>y>(nv?-w;XAcBDyARS6KN;fFd zCEX$2Idm!tQiCvrwB!&1(lEq;2*ZGYFm%Vz-8H~He1GqI@8>>$oSFmb_&ocpz4qGc z+$&O3dhI%Xp3;?ek{54Qd1Ml7mQcM{pj?w;+Yc)|EpM7fJE;P^A`J2ihE7`bFb+L-|99ro4_fa<4xC`$M z2LHbJh2I9!`y~h({}@V$$J|Z+=>+sV^v*nxi;$AO0P^L|L);~xY}QVX#QQ6#XISKBlciR3}3EPDRBDvZx%zx;AE;4&i@Wb5r&-FI3jO&A`pXr?HEc&|6 z4o1A)5uU**JXT|kJso1op5APX1CP0R2G1HVEw&xzF|8KPOV_1#)rHpEeUr0)6Ft^p zKel(1RU(}o5<~vBM=&7c1?CSey-cSoPk$pl+OCTjntg@g`a5GxaPcOF zk$||5y^zw;55r1sio4j@3**dGVqrL2;gC0YUx+ka2eW+8XwY!fusnm;OK8a1@~?t< zqIiOG;CGoKd>&sXpbiA5}BW!V4^Q&0uf zBiTWnXFtnl3_K^9y^gI!EN22lxGS9pJHS3i`e!1B;(;_*w30+AMQ76~exh&%xBmXS z6ZrkX$y5yaV=nCC=bRr9fB3L~}ZGoFG0j;m55C z4&Xyx1%`$~U$m)wPOC&E_Q<{waeBK&yEtF;L7Mh0<$Q()Nwh_1qV5{}^*c*Su6Nqs z{(Wo1rz-;8{Sxm)09b68pm4-w)IDf=+i9$WUMW|H?&0?ZB5y|9E`MYuX@Y}9_|bsxpg%$^xvaf)Lz zpExeK1OrQ7Cns;f=%4*r8ktDc`ea0y4q1S~)M%#=^}mJP%DFf$J1Q}7)kij^$~g0TQ|y`eECpJvee$KUYcc_gZLF5JuGm z4n#A|WHl{bDWgia5xTzTnfqs5X74#WsNxM^>NG#C{k;~Degc-pl*?% z9AHX6Apa9e*rAy(Iro;E#g=inm*g+@k%FCl%qeF}Oo??=@MoR2Hwp>fc=3#~xVX}H za0#O=U7|2;pC^>9rm7x2PoRnZc*Ytmcb_=wu5eec#TOF&uZ)r9_lV9Oq%j2-1Pyb~ zbM8E3-<=j~`OWDRo%FmhzJ3F5`cI+s1IAT_IN$dP_tL&i(SI8Qd5BJn9RUs#k;g%z z$ns&!{prao^+qqdV*6QS*ERDe-f@ALV_ygo?2WsP*IqsxRm=2 zw=EpBGAw%-Hmf0@qOt+b)I$vy)z`$h&*-Uh#2vUFUw~_>-O{6%`I_=kzpEpPBYK9} z${E4@sV+skiNPTvB}cxDUPlHcihN-(lsye61zVvdRY{kY`x^0hQtB_v?k6sl3b(twvd<>cm~B&-A~k-IM}dlKY~Df6B!LF3`bhZ zho^XoTo?xp$4?&*-pEzIby%n|Gpn#NzgK5E?m?93%cniDkDk;J`zE%aEUrrUx z)S+5Hdytw_@s2j>%ddFtF0}Yjk+Mz(ByZ@~w&L*;PG|;6yBoD|XSZAMFgnv5(+>l# zIvR>&UvaklVGNI#rgJ~}wLOjd@tH!>legc!h1xCN{hKI|$WK(h^PyVJM=N$66X>`k z>}`vbWY-R=C}KR?rlUUFqz)<5ANjG%>ps&iI`CM$ye8w`cZo@HrAl7Rwi-@h zOMP*|FFV55X;Zpw=|fvVomaNrqkP!;P(C?Rii&zCwp9NRTO4dab-09;gk6*RziNt$ zSl+v^wL}!4+Q-@@8pT)Q*u5Gj(U|!zjRhZYs*f_%YoZH{DP{?ziBVO%pLtd_jUMQY z3s8nfO#fMAhV(1?=%cKALSWHc* zH&6eHW2Ldc({*@&ehY%>v96rxXZdIh`K;sndOc;hueTkU(3%|`r)(Y(Km3*zBHuzA zGPRD4=C5otm>oif#pgyqTM8g+n-_tt0nM4t)Xy1O3c}YgYfE4saOLzuk|(4tj*f7> zEIv+=GRg+++n;gJRPe!^K_zRH`W`@-oRBCY>a z$p^(e#jcvEC7ba7z;eYddztv|o&0X#vEVhL6d-Tal}nXpo$7zBTxV;9mzWFTn@F!o z6)N<^Alw z`_V4Z-x|#o#Farv!NmXzW73FmDb3PypUv-9bZ+})b^cAIHgAlh&yqi0JCo9uCN<@y zCA%$s>wGrjqpDhE5Bn)rO%@85yG4!(58jP2mcZ}s8gglv8w`xT`QRC*TCjigpJ%1}rjS5SulOQYN&HcoTqL97 z%c31Y_|f8T}&Y9pK+!%_sreZzupKp&+Vk6Qvu z3F{fCufcM%hQzD7Ws}E ztMU9hy!gpOWFVVoY~V_k-MfelOiEBfeMtY@HK?~7kKP>MF0Bs_+EW>W$TP^NrKzLP zkl`_cxD4m)&-US};`C zy69NpFe?JZl{(r-2hCKIN;aC5AUCr+%d#aXG&?&IHLgou)xsMP$?vNYGYm|Ta|%2S z0fMkl<ZeC4H#EWRArqC?*OZr}@(IEtZ;0bqQrItz`SJ^t7~RUZN_Rw@pZN=)+VDlgm`1r*lAn`! z*SJqOc^nPqLq;KD3BliPL+?Q?_3aCh+g`Q5c8rGDZ~y`stF4s+)Ieg-#bV20h! zE&#rOLZyM4`aO_^^bH%hmT8s2bjWuR0L&GlFdpY&`M|tQ1#d!Swll$+ z*jlMvrEE`0rMRk!io?k{sih|zkP&E`Q23|(R*u8xU#ojI^VAUiZio%Z!DCd#R!}MM zL?P{+X3j}$#HYL3{LD0+UsKuHH3_~w;aFa)N6868|*i~?4rRMc(@^w3rojvHb;N%cx@HLW0tkAycL+eMBRdp z30V|iaT-hQOb;5eX%RZD&c1ggFRzjrpfQko9I|=^e&sZ1X1IPDCHj>sZMq4!nBm|2 zki6cHEYb?+7SBjd0H0MP! zLIvy&v5gfn+00^bda=Fh&_;q5U+(B5KG{iCx859vc2xAytQ7Z>3iB9s<_vS`zNl*o z%dvdefGnDS{_kF&q7;ib?}+z-FpQhh-!{#Jc+%t}LqKh|V=gPg!7dyj-qvm!c@`_e*Uqi}wyNmw{$@XZ&jn zeuBIMVIiuJB~rhgN}pG9McZpj?Z~!zg`KsrJ3@VsSqMvjGF|@C+C1R>^xy|X|H_dk zniZd+^c(QE{*T21imQMS4)?!PfZKZqoB=05ME?JV#eavuRq0nxZqYFQ3!t^))=3Pc z|A(&V{cDgG;6D0d`$4a<(2J!tNWbhfs#t?|kpFIpb$n8)GgQlt%3RryLM(}Ux=-s-;B+UymY&(5n5(}c++QjuIOy* z!v@}5^E^e?w)CwJuD-JI#iWUy@o_ew)jfNA!?w;$US^uAJCJ5SFWA5#Hs}TpAr_a^*T_bJSJ_2t`W8T}-iBS3uG0+S5%t% zUOWNf9%TjO65hPDr;a>pVZMHhikh{`h}Ho zD-YQTq{mDNuby(2^_h6>$=UTwJ{bCW#&oo2>ChP3x^tlWx_tC5TntV=Lv8#JpgW$< zr#6$f;75ruRL9w6v{37Ch*la=|GKa-e_80|2`q=|X|7bYKaF zzx-JEwITNdYRrkvjrgPI+nj2ZenOM-27cko`$$JBTb1djPL1ssBz>Cf>=`XR8C#ym z9Q=$J`ER&6x!q+^ODOO?ZsfDhyO{T~MNzrFS5Zuqf;};**40nm)VwudOHyYdQD*~| zfMME!qC;RtebNO4@R+O64ayYC>RC=o%@bqkVNS7G8UHNGdjBP(+UqLZ@LU6OQhD<6 z0_n7_t4FUp?8%UK4kBygA;M*QM%0pBwULafZ!`qq*7}-9jC-2=MfseNAE;_|wz1$0 z-V>FxY}4!zT~sTIF(`eJ6Y*|jTfR%+Y&OW-@1hSa6ng_QsP;;E99B_i#E=?C^*PaS zhOhXeo7-wd)4b(R6IJ#`#sDHHB!?JfmonPATD$IkLGPJ8($S0PTdR4!ctv;vA^{Ty z=@lv#Rir*gHOW(!h&_$+-E2n_H3eSFuc*O(WI;8=J)bjM77 zAXMwiZ*^CeQmTdp%ZDaEXL5(J#aavBm#N-p$uINt z9SJGzk)Qf$)fg#~W1*s9?Dw9LDFJ%DhdOh`eTP;vs0r4^t)h#x8b3E|eqn2Vv7lap zgP-wG!EZA5%}(UDE+G1gNU2<{MiggdFE<<^<16}XQwGifBf5rGUCC61!bZ-a8<6@l zgk~Sl(f(y7@7Z$aRbCx}{Sw#c6E=sq*UT|)QN&MlhT|Y317=omt!-?Kjoa9nH_Ai& zFv|P#aVJjZhcP+E_qG2c`Ux80J>0)5-((JteRYL%=ml?2SNO|^Qmu9{PMAFsF6?n_H`H%?s> zA|;YysKGOsxuaGNc21nUAbYxO^^{U@igT5UPcP)Z2`{qNY#B9>TeVl7#Fod*>IivV-nk zkW45^Zqrahb)kqu<2ZICh3d6isUSf~#O@ zJmUI|U4(Sje_2hYLW|cO&;FUYp_gkiGs#bukyBjgcT4>X$>W&c*8GRcP__FmUrNy} zl0KAEZNCu3bjlum$S^~Ad4JNLmwQD%W)17wIEsXep9gt$THt(44h_e9@L7TU>5rVy zr+`fTo&^r?&vR077hNNk%8pIZwZ%@Z4JbR-FC+^78@-S{(s&Rv0W0c15c2LH_%oxi zaqRKQhvam6$sz(;&ZjXDP$rz!!-|H`@iCe=Cobtw3EAyS?yUBTV<$H3Pnu~T&p2-= zTCBhS1Q?fi0ve^-jmp-H6|7wRV)eBRcpuP;uHJx7#*5u1Bv_8RKP@Bxt5&Ub)u~my zS!!a&EYaO4K5qG49%>nNa<-~qgV_XE^gwj2y!_3UWjlLO*X1XV|HjFpn`u4oTnw&V zxW+YR$%m2Uqut_L+|1E%y)}Eo411Tq<~GehypHKKPEs#g2%A+5hUp3Z6WJ^=hZYDU zhFd9{Jr{mB|F}!R#vxP1`eginPgP*$z5rG-@Sy!~y!dYm$aSP%ym(=b%WClpSiJW@ z051#r!}}S8_XzaUjuiw-yyp#i2T1<^fo|O$K80F7!KrPG%79gc#&)4xPBusPi&1{}cQ0?SKKS}l#V0k)@3ES1KE_MbDp%xbaiXdk4-3yvHL zJ^pT^>6A8Yr({6IF#YHrexZK8W&&f@Vl?eCALPV1tg3BbQUL!^1hShq|HdYH?>l|fZV-2;&C*YjpO@aZ_3B?^!cPOaHU_Ky#T33wFOZ3!{TK~ zGJQpP!Ktekqrua>-q-_;gMrv%RYXcintV)Gy}avUnasd&hRd)9@=wvWREc{ZW^HX~ zr_iTn?{gC0mjZbswb`jGBDI5HXq5kclL;?bs=!8oOE#slB?_FOiV~eZ@n>zwk2)8x z_tW!KD2d$+qfPnjSY2~=U}X_dVg8GQCkq?2hgjTe@lK;N4&gObkKF+8Jafoq*`OZJ zOQFtTa(76R6xv7rK3Io0I=FQmozt{5*c$U*F~y}RF=}ncS4eV?VkvCtW@scUxid|( zODYynTW6xS$(>2RjWe%E3v4=7uM`ds_OIv6ejj*^xJ2)DFly(%5#?0n>#!-^-CyO4 zJnAz-ufB&)w8UBG4i_^u&L4DK^d|cF3nE(CpM_{jkS}l3vGmW6oW=#^4LCw8VZBxI z&>`Exdd#kUHFNv`>v`qBG5b*%0XRh5_f)vS_PJ;<(KU6HBC{V)RLun>6}q2hAeAKb zw=~>eSVRgtM&u$j?eEO2uvOt%M)*$|x>R`vE$Y0Y&etus(YmEZVw%qF0Oz`EC{sY|j2(%xSo8 zj9{+1B`YfeBuv#WqR)!Y8Mf(SJFjwi%pyY!f>%44hL7uSK*N|DP;r#um3H!ZRmd=M zQN8<88R$#7@|~NG-hg{uA4oOs3zhsm^|QTRGV-1ZHe%Pi$ZqQ*E4h(>!duj^peo4(n;Z}mt)7HV$qBV-CpomoCX z6SAAmjm%MGJdio%nj5FR0eSjIa(%R4cz(WA2_sU`pIf<#Pm&^&$&c^lruMivURd>5 z5FqnX4dh)LC5P2Rdsb%UZFP&yqJ+;+oMwgp`a?txtWiN#Iy8$NDx0F0pY?`1!!E$Q zXaB{bZ^_J4FA#aOY%YGhLH#_D8${VkUUyQnKZ8Xri&6-rST4jSeU9_c;La-Xu5>>J z^w9tw=IngDDRq_8kPsSO7(XvC6H+9j!P+6F7(jb!bOTyX4Ox~nsZibIb**;~^lPc? z+YfAgu_18mVDn-4czV}wgN0?Q-}Qa>etS_%zoe?JJnc;U#;{-A(UZ-7UPNXB&+s;Q zH(Ed+)5I4zey%AQSl9=@ufAG9y8SRFzxHG{VxOD#$0bia@5*EBW99p7o&15yqxalQg!58#{rgEY50 z0N~u70;RQ39BB}U763Y-m3|bYPugw~&->SRKfeNcN?sn|C;)6Kz_iNT$tvI>40&C_ z3@bc&$t89)zFSYjZji=lm_Wz!uUtRP+zzX}*Rd~oVv%51jLOM#KKR?B#A~hY$g9jz zRctd|#ZSPKeC63!6sYtxTsVrzS6ZGx_EZ zqDImL>R9N1!bDzQ>G6B+)3}9THR929c7z1u-P+;QKxPT1(RaLxc@) zz@`Wq4-wH`2p-j>*`r>`l%)3?&fxR>4#6O6}Vz>1%&)|>wJY~z#gRH@;(MMt* zlE-_*u{o=sW(55#y3_WQ+}xq6PFhTpCjvGL;d)dJNASQ+K>^0oT+Diwk8DXYb=2&v z`WuKliezz{57~=^&Fx_``&gK!quepcDH;^WPiqL;2ZwJ5SGz98(3mdU=rQn&Lthk^ z6hYqL263rvpTBPHy61`F)#I>9yJJD9%C61Q;WSn+nkzU9sh%EY8YIaT4Dk;fR3p~j zZSNS|2uRTN=0DfTkkpf^NH`9TPtQG8f%_SD&9q-qcq?J^HtC*%or26@t;4O}0&ejK zKgU@j827DW)wt6nla?LI-3J#KHvu-T9sJ6_lNj2i9mwnM% z?o3n~xkylJDT)}r0hQcw!buhr!Am;j+I~M+lq} zg2{dmY0nADU3%{!52lP=Sl3swuy;Qyn*Mf~T}vOrXb)4F{`TdSB(C_St>-u%m(u7l zw5-uO5#ZFZm+COhboq*1W2H0Tz_g~(?3l47Qi4`3z);%b*lRK~BWCXV_A&KiT9O&A zD>Y^df#*v`yySJm!TI}QRYi!U>q1wgDbF^|@zpbi*ekm@pFK-NXxDYV??KQG1zI=H zj@fy=!jd*8O&_LuZAY%3 z+Jm|15vTTatlimQ;rxO8K;oiZ;E&nboay0~p~i zfHLF%!Dcw~w~`Ie9iY^xOZp#`4)|of$~y)$MJu5okPzq>&KaOclKBPv9C_%Y%&3yj z`z6dIt}YI=BsvlzWl4R>T57?@4}PMc&kaQltcsAy$|ph`0{tk`W{Se1siZ>d?m8jz zp9xh=P@``pg53%kx{L1?L*e(vVi`Dv1T5`39iQ*Tp7F~(N?J@9pZe1ES9hdLvg4fJ zNm1uXq8}fi*jId17CySz(i3G{#jZJxpyyLWv$iPx>B*zFA1ADO?2)T6F;4Y?<3Qi$ zPoI#DHYmazmpqgeqzMjP^`dTR$lp3==}PNWe-@IOt+Huw`Kkp=M|zf`bq2{_3V1h4 zr^UiS1(R!$=w+&=e(onqso-kkSD~IWztEg%!Y?RqBnvsn_XMwo`mIBC*XOZimPawgEJRp?C+>xVYlh}$n52ZQG)71R10 zIa;GR5Y8_8(_w_CZ_B^E75^w%>h)%g!K>vg@o#P!Cj6soD@t6-b@DU8LT8dR>LkY( z!mJxV$~BY^8J2(->g0&Lb$17DJF(l1oytt}z%&^QtxwJ+UmMR3#90#N`H&XpmMva) z_EIFG1C8qm>uKwD!2-wZwmgNKi9?-2$G)~on_yoN->r(lv(|S5&nYa1f9@Qq<;^?~ zcio69#b8v~y0EEBBKC)z-vV+!gsA$7^FhhbVE-tXZGdu-D%ZgMA^2x6@?7*BY8`Bt zIa0M6x4kcxqO=Y?kKZ`JjVe~4y@^vea>#v4T!IDpXXf=Ly;ouEMfX@`8!q{H=xv`${uSWTEfa> zcxiGS*KQcu#@u=ACh-l(JqlrV$X8S$fALJCSYR@vsAH5xo62nGDL|F9Emro-~qvNMHpf4Ip;sIic6&gNQ%J8!7O8km0s~ORX zbKsZb@@NVDDdrK7eUyI#>I}2z_Ay;BB&~m+o6xH~85u031>vdZ95&12{aKSj%8kiR zY#ZdVDOZ$T?VZGmJRcBL#-hD;WLkxeb^LRsc%Q0oUg^$9(;7n_Z$gh$Bb79xLQqvO z=rhQ{mvRE?vjCIj*xGKL(x!{5(}{SmfLhniJ(_h4|+_=?8;v@?gqV` zC7FxBEZNSlZ`SHpeNf_4(_6@B-d$&M;OK0!E8fmN=4`tz)Pp+9Z`i=yZ$P#>QVW0T z$yjr#7NWU3QJB69qQ?-3mp|ADZMv*ArxJOzdQALa04f#z&pzb!hQHAat&!4(!qFAm zPBd!&!1CWl{dyw;BdIt%g$-O9WjBbS7Lvh%;PomE|Q7ew1MEsbg+Wz6i7(ACqaX+MJq*a8SR<6}BSWBY5Efo=2 zggi+QS3%_1-+-o%=I+{TZ^Xx)?ALf;&SvS%-s8RwQL>5?YXnx%ErxpWKQsmC%D#pI zaSSM@1D+x;T0(C>1xg$L?H>LBb{ypI0ciCE)FyMAfW9II>g~WzFbw>exj%*^lR;2% zd&eNzh}>g&&)``O;9H!^Yc=&@x!We==X8vrX41DT%un?&g#qED8v6tecL5GoIY9$* zI18b3)tN<=p}jV-?BICihm*(2V_|}|^zSnzRbTa~Qm{H&a?ltXj4)Ym1oc|R5tfPa zTlQZm7EBorKBhO&GXC;|A$}&+!^1um$}rmtN`JRR|Ak)3=(C+#SK~`k6?UvMgJyt} z1(K`JZ5|L2O5@q-d%T=&qi-JC4&!?5$TD^RRnoE~{eeUpK@ zXCfZU4VRLnlGV=RBJ#y+A@7!WBv(_>i_l*3(XHbaA$eh@>RQwQ1)A1003M(!XeUnP zxj@C=R4SZi%~}pT;bdA0zr3MZip$P4#hE86H^;qg^}`YR)w8nxinUKvzQ2|G%#5~0 zT`w;RlHG@>7BK^=w9S6!inPkTkruQZVk#vI`WtLVZs(aL(>Wr#h@bZvJ{pj0DPPJPq(GDCzpJtlb(DPrDB z(TSGh>$0ZJrpwy5t}hPY{TZ+BA*!k^pdSF8@rbr6-SYK7jv@f^L*zAgc3EUlU81I$kN_yOdmDv_XDv-pGJ@s&_w8y<}$?PvdGZ-H)|?@w7fugOEp>!C${Pt|0Og%sdMqPh)&J9qt>cjFkk4NJWgQx+YaPKK|`6ce!fj z31c@lWC)0r@#-@)aWdf?GP{g8Q?hs-X&T&Vvh_f@p#I7mJgQ%S zJfQ2-fz$pvDYsk?K&L-GwvwvrPwOLNx4+I$%vrzcct7KQu*MKU=kIEZ>B~N#$plv@ zb7fK+k4@O{Ud*!Z1$#8#fY4Ahy!%V3P9}Nz_aN8byAOD}PUTd^5ufb=wF)LU40*OO zvM&20#DLRiU9!`k#lUeINo9QKJC-+uCM2#-uo3ACsFOJY^hJ>Zp z_<<=!(*hG(3vkIMlI8sF7V{fW!#SOPw22Ip4&v_q^_Zk9L@kHExyB@dX(`H~=dee! zYdCo}2WH<Ql=MHu-E09G*VL$S5bQn3h z8*;5TN~)Dpkj|u%AW~zl1>(l0+{OMxlB`?Ld=zMRU-7?9`TlS8x}~>4($bx6AP~W~ z{{%JvC4wN_HK4jA`5TC6FTVf8N8c{gQ6-+#jIH>Y)KDL73wY~1Ib&vc8Bed7;u)^z!i3zj##f2ypaW@fK74v8Y4$8lOSIrd0a4*EmVN#p8Q zB|EhXw+oE&J$p>R=gp}ulc=&Gr0TFP>$b*D@YwIG*zZg4O$A?B_HyZ#GUo zR84Ve#2T2MlggmBik6pwf1F9{mZWDRr9zeq=duv3Sr~VK3=Y}hD83UoupXo z6*n+nNT%ZNcT^RkV7DEYd~p^+ru+NAQc1L^tl+A`CJ{y?L%(U$#%#~USXv~H?alzlO+|pxrRMcrSNlf&8T9yz6BU*cKh2Jo7 zsLtn=HGKMTS-`lpHDurHU67FJ!BX5c9Y@V(#F`(Mj9HXwIek!52^cG31jC>)il;mU z7ko>Z>TkGc;rgC}Fno0NTsvx;fB*2qruU!1GS^>*j*jD+pImKNW#?E5R@D=U*nhHr z6dpN2{KM%=p;s(7WYKUO*kE~X{E?OAZP4JJFn_!pj8~~_5;p^$a=$)!dQbNlB9!p@ z%SGLXVH5(^l;t$gf&q}_|_mg120+~qMMkHD) zF5)tPkZL~U0I?&fIO@I8=)89#Sz8d&arGGLg<=}vlLfrzKmP=>P{(W`BoBR2ZBK5j z&_i&`7TjfBxa=zC+lAFq*J^ol-=O!dWANv!DYJ>^Ja64k!4n!x%(+7$?h9U78pkgZ z%e;57s8fNG*b8EwXvtR8pl9Gt%BSFl#T!ukp!n%;idNgV?TBSHscH!v48rs)5WIjP zEe(Xcj{p$+U)c{t2weJ~JnQa15JSfU%V!|+?|*LZyd9zdDRv9;ZjUVhG7K0*es#Ro z-7QL0HrsLrtM!eu@-zhr0jX2dEIm}|)`&KWf1G0az(WpU>En=F+yUjVe5k^m>a?U%uw_psTTI{FaG8Q<0dyiXyjaD2 z;mxzL`@U?yXV3P$*W!0$GM^5%$0}Jf1`?%f7??KXJfzlT+xhKZJ)cE}^87Z%pc4ft zKmB-5yta=FeT9Md;|$x%*^aln-|6@Z{{RP+W%5o20OJLRB4ORonG*TR4S&dA)c`=h zRbhPSaIG1@HSyEdx%uP{L*TI$T^ORX?H?x$rxx-?~q%qN;kJoaA25FdYFY8@7$njT2K8 z=wuzIf=c~x`)|ps5oaCB(cF#vi5?AeKE*rpWm#m4kv?7qJX`JbI`Io$qI%P4RaNrR z;ISSFxeBG~B~`t@%C4Rti+_(GSOwU3(#y{I&MD0Pow;_19>yj5W&drVoZkZXx%Nk( zx^F;{&+FmB9{W2kk|`0Gi6C}t{Epr-<%N`nzrEI<|wy@PwS#VEI~b z%`6Jdodb*5cMtYAOJi|VOoy{&J~wa|R%FgEuF&@E5DPboOqN8ee^C=)ZjO&uM2i7Z zg(Lf;tYUVZFs@#z8_=Epp37~2|7dl*sfuaht|r%Vv*FA&ryZ=}EV-tXZ)vpb}W z(8%{6t*g*NZ8A);xq`>bIWHV`OE_|y~$l$hm?0xM-|)A6 zEoQyH=W#t?oqHWi$Ff-tZ_OJ$ldR0cem$2mLmZFh*3ImQhin@+wu&SqxVOxO|8)#J zP#EEa@RzO|Y4J`b2XhP%lr7rwrN@rw3!C~AyTbPhO+U7kvoRuQ*y#W^HULYcZHv) z?^$Z6MjLf;bwc6`IV_&Wl5)j}lBd;x-f0O_z#cQ7K#fWI@1N!N1erU0M;982JM$K^ z^Y`%0BU91^dc$aK=(QiLaPO-HP%8C(N3prs_cBn=uBsSss&UqwijuE7LgOIXeP=A~ zywM!4<5h&^+=Ief7IlLJM^N@KF5VwNSFm2P(rZq*N=I4mRO}8x=2?VsrFlBwkjG_X zTQoAj5P-_+UEImPG!@{QSTt|S2X}eZ1uqwjzfNDOQm9am0v>*H5@>O3iq{F&Si*hE zG+A(P-9K0q@bD*k=x8~#Ug<5%&X_5Ft``<`TVJ?n>X6x z#CD+dC2D5G^O7GCzssGwc0Q)tQ&2I$e4Y+x(jOpms~gq~_zn+GRc!uccF40Yz}#A* z%H!rfVbpMul-b-GsP?S3UE4#MR5n3OiF0!k+{3MdWX1GwDHeWR2Lw&D5voOyQrzyw z>#Cy4I(;DU?PITcq6K|v};ebo$|_InA`xCgf{bX!GZ zo}>i;39)CVqK{l^X};rZoOTY&kt+Jc#=U91f+b?oB`B`M&Py<%x&_wLq{H`T%}cB+ z3t2F@!Nrj5yMDNAvQMWFp})?DH0%7d({(ifv1y0W+TNEdAXD|{+iCFdk&Da1Iu9c5 zmm6+rIFh;!C`Zy@T~y5s7Y4#ttN(Z_a&LASRTG;%DH z%q)GDAI)bZVH9 z&GCdO6D}-YZ^TIuw*l7CJAS8iwPZc8lU7Ud9FTJA?yv;5N=ap0tJ~(8y;Fw<%GB!t z1&M)LzD-e+%0K5UW(hYS6NknSy^l)(FTXUfk4l3^XKnkZdR*~F*RCs|6N0Lz>?$O~ zjiGAp_I{WX@iOxD5s9%JCl|39DH%!8`Zc?vV&;NccWdc_<6Vrp9m>=A^=xlY%BP_E z`<`vIu=(bh7Dv)cb>cX{dimqgar^#mxFnSTD+UqPhh9^6a271u|RA}PJyxvCQw-aklejup~_$?GS~x0 z%JEouTOpHY3<7O;tjm5r>OLjvCQqyUvUOMMV>Yvtj3v;c;reOIbConcf)}%?PW!jL z2&q?D)aPN#9#3J#R20j{nJ(JBs?0c;rG`>WN{^3L6}8FWo1svC$!?MFwXZgq%h?Xg z+;WMYU$*>dhHtEeyS(wC;jRoBNX{j9JIk}ok(85nF08hsCy&7Ce6_Ph)v`ml*yZGz zOTmV?p8lwWX`Ras+m;3l>C|8DS&vy?f9)q~>qXP-BIT5Fa$>1Sw(fSSD9YjPnF+jd z2MkelwoRviUs9*4iPO+#7UXBrWaytN=)dChO(+?k2&1WSW$EtanyI(@wdcJ+JI-i1 z_@St9u!U4a(}AK#Ulery%qX4lmC2gTN+(Kv{5-4NIK51#3nncX;258G*gvsa za+G-Jmf+*Fh^4*?zAG%)Xp~SN>&~Jkc}+B+G!l3v)**C^j03xyab~594Q*J)yJg*g zEVF!f?APZpSikKx#`@ft%CbH_2MsOAenL%mLow2`)4$^1LeT!yAeboc(Cw#3h_T?+ zV@ve0kWn`K;D&YXNS8evo?sf$x_(isz`No85Drh_JoC1f-T z^IoH1hH)um^x)~;$sAVJNp+uKg`P4kMV`AA%fB5r6#eB+5Ds^l(Iz`QiKXaacA9>+ zmXWeziAY67;9YuH0ky9%D(Bvf1^%)J5>YyA?G;>NHF%fKLbQKM`)@#h%NqH&g9Mh$ z&%fs}FEOUqqy=7e_ezp!oS%Kbuh>X44m!nkc<`!~Yp+iHR3|#Tl>Klr3u(Vm6De3r zjww%X4gP;<`s%o*{_p?UzHL#ulp2k6gNlH(G&n*@>F%^Z`V9jnt-$Dz9HXX^V*=7K z1_B!}V!-GD^LKfFe&6fkaqsSi|J*pQbI$X5p3m7H`VxFkmVVko0NWUarouZJJ9PSz z2Q}|_XMJ}$*t{Bay>4?|23KVFj3FsJ1BTsdnl}dZ$B+E47 z4BPr9MuaKlSbv@RB^-9Q>Z#=JRE4Y&s`5rGAgkB-DkYbzz9+S)enh5|~Rmi-eEQcAy7mqv@baK+KGcJUa*C=9xs)_y3NQ z?@2&2?Jr<;(g~6Pu{{Pb0)YMvM9BrT`LjQH?~a6Gr&c{3(nSSDpidKOCv6cw!l2q) zU2SzHG9mOG*YYP9sxP}a+kBu66inv(tm1UHu zMesy9Mp<*0`KxL(RGd#uabVR|Oz2`9%kQj~FZ&3Qt<&CET|lUFiWM~8k`;UY34g%h z=OfzV@bF7Q6Sp1|9<%Q4sW?z|>sFB5!q`R2Kjn;0{ln+QePb*c_Za298lRw7r>oOq zAtYd)O{FTh($;cXT^HhuQDo1g4G_;4S-5~(nzO2nD-Jb5WJp+~7itS0lect_? za7))b#PsTN?xtSp0{R2aZP>;;c`eu~Q#3Xe##VeAPCTBT+*lqw3=K<`jAkoHN*mnp zV|8EYGb&ke5)IG*<}Pjp*=4Lz+~s54Tx}My7%^YZjz-!aubID23xIpCb>hz_8^r() zae8PQBQ=)jOBZ|*{Af9rWi`R6AQN+`{t^d_TLx(oF7TSxb&WG~lB7|l^1+`@!{i4r zpCh9-b-nRT2eVB97(!)N9n<;?!oE5BFl}y{M^b`qTeK*#|7s$6CGDvH!ku8m+q~l2vPy%UP)5~B(tNC_ttt6AFUQX_>l_lxsD%m%KxtcPS6Heh;8*K-BkM{WX ziA);c9`bc1WM-?fhyxgG_&Jqmh>x%M%$VQ@>3ec~R{%aO zTjj7gk-1b?`5CHCsvXxtXeme zKbB4VEx4Qvjr0tfj$yJ``&+M1I2&RWV3SFUk^-l@2L}S#A$Cu4`&*~Y_GFK)Ofr?3E=CHIyxk7!PYG!D3~s{d zdKoSVjB{>!^7#-Yg1yn#fmIMWVAzvVX_NA^sOSrV$nyPGbfr2#gBFec|}|5li= zG>ok!E03YHPp7RB>mY-(INq#NNzP)6+zSswTxqP~xrs6`#OVEfAe9g6?0n0rVap08tDC z950?7|J%<0w+B48f!-O=6}$7|#-&#m01^l2+~e<86U7DIG?YJGuLC^oZ13svnqLJR zM`RXsD&j<+CS2osReH~=$i?&c61gp=i)4m;SmgMr@+S=047IaQ0`vqzjJOUY^=J?I z12fy=YA*3K+1FrJ4Mv`l-f+5#rI$|2&WXhpe9m-nOV3bq{HD$y{@fu)m2};r(pGao zILLJ%w~hk`Mt1cpE!WIlUCeA;e|$xq6R>q)dW0%v)sdeh*brDPMdNW^F7YLKzw)zg zZ2}OWl}@6m!B}XkM_58ot$!z3`Oe<$v?vJao(KK5@{6E7;eXZ>FJBGNan&+TTN=Oy zAnR0OXP31`J)&>BX4CDcZMLNoVT?5(*neOE(`0niWixYixL&Q>mfV) zY;o&DdC~=s26VN(vtV5GJopj1^#y=GytwmBRMouF$cDemu%r_$3lZ#3!QBtK%U7k7 z8F;3~Sns=gNVIg-F6+rW9Cv1AXH(v=x9*$T`HVg}k~C>*za6nndiKpplrms&3OgOl zW>b$$S=QI5kF1e&Vk=@L%SS-|O78*?9T;D2<5Sra;?eaZ?Kd-FJNLy!)_RUo znpHKg1&2bd^O*HWxji20u;rE40+g@2sI5o7EH5ohUk(!`0hr-7d{m2I*KaymSgLr+ zdK=#VXUuLygFM5IV+nFN(^(^C``5JN^-Fu&(rv=3+OF6A&}AJBT}$f$6StuX{@CAp zl`1uDi?s*pNMbOYx5tM-2~E-~GthkjfFVRd;K|DB(_6%r637|$n5V~+OYcPRX_BWnT%Zz0He$oFhhoR zJ$5sGrze$ll-VS_9@~)HPL9Z=E-p`Tz*zEBZnPE6D%6Y(M-R#;r*Gz6TxxL&FO+sv zySx7-be#o!y09D>HQ_Q<-BfjOd3x$M__2IZvb20iVVX&olN3;mIw`Y#sAO`V5aKXH z6?$aFabU}~muJ%12Tt?9qw$D)#rCRAv%ea^W0NRxN3ARGvp#wcq-O)Q?ecrF+_bvk z`vW<~!tn+TiM-OmVO3-ov!n|`+|3nex&qj`)pyW(xG9E+ zS=y>>CxV*+^iF64o`w|ZKTqteV>)Z)(^S*d-c>&LRpaD<#@c&Fb>&~+ z+9o+>zjRd7*DeZd3<3N)>E5k02O=in`L&JWe1kBz&V4l(Blx}-0=M2wvmO(W#FYD;uf4U)IDe3l|; z_UNGk??Tx+s@BGVg7?SH&2UGUyg#%RlZy>WHEe^!YOOK9a|B zk8SpbgUqoJ#XZX08?62&dHP^@xUBrDmNp}7&U)c;e&&cBD{Kl>u$ynN+JEeS45mbykqsy^G>W841Wlj-;3cIZ`F8Id`a zm;N}N`gT=kuDPs;JlvDB1bKU6Gwuk35%JD{w%15DoC^9|gai{6uy zfDLSH{+wQLNg^vNt%~ZgnRh!E(=ALCki*kDmi&NefQr={2vc!kNCOL)es zeGI#KoFgQ)>+|g|NcAU<>??6Xjn2wi+z6z_5{aQ0hlF77&4{f!rG)*${>(Jo^@S0o z(B}RFa!;u58~DtZ)8zGFEs9NGVwQZzb%LB?-t(L;wqJRfgkwbg&_tg)T1jE#BrjHy z25uOezC12LqszMmF#4sR&cigSVy870q0~hdQ}fmnXkfb=cWoLjR&T}WX%1Ohi>p%X zmJWI|WbR4>!6VV!et6!fMfAY3$~tFaMUT13`v9WK@H)AJIo7|5Sfzg08mq%6l#XTU zDRP11n*Eybq0L$mh8c&yYEp2nO>ZWml?N<0Ml9e6vIIukCOf1Obr`05&>yv7H++)P8Zs6Bqg!`g3R&Z^NE{gt?$xL6+ao0@c<3 zqLns?_coyK^8Yz$=WbYmfOPL{`=65E*{3U!=OSCF%&)hv8xpj|7LpRe&Y)c)CMEC=Qurxq|! z@U|TEO(0tk17&57C9CQi^oVm5`uK@W<>=`4&aa6XXZ19S`H(Tq+EqPZ*O(R0FE*ek zP5D}`?efDMMWth2)&lK?nP%?pC$AqLnJ2s#;Ti)H7kIVg4ysxpdtJR8yZN z+^-}FNSk~fybme(I$gZAo0YpYW)O93A-hX09Uv#BGXe;@@d) zg|$+nT=cEA`lr%hGL2ly8uOWcCoVe?c(Jc+PXBl?=Z?`Eg8| z>ZE-Gz06G5V20Qp#^d*lL!epl{HaS|yHVC=S0gq0ce8GFv*^r`f_V6q3R$nq2gl;G zz6m)}Ly#~O~Ey{v(f^4ozFD-Q_g z-22duaGh#8=}*7kRG?7Mz*e`Io7k-0Ii2m9@ah*eTm+!y7t~?U#&s);K+GaY`u6?K zup8g+Ww!a!sqyJ+>9Bu{$V_FvL5c@4HgSf7`FXbg59o%fC8?A$ZTgA%P=JdW zsqytx^S&VZl-c-)kU34)5r?nD%xBTESOkRGcc3syS%L^Co8T~6H29`gvYzR!5 z4|Q&`vWp1UVs{S%;_^ng7J)J@M03!7h`d#?wUzzN&q=kqxFuqAPf=V1(+5Ltw)LY# z(Mp5l_V-`W8v3SPmhz`=TT8|FjS26L{yol5xa<-u-(&~Bwm-8--so5l4@6&vL;g+2 zG)TAXD&FpD6F4>AzFdCW%@(@ZvmcTh1n(!M_n?@Oh$Ox;<6TIIh&2a9vHVqv(ZSQy z0v0WQoTpQ&m=17+eoV^-A;`HAZ`M(3OzYuvY#`{quAW;Ssod5gwTqKBb z`x!QdajU!k8-%s|F4x5m_HgeQqeaB!s8|9`eE-!(eSyjjDJJ{mkhGi6Y3fU9@cDu@ zipfmR&;N*QrFFpq^Vimaoxyf)zu{`4kT6!59BU0c>o%qTZytpW|6n5 z0J_|r;hB+lbbSxeEqZ<2&eBfvnp3_x98LJx=jBrQ1$F97Ym9!Bv_uh~AA30gKB?J_ z7Ob;1mGuj`%O6+Gb1g6|kOS%X({Yag?WV6nCdGh_eEXqK!OIWXF1s?Q+r9yLf{=u{ zn!SO9;jcv_f+?{^ZI?)G41?O{?b;Gdj#7w%9zPvhOb+QtQN((@Xoh27Jt2*N314bM z>HqAD8;jkKCaXSIRY zXxWT&R?Jckzq+)r8jfyh(BIB|s@2PupZOa|su$q4bOKiySU4U4S6S)&+x08`a&q1phUyR?Vc7a6x?|EdB^V}=>7?$fQhX|GHYeI}EFLZGwfh&e zOjyf8B#cO^Voz_F%?&3sttM|D@s#hKNPBgz$%ObUX6j78A?+$c(C}_-*bs&Fn7P?M z$8l6sDa3WEa!BE&M+U8Bf>g+%_x@s5xXZxL*LZ^RL=o|2?uxq4Fwt9@b!uKtI4q_8 zwtYU@$=z0Fn>uTH3f?U)Bg(mj%gEY|*sa5y5mO?^g`tUNV%uczh~dE@oR(%oo469A z0O@@-a>t3tY2h9)KWM1S@|m=;W9~#o9mtAMO-uzDZCk$q1D^0a)!a<^GEw`X@+r2M ztc0#V4lR~4O{c%NU!!v^oBjZQ(zIu(Riv(8n5lJ`Y&jI3+ogC*dMUXv z!nDx=sPsEWd_#Hu1sOX>)UnU(%|&^9LhP#qvsBS!b|_7fj|0ICF8X-X7*p&L`>(RV zT*0t}O`L9$MU99G#>Hdl6h9SEU#Go&^2_I>_Vf~MlNO9br+5oGKhs>DmVtlK!3);% z-+#0pnq#7^_gSO!fK}vv&2En1v?YpPBxg10;n-_3WxNO_Sd2RckU9!Qi51Gz57egD z3BlQ6T!6}j#m&&pqzuehc=@}(AlmIik5fnKl0^8zY~}`PTT1VKy&MY0gX3=V_5)03 z*kQRe3z8hlcWmR+S)Un8?g9=>Zr!HKp{2yZbmcW5ZD#$QxC|e*QxH)fH3kDdTp8hM zYCcKKx4TZS=#AOFH%z~YVIQ8cbPdwmH!LoW;L+QZ3Ii+96{yPu7xeQ6*qa>&XwR{k zzVsPT&%kW$N3+S65MO&6yCJCH+;LxR4NRl(?Jjl`OBzPl?tlOl0%UE%*6$^baxj+3 zVKpK<@{4JSQhFl`L84l0=8K_SLv>FHENJ!gvekiuuDKg_E5VcY=IO4oBsf+_az2|? zV11C$bA3~IF)h=VE1RhiWf@nWqCctzpUJ7V$(@vy$~iq%PYi4RB>mHuPpQ3bOUa6q z1Y@V>IwEj9!9HD~mtd>o^YdZi)%Xxw3~VB3EBf(eqez>p06<{?I$!@-nFENdz(D+e z@%6tB-&v;e-ziYqo{#*W^rJsO3Z~JPAj8i7Pvuvh-%R&^%a-8>cjQe7 zvf{soHym6We0}^Fku&CdEF>TCRpt=!z{N%}v{ku?kFPBl$P$4Z%HXT$r{OynKv6kN z53?G)9hiOJGFibX8Ip2E`D3J~LHCX8GAhQN-c5z`YuwXnyj5B9;(bO? zr|weN7VwD`ylhGdJ4vDMV86Xzf>ht*G2PwhiH1}mI#_SXd}WjwR*xuiv5mgoajmeG ze&EG#Vhcx^4jZIw6%t=b_QnYL&h1yR8x4@{QtH^CS9~|Nbe+w;nZ0by7S*;A&BwNT z=b0>Mjs{{QiN!*dM-@sg?V3?HE6nXz*~L_CucbAfXN?5(41rwm)kEOIJ_fEk2xJdP zFGh2r>gWK{qPVm^%u#zxBd|+^bnPgr0BIWsUv)gdNt^@Ap${)Yi3^?zy$0s4S5(zpxrj?7`IC(NV%}I2_^uxba@N2I~s6 zKg~AhJ}Ey@EeyM-w?+S?RF9dnh=tNzEkN{oquOcKg0_puu7zB)kL|W4fn>w~LMNS+)!i=^y(s z+b7`;ShcfKz0sz2G~pX}osiOhGBq|=Vrv!kel!Q_wVQJkW@i<50F|guPOiZ1m*Y?Q zQwHU%`llujUs{82@iw%4fFIXE#~Rlt6Kl!JI8GQiaH6iGnUFAvh?TO9&{VrY(^TZz zIhcfz56AShsXG=9)*0oMz1eiAptycM(Y(oKs|QZBoQ)1CvJd*2V#WDV9H=<(9z2XtpvwrY^!+-okvma5NKD8YQ1Z97O1eG9q~tehOO}f&zP&Go z7MY>2rA;eEY)iE3b-wJJ5Q|3z=6jy{;15@Ph3NA1i*mJ_Y?G1uriN7HA z=!iqW2<4h2v`Eu)v}C7#65UG*z4e!udC+wb;hb#xpCr%v3=Eib}1 zJjOQXyh{`c!uy-K{=owgFnV@S*KBonzcuZUh_Ry6!*ev)H!y zNk{qwIv~2NA%qkhDbG5KhkcJCYBEv2p;Kywc?C+P+Z84rQG2v4@8kc1971acP6CP* zmfd`hM-3=>Z#6V@tor2_K6O=A@`t}59aN&0@T*IdE8meV!L9QlcAbAgY3xr(N|swu zeo2);Q*p70xseLE(=Ca>$ea)#498mwV4W`gZmM z;F<|A`0jka1GtPH0>yaL!$`x&z@S*Cu>|O%%DEf-O_k`ed+}1Y#uEpg6|&+jUf!j5 zNkxbD|5}mHdGDsUND@1^XYjuF%HcF-G_-F+9|M$HcL( zlqr5fSzikJNQdM)D(TvJByU5|zcY8fPW#^|0bXs;`4^_LC6zt0{^hd4xR)OwZU35I zt}`j1nTgT83 z@O!IriuZkkAx>a5tE7<{qF1Rzidv3UF|t0lmyrIFvKG>u=<%Wtk98&ER5(+!b@x$1 zs#D8iN=J>qyfA4v+mv56t!ASEm6&Hy!MPCs%MY%;u>mpkCR~aVy}=i+ayB?8dV?Fd zn1Br2x%20;Ni9kP(G@Pg1PK=~q;RmqgxL3Z-?C*@ zNo?+ZZYlWLn(UM@u=ldt|Ja13X~v^D#x9i$slD^rue!nA`VgsyQOG4xs~>LTTO_?= zu`8&h(76)4oXfvey+M?iE{i7{zltSQ2gad7Q(xV7b2asN~6zBnrLukAhUWSt3H>$+#b8-rC# z5!enol$zH7H5bKPL2w)yC{R10L2~(c38Tf`b55ThwbrfewM&Jm8#i}I{{>xl44G#d zb!xbYS_58fc6$p6QX(mb7O<*I!M3osJyysebFIqrPggHH)1BqsO~4y@$I3A2=zIzY(yw;DM}Au zq2~5wzp@fhzYJ5fpnWGoX|IWtPr)t?*Z+d>j{1&8Ik_(LGpIv1@7)PNYlvEXqK;7Q zS|vL_IK9D?v5;B(!)V71ouuTP)RbY=)YG?TNFkR~>!>?#vnWoiIa;k5rnyHVOWr&4 z?v`k_R+lL4?H1{k*XBm2b7Zl_AJW_ntmaKBESyaBYHZBT>Dn$3xuTM zL*%NQ<>|lCEzftSE458kdkYa}ZDC2^%FLGuQY=o5v*;kj%P74Pm}dXgMQEPAf0b^w zp_w{*r*5B6)t~IjL1zkVKf<2=Yp4FL;&q5_|RJr`WP{{#&P0xAf>{k%rWAgw& zp5FuA$+Noj+@~|*Gti*~LO{p&b6a(Z6#3HlybY##}LBo~lvR4$n;cjY&xU z(bL$%5}xFv81E-bRo9C7#rt%RBnz?H4L6%PcbLV^W%}MW42Li@Fwz>Q+hO!)mYv0L zLw3_I2lKcQYTmQ6OW&AROMNRibAO#lLDFT|L!JQeDXz5X;18So&^ubojJYtXSS0(9bTY z*$q!CjLN+R`-=WO{{oP9H5nMNDA)U_8g6^*q|x@o%L6lNA~{80lN+4Iiz;PdnTFxq zYT4ucOg#H6Hg&y!IlA~!ayQ}Pxw0C4I?0L*wrgyzVSnjDB2+=He7|KXyFz7(MbY6S<}F`d5qClLlT) z>R<(al_JsJX2Kn6kr-ZF>Wfq&IzN&Q|3&s~xM<#5+E!0TbIHIE2R{yqnIhuk#aXDjIUrtn1QSzr)zDa-<61UViD_^+LLMB)YzWS8m#&Y`bp#z zoGL2i-GY^e-(6Q?KXg|FKchP6W#w@i^iB|r=OZ$Py2$hOPGQN#%W9%iweyNzqn_lT zzaXjbv7WINaPc5if*Bp_K4UN|T<&39Bg9k1Fb$des6D5!?Y)c^$++GkiAX^Z{Q_r1 zc#Hwb6RV!6!??@k)qWL$&Hh_v+s3UksN?mjsN-r;e-vAn8g@X~h>aU~r)Q=!e3iuCmy!EDng&vxbw&sCSqRmO<# zM2zwEonw~U(SCvBR@KZn7qZx3n#e@SdYlDE{AW%MR9DAn+*nu8Wb7Zm!H*KBPa~9X zP}PDd*|uIVTto~3zUA>kch*h%)Bux$`Hv$4Y3EwaV|wb4%BllR5V2-Oxqe@e*tXJa`p~# z99G|ImHj|YY(h8@CYZzv-D>adbu)oNyfyVHPq z;h(t?<|$74koiXHvJ;@MRjo+aES~h*V_5tsc(}MZ6YFa(=ctE3Y%Mx|CN40C!A$5X0(Ob$H{J@CRT4xC}Z^KI2M)K&@xHE1>hQ z&W^zL@Du2NaFxkf6$1&^0n4i@XqY z|AaK)PdA9MuO&*g2hlQm+qLA=WZ9?=zx3dyPX>!HmbHIh#BOU_H(#n;poAMwR(ySDnnv< zf!EEhz9G2Drh8ecfOa*gQWvHC;@9?qjxCjZNc78bd6DO0w)tkfr-GPwb75%yC?ln$ z+}-L{5cyZQV!LuQj2q|GEd8XYI5~Xzi+9&sK?bM(^=VO;=4>O>?E*+pnzvu`6|G#o zMLW}FpIpWe%eI+e&-r3QmA6j5t3I=OKEmb7zIi9~vPhyKV9uuH;z9z>a{tigxI)KfcEuXe`F2w`^ZhVmyAX^Ukt5<9QV#8y3)?|iT zfV;RaDybkg^r_xa!KnEnl|L&?i%E|>zet+mAFSp~MiV>&+_3GJ1e4c``MQqEtPlPH zW)WsP7aEb8uo!v%f){Wmy}3T7qZn7hdTL4bmubyLK$zoC+=sNLo@wImOZ`uU`gBQU z7U8AqhBH_jht097BY&t+{Xk4^amsFmBze?c_u%eumT;q-aObZ8B* zfl+H^^%1Q_%S&%3tI@G@Ryvs);Dt}tQ@5OiWgZHpnP-j$TSo`CD_$0Cs@Vm6FoLlQ zB%A;R@zkEGKG1?AOG@|L7@Y5_##pOb)2+}S0}1OhR4;oM<$hzo^nQ;BSt$^{cJl7P zSNRs0Q2j+Y-d7n5$gdwxvF~G^<;kK}6mFtkAS{wPV#76o|GQC@pp40)CLO0(GXvFQ zT^{u#)p4-0IpSBQPCk{zkZjr(!9t{G*g>6^pY$znx94@U^apQH9iun){D`ER{Or;9 z$fn;0w_5_|dVg?BcNUF_40#7_+%_5WJ(&`>#rUAXe6y=2C)v~NZjvp6i`~93d8>?2 z`x33tI}yhjvZ0Py-5KFX_9He+KozToj=H$LNM+k2a&L#{13-VE$my@D2s-E7p^lg^ ztYhAGNHb^n#}j~s9kXdUv8~&3EMrQYpxW7QE45Kg6P1rWPIOs6{snPRY^iKxQxSLf z=n(@z^T_6*FlrQtq22(NZjJX2I!}DG)UGoD=`EasqaXs zV2jP=x3gDJqAFKgrjp@5Mo^7o$P9)3I}=+wtL ztwIa=l{o|=W;u{JZR+m7f7l$5(B7U;n)ls>8UEX!Ug zGn`6JMeyb7Aeo+`q3+rlj_%P4unta!O(c?GN{utCQ14y*lyfvl_|mZ zp6}+|4-97eR+8>CCPONZkhp{=##zRCbnuV5NHog?IQytco*ErEW=xz|Lj}W4qF7@# zaQL3D#NdJQ3_XF=7NlDSMo8YvlYsVP6>{t}-%APfWyt2(Cy||r$~PRx@a7FVEpriI zmttQbux`hWkAK+?humO{$tA(y`)%^m)I|)szvS3T9(|S{Aa>*EB%+3cRtEq=^n1znix=7yD6vCD%93DGDSM8(OFSCset*~

%8JYh&q;^eyNI8narj!FW7wh8F7cM9_7n7S7c#kcO66rr;naF~=v$dRe zstm>-cY#;v?cz%`U>E_z5-M+ZU|nu z186?~1l$W$0D-~pKw|=QV_TUBJ`K+9! z?F%(=&;`hEq%2+KGtFA&3jF~BWRAOa`molHfbaT}<2Xj}VdC9H8CBEaQVb6DuxMfo z{EyeoR;hjNTcvXnWL4AjETG{Uj}3n!6`Q2KYai=b+L0`)@zQkvdCv$rOoLZ8K!ok4 zyDr}Z;ouW(pAHwU@swK#m0|6Mlge-{&@j|czMrqpQ{K2i0qGcJB8-=9?sN%G*(P3V z$+3WIgu@3}UbVYd85(*UC)K5q4D$?k5^LajAuEnb2dtZCPWe6x(k+SMl9+~as!=!jgX3_#X}_W0)2rbZ~OGQDaQ zKTJyceiaU-#UxdPI{YwkKX3Kr1`hT6BRB+3fvJr)ShWPlVnd)QTl_jCqAAbIe}0cI zX!iI=hPAk^zg2qC5=y?Pj&~OdyxhoJrdy~hYnR9EbMmvcc4dB)PcB7LEvwncD>YNX zX5i0h%-3;EzBy<6GK>8JDZ#C5L!GdMf6zZuVw0MA(RpBJUuuy}Dk5B`x#C`^fTLn5 zpCq^LPi}`Cg>nv^^&_z!Xn^jp-PkHkVxK%x=?<&5cq+%SHMrvNo+-JVv+D{X^rb@T zqPe982Dk3l&IELLPFd2&k|D>R2YhFht$iTzvHme^>Yis6a^yuoapixI%mb!LpeR1u z*q%Lq3_1^}be^3&0HQ|ZyGRf~lzSTktnr}BAI_i}7od0sv^z5rO)Sb1!xdVXzCzvg zRK4G*x3lOi6Is7o6qW>Ru{^UL}EIs`p*d101~nuB>Z*THp{DLuVvmf zNhHrOPhV=8XY+?<$!ULYVpMUNi=;a|xto0|v5TR8XHYJog)ZxUoesa>dT{0Cq+3Ze z==AJzJ8uHv^Jz${-fdyvy^8UTh)xsCND~eq2TPCEhe@+zI%xT-b#KwR7eKi}Y>sVL z;@x#x6l8a%PeqdEU-vNYwVCQyz$TLS54GOkD8lz71h`=wT?%$@P}Xa-m;=^rS;PjK zcY;_#8A!Fhq%4?urf56_WxIyD9x8D27Q?Fe53p(TAH;N?}hA3d7C=%#}s@%CW1>|qQ zEe94GvojZ=o8v1-!UY2T6@z>R9$eK2N;N4ibbRc{jmWJx8#HH`4V(h z2cLTi&Or92VYSMTI;VTFyFfq57^;&$D6;U>*=<0th-!JeIorTQf=Hup z+QjrHl~s}+F?z4)LKS56+J9uSiK83NMK&F0o6O zA%2q$&2}nj#%-eC?!z0`yIS0JZe%!Sx(9Ld^*3TeVn|4uxNzlvi@B3_TuSYJNLi&wNO|aK1ku>C23O%uRkAna+@r+8ivW zr7@*%scst4iR+kg3Yy^`P0`ERUeT1MH96RQc&QydQ7XBF6yTFlE3J(4>d=LUa9atX zCaXW{epvR+&U*eOQx`WeW1w5sxDVFXBkDAhd;5gCvr(V#YBcD_VrQzfBK%g&A%-Er z$(g>ey|C})h_FSSqkD;XY{E98DRX*%u8XnqnFs~(%{51!-R*EPah-2xUBi@4CB+LD zN#p{D-@)F@oOv&0tlP^Z)+MuUu&9<%7{ilS!^Cv8k&*jyrtd)FO-ObKH_$63xa-n5 zeUYz$ZV(LiOf)KFBj7!ZrkO>rN0v#NBF>Vf64idBOEo|8yITs1^kxk_j_z%i7_mF= z&eK}Jt@LdcW*CeL1dK{qm6C+}wY`Jlllx*#|E%mTwPY@?+ls^`P2je)P`6|$U1D=r z#J{X6-yNz)GB^H#$~h*l02Wt~|BF-KfhY1D9@zbFd-(M~T;#t%1p?#@0BNbSAI_4U z$f&d9xyW0cprAl><$AO18ajC(8PXe~=)V&pS2N~Wk+%RV?K&D9o%s5pfiYE~*22VY z-D!K!P{Pi*FLeoeP$6^}pZ;o{iLQj06%({3>xpa2Q5`0q7&G7;9-J0be#sM_$5 zz0|i~RgXDWYClz z(a!2kf2`NY;!$9V#(ld!{6^i_X5u~lqX8@JquN>HI@3|dObEvQ4}MirVY8{uVZ&sq zXWYfePzwqp57dl5Y6x!D#t*oAyCrcEWFhvB)k%rAY_2=V7oaPq;=sN61R&KvfmSTg zdIczJv4@v6}!77pl`U>5dOgqE_6_h)Eo~*O7a%F#6CQvOxa?Ge-t%b*Tji@gEN%A zbcP|J+qKSAE1-Tbt36qd6{FZ3g#v2OzpOHa1a`BDr z5jLD!6aThoc3 zXH>U2g{zUQh7fV`Orve8H`iys@c6zFBvDt8_^N;IdKy2~k=xs;lO&%~;m4NGT3+Y4 z9DcP@bscY`H36v_y8gfV~QkV_#DN9>uem0W^XD@c|%m0F59v?m_qGW+k`3Y`=#OFKsW!L0Irv ze~51+kdE9EjpBLTHI&Uit9mTMu50rXJsg_*3ib6nacSsX4v?GBoj{>ccPsS(;ig<2(G-+H3l8Q6Z|g%p#2@J9Z|EVHEO;7b~O^CGQ(^ z(hSmE?UQ7>!Birn%U8T=fnV&o81fV2=(X&)WfCiwlo#VKe^UP5a76FQ)+oO~th^_B zRrf`r@t^Pprq&Gm2$+Y$wnSydPQNWAr(ZXw!4tpTW)oZ?9yr65Moz|T6I{Z{s&X5_ zI^Dukz1cH({L%d^kML)~-xfdjWGRpyYrp=pvh?ZZr>~L!Bk-NIc>r?Hr}J;V1Bz9^ zb-aG=DR`~t-$~D4MjPM<`W}@GYEU7{yFhN*)U^ilGlU6sCF=fi24dqI)hf+P`uHzsvf!Ry zKlLZcP0nM^)}wEvoo5r5YBzEau5nHUHd^{nx=rbNaT1q-TX^q#kB)%-^UTV6zmt{_ z5x=0uZIhPcoyI!+OFvqS4)VLpBe*RvC(plz{n+?Et%bX=Xmd`e>Sy(+MRPgRvHOLC zuZjoMClJz#^cKqVnugopBv z#`L&-lxPS^%&bH{fVX!-=lp+exH3yD_;IT}ubphvblctB^(g%d>Rx>${p+6k@X+?= zZcwSq!VS+5E2+kvANv=BkYM-8ljoOgAN{5U9sxkDqKdhgYDsRUoS>O#Nl7ItxluHc*T3s-3Q3lbj_r2p>n}EFe%_(T ztoJ5|Xlr6Ssw-Nb$k@Chd{3HL(iA63H@=pe zeL1Wf*sGY6XUUR(jh@Y}{qY_2D!}VT%tNscKpX-9%Cn{b2=oS^cAW9#0MByJchD1{ zU0?>f_WkQ*w6^%iHd#8^u`F1lti0$=0^Dg+>X83XnqUwRAtHf8_jwfz9g}a=(b9C zLXsAku3o3TrFd1^u2f0YVz}1$BjRmic@%wPuZ8>LliO`_J8(U zNc*BS@`}~W&B9%yY`4aLv;Di!S_;=((a-!(g%UB6O~w~qKZLh^SaQt>yl~f z8}e8F^<;%gGk6&BNy6J5n&&|Z>lPzveZR3^O!TH`VU0qsk10s5C@OrwZpPzKR?>-UgPl? zq8mK#oTC1Oq*8m}uvg@dAJmvZJpZ~f$~cL6VYMtRWz6hG^6np@)1DmVbg_wliB=tw z{eL~Z2|U!__douc1!EukT8%N5P?m-k+gLM}kUiTNOZF`(5tEQLj4h<>M6y)YWb8vJ zTSZh7g^*+~y?gTIdU}vQ;ilmCnDCZgzN@Cw7v{^^YJ_B(nQswFNeL5qgaOQ=4o~PE4Nefk_*!P z?mFrR2yGz0K|TcD}rMSyA4IoLdA^4 zGuS3v)1-e_dHc|NV}}=wFPnev8@~N!$o?hP3T=V^-9ft<$&e$y+Q1c@-?#-|DDB3z zd7Y)+9nItuKWt)L;-zTNAvYgoSy}Y$5$@%BX6Z_Uxc+T&zLzigb5Ju^d7GD-nui>VvLF$UtB6d9ON89K4;d=!e7I`5s=RBKKj{mN zMid{DXpkU{78gs)j%U;0H3K+&dn0ZbX;d^Qd%Jg-;N9D}@Vi#~)#Hup$Im&`gXp68 z=Tj^A)OygYA?&&6SowD1%6@KtcF1Di#*A#;DOEuzTCfM$`Jl&p906qblf*LNPG121 z>Huf}y(WR&{~NpzjBwx{984=12Wuim6N5m*`cuvCF@0aY98zF^*ewtA^~23>D=uzY zbmy(S%k;Ude0b?XZEpCQw&Fdn%AUE!r|J27rJ*73r_CMfC->?lM>iHoo$P8>0h-6M zPutxS`l6}gK=po=%pf9`BhxSN{Bw>{j92ib_4#1mZ`saYE*;qv-Oc|vSns9e?LPfR zXZ&5+h|!5315Y%cEu8A(T1hNb?A|uYSyDWPS3KJ!>hs62qT=y&J7!$gb9T%74wGIs za%HZ`PV{$`1O7Rv7vcAOe_U7n!Z+Xlv;<#p!lA4_RW7-=vc(@Ao+g|ne!=9)$&I8o zSJBOSiSDW8^?8|D5q;qjgDQ|0wxVg3scqWTW7SY<#jYY{H6 z(IO8v3GfF|2fES_WMPTD6eEOmqNVF`9;o;^-FN9zU$4>SBk*?D3Ch*w!Mkvf&EWypKB3Z zneVfw*@@~j6$f33g%;MQby*UtdNL6ymuRB_p?%Z{$SRtHS^qxe(8TD*bdDRZe9QJV z=Ab#`yX*v9UK?6!rZP*Ws%hy^QP+%DBb=Bmu_}+ts0cwMo4aA(rAvkL7*ZOf#x+OY zmb8_-ckd^3d}~?X!Tq`SYyXgk`J1J{Pck6jhq#aXd+hV(M$Z7+IQ{Dtg*r4_sIJRF z4)?(*1V0DCQD8%}kU`N`0yxL8mkfj-Vg?1V!6cFo`GW_*#G-*c04xGTzq^U1t88Lh zNlgZ8j;P=|DJVj?p|sLv@XOr9)APy4P9Tzuy{#T&Ti^RXm9sD(@YkrgB5>Xg({|z0 zz~>W<_ohWaL1VK$kuNu%jJtrT0!;ePcfLy%iF^OJ9~)vG!xixIM>K ze=NCt*Y`P9j{Ov50h+vE=I}Y62qHw0e^!47)F3&R0q}DLXJ>AAEm2D z78A-Z%a>^&r_F54;EH1TMLf$$yr!3JmjSB(S1d{NYQ;vhsr_y^XY(@uugAp>xv9w{ zoL3XSYo4KH!Mn7od695*mHVT8gRPY%24B@HO|23pEV`B#J`Rr+{hD*Qx=(Pd&DYKl z>CjT%SVP+TUD7=z;;RPZ|3Qn}zqyH#^Rl1TEi6dHy*Er35t*|JaK(D7JbIysf0k|{ zy_%@uelCT53B{&?=l=L=y}bIh1B6G(_K7=bc$eBu9y5vzHW3lr1l8=~+MBVbrnYo>bc;W5 zrErHAQ!YEO(6BltKWW8>eT#bxsbu?F6#q+B*R2LG4V2`C6GsSgtt9dmcbN2eg*rwjC^o4UD=?nPV_rq*?5%iN9w z)wMz1$G1&&;lLJh>&8VXNhba=%Xd;8wk6UdIaXr|-_FfE>`hVQEs7}8l2$eN;d2dN z-}tlI>DCcRA#E!O)8Q9JK^MK7j%QbyRS2nWDU8`u!!+_R%bsVZ$KR?^KXsq!NDg!Q z5x|tNmu+NH^Xg-U*>Cabm65xRCcNIfXEi3ZCSO%vizVBjS% z4o3qc9^eW|+PD#J3X&g!^S~xpdJyD#6(mOw(9%a>WL6m9O^`6YWqS2JNw}LwMPGHK zyDqe5e{c{!bCz@VVbT%3fk>|?h1&ZjA4(@JOaf2OC+3WH1XnyrJyfJyQ#~UR@+>XP zvZIRr?0aINTzfl8F=G6WLYP(L`J?^$1bScSqsr{>6ux1@_mfO==QF}#{PE%3O>>85 z&XNk@5Ov0?E@MqPlBlOD-Xd+-ZgA|}n-d(44Ufs8u0#9c(%Ev4ldKgKd>b8Z>rHtYVDC42*tFi4-@w0!BL`=XtQlflc z-P6rXvs|~s^PA&c^Doz2lH-Rh zDFo2E6YA3?A^5uwqVIBWnhTx61f)OyKxMN5@n=dqkbST+AlfO2^8kIK9f`hhIywsSb1d%>O&;8670y zJpB;1d-~)!1YHv~02lnPIC+l(55`unI6fH(&@m_phrx<9$id>t5SoR?K*AJv(Fm%n zd=#An%R`V-C`eJdSg=#ycR}>(*F{6m4Jqo*3mLOc#y?GeqMto`(i-_=F*I_T&(x?K zaC_tb8kFn$cRjMjC+%-^kTs=kLS@AytfQnlde5)8jU8IrfJQojUe0dk`#xg zbL*Fr&;NN@hk>L+MXW^I(Ogp zanozkH+-WM^nOlJy=%DaN6yq?e_Kq}X-~C9TYY9YQW(a;tb(j|!Tlhal8l)p`|j8C zwiNqJW9)Z?wXDw+O5U4_o*LjyFxUOkiKpvxhkw9&U4_%_!)4_YJzopFcf4)Ai}{yHS6zIUoc=!CoN|UFz7+34$3?%{)H{! zdtm2I(#5Bdw{Gl|U*ETRuZRrWb=uGh&nAw_gon)~;@%`0wfJ%dwOD$=96Jz<@0Mg) zL>;3|{7=zwxLasZX@Bh3q~MwXC9Z{m9M7f1Wp?etu$1edKzDci((|zM$>%HCs)1-Q&ByeHcA%7{p2IVWt2y z`%paOD(+ebYDa=1IA8z)0a^+GNT9kmK#>vx6`&bLa2}la=U@SN!n;4=Y^R?*fwNVG zUh7h}LJ%OSY$<*7zh6|Ad#SZSYv|Rs2l>zIC6Ca{q?3BV;oK3tLnFFUE%`VVyoz4m zkiJjBDT|pKk0n+0y}D8cdlPA78Bq8Q%s=6O_!WfglcdF>GO&YalpI9Bq8jA#F*I#g zEO6TaTc0EggqrVPs<_Pga9NFjpKRlMjULa=Yow&VJ+0~b)$zjheN%J!olenj+w7G> zBG?RafXmvw9{cA6lVurPv1D|K&c2rX`Ew^f-w@f?N|E958NR{zB5jT!un>JG&~SuL zq~1^^p^RLpRQ_39J8#W~%D$$}vl2pUbT-$Wbq;OB4(pR7XZ4C>4sI62h$1NuxG!t5 z4d$puTld?qngqgl9R(U>^jD5EIG;E^;GZGUYR9#_l0vWX-<7I-*+8sZ(`Odrf0Sq` zTa#A98o;3YU>E(6gv_^U5br3bF{BSj2%EY{EyYw(n2XkA-7+>&yt!oA`IS!PZE0$; zPm(O)0AEamRkXNWky*DFM$`_Uh`9H(tl-@{=a#J$xwbm3-$z)+OlDu-_URe>dvWTT zlU@dq@xIJ!O?>E=osV&PoYON4p?J*k9*T}MBZdH`nsUHyJqT(*00TL&$_@sb-2bU{ zSbQV_aARkX3dn!5po4}D3!)b2M}QltxOB>+@8SzqazIab1i?CC;9qaU@m9wdd7zjxTku;tyh2Eqc0HmhD+vP3k08dU=1?g zL_>EbC^xwz;}u{C9tbD_H%r?%dLsmfQw{-?lda8zKuRV*e$*PqT*&k|x%O`bU_`90`~Ui%_LhuNVqj&IuY z3GMVlN$GF9pr{~@v^>unt;J$(9H+5&oxMe}cKF8`ScrJ@Q{lpqT~uSXs&lG5t53M2 zBlv!xar7q|-v!Yt0zSGu%f8yt_luMti)5w5*C!*(k_Ej2X-%)!9&WD(s zFvxdls(eIamKB~zNoKZP9C1Qx53K=_ODQ_Km%5BC)+JdTmi3%gxeQ` z*vV7F!eX)^jT*gceNhFYYpQL1sVQ2k*U!#G?C+lt4Y=CGlPb43c6)2fz|#PDox{Rt z@&Y!_gVz%N4Z7WngjI|j6l05cXJ!lXkpgS9t6P(E97 zNj>(&Wwhc&tBbN4FBiQpS_d}_PMu6rzUPpo6zuL-AkIsHDs^DcuGpyyQY5}qNo-u@ z!k|j>uA*>Ok`R2ByI>a91i8Mx$86-Gp2* zv=rbzD8kJ8fULsI{$1qP%L7{>)3ty3BSs@eHjX5$pV}Cxp4*+9T7|3Etn%XXb={VR z&E{f38dp4pJswFI(;^1;zE`Pam}@)CN9Cw(ZIt#N5)S**5I4Kj7{)pOMNw z2|v0fS(CCHL-At%wWMePH=jt(YtWS-=w%J6n54V$ZTZT2KK9nVV2mnPZf?_^eHWde zTqnJ16EJ>7tjN1Rk|<~N;^=BlHET}gNMmIe*Pl;A)Z4b5(?Ajun&znbA#Gj*4>ETq z%G%~Ep-HMif^;j%geO5T+i9Mi31NaE;fM-`eOm-p3i1zydku~&fHH7*d=1kG30y|O zJ|tnmj7Gz4fXkoL=sEqH+dj}dgtIV$;a>e*&!_o(Sc*Rez}haA8OsSI5znzfBM~n?5{$PACjx` z8?6m>P3j2%)FzW)BuMd8IRc?#Z0&JZ^;{A$^Yx)@%la6-7R9lN2l;MLEXe@G`VYl3 zkl3_HU2!x5A(s)@mME6E5p8Itx5tRHJrAdh9NA2nzbyNjV}hr?O0 z)apa_Xv`tbrU~>8fsj2eQ=g_c$-zudBuSCTnNHBu{akC<>j2g;=M*hQu zQ3$k<33RWl5>XmYuolcaazn^MH=V2Sm^Bfdpn!XrVS+ZkA05*o^<_Mncoib0VGU{0 zm+NeY;ku*6vh*=j&Vpggoh6zV)sSu>*$n#>ZLUjhYVazQI&}M6ci3|qJK7(^*}##e ziutRTca-FLbO-%GZ?$PWb+wb<>#Sz^>kbp1U^P=i12^9^Ky*=nmr_4fO1DjDAJlKey3I{^byyF$vwYn)lWQzn?Ie`?jDCy11c*s_}+FJ zF70b?@ff4{YJ+V5#KI11Kg_V_f~%Lzh}3ftdPFI^tgL)caQ|NH7#~I1jrqC36D>}x zt0zJ0`Yn5o=nqh3%s@lS8Uw(J5C);L5Ik`1DYi1$Df_KqT_t*ft+LoKCPCgzSfYiO zsDNvf%%09FH?A{U1|4~Elv9Tn;r7%B%5MqcSdoQfgP)~7%`<$0jWL}(Q=>!=pzBm` zAoE?H2pBV)jdCIgMiU+ID5WF6u$fI~4xL0k_O91Eb~jzV_r9~!!caRd;J5Tr`K3L7 z&7AVYeU4}~oA2YU|0*@m;53rF_yHUOF{aVvAWu0bFsTYq;lZs3P|1P1KA2{_A`>_Z zRwq+BKv=-UZoxSyapJy-f@vC11-?p3-u&3)@T*19XFo2P%gTMo{pv|=NT{_aC09Wa zH_8cd81Q~;Fal^C3Ipp-QK7D`((q`BhOvF1PXt#`{qc-*Zbim7PrCO;vgIm{d29_O z_Nc^I!t3DDb@d1dgqyEme4(5We^&;2*%(uYUas`j;p2r6YoPjA7pUXGaGX(+>E=#_ zNZe!5?-xCP{b@bhx>KU}Ys25mA$wu%r1U_aL!q3TeW9`7dHd9-37pLo@2rHn;E7ZW z|8ac`3(ri8{&5Y%vd0sNRxSpJG(PU~8#wk+jCK`kqvZY|UmKDpcY|2%7Qqd0swZ%P z^kGPSFjzpM#oCPl19<^KKNakhFWt9f@a`8c)pYZOH3oZL_bRp^8i_~FDk*MAynsC- zO3EM;<#ezK$046#vQ8VUD7~Brtwhgxs!_(K>(A(UaT_xi6-#?!uPhLK^#nfmtXot} zMWo~zv5C&*+L3BhK-q^M2wC_tR!5Ge)^rd9AN z5DOIOnFv@GC_&a66V_{W2wx%Qb~xcV%G~Y&1dIo$64290kQs9_!Ts&* z?)xz9mb0(-Zkg_t&OR@_js?*z>e5wJWed|+U%mU28}IvAjwrXDxv;`{`4#J>oM+Cy zjh+n&jm=o*n;Tqa;OTF*+ zA?YN0Hi+Us;44Lk8&@Co4$u0EI0X%fK{RF^>Q1IkhQG#}#0SpVBYE|XluzOYiP82M z1}YP126N>$ZsED24ws@>$adMwmsbyu#~SDw;_@aEk5GgUq3&YmWhP))V!%vrYCt}( z(~RLAi5bkK(J%z%6G;lj1TgEcczzmQ5wMN^hlyI_X`TogB$mL`3|LGsN>@{0j0)p~ z2ND#YjNR>>={PRgq{m4v zVy5tl0r3Hf2Z5sW4W|G`a3w+Uz&C?I&}~k~?(??|w^aK$s&9Q=m|tp=D3IG*ueor# zb%pc#E0GgbC2jRYnbQ#grn3G@LE(y@THd`~5KF&cxqsVuZLaUVPpWHa+eKZD_!eb) zTbI`v7NcuoACJ#e^JsbTZMSl){DGZp<4bBItG~?07u1Tm={4ii0tSR5=W5p0~K>WRiD<+t?ygKnkEceje* zUusIGcE1>q?^ay)y4QEVsATOWf9@m3p`)e~C-KKr*EPE{e9D;5&v`ErKsGW=dNOt*Kcd0slJ*#O`P$Vz9-p#P3foWKKYm&@$ck$_abt^6pRhqNjtYXGb>D%sNrO4+|83+5KR_z0nxH zBa?DX^is`iJ-4peNE}s&t2oXee#DFhdgaWKz{cGtMuA`iuwN9hVSv0rXvQxy2h47e z8P9lx1bi$=^9P#kfN8mlMjvb|wL!7|u>Dy5iKDG&Pgtn74^6tizwK0PxT~Bji~lgt zfT2x65J7=lhe3XEt%Gxj@EHlOdGc60=DB5}!jzl&40(qPhY|%72IX#|2pDMyI!=Ke zLW0a`nvgui%N1Uq&>+*&dqUDd!@N1B#BI_wM?%;4Lk|0n;wuih={9l?Qjr%R5jb5k zhDQhK#U=Qj%j^$OJ#lc*!;F&aWcxs?cULbthVpZ_@aMO?>W9$PColVI$~zvl`D*Rb z82sq*EKeeEI)#E${Cq8x*o5#38LdaJNly;@J~9nz^-5YZ=NS>eN##fW;owe*y z-LdvuV?ScvIa}&+!dDHRUbCT$HzP}2{qm2R|0wC2y-Z-!A>b9oG8I6?xY-r`&(OyR zLcGApIMDAX7NChJ5d2$EyxTupQ<@P%KyY8+Mt0qZESVz#bh!{Jdd397Yb6MngX4rhR z+x4F?3*QW09+RKR`41BO7$-N12pQ8*7sV`(Xz5@C5Zd+Y00CWqu^r&HW`J#KK-MYb zIBOqIohdZ9Uc9a#d_4LCAI_e`Ox)?%oKLEV5U7G@$zz{u>lG#!KQ3}BqFHXtCG1zX z@ZV=`2DJfeUj>rNT>SzxE0;?&^0_-J`cvcwsq&|6ynY_n*JJ167UmX)6O$8h5FU4e zAQ%UXc{WImvdakT!-E%!XzcISjg&gjtJNtbcAMsj$gbHVB$M|w1HE_ApE;0@$42pGhWP{#w+Uz$Tg zk{LR1mNHhE>@)aw`hZ=i*KK04idVK$&g~RGJcYd+15<%xZ$NekZE_v9iU9svrZ?V3b7a z_F?1C$(RR4D4)$7pS>Dv$R5By@?8j&Tf7_GEn{!wb$ulHn^DTjfblu(%5>iJ*M%YF zP2MM7FAgON!wZX^hl;ydOoU?AVOQv9V5(3xpT8#D%{)Ao0%0Z$LSZvDx;0$u(1&{V zF+Mc>5b(crJRxIEf*^`K*Ql^+I>FMHrfe(+kHf$wdeR_Jf=zLF!JZQWSM7u1oBkytZ6&-}CrUkTKu8D<)-xDDW@7ruFo-z~7&5*( zZUo<(iIL2x6xl%8OzC0CxG`ftyzU!mJIne#0go(HMv|@|z+?0v_`$Z+Sq(8;y%zSl zDd~WpI;$Q3>JWXr)uUgj(&KKkTJF4nfbsX^6OVNj*(xEZ(!`G6_`EgJpixD)QroSX ze9|2?Fs|@tMN-ec=G}sinEJ43*4$zcxoX|m%7sm1*_?!Q}iVY0e@?mM!emr>*o*QqvM)k zV$s$E($GV%SpPF56XCU*^lX`w3GyPWgxjQaNB(Y!;JB;PyjLYAS@csxqZ8Yc$EE^D zt863}eXq-&jU|oF_HBHyX~BIY~Xf5mU%hh4vYX{;sBNIWZj>1 z5}X8yar6+F>&PT_3M-{f0mfyLNYk~z4%1lXZx6b&CsrLeBlYmjQQ> zXFN#m04c13Jq%jX_%_tirglTlwTM>tz5$;;%vn5@}S=kMTrHTp{9{L}5T1uK`gPhV6G>DzFe zGIuBmowI9;n@(R{u{t)Ao%@ZwAlP~)g}-!5T*Bdrp82HbIsA*pEzFzM_wc48TA|cS zG476oy}y1wu-@LnI2O+K%B_8ins8QE-gW=YKor}`dZ8}6oU^R+?bV8Fzy#~>D?G8e z|3O?CZ4oAsW&c5Es>z6koAb_MziRj5P1Wvm8H7Fv^*t058Ipr%m5oH}w&`YXSsir` z$n4OP&kcXQ3k$C^-#nUg-S6aYCVv}|)yqq10-@!*xY^3VY}1v-lS1mx-8usC(nVXm zdWOsuQhU@NYj^m!!Z9l{A9jT^?CpJ7Rk>Mg>MbAH`*+DU4Z*H>hE7`lE$XP`f7(G= zk#z{h*Q_I#?r^QN-_W}Tlik)`)%et6-_PI7OUj`fH&g~4`V`A^iY)q{CMpEbg!#A~ zpZCfre;w!zhlN~d^LTbiNlR)F|GB>{d%w~uh2?&$-k{0KOpR>S&zTlnR{P6`*GywJ zwlg%!YO=I7Kfb<@JFsvjpgZK5OcV7-)Ppx_yN>UCFA}-2xiZ)ZF08a?rDr-9Wdtjo zrlTV;;aNn91D2`S0jLWiDo4l^06+I22#`F8fZ;Ecb&I}c`!2GP$aT=)Lw!MIvd3Uo(jydzS;r$~o z-_=)O@7#{rcs`Z++61?yH+9Ax{w}tbAvj5ki|p!|K){gT5E+AnLu(kaxIXZW-X-$u6UFmzHer@@||?Kjhs_l8NQTpW{k^Dfg5LuOy@Qz%6ctK{mc(D zfBho1W<>9hot{yKiUWV6{#WDas6GXWQ>WTTczk)VJAyFFbngC6hwQIuF@2IqiOz4z zSD!mQ3UrY2S-y6*lfKmapj!qM{mUH;X?B`!-!8W~^)#~V%_bLh>fX6?$&cC&5A6>& z1^n$x=w50baVUF=*R%X2ZRPc8StaXttOUvCafCnTy^~vq0%+IiObzy8>W%9sw?mFp zTAp-ypA&6*kuJ4_ykJDT)G4zm-VhScW4S93&>~rIYbuR_&uOM_OnZs~v#D5BX-6#6 zEQzP3-;8c>*kB8h4+3u#{hUjJ{dzUCyM*5wftqQ1`%&c-w&_(pkvcV!uwKfz;gr0^=-t3#`IYNAH{1*U0& z^=IG7)_{pAkst?~Vx=#su>%b(B`q>NUyR?B(KdyXZEa5EIe)zvZ89=U zu1QhVQ-5B%UlvYZ{;8$Sm1s#Vy#TuJhJ6@K5EIMB2*z0|X%i3@`z_*J+@4X5nrtYPSOVmqZ6YupH;o_Bw<%Vi{ ze}(*VdYgiipdI!&{_QW)X=T#Cij$+ttfnP(qDI+zq^q?$=xL{JR)_THOiqLQaru@8 zS=E%a4r{#+XY8|8+yCq_pKqr{S8Z>Ln+|8#?tBj@P4=G`ITpRwXh|7KP_ODdI~zwxXRYT(qTVFCHc~5@6L(WXTwLvv2WJn7AyEKSU2k_ zbxX{w{%PJHoUbqiJs!`A-*iHat>1q6q<%y8Uivjo_c1EtuIE0Bdl|JoX@$qQ&|Xd{ zfk|M2kBhyE3xcpf51T;@IywL?G-DgrbpR@MG7z*0vSEzhRc@ZN==Ufy;=OT_@fmvN zA%)aqE~KT&XxuD+(??8#4B`RCv$KoEQaX~nBdL-nnfm&Pp}l#QbfTS#WC}K?UZBM- z-F~j}>!$jddzyE$1~sRHU3^?e<`Oe6M4sa);pwLmuigEX^2KV*d+ayw0Dk&H!^$G| zS-p?j_C=M+`KhNnvh#1U2Q)ss;TxnRO-0L(f>=CfG-~?tjSdt49|2#!l-b_Lsat~)gCeJM7Z2?1ow`QTne8Cl_Jvez1Br2qa0U- zja3Q-DkcALG~r4jZtw-9t+wB?w;hEa<7kwatyGy|;8l5^_Ll%R5ZvJa%uxD&kXB7U zowafI@C!FY8)W3t%jV;OFz662P276on3S~6ulyy6C{?fg>Ni#)oZmI&`M3VUKY5ylxWR?RD4h(?*VCoKzf%=2cy>q0)`WR^v zq*XoPMtCoB@C*nR4CF5mKn(d4kTGDmK#*Q?(k2EX08HADz=qU2KCbu0v{MDk;&e~G z({kg%j`BpX&WV&sXIf#WB1LJ>4jDmq!rpfKQP>=~a8*j@XbTOsedP@awBj=Tu zl`mB5!fzxZ>s4-T?)m8Ic=kNS@>0W0P-yZG*BWWbJRh#^8 zn!o$q(BFlfbV3?-n1}u#u?C(?d(W~@vAkm&CP9#g%>+;kP+N^}=eD2g+(x8A%uRy~ zGV6!6IzQ56g+qE~``@=fekbd~QyZ79X5f8%b>H2_OrT@8$a9xTtm~g{L{}9OudO0J zr-<3C;@?%l>FX(i8BxLUgDhE}Cf>zyn5g7g?bTb$_q9Fq?Z~YV4WBE{{^4f1=zF_K zdsJB(&`58!k`)r5vn5TF*9bQ$K<$ak zg112`0?o%u0eCbFQFN+YG1GFbfB4Y_&kn{kk@7oICC23!&dk25Ve?zG;E0?=61@8_%X5^G&>1;=p6u1q`;3k8 zz~^*AQ7A}D$%iq8xunWEk8EszuiapkXzA z_%my`SZM!n;>%yIYo(ti%wF@)Kb{zyI>HRHNFreOzez-O-(Qx$yZ!Leev0> zvR|iuEX37&3;+4Pr95#ooClmdcjfQ)E))Ib?%<~dpElO|R#r`2m5!t$RHTH&2(K zj(xhXGqo{<#5cPNmbPDi*)COn)+ojC^mDtZM1x=7?tKXAC-zXeh2m1UwRI_s6c%B@ zv=;yewM5h*LGwMc0WKX_vJMtx)QrQh;vkMk0#Z-${I@QG!6Ag0Gff911puLe2S?HX z<^m|~!YqtpH!jUV5o>-_!TT8GGq%{hm{|X;94WlQ)v|F z6vViNRl!O_T!?xFxHP(lfFi*KsL3pUdDp@3ix6&0_Pm6;^v zXP&8pI+OUmk(+j9aaWb4CnvAw6dBjcYdhqavR03pnx>aOzi+|Yp?vteRdJlB;W5cD z$1CRs$_KoUn{7HFUw8!tOS}+>ewkjrh;}9yS$9cT(I3Q$oorEQ!j63+u?j>LF44E@ zSY6xGq#GP>nE$NnpVD5zh)mx!&W|4tNRyq3SS5D0cj_Wr8k7p~cJKEE)q?+a?^BY( z9oaR-mkT0^kv-W*HJ3UjP>geLj{;$Lu9vta_4jTENfv3h6VbFU+CkbCirSd}%|ouQ ztl<9b*k-(qqOJtIlV^D7~|{C8GhY$FVHM= z8PzWmj62De>ct*R!+_s+2h4gB+(HC z>{Nss3rO@}gZH{2NRmi1AgGXC8VW23IvOrW0el4zD5f!*9cL6PE_R@R&w#+ipo~d_ zSat{|z&kjf!k=&>&sJQX;lzm6&PlWL#Vh!^*E$R4>Z0$Myn4BU^tSMy)sI`vq<(I= zcIZbAx4iJy;r{CAjY)Nu`SJnh%nc5fX1(C(NVe&0@~?)``GED@^#v*XSmMR9Oo3wA zOo5`L0&nuqmgk3W+k^bnsD`?><=XLW4%XpwtRp<@RvW3De_!bQKJrp?(o=rhb8A0d zRJ@mG-R=3EXJ>yOW7@a+ow}c$x@Eo+F211Gd5v?x)Zpj+JzMmmJs#fv)*v;Xn<>#CV&h<;-R=2$C zf8^|4I}5@C9)ZsD&UNp)FI?W&`+c}bkGV8gecjpim(S-RP4x~ss7B5jUpui8QX9h| z9X@xh|GpzD%T&`YH`oR~Z>YYKx%rgS`&vJ9h_Ui6@pwvH$I+=3?G>q~%A%J?*5sEs z_s!$LHI>vFsG4n6SI$ROfd+>z;Kf!h|3PDC&r$sIZU-;kiK^!|U);%f&$XZO7xEqV zh|5-7OZXGNhn>Mx&*=BzpXo|FNO)U?M1Zs$n63bvhOP<lK`$^ZK&diC1y1-= z0!D&d4@hhcsxZKAfMALALNtYj0qbn1rWRh0#0|5<|x#X$`Sa4uCmu#KIOeK4E74{g$ zYLT&Sd3+4Ix|M=luwfWlf`GgNqi_{l@`}V@1R=9HOeq3{hXAy+esJ{=BZ!&<1hx>D zfR)aJ758Xy>m`>f(B7=?xJ-kIS%6|E77H^o8?Gebd2tFj zih&DLGY#@Q&6ixKPza~|?;ZIMzAU&s2aieM6u{Dei3Vt$f;R)@Ki`s5gEgKlL=>(= zk^;?lSQd-{+z$+`Wq$2|#Sb81-n1>HXO~y0iKWUZUM)=(tBHjbO>!wQH_9UeTt39A zz*#r3cc26v7#pSVAa_*h;By!;08Tkzf4FK3OM3!nE>03u&IN1&7(_!+df;4QFn$>v zFCSyfh>Bh!cChpUojzFU6U;sLwD^HIUzxE9k7trXWdrU#cG!!H+mj%sqzxC-tt3cd zwZW$x3<{Wk3P^(ln<5Qx&IsTXLR%0Tj*G@66h9d#d{FEeEtw=lgyPI4XgzW0t}a?p zEQJ?OH0LFvaJ*t!h&oP;Xdsiz$Hbqe4Z+>3+DEQF9}An=j@ MGvIq5rvE1YAI4fsod5s; literal 0 HcmV?d00001 diff --git a/media/tutorial/img10.jpg b/media/tutorial/img10.jpg new file mode 100644 index 0000000000000000000000000000000000000000..925ed918200790bb590009f9eee752e77b7193cb GIT binary patch literal 129990 zcmb5VdpuMBA2@zCQ=FP&wLL#CvVxmZ-sGRf`2^obQyLTz9L5jI_BR;Y-(i|Ui-8DIdxhp*{etv9cv+n(@0QH z343AB5lal9ef_4x`Z224`V9#Y__GP)rDOOI(0Kkg0ORk6BBTgG+~}t)LkYD7wt)ws z%kU7+P{P3QklLa_9gBBU&uUwc7CIqCJUZvIdhk|D=}+ZWZ-p`Pt2_-x_cqpc0IT2$fo>T3ddQdYz0x+8v~@;u^}yC|X8?a*d+vL<>O}yTA73Wa0=O5}sIC z5w{;(Q)-rOhMO=BPiU))H6$<&H&0IJ4LMF-vQ{j?*kP}m^Wh@?f)#=g4D|Nu8zebJ ziqcEy!F5YKL?jW&<(_no^D*B2J3|2$oSn*IW!2<;A$M^s>G89Sj0WkJK*?3nX(9w0 z`L!(i!82OBk!n_!TlT zM1*b~e?3*c--5*)phzVLHNap;u@D}HM}V1KqE8AGJ>fhYFDTF|#RDtP&tmlW7MxE2chczVc zZt_=dFnreJs`NeY1z1U0^h7;>C`Rbche znL-EODNxPVA|g3i2@8?Pctr>jq~ZSu7}?ar;^mKq6otyDr|# zXmD?8oHr+v8l*M_*c!0^X&B6SZe#FyPH*_Vtw1q4qlP(vP-jQJg&;aupdf&rF9=vk zgh9@@i*7?+e^(FS3vRMMH*SCSPAUQtCKJseh#&$(l7-Evb34lgB2qOgeEM*4eLo8{ z#%5wStt1Rx9J;8j9_^4@P_G*u#@hB^T)bg?O4pC`b|&oi&*q%!@1wsC?RjOpPls1! z6FJX*A8S9xO&|k(5iu*Vq!z-AA;Fu9cs@c9lqy1Nd~wA+_@fBS412H7sxvky>t4-E zfXQiJFf3Vu#l*lreNVgY;AH8yLp8wKwWapBc&=uly_aj7NGaK;rqy-zXKm)#_`>?h zhf(W?wjEu?h8hJPx|STgdNuKyk=JuJD+EiO!2ZFrGJ15lB>Z0+0rM;cqCkPbAqn(K zkoqY-0tkMDc7y%V(yV)4VeUaB3K2qdr&@qBbo9Vps{~imqR%r4-*ldurq0-ikFqnm zrpFzM1CO{YhO7()O)obYP4ng#BS*`-z25&ATe980$nB~+7S{8rdC2p<*bGhYtH^Z# z_K3aa1IBpbJwRx|>wE-Im=o~-ObNs{Ffg|#t0|;D%()3!`^z)k;hh=2_Rbh2g5nH8 zCM_8?(#gtxn!Pc;&fy`<0F=l7i{WBW8OTB4K}R$f*7!hbQmM*8+cJ>3{Om|c)c z5u^z$?$r~>Gipi(KM=rMC?AUvp)rs$;F@nGA?Vc1&o%$1r{i}RtO3i zA6T$&qXXxl^kQTw?7+l8Unsj+^B#X5G!5K?1oHs(km$KRDco5pez^^j`JZ9|F$e1{ zB!Zic=0lsSUQg+J6&=Vkx<{+tuiBI@mHnBFgb;#MD!AdF(SZd%M2HeOS1>=*=H?yQ z_*0Gl0|e#sXFvmdfzVLA!gU_gDBuVF8{iKPj0m-mf4M8^2z|keR2epey1#$dr<1uM zvHrkX@o#|?p8PUYYK9;Iqo7`cdxpdNi<28Zgyd%HUsR?G8>8W9C?6fC^d6lcTBjar z6F?iAwb}N}XqiQ^)b*;;Ab?5We9s2K{+{80U(x0m2nrn;Sm2T>f~I0>S}x7L3?B_k z>%2$j^Ay}V{BQo#8{lHRo#WST_;zLJS`~I>%S`L|=r@VPHGwgY3L_h4q0xy|+DhnD zQr6X&m8D_Zyr|LED$k$8&hx|OyrI#X-*oj71ER$^Vz=GI0U_8%pICm$DxK~CdId(Y7cL9ZmpiM=OrCT+LZ*D&p z$|s`Zz$gS(9+M9&05pk$Hid|jrlK)G9sbjT{~$;Lrb5tDZtWnZy0dZpp?_Gn9sCQ-(YT7w1Yr7;W5DQN{s9JU1;P*M3F9GA-fY)IHJ=^- z!T5Vtis56b>=weEvT3Ppub1xJ(_X(7Xl9y_CEwM;sdRLXdgDN~XZ_w#frs3J!pv#_ zfkNRU{{IdEI*>_k;&^U$+XKEl0SN{N1-!vG8J7M+}l;ci&| zcO5}f-C?7}1|P_ZkfaO{2mU&+Z|M-MKkw)a`2nMg0R!#~&!6NkQA8jBf=~DV)?vBF z{Qo*dNKtIDGJ?G~%-&uRkXFL>+L8ROps6mCeIY4{+OeLgSO}P67#>)L_uXKcL+)-4 zg=xvH8Zkl)@GEc<7(ogjiY!q`yoD%b;rX9Tbs+?0;^8eS%013tF=z@Rq+hRJJj%ix zLcp74ApOFPxNrTnM6fV8E!*AIS1Y|2y=B z@dOwUShmp<-3mMr1WLfFz*UrDHiz!WJwL6~5fAK;r6Pow`u6jRpTVkU^R1ASB%`MB zuA0A$r9+$D-Td<@klkR?+0SXoW690`i4A{x1Rb2fI`}dq*Q4uQtOk=VQ~@N0BsW`y zR$kM0+xD;q1W`B;QS&`||I-(9rR*Z{f1HyOI8AJRJ2F!RcDY!Q+qt5~> z3Fi3Up~w#?{|5wmrT1k*QrNQ;4?+V-eBI;Z>-rl>!sB{Lf#&l;GL~{HKiBCub18_!NMG=NCvE*C&kIcZV z=fcm+j;Vk_zH-V&G!5OD$(d-t-mcIcjU1mqS)%?9!93rK#P!=KZ1F$W_~e{n#Lwwx zw!3WoMsP+mqo<8VM;yKzp^P|RC)XsB3TBK>7!^!7Oc{k3MZY-t>8HcMe9uDDFGF!$ zL_^QuUaNF-4Dzy8$AU1P?*(CS?~CKwH{yY6J6qCV{pk)9;m@vavwf_>;zI_M7mP6Y z!+BKG5Yxrrva58%Wu5t{6C4S2A|HvML3d@z(tf&zyTo(KU*_2!(ABCvIQi=85^d!q zG5HGz!`W-$DMGz|=J7>6zdN&GiA$^`o2G*PNUy=j!_TeM>3n$t&R>&VDT;^(d_j~R zcXyMJ=w2OG;e7LBPX_VP;Ad$k0}LJBVJpwZVl_LfRKm-g@ziG2ed#-N)InC62@+0G z?z8F^wN4D8f1N#`(9p9Q#q@q#vAkZDVPw18V`pUTJFhoO{wwSN+e5a;9pskARwDnb zdnLKAr*N5%jBJn8jv1Vs3aK44VkO0`1uq9SNW>ZqEGN|&DXd*wxIGCe0z4FfN#*8@ zNH@z!BC4IF7r0ixt7_*z@8>M%ou}ac-XMqw<`#U&Iai%?PMHDB-gq}HyK(HzE$w6< z6oaN%NF6|BDnl3tON)TpzKd0wg^6JcXBwXA7&JvC>-_WT*x^bW25UYRTWT^tWoy*P z$$eb#j>|-lNeBTrs2@3Zf1-XY$|LKe z-_(5;hz4K~5pO3IWE)x2Fj}nRO=JU$5^I6gK+qBSa2PSah)#hQ;wolka3vKB+_zlE zVZ$#8;x-LhlR7pZblmTZU(n?~P|q>NZ0(sw@ebPLTzcOP0&qOcJf9e?2gHMKi>1fz z^&uo7V5krrL%*@`t4XY!t9?yZ>oK%aybvTPSq);@RmocU)ywf%fG+Cgb*!RN41z(j z`d~qZoRx?wWL(n}#=$Q$tK9?-Q0UFn{j{KswMaM}lJHZR8(kM}TJbWisJ)12npl)l z$$Q_~G+hGx15vS?FU3IbHU(I<;UNOhOIZJ1_4)PTu3%o&wSRwYpF{@PH%s|SQkw;# zEuVwR+EttKqYYLsyT-)xNq~mKov{o@6x@#da7NEkJfqJyc)aH&ZP+Ng+fPq7WW1+O zn`)^(wy;8elX#_3v+}cz8-7zrN}f$r#Z>8o-tID>=k!u1(E)%51w?rJRDlbT1cEFn zP@lv(xSX54Qfyn7+96{?2ZD?hyzwh|ysx^mN{1lKF2=n$V|^AbNis(;2#^XA4m(p> zTk9nKb}C+llN;+f#U_4;Hf#vS7_&+06AR(vnX^6PeMI2dP1AjB8o6bhT$?4f&3BjD z0-5(>iUoQU2muHH%ZkaUp-3|DFuW858%(nN897`(&-FN2J{IMz4{ku50w=?$uwNDP zQ!J^?s!eG^1R>GuWTh8a=@t?Ji$GuwoD`^RIIpK^?dtMgOp{RIK(hB0xpS^{Cu74y3{^IVVZO7i400SQyJh`$TGDNKYSDFYKRea>2yKe#-6k{g`4YE1cS z1TAR`OT373`NlK*e6m;PT?cM7Kol4ZD~Y1EVNK}xsfQR9<+o|30T;iG+f@2abFGJh zIg&$~gzCRi17|EEb|EDk_1>1NyEky#(X%Ha?SDD1?Ehfe?`T&a>1Q zgpmjgAT+%BuOVM76awi!1k1X2ui-v`1!e^f-jcGlB60Z8^vaGE509}`w*PhrE<$Z) z$Vwb9@0&L;GFJ^hXb4oKlNaEcrh zFqC4N)_-4?RDcr@s}eK_XZe@WeGrI;5Qu#wWfM9B!5@Rb0AY`>NOaM1g#U_>Z7FZR z$HPdVa?~2F4)90^XK(NH&ow{VlX$sPiUc5El5ixPuvKn5!<%%w%_UW}y1>Ss#R6VI zywddHm|g>?Am{MQ!!L1{tZS`Z6BPNW5u6X4Rw9c87lwBb7$ii^mphYjr$(fshx$OP zgQNBdyaxq>z&pUJAX`s2F~^|w!~A-EY*p5xk;i?*#7lati_>FZAmtvY;plQWi$;eA zYmc zu1$Iln4l0uyf3wG*6%eZTy_IkO8=!0kc&mlZT@?$#2NskDc#n{pD7N~tQ3I&pFshu zR;zTY1al0a9fXoHhYS^(JdUvwCRXzfhx~dHAwOcC4}YQP*|r_BB|y4n)!g!HUKdeXtW@m1l}B~UiuXaS@Sc4Lr1 zfPr-))ca_c=papPe=$w)vJjz2!?DsJxChP*-hu|2nvc#+6j_R_sv4~y`y;U{$@vb@ zD*EQZ<-Bv<*5_EHshBq{Sfyr2x(pKTtRwR}QQ^;wP8o&ukZhPqN5WS1MmgHsjff8~G5tbb%T8widY2F0W!ujSe_E z9w;|rpY|Kw&J1^3kHjVoE(wbp{FfB<=l4+d=g}|^$(rlrzlFb3PBI6n6cJES0>*-x zUxGn;ioWH0Z)u96Il~fM2%BI96`?pqBy{LGcd@v8?fKz3?jH%6jHOt#(hKA7Ki06T z(%m*;L!zBA90j2U={F#BtKPh;sqj_Ey|6#In4bjPz5LM8$#l-t{Ay4HA9}Sh86sIC zgRBeFK3D?9p@0Zeh6c$NLTCXkV3cJjFh~lp9!-IvEtQ%fC=EpC0vyiEZ#^qak9yvI zccbCFUiN?@wCnl)B4&0isoki_YSckH<+7n%PfuGJ-$a6H0htwY_v^1^TlrcNVe?hP z@r8&;X2sBl!XIxKf-pQiN94;S-=3d+ z;?*r%4wCVdiuQeIE}2;E+9t5Ft1y z3PVUJPU!`jAV`6vf$N|EXMvTqJ8Sgs?juiwM#I;+U2NA?=GB2;g?Bl*<+Fqwa%YkF z<&HFa5x_DS{1P8FF<0W+b%W$?yuy=30Gk(qnhPo!ajA?LPqA+%675Q>3)6@o0+4~1 z0p^3ySr)QPBf<$t;38a??UTMBgztCc=*k~B#?z*!UX6>K3FaU?J<`E!Y86!LjjV2m4#5W zzbTtQ@6<}pqVDq54e0Lk_|-${OAf>*EbXqY8tFH9$7C5z3Fn!z}QStTP0&Dsw~%!662` z8BR2Y;Ba6EkSb`JbPOPbJ&*+$88^35$1Z0oENXJnY@X1#s-Bd%k^^eMIXO7&b$#5y zavhIkHdV|mt_Sw$cE2XTjf1?>jhec;-*ojk$gg5ac-$l}#QhPACWwN^T0(FNTm;Y` z9(`C7$blk&0jRCi2G$G|0f+^PAJIc{4{ahEmaeRy?61w$GaE@dw)fVR*4wki6{F;KDr6} z5@Eh*2xegpCZ`L4UJt}CnMhNFundy<(Nc3{7KmFx69x@Qw@`!_$`8Hdp7dE;2jA%* z{>`3p@(y<$E%K5Zvg$VBmxAttQ!}Jopfdz)0jlFxZNV*UY0lBiZcSXKvqfc?{=i}O zkG>9CK=265APZZd4A=~pXkAyW3@TvuR>Eann4O#$PZ{>Sk0WX+=MgE=8fG3 zJr$kOs6%?3Zhy@5=s*h5(JSJ8Xkl94)Y?_c$4sl+@owF>#r}Ydq2L~Rmcj-2+A32 z`)euz9fcUIkmy|S8#X?u;C6xTCxfMWeH^es<%UltXTz4P>5Z@09@qBQ>di;!T&gOV z=r^4R{k6hzng8WZqk#|#ofh+`)AVrc1)bQV{9s)Xa#r=BfKLMY1`;NMU=ZU~?BjFJ zc#~@IUDeW@h$lKNRaa#_I2I>$hfeDD-1a6Rz+>Q$Zt)7!^(Lijl5WztI4ZYTQ+lF% zIV$@=cb_k-(OC}HB>vo#d!;b%$aLh(U*U`StIW^`Qxl7chLMB%B;Xz%rA>Cf1<8}> zM^r%<%2E;z(Iip8BD%igmwDq%5OjwF&>mlsNppHwMzyl#YiU^10YUXnwE> zdleK?v z^pOdwq-w0Dl&sIK1m5g~yC;!kdwlr!(&W~hv#gNR_LN?3Qf$)wF#-s#K33Kip(t=P zC~8Qz8XfV-)zL;pga=ogQwslMb*S?4?iVL296D)#lwAQN_L1e zOyPAz;nsZtAqR2ssunrt?n>pHWgN1JvY43aK)Fx{43Bt!{X?p93c(XNPwm6VqL|nHo@AUb|KwG@^zWUxecGvQLwj}mjFG^* zf_ch61{Ws><@*nv` zwiu`MJ`^a4l zKyOX>Ne#thT$DGoSFX?L_!dp}r1cJ`+9z1O@Mqf%+;nG1pb~23Gds63wBmjwFe8*Z z)$`+f;*jnA5u+Py(;cG&nXKE>JpE78Zl5LrioPI$A;4p?M?sXFZwc!6bPHtaF4gr5 zWO7ka{=`IMD2wBghLEed*Q3#J%wGn_(HdpFv=maYsq@oo%sg4l#;$D{TlHV$qAZkZ z#kvyI4mX3OMGUmPL6a^hd4zRHpFBPeEbgvEg>Su?>8H5wu|qPMwpoL@A-NA^1*rr2 zt4%qDi$CU2^Na14D{E88@QB2#a~TVX3OtJ@|BQx1?h0NJ-EKge<&iL~3cJiY#Rti! zv7q4fko$JkVJE98G;+o@in+yT14@~$SkrO-#f`i@Yw;oLS?KTbt}mJCrs$c(~o zW!c-=AFYNq;gzt@kJKl3&*|6nraSlR&Gj3~_1%PfljItN%&D%E!K_a1?8G)4QD*IR7a*NILD`(rKi0r)`riF%DxlV@ zFgg?$*<{GvnS)}$?aqQoX3@~?cWy)RuE`PZ(n@(dC+*t|n=_Fxp;SMMOCQQ}7O5YdO$b}|A+d6d z!b4X6T<%ntpffa7R9F{qqFebaD_{mhQa7XD4JY~gI?F<66zx-oCCNntAwmPm20^o= zVW_sS&N)z^@YQS3dHmKL4>@Bty9duM7=_lkr=jTVltI6?x#*;~E7y*42h&(lO@Hz~ zSb4crtQq7!x$a|hS$aTFDNclTj6g%ww8e{@kZaKWz5W}Q_1?cR^OPoSG58fH|Gd*! z#*l^FF~<~=ltsn2PkrKYGDw)WX;DzqRDY6vhpV@p=3sK}h0FS0dWMbaWwe{X0f-R< zyD{(+a0IYFzL~7YIet6RKAaZG(Vf;FUkoo#tr=seT4oCAM>IW4AJB9Xp;g;%v$fS5 zR{bRQy`v`4p-QhWVwqj^bB&BLx{wN@Mi{~v)0QuDbKe8``Y$%2dOedY@(hPv0GiL0 zq5Zk>7f9HB0rp&ydV_F~)wCGt?WH-c?oIea%dhc|_5n_X?%9vj^-k})<|MH@t6t3J zv(9%zhpu!^jfnV&h( z3i8$ahMoJEA*m3|vjM6`(-fsCQqkR`wa#waiVuEuoiW5NMCdLx^pb*aCLfjbCaH!{ zxg-&7Z&M@pPZok81n2C`e41uQa5`i-QLM0>d~v4TAxbUbz7I&E>8@Xw6 z>9?U~l>3Ft3c3NTv=cGd>p|9m>89;<0ls!QqEjgr$K4IZvzJo$s92bqpK|omnj36O zx^Li?{)}7D-N~7#oepgMp1IPf41q)}Ht2x}6?-2?4U5`+gp`?sZTRH3BJ zIL|Q$l}19cP0rnNd{t{Tu!Gjevyop7A`vAYTQ6u9TQpqkvmUn&ddnSITJ|4ruR3^c zf&0!E_1@02P7DRnNqEGLZjGaT+9^@G7p}Pao}vlAyRecUUo!kz|Pys)atSgNpRjA{`pqkk{U3~jdGCMx|OKfPz_CFfq0)@HUI(VvW* z0nPt|$9Vbqr-Cez87}6;Q`816omc2!DtJo+G@|fYU|*asqMXEwQp;+AW1Cf)X=2l^?uLjzJ56B zM$QBtM}cRP8ygT>vAFMN*R=g2&*vA98y&%G@e?QuXJsr-a@%_+_NP~=*!NNh;zN}R zyz(4b=UChUy*ur@kKff9$sw>Wn#gXmFrzhgYtiVE74PpdGO~v4)O2x)EnYBaVEQ>vF6ti7A_$k+uP+o+YL@Ec zQwNAe;YU$w@!F`wOtvrYDJg8IW3-YsHj{j+HvHXHk3gfv+|pyU$1a$4X>$_C+lKW7 z9JJ^?)BzPSfs=cS-G!rans!B3R182;<_tW^SUN0fmzcR9Y1raiwxNMn?&^=)Vp9CA z0RJhb0(NF!w^c_V&Z?&xY@tclWfXNrtc@>cEQE{K-%5YTGn>sdyxrTNSPdj{pWYeY zPp?ZWZYQHpdDc0c)I(#y{+tr%+_)~by5U_2a85Qnu$OONl4(~GfmLP7GSu$8H-fw} zcPpi+T0A3D^P#Yuc4z%olDP;?u_qJL@&;RAQ4?VL$;u}mGKP`OZk}85=gn*X>-x{_ z#nkfl3WL=gxv50vm7RC8GOF+EJqgy+B*HOV6W7Tcb@J*}!{w8@N6Qh6e#2?M9W0JU zC-y!T%XsphlyELE^1G7|AgHf{lYJpDQ(#}zX2TJ6a;?it_uM4y!d#o|3j8DGhQrr$ z$YH3=p=SoFm#dYhBn#tFgSaAp6!pVVMk6d=Yu^ZNze8R?@GsMyj*?PRjx^N(t1$iW z(2R=3>VExn{Sz7e2#YK|bq5!&wJQNvVOlPS>!&OX8>N&RVqevo)0KYAymk^c*&)5z z#x2naiN!XcRRhQt`@Z8+h2R6H$hgZmGAKAoGPVzGk*Vh7nLYcxUKHj=$nH4>FVrl} z51M@)7Puq*Gq?Pv89I5gt?vXmO%N7zpN#rU$gsCh6Vo`{W|XPBpm@|Q3xzNVZ(ONh z=M~|y`W2ApG9PKS)@`8;eH-;b9c3V~RJ!ZC{shAv^XCn1^sP0^4}p$b@=K7<T$t#B^U^l^lx~RD()Y0H%#qMcM8gEPzfrvnzrW>y_|KH zMuz<84H-TSkJ6Q_$CLtI*UIdxchGx{Jtb_6mwqoWnZfNjdSXYnoC&W#F{3FY+qGxt z=gozg*S0oc4i-SE9D7V&5mYU5Kh$P{M#Mq$1hej*J;!Y>vrXAEHsSf8EEK5aT?7hp zpiGi~xmLgF`?)fr2(4bLH}yg{T1td^7kV;eXRB&&#eN3z_X zYnM4@*6Pt-y-l_1{!)Fe;G*wQB#4aAC?cYu?#X1Oi-JyTx#U#XKzw(|#E@_W$HC62 z6@Q{3Gwn55`n(h&Rdg~9!6=9H=JOSft+!`fb@B(Bbr5|v_lAVYQdWa0M75!P)mi(R z^JVQkdx5=CWY{}8t01#dl-g~g#3Gua9KyY8;g3K2nEUiEox@`6EpdrWC%xq&P6Y(%Upis(a$m?R*RlY#Ox$%d zYT>rM#I5EqBvL(;8vIhbX;zGIPuADI1D7ekhzitWz{G++gMBn&Z{&JZ1RV|&GnHBf zWFQ9Syn2Zyx}VkLhWmn~qdkNJJ2TVupf@c=)U$Oh!XY@UB}79C(qfHG>^uwA zE6zjCC=m)R4T)6^$r9AW3sQ-+JrFtCN zGRWz}X)+N*l=6IlAz~4zYO<_jO)LCD(|N6UEl`GcOgnK?DVA6ht0mX7514$EnOP0YY)=2X`zakK{j$XDI@y`^x+3KPE(4n?d>@rD zw68GLrAssS-X3$a-sZ`d37Xa#TG3W-3Ajt*mBF80AFO#v10h<=ho&jwsXLexB{)#_ z19dnEB}f5PZ-|6EElZRwG*}xy_b?L|K0WH6JcBCrw=mE5wKo&})@@8=UeOc7^i3ZkIvxa8pQXsbwleCvJuA3({pBAq<6N43e+` z7ZH%U*R%jo{KG+y!jMs#Zf%V0Zu<4p%nT!*xM9<_FK>!S6UnnamMaGv2-Y6wNj5KdvOR3LJ#)P2<&65V{BHM%Cm-!R!A)sI&|*uq2*OLZ zG?zdOsL1B_^mvY0^6Ro#=c(9=n=tBUP@Mpcp!{ZrY6w!sb&^FV67L)>$kiXI6#rCkGB@qbF-F7GCI24Kf+5*E%ZiA( zPF=#?5RsLn!$Cf2cJNi%jd)aYZ*oyXMJ5AOdfzB&RD)`o8Kfd2{Q+N1hRG5I0XRCz zQ3UBpgoB-8G6X>(BHUiaOo;-OS~?)5Kp8A2QD-i;GNMbbx-eBWG<=$iF9Cm_IQRN= zkcuK5QUcab%A9EGKi$Si+jm2`FX)LZz0;A4yPIQ1p+Du?7eeq)J$2G?rNGF-3xV$4 zq|@P43TTlak?>A2 zGRy}Jf$lOW{G({`f`B*85LDAbs|!hI>yvdqTe29InaYfsw&dRN#6~~%v!L|KpaMNY zj_au$6dp^%qNsF!ksCx%o~Rw&HJwl_Zfk-?Nt#P)aCC0yb@ZE;Buhy?zsY84FR3@c zmc{!Q_##78bdjMrVu+x+hJ?3tBGETdG!kKY{*Ow6Bcps@EZSf zdyY%E9q@aukcZ2?*soJVc@~y*l>0O@RY*ErXEJNFXfN@h-;RblM;I1?H7gZU(t1;d z3^GQZ1>M#X)oO>!ozfkauHC4Y`^ru@%CCND-Xlvb!~@1SAG}d|{xrspENfpVBkO$M z2O>J7jrsp!sG*=BVYBOwG>_1?yogKBGkaLYovTI%y(z<5jCczZRh!1qay`p)*pd=% zV$;M|*_j>Ig*7jP>=CFNr@-#zgP_arpJHJdk0BzPwp^?c_LQsh+YuYGm2CFv%4G{6 zZs@dTP@dr^4+{8;-`)}`P>`eN=Ig2_>i+D&jn!SIDfOmZ3ljQ|YyvVs{SRwwe(E${ ziE=dmgr<+BQ*p_vo+gJI#Myf5aURW@SFcqs@H|l7)_WK3O7J{~)2ZK(T#w!GAw`Xxz?Thu4OW zR(=~b80|mOWF+D7ux!QQn?!tGgYC_$<3_Sqe@ReR@7d;ErLR0$W1d*)pLSk(Zu-~- z^?&~Z1PK6<-O~(d@mPwGd&p8B1c@0e4d5X&1757Vkm9WkXnj;vYkdP63&OcuJi5#= zdfcWIt9xvPtop}nYzH2aFqnq~+lQkzpjC=MlEGK74~1>WfT%*Ky0sszqSu(K&piSH zvfm|-+Grya@aBt*bwx}KNfB~j8$ik7m8k(%-c)o?K+{E_sceH^ct}Vw?W6wvAwwqn zTkE>c?|Ulk>&&IjRPVLT>Zx;$LMjxP7}`cBX#@HmjqjH6`>qHO<**F_JRwxg>djV# zwK;ZeKla+;)zDFckF1OL=C3DSDpzERL6ADDMQ&~bT2^e`fHt6HX%=YoNb=a`kYb$F z_fM6N2i^3*NaIq~_4uwzvvQcXx%vGY*_>XQttzrf;ld;cu zosiI;z7!~}}6Jm2E?i5@1 zw^|E;)GBK91{ug)8>I^IQQv@`ht~FFl-~|~%47XQa2jV0Uz;ge`go|RakEx(=UgSy zH*LQ2T7_CafXfbAy9OTp0v;XSfF_)FU%RV`&JFD!t@;X?b@0R@>^^|Ob@eNifAxG{`Va5C!a?IDjI zqlr4BH8EbywF8Yi*$5y=Got@{n!nBptyXzPD?n&X$G5{S;N{Y=-R8GWSn&Abn+Lzz zpN*~?8g4+}LY5M)&GA@hj}53(0zAIXXtf2;RH!W-`N;;Vw|-$&<_YdkKgaFYgn+18 zXTGw#@PU~b??IMN>XEUuDHQ`=g23<^AJ7KWr1tk=K7!!U{_kt?6@ohsUh7>NBKVoK zit3f=P1mh{sRNknV{1C*@`dLNYArRvt*ygT=>9p7~>P|p##l*(xTbW;&Yit8e{L=c5{~i`qTiSr;TiMq(AgqQ&39-55TR(r& z4aoJ|qcaD!wp3BeN0~8u;;zgw*XUHCKqilEaQWyG;4}ZG89vhB8X&Uv<>wHh4r)|8 zy|g+!sRRiH#+84`KlPo8Ml;vum@$Xqgy-&nhcDs)mDK={)mE#Jzl)!9$w|<-&yGJL zDtY3DENjQxw6(cuvx}`J2T>DJ(LG zuC40)i9A_x*LdsO_aeIiMb~$JX`BJtg5{%YuE<=Q2KL(E2Mn%I&0L#|7M0q%*n1q< zjo&v8i085UC8O5oTO{U~u|{dHC#lHqjr>I_ChDM=tIZG~Za%g3`3A&nlQi2Q7Pa*D zyz6*p0DX%`!gnKjM#GP3`GD_S|jAONysZPY&7xd1~e^%YN7*oLqQlnU!DAH zEGT$k+wf_GWYn+j`Qgw?8)-9K-s#PLF%`#tWHw)F&%M-^EXw_v5WSd;>^zEuOHsaXnmOYrWIlAlRVl9 z@!GI3g5;ry7GX7~e?6ie-7yBDbhUDHa7X_7n`qnFd0WHF?QQ98-^YJc$>p0*lYJiD z5?(HvhYY^rAzrJP2i??V;A6^g)D6j~rMXdOqxnAx&KOumkDU4k+k0;3ed6{5*1wdHY1***n%t57Ptb|6ZFi*4}Y~+1M)o#9zKa z2lkz=O3oNlX=42IqW?YKL^7%wLVSgx)9>`HeWUKyTF2!G{CPqZ-9K78U{~Bn5MSip zeojyT6`4`lWq*rkgxXEbOERCFHxJ_>;J2wtLfR1>zJf~afki$ZvKN_886*kSwJe8=e+FM8tIw|x1! z_&@^rK`+6z@rwKNw+9dRM-lA`FUT(q`)jg6XrN|#$9h7*;O>Zq(B9mRy@@l*LDx#C zy1#ks_TMSC7j9*715>f;qiihiN2}O&UaYmUy>YbY_KU5e${&vgbx50d*L3d9?DS*L z?7J6eFlVSWT3riScxAU>wEC|@;hL=n)#W*_wku0nA0Ccs5fDOf!fzbEB%Aq<%0cE6 zEEBEGoZNQpHg8Sz$Cv(Nb)+A_FnGxffA3Uy$jsW$Jn)Sy=n>u~bz*G0-PWFv!kvUi zMTvd^x2~K?dp%O4xA=wFCC`Wn8By#SW^6!*T4oA_B(mt4XVQ#AP7$k5K|!C44}UtX zZQ0mR7Pq)_G_NFiOPkuBBvH2VlUBA?{sqcz%{5W&_804yTO?0eo-at3JH4_`s8&Ra zE}SycC9%kD5Y%zl$M)t7Hq7WvKn`E$byw7CWMbbNY+PVDoFBfdw zWUfeIlf%CZsaQ#MK?Ax3xhLns{-G#ksZfKpcUdE?GHjLeTR8#xq6+N>EiI zF4Sy-yF94VExot1P%Xj_yT=x&BWcm&^bNNQxVKTjA&h=I%eRj(r++W=ZZ$(&^na(@ zXO(;A5A8TAd^&kqnHh7TvZGBjg#~H85yFdv93QqgtPs8+AN5Hs`_RRugp1X*pS=tO z!tcsfZt1U8%(F+^oL0Uvg}&dqQgZ97t;`oZVm@Bzvh4Z(-Qi{mQU7F~_!GtTS8G*N zF~9c+f|XP{k*(wFGeuNChiuK9n##?1m>3i<-)v*>12PEeG*I4QcJdQoQq;cG&`+0= z+%+au9&BYClb$M}S$G6|TuTnqJKuJ?$Zs!m3k4C>jF{hJpg~d94ZOcu!Odyd`nbHY zliZ2oOWxb{RDJY*ckH3+DeIs7_%I5Fo=ppn3%Ip5nXM?OL)ok+ECjuqW0tG*%Lm)_ zdsy839FDlR=)Ls1o?RC3c+-c`GV#O@UuSlC}aa|X+{Lm6N7A$KNcq* zsOq0v?_Jtq>_j|&vIay6D^~}61q83hIUjmy2XW@&V?gBJ)E@^3K5e+ZuyS_2>V&7n1awJIeg%k-7mPB!wrohu5R-UY*_i{n6U~ z6Ny)DLtA2~`g7DPRh3hy+YQQpa6KV?jsbuIr!R3DUyYnoi}K!LN;HF{43$ z-dA4w;ko>XA)z5W*BG9^i!=B3`U_Oz z+6;5WKi@e^`}dxNO|tFm>P-&gWjhNq0VHtFqN+*U|GBc;*L_v&Ic7WI96+m6=D@*9o(UrEOX%ti}U@nH$iv z)=-rMYG3%^WSNYEfkAd0QaN83wdnN+@f$b#r-7}`$nJMG2|HLIsuTBgrl{1X@xYn< z(&v7|MQ=X;5f15b@R_U$mB?H6p$d83y3$sX2a~aew_w7mr@kIsygPkLu~pnY(CRAN zd_1{h#Eo2ba$xq~9&yt(y~H?aTxumVMv;1IysUId&dF+jh2z~`2{SWGt&vV;98_?VW+rkCo`FaB?j2+CKNxt%Yve^wIcOVftNxjs)0sen4 zAr-Oo^xFnh6-Oo7pWa1gPNHgJ!Uh!_=fnzrZ}KUiMn<-Sjj><{eCf#@bJuFubU5O_ zIdi#JVqd=WiqHK}>`*(W@$1z1pYPNmwKeg&H}cCxac$Mkre8Ko=e~NZ zWA6O@&V_07xl9@BUB<6YSfk<r$|26hJd=hdKrx=Tc^_a>w7SDyp_ z{P`KObZBWUOKUE~Y|pG&``kR6_L5^0Y?O7BW`De|V>FVO`p=_^-FuD@1f7?yR8_GKHsp>A4EPnXsk zi?jT3)g9wBdO_jAiB6kpZp3+}O<3LZ^ylLf=(`EfeF&Xh4JB_{zK>4+nZ*%3vY^qu zx#+>I1L#{=CXb=y6ZiF@&9(O1v-x=o%jyU6%vE)FbgSL(lxGMEur7?RKaxR~)R{K6 z8(wT;ym49$EbCZGx;Fo9&kfkp!|$$9bLYQyR^ept@eK2Jog?74x0=eoovYUkTyqPZ z(Ve0X1+#Z8W@=bnAE4)kqw}pI%Vz$R ze;=2E-L-0m)XceYLUe_D=F>ky%9%p@DlS~ndHAF)LOE>%G8hm>nc=Pa@uwlf#zwe> zj)0if;|fS5;4b5Z=<)u-1uEj-{uAY{Wx5r)Pn)28{lJsAB+9PMzYgfPwB5Srjj-{t z%>zC{P%BnbWbuyYqXT!m=ADfH?r1##tlt>rpHK0iEy$VR^ z0%EArdkwuesnS6LgkF5(^ZTCvIq%8loSU1S-Mf2dc0MzAcCJLPLBH@u1Vyxw#CHWi z*Qc9x8h62Aiib~DKR(9|_dCMp9ep!R+HrP94)lM|FJ0goTGdX`o^&VHy4)@;obYwc z9ec1nf>7XV!^2zyMitg~xzOIZ;+%#VO*iFh8Cf9)i)5D~5ZO=fQsFgKg3k_7ht()1 zEIc53CBN;fkcMgY1M4SxZ?Gd}u}lxJtd|fY$Xnt(jXth zPwPQ~g<5X*=SL#~p+b~E@CX)jrQ~KXSJ;5?*B<8HS?NqROyUtvBpHJVbDdJfH&DSj z&h1BwKH(O<>g;_>L&t)@fH0jW;lz_eV(-!j;vcts0N{0&7Dy5P1uU-CH*Xu}FPoKc zhx*dzlx=OTbf^KFYMsI|n``ecSsp$JYT1}Ji0Gu(R$>0|TR0ydtD)$7FFJJq-e^cF zMot6oKZ?!Z$Z?2_*{vDYij)0Q9&UCVIYaj0+jnO|e0tVU-h^PR8C>wWO3w9hv`$`* zRJ2nKKKn;d(Kp5k?#tG!uE@skEL{^^&NY*q39vnBk}}$czAhTcH=qXq$jgq0P5Ynm zEGz8A{yZL{hcCGseGS5`8~lYBRdbux_m>=(GCWfioqG)^XL?|#t&RXdG~Zx?frSZs zzNhEKVi%RlizpIFb3e4s9AHoV!h5vD-w#&fT$+4SKO?pp!BpAKlMo-;w9dm#s+miRa%2_aYho0`ko;3+a1|;UH~UKbgj&HO~_NeAzQr8TZfO zlQD>P5QssQ{^cm-M^7ebrto|LR1a|IOa0!YdL1MJi%MvzVm1?sl3CY^ zvo}LIh2ldV0w69bq>n!0t;Gao4p}-lPqfn8y?G1I5~w=O1s(`29(d?RP&a#pjh#JH zoZR1j)3(^1?Sznpv@B2$1A?(KsxPd<2y~)ApabnbG~m>wuW=& zO7xf=%9_De%`~LqN;80`0!pN;@mJCV*vv+DskA;5NDV<7C%0)*?9;sM@*D-*wx0(# z5EqQ^P`z_9m!()sa+CIrW}RVO2s5MJX+`U9FSa1tf@Dats)z2G#+~ZVh0)7_{&V5f z7E^6D3XeowP{o^d^;%W(MG_Wc!>Rx-%ZE5&XQ9^)xsJ1@XQWPolP+U5S_1E91cHOr z@&hdzOP%E`WOT{<7u?e$OQnouHt}6Tx_Jfa`-YqPYIU%Gd0f*p((rX@vZkbwa??vDlvt1#@@NC zi2whb&IGTecUb~t+^xk@G z+`n2tk|iwZe0TR72n$(|=^6zHvs^vRwIE%Qe7bBazjA|>;(;Co)0;ykTleu8$pRnG z#+VpBo#2_+EG-}F^KY}zUy!_b_&|D821i5ooB(!aAgMnldl9b~40JjK?MpuqpviG` zm6eI`AWn;u{$|Sa;6a^tc|LGa)++^uB@3G(gq@i?VVOHwlf$-%JkXgIddt3wKH~c< zvEIKMqhx5P8&0vXgIT1mf=&RdmG$Q-c6Cd3YtbY}v@jOefv{PN$18RZa-IIf>#m?5 zmQ)l~9_&k4wk0VbZ*QtXIG@6mO@shg;gw<`lmSqJ=f59_TwBYoG@71GSj;XcTrAIH zk&L(m)Kacl*Y8$2a9%$2J{lVP6k9UIcK6d(O*~^+63SppIBNH3MDjcxZ*NiZw}$3< zykH?pkz~&SY2b<5&R!yRy?D!p$q>+&B?nyHW8-q>V0qD7mux6F_D1R>!9+X^jd7=B zw5Vj>qNkipv}e9Hb!a0go(B2aI;TFD+*=DdVxGh-wB%fG>|CXOooAyp+cj&FAq6!4 z!8HCT5-aLe%_#tLPb<^FoXctZgOK4^3RDFt$O^h^w=42fh+I@-o(CxP#{|FlB}9xk4wVY` z`9rAnXi%X5sQUQHn@8%{1b7fQf#$_5PX^k2GK8wnHr#lFRQGH5thz(u?N*VDAwIxK zfYzz|HIjt1U&l!HsTrtCno?dJvWhSKmB93(@9~n46?L#U-+Y%-SS*nK!vl!?dafZB z#=!wp6wH={_}o3_lDyDxdV~vjgb(&y{*aFkE+B-Rhq5Z;f1>qAa&9aRMA(W9b~AAZ)Nfy5K<06m5D+G_j9?~xGw}wX*-r4|BMrdZ_VFMA zW%e0T^`KUP?k4g=8T+AKQ={9{Si1u_#&xd9@;!62D{Muv+XwoX+IFlRa5Coc^*K(T zk>q68k;lXLo%dLLKp4^O)|Z6~E|%tJ<*8AB>cZ(`vF(E>zjj>A>E3O5uqgph4@rL$ zz@BPL&Q3^H$wKn!x$xs937K@-0-mv^uduDTjkYEY*If z@H)l_kM!HGtu=G55G;HoMS>E*x*&erpW(rb*;Yh4nru3w{l0b2n&tK{fadhmOq0@g zigGyi2F67VS6~T3vN%0m8O6K%NInk!`cxzYyM|407t7r7DQ$;r8v=9`XIS!2J}q<<1*$5!U5V{OmqQ307Ndm1nTo_3*-mcnQ&x&ddK53;e;K~JZ24@BL!#QR6zNGVw5 zG#>s1j{~Mff!2hsusp3E;&$5KV}Yj7<4{Ut zIg8A}x0wUeHBpPP8>*^@^>%%R5OV*dXp79Bd%DGAie~i|qehU8Rt2M5|23c;miZd? z3{E}O<-R&&>D{~hHy7POePxx8vBie@0yb!gok9^u-6VEsYVATZ6((6*0MTPkb9#9r z$=QW=^L{8-si-6VCSCn&OroU9z2{`IzZI-C=b6J;)o);1ZY&Eh(j3W)=|B>N4(%I3 zZh)lc80-%~*2Th{FBL0Cy(U3{UK8aP^q#GOp7wrHoIPKm$~~3pcL>@@awZLiWs0xI z2YL7qXFC@bY|caIr(&qHj9348uj2*3qOd#0W!=`qbqiK?mNj7VohdHdmV0$-0>ceddBqPNIYXeOxs)1}FuF2Ytf9^8CD{6LeSGPhM8#1||JE znH1eDeCP58vyCxj*>s5>%Q1kLELkI2p5Bd+U_#y7+Z-(NY3}nVY}F}wlI~U^_-0mL z6p#0GRQOc&!snR~{i+gW%ACQ%0X$yK@ueysSRJqH5drCh*3_r(52a`xWT16)-;pj} z9L<1Tdlm=5l@iTJ%(FCPs~TQHl8+avyc3tA8W%7&s;n6XmRN)xl1Bft?TomL9?$O9K(Lvb-C!=*yKq zu%{rPQI`!#@Ofi1^QRe+=;Jl>z4xPV_XKzqCkM1Gpc%{PncyR(DPUC+g3#nlEjai$x~!*mmMaa zD!ip0Iz@5}kkw^wA>nWn zPR8p~ksTW4|B`NWhCAEL4f&2z=3x({`pmv!jN5LWe$>UwgugjIJbC?_V6r?|D{nH> zDJ$-L{|oQI8mYaRY0d`u`_gEKCGoeJaf?P-PBdI;PvSzWo+$oFH++?Ia#60a9JRtH|%lw{pNr>J$)5}iy< z&3GlTd3yxj;BVio*2n%_th_x+n|bI!Ul$H6S0TQ1L@Y`cR^-S>`?*Q&TA7V%>yzvG zd@7^1NiZFc#X1e;wWyz+#C@VFwo&1`@gxnK#xisvpM8sUBX;)v@$mNUDsh0GPpc3N?C?1bohBb|kv8rl|?GyV(k-;TNOTk$aV4-PrwYALsd zPT+tlV2h7*jh3F+^4JH^rT9|D%0R~r)2dJ1RO8L!=In)Wvs5D^bYkSh((@P z9<7jzb7CJarQx5aYF$j{1_zO^D|I-VgU^(E5{L}5qVd)uVuxP!;rS)~s&^wz(xKR1 zJo5YtsPJA1aY3d;_L;hqd1}0Q^puxm-e;Yl(JK|Jp30drH@&)p=o%oBGJhkGb~BCG zE;J@lhFv)S*tee4taE)iu!!nWE1gNeqwj(okG+N1#xUcZe93L1wf~~2H{#A`i`DV@?@zCPehs=e=ESM|ll&@4-{ep#>E70& z%IJykk0tP5zy~Xy>I>&kx_Pg^fTio%iWHU&hMR4J7=nB#0IM}JKZo3A-KYlX5}(?) zlJZNEWA`h>g94fyW>|q*9ChiiCVw(?yx3afjGa>Ul;66w`i-tV#R<#)cInI@zG&nkCKWTRO7SoiP+ zM5-}G>>l5lZV9`{;f<#pJo+)J^U(;xM)#uYwm~s+tEfVF)PNy*^h1~A;b%g+M=Qt7 z#4KMm~GZm<@Cpt`&D-JFa>;R zCdyZ|3jmPD;)Fc9G|i)$%w4kkt+zdQ`l5X;9_v)_01!msMcWD4HH1cY-9+gHMGr@4 zR&n|p_PqOGiHZE_fv~`aCJqyeSSI7v>mP(Dd{6|ij6wu=5jw7Y2Z+%Y!(P+iuBwtC zbKV=Cw`~Ek3K_pBwAJW4<@n<6xPY(oxtmYrP5J0S^lxtwy$=M)4K%uBGK1$-PNd9# zv4}6?rRDz2y@q_)E(&=337dE1Eu-g!*vntb!L4`qN6neNT1MEP;gX1U`gv%A#Yd8f zM>5`IZf|&EaVoThZ(Cle6OpITM-)}z&ceX{MpC&Z{W+b7S9SM7KVo|f40&LiMTwcb z^ftVZ_REXMt3AENaWo`3J2%$sy!G{$O3{vW5f1^Ib-&AXa<9u~5BP=x2>I%4epZ@E z9-ZF6u72xc%|ZxX*%Qy}kG~mqWQpEKe%b?^=e^L~p&u_^~18f$Y<7 zSLI4%2=oSz!WG_1-zR?lwBac>p$w5{IOos@5G{ zX?b+DUgCb`L<_=84~gw8yt*E{JfYq~Cs#OnV}w}`;7GQY6_GK~I1Bc?0jlxA6Z306 zJXSi{R}J+;UDtb$V2=^TOt}lSJ9u0&pfFqR)yLjE>4-wlnE<=pt!36=5gmvp+#cTQ zb3}@$tn9+2`%S&bQ}c1! zrN78~BecZs+cy74%^j(I5u}%_1DB?~lI`SEyNv~=R?{uSH;M3g{6H4;A4BwL$3qfA zxAQpvWVg*&U;OwghA^HF%3j$Os@IdA*BfYZ4!ahjI{sx&xBSR?{X!W@=|qtOkDMJ6 z>B@h+yn90N8DHmC)#^6*nn$?3<6#my2`6Og^Uo%70wa8C3Zp9I9G%UeGCp+zpg(0t3gFAb z=!nvt7jvucS{{z;wuJ{1V!|{&n7^Nv)sga5SyWW~iTd==A(sYi%s%-z$XyI=I%!w5 z;;pnLDsEvjPq_4L-%pOP(5dAiJV(?XTfCv+IBo0KtD3Fx-2!Q7;;P>3ym6PiIMor$ zy3uTyKr=m|?8BqmkK2&2s%NV|b+X?)f52CKx-0)-s13u*=@c(6hZZb_jHGPoKIhvK znY@F#hlaoLBwMkHm9(bm`3o>>`rI0( z6Wvh0QvcYeM1W8;!Nz!*S4)-mwBVxp1Ng>?%yO0=G{#(gc)9gaGmm5$n+LmQ=GCZ! zL);TsMxcW)TkT07Zo(@n(pNskx;kTv!q@rxkdHQ#yUJ^55ne_5Nw1~7AwckxQny~# zlTfo}`x_d&{U=B3pSV=%_X}LyO`ke^T`kZ19QI61e9@63X9Q2%A{~T?gjkHqyUj@S zWU=qeO++?XR(O2wh$@X;-cX8D_*tY`Pk^pbK^PVUSyM4z}%tZS}0^$%QP?Izq`ed9g- z1R?l{ty44Yxk4a@!OstU`e&XPLVBb;!42OvbD&xJyBjDlT9dBk5@(84VBqQbG zzd}o2HTve<;K5M8EoAB7kY1;Wsm__yHSN1I?F(sIo8)#`6Vy{IzKG~`rcpA;*6Os|^IIj~pq;ZwwsbfkLX^?64XYk=R@wum8799LpV%0@{G@8sS^D-3)E$J;jB zQB7HJ>dkzEeh%7qB9FjCh27uEKV6u(ic@xcBAWc>eI-L~i$|i=+&Iw>{0Xn?qrR}2 zV=1>~WZ_G2v0aEoeBE zV~?heHlSQ%bX_Jhm95jzt*6zL9)_6rQe!W2vG*>IGqt_$&s>zaKFAM^2CctR#kqY* zGrd_;Z-!q9s)GB|2A0sfuM8AWD)K%CNJ#^V>vP{N8AQu9GA+xl8^gbOo3zvl06sIf zrH|>-hWH=O)eq+5A>Vp$Z8G;Bjrgwx&ArtKrU_EutxgR)Y;tSSvKwRvj^Z`l?7sNTVA>+5}OPwS4TMHNG=;q8C9C|3O_&^_L9Yaz<1m3+BE}X zb=Veg1hiAW*^#c$0g=r+ujNqYgWZznq$PiRy^M9Vr`pzI<=CH8kus4_rDi*t!MwEq zM2Jbq^8oAN!$<$`^#ubd%y|9pM5^IC_^8deO1Y*%Aj56uY8A4FL{rw;f#+=3P}(Fa#3Bx# zCnr)MS#ObNjm5^mId{jvQhczBZnlBr$jL>|wlXLs+afN(0^c49B+{*Q8#jq#r?o_G z8W>pija4(CJXs9h-wTppx~yH}eBHHeC{5HwM$uOn1G3i78;rUV(3E|j$3f|C{(6ui zl8y%-4<5GDwhEuS5!A}_BcaH{n6h3LWVX_61};L1( z1%H>-<4SK6(v;Sjo|9ScRF?jFkl|NF_`Ks35<}%!XUvs4YSXO0OYZHR#<@031@2U6LmKNY5W$N?h?b$HH|bm0~Tm;;fvaU z4#`%eCQa5tBTLxW<;L<9&rHd@-3w>moiqcOt9(ltBA|+|($V$)L-)TE(k*3eGjf6l z$v@%B<>Czt%X1gkkNZf^mCT3c{njC^!cK9!M^^4(br&)|{vQ^BW8W$KtXHnTQ}Yng znbVj)Q>ab95BYF8dM8fBNjP^oLy%EQ74q@~!v*{qDn;7t$%9b-$V>g&E!y0h-*J8{ z9kL|)Sk_|&8PJHEVJAa)q+GHVyUTZMPvxmeAk`5*5va&cAd)pniJdeO1dr?l<>5rc zWXAQ6_7A&qWu|X4ohU>v5@VuR1gRRx&USO4=Mn*zJeCAvkmK50pW0x8f3>OF$=>LdA}usWA$z&>r%G z%t=ll(M~GMY=>;BS>J$ToxNr5MU2aUeZ*7ypJ_4(uvkh;6c5fjB#)56%I@3yh`@*y z5?^M9BY0>OPwc(c)``3pT5>NA4|6WrP9ReW1V=D~dB#~rfdL`+Hs<3O?TtVtPFytS zDw}+&PzBCjOsc(Hf&D*z{amGN(=uc!&_B*lBxywT9ru^4t05FVUNRH&uE0SsbNF2~ zhNJB<(*<#@RWV=Jx$iAKI*yB27uzzW;{jXE|F&x~nKAUPxXy5_!d#%a090)h?7=C! z7jtxc5&F}p+i$256!qN!+|pke;|I}dJL$V;`3vZ@&p85mr|yBu`JwdMNn#-FfrB!HA& ztovfZc6Q)rdjI{OYQ(}KrNd|8Cy=SibQczfJYx*t`I+#(WetTSI7su;H;5hZx}or) zk(+ACQ)=SEr1wrW;(ESLSfK1m?#J5p7QQ0mFELSK>mu;%Ns?j#{2#L-hn?PK(HLD` z99uoPW>`~3F#ovcpZi6YzH!UBCJ`O(UAah95w|KfzHg-$m8X6!VWo>Q?}?@f?~r%f z&yEADw8^*_CZ20lP?bBZN`!a^(*!5#1annp$60oZE(*x(#^A&RN=O<6d+;%*lJ{8s zqV!wj4sWz>YfuZVT)09K#umx3gEi_~Qo84U&y!mjSXv%AP!)LwLs$iSdr)a@GE9XQ zPR7(18T|b6-+`?3Wy@qBYZ!dSQ1D##4rn!KWm2OlYgw%VkM#4`ydkIZJekgv-ThDt z#mCND$Df&Zmq%RxGTx=qR4CA5CyA70Oi+Nw8Ad`7MsC=PL_Hq{CK&Hd`Qn85a$ePz zi^m>=B@#$fjYeYy8X$2yrl))uo~lhW>%POb8LPUdUFVoL2%tzfW=ZLJb%eXHY1JvM zTg9ET8-CL%elJE417)oGX@JTmhgwFiB5J|}!bO?+P>R09o#F#race!sb1C@tE3Xv1 zrNE9SLNO{+!z%x+q|ohdzJoYp!*dwn{d4?<&WqS92d`KOt4>OjBr1@Us1@topO$5D z)VcRcMS0@6L2fg{HQ@}9%Q4z%ZH-5o;^#_zvMEp+Q>y|~>)7D<(0WFvq|N#VDy+v? zi#}1>TfvVr1Z}1{7k`Jp`1|-TV4Pty9(|$cyXYB`%n=Y;dMd{_q&K*pMW;=C&Zson z8`npC+CVn0H};oG0t_8g&$;l~$9e3pw5m8# zDM>trx%;BJb;BJJ&3M)*1P)SX*ap{QgiW98vtfqQL!f(*wC+bu&BJ>j{oBCSkCLuo zM<#8BMz@hDubIc{Y?w{iD-J)?e0Xfz-;=3_N_r6ZD&bH;L3+#9!4cRp8WJ5x9!oY7 zdPFEo<#_99EAR|FVMn5LCYLMS1NTN`NOq!MzB^(E#ll(`Z)7ho=2T>hDCy2 z04S~-^TEtT{xJi|Fu16}A&9SDN=GqTMk7a?%h?bfQd>r~X($`#JeOeT5EKcj*rgL5 z>qW)a8#;tWF5Ka#yklBwA}=s>#`DwS6wvESmp_PutAj8Lm;Jl)R#riiGQ3c_xj2VG zJ$)(}D@O&4b`FkV{j69N2`ZldIu2a3f5T4zYzNmACyf}OhjM^m8i2u=@!Hpn2Ue?JZR^MRYi+TQB zPoIC7C-GRy8ru4ExxbO(nBlY>anKe!qqC!S&tVr&n;yV7NtNHu(1J~MkvaUqCZLK@?JmTx-TR!?=@ImKnd9Kt=k|yx5L{u{&EJ~mhwB$0L9}+kYnQL;y}h# zhXH}eo>W6iA1mp>HFc{iqH~N;VDckXQ@)G95N1Hr!m_~A4G=`$CjMs($g&3q=wt&^ zS!;$BW};-%hIy35fm&qb*1_EUTi&u&bA_E5(5)UY0{(MemV`fGnemP)xW5V&#g&;+ zGBy0J&i-AENL0TB=QYh@9|q5I{}0bTcnrXx+J77F0RQmpBMhD;Vj#wPBdMXuPr_*N z=`jlvv?AL?{sX~j7YfGCWM*hSivwfwx#fKx^uEL3 z2BPUkl;?nY?kB-{b8~avdriz-HNOh3x*tJqDdfQ-=TIS0i?lM~l1f7MeZ8urP`$qM zIz#ADQ>TGn{6$N+Kd70(Pr%MD-+XDAW)$2Kb*R1YD+-r%82U%S5dlG@%En5$+wKQe zWw84p29earo2D)wlPOL42w6H7I<_b(pXz}el{z5|NcZ8tfPBZ@E`Nn^<=U~ygp6;6 zae@Oaubfkl8E|nOhDkIH(FP}BVdv%W2FF%KYy+tt(#(bH)ugkq^U8zDh;W1OpDV`W z+->^MBTF(y?pHJS5p5=zS3_WQUSI&~M@V;H)6glk%702hz9J=y2l~hAMy(zKmN9Wg z^Bnyn8TSJ&i$AT4+|WqcB~la5A!C~RQ4eXY!$6|_*x>LHg7Xx_-Mh+-ago9In<2s6 zPt#^*XO~;1>sOwW`T6M)L@uA4x3&81eCMQg7L4rdJTSrMU-%1<`+0D#cQN;)iTu$} zBj&d;)Uv*{2Sc9WQG5TrxBF*$)lWL;%zQwMGXf!((kcZ0F5*#V{?(7{4&>9HRo~l_ z(j!xcM00(p-4)_R53<@%Bu#sObg&__M45Zip>x4=QZ8kW_ z3>h~W{k*%qR+4eH5b!!j`LqH5lUp<2pOyiOyR6mS`I39*!js!PS1`9%S}@;PvZkzK zpy%jq0Q|()xyZg_cev+79``_Fv^^Bk=XWzKBCIF?bJUsg$iMn+V8Y|Dcu9!i##RM* z~sd?s^Gm+ZSbP2*b(QjVnhpZNYK!$cVLuPM_aD);R#K=W%+lhlg1VAzb+yzr}W z>RXgPi)FPeX(s1^Q4Nf&KKK?oDW0#qKIMSA*mEh4@JPQ1t*@+UsXTaBxws?;*Y7+yhn#dpCY3sqntH-CrtL56xyNcNSY-Y%xbvF+A^=+JM$K>zSPMYIg z+f3QE;LL6~V(uz7{Kt78(LUc%NI;cRZlZvP#o6mXnj1lZ&3qn8$20>IzJJ7P<`rH~ zH;I+?fV%iN=k|6;B{Tk^#!j%azYBL&Q|EGj3xrn~{%XZD#gq9!7xogkZ>;p<)1z!B2Ym8$wCRiVX~MLNKe;5^>k*3e&iM96 z*%nS|#)MClablUFmwr3&)-5+pX{U>@7LTDHbpyVjs$=qlfS%Og{mDD5LJU!zIiBy_ zWqkadMY!!P6wKfe8WI}b)^)SBKQCg8T#YIj+04^Lz@cDJV6{Q za}16Oaz#_9CSW-?$F>#yZg{npCvs)EpW6e`oUdI`qBb_x9pK4L)irF1Fia{;`8KfE z$bE9o=NM+-zvI}FxKj}xhO+7+f4PdNQs)|XI`Gre_;HnJ`I)sOmK@6*abQx9xhm)! zg55k1it6zrqa&kFSpN@m7ie{ky$v#yq~NXC4i?APrn>x<;X4l~Kjwt!N7o(qSJOZi#N zK8~(JA_b|dKr)32QeDecDaj1ch;UO^dv^vX@p--E4aPJzhB_=Tahg2;^FFj&Lgv>s zLFhT;`?;hag7L@LIIC{nyLP{fldXZNFnoE z>|Am4Pu1!TF8H-hETz~uq|P<{3=p*OJBHRRcqX>7#pvWoDL;+bmaQVR`JMbZ%FXD)cI3IAF(^Pz*`l0ud)u zbB~=THAu>9^7PR>89%|*43HPjWrWOHWy+QzY6HSOs&HrKpPw399&uvB@a^fqRmae^ z=N|@=QmQ!S!gi+9;BK}jj%G-V#b^f?b4+cXEZ`|gZ!OXZEKRsCOqf3D+s?WB=N1W$ zYsXk0&r{jjhZQmID#lXmjMBrDOO|4@v1&h1kh_1CT1YvUF(iv^9=bj(qQx^#Cm*aj zTYV=JcSa=c1BAro$d58q4>0@W4~WGDjWQfK^ShTPSHw$EvROqKBs(7aX%n)R7^pQZw`iXbXq@*ua3&Ot zokJLeT@hb^mkC+L(i#p`nmQBn`(2rP#aVZvoAc#s_d%Dx{hji=UEq-d76GTwHAlxP z)L1svumB4pK43u9Pm|$KE682-9-q|*!hbnmC}G`1rkDRsTux|_+?vVeW4WI!P|~ z%2L{o{eu~DahZ^dXHC_~f5yy%G%wzrJ6yuj61wSb_}hnRfKK65IuR1atX?jYq+^HK zGRk^CZ$Xv;VpV#?&|iXI7g(u3JclIQ3-S{y^*p~%*@ms zyYp&9E}e7G2Jp=b1_Vpq^k$JsP#DmM)LB*K3Su9yVfNv8DD1omE`qHlVJLp?m=gKBUTIb2?4bIEzNwAQH3aY3DOX;!704g_cgfvuXS z5QUVQ-zm_7Xs*U#iM`wq7vjPZw7q2Z=ND&d3*%gCh*!b$U$HKC|YBbigX{ z&{3Y<3XDWexF0ihyx@ZbrW-GSTxjHpyQjiX2I})v35AE_8|F%>I1hB>o^@PLw|vu7a;bhb_+l1@ke+Fq0s_WSxKT#^MikJw)yRGh8plyQArCP0|N?C3i#h;`?@WAAxQoVchm4AdNh!-1>S>kN5v0 zWTM2p4q)sM4{FTLgq1O`5Mo7TuKa5X^=k@b!JDqaN)+;pgo^zJrr;_kV8xd{^o~_G zBl#WKTbSDD(!t%xFzpxF$799(v?l~to~Rv7G_P{rJTh-?=zwMFGSGDbiRE$kwRb)y z{r{DWh=0eqTIFRNgVzIuEMLRc4A-1rR)UHe(JT<;{3j%*J$&$c)( zSqF>BSB$2~NzQO~_@<_&=TM}2incu|ggyVi`_ZQ8H9PfP$MHR5KGWADFL^Uh1-bj@ zp`HPc^Sf+VmEO-7SmoJR!}Y!#I93+^n`X>itQ^}D(x2hhdFeNg4?1gLSZXjB?klNp zdmli3aR!!6N}}UhDQXo^RrGH}X9td6`jbcf4VuQK0ka39DM!k4 zG5xy%OScl6ZpOxPy@ClM>fx#ESDsS+t}oL>sjnaZn}!)7A*BtHH0s0VjA3%O>Efpx@&u!nC9K%>cmguIQ4*C0BkIL3 z4)~s3;>pOn3pRxNXQr@l&a$qJjRUC6zhhFCZUV#{WrPwC$n3 zmR?zDj81Q~U97EVv8`vxA>l%*kXVfit3UZoxZyl%UwhpO(W5rApc`P8hN^>AG$NVp zQfAJNtD?;LI1OL8?&+RwTDKNz^0!hq^aq6boo}yng#QWs-1tgIneQsf*#0$BE$qd3 z`frieLUZF14LC16f<%r2%|!$fP`DKde7i23K3Cy}NpA6N9y>8a)5&^$-wWq$d3non zy$g*KC$*Sw%&gEU?b&bZRt(GellA`jUoX-P&zI8YH5FJDA1$V0#DI^CxA)t~2rC7ew=XY<&4w7u*KAso6K9rLoNf^=PPQ^ zERjQo$ENm_t>@8H3>Y1o?^mT(`z-Kxp?ZWZv-5@Hx~!m7rB$9fOC5jS%CtDJoMo|S z#wD1X{a)-f!pznDi%KI;1 zK)<`@S|#i(iieSsVL4PxPIM(d+GJD49}?0fUfjhsk3wCD;_?}G__va;OQcb+8^KuO z_Q@pD+(S7N7>#20NE&mZ!fr<;FVj+Ab=S=9f&&eH+#=#MPZVXUd>D3DS zPZ_9};ty@w74CDni_sTT_t}2})h;B8zZav?f$9+`0`Z4W+uJWe?&8lz^H3jl{8=#F zIbH*wW4iPXNcs^bjfj&*M9j+^tb5wFM`O1~gF2%*v*Y$==={>J=sp9B*J{(kq;Wn` z5PqUiVSR)X+-bp^4AR;oxh4iqmrL+(IrZP>V`{ZJ&*AUQNTgRTCT&vON#LIbv|C+Q zq-}Al9?e-bxm+vL4&Jv1>QEPZ1N;gVf$X`$gmZPHh%z#+}LLIC22n z@^`D*MBnIuOe$|ZzdO6Qo!Z?DYO>oQj8^2-7NPQ{k=V>KdL%Ed?-(el2UCG7jSVLs3p>%C%qEUmp~olx{S`Oc z`#gJ&(X-c;U7b2)$%d60i@6S#;@P=7#;H0? zMprgsNbEBTM}!CZ_=Gci8NBP{ zyO-!38a>SkljUw6lw+dAu;MQ>-xLnLy?-EQg5r*(Z8w(fWQ6#>a_YmqyxXhasrhFZ z6K%ndHlHR}tJs0rU;f9T@lsi;F3llH$tF`x?tb9!=2{hfT@;+gsCeZKSk6-)$IBK??k($>%gM&-ODi<<&&|bM#W2uQ=PaXmG zvGSR?07%oTvPu_1YU1 zEpc&m=Mp7G?(%0i_sM~pX}c07ZR5KXcQ2Ynx&w?EQHvedu|Rz{AagBn9GEOsIwU6UUZTlF;nO||woR3Dt2R+#H@<%OLoFxDTCzNqA!<&yR3wcUiv^=l zf)(L?5eLP~GQwr-m3&4!BP_qwHCLz$-4*N^U1bZ#qnZtkK@00iHa&**4HXk7Z3rSp zIbs~C(Es}eckQO%`mrg(e`!I>{Z8c9CJUCt#NxKfHV3%m-K0;Jdy2VdoqdIx0$?E( zXplxnLU5<(YZ4OqhYFn=c{be(h8{qQ;*xFhmN^w>l`y3Y4?dQk6_#N=VsKFhLq7`Z zvv&_H+t>ufOn-KGoIhy$(VV*Wgl*g+2oY#*6?+HHU zKvcr&DI&Pt0;EwmW1dD`@q6jVL3lhtYjEENvc=+DIDKZM1y{A;Luz(m5PIyi?+C*^ z48IWdLd!2^58j6jQmVY<(*Bq&R4wA+0;z;KJO(j30P{k7w z(q_yc*(`J=f)~zY3@6CQ@Z|Abo*Nbu&Cpq^i3kMH+9|FEWY|}xF^73B-MI3(Iy!sy z-X8xBS>f%scXlIllOIxN3{qy1+ZDq1W!4DL|e;lmx8pg{+BDDLo1ac|HDZGZql3nb8>gF6J51}G39rC4$AFEj7A z{{KbRWo2>CxyLy7>}T)&JYDKZFk-xZv;qr#k-9s7k@~yUhmrA?HUz!H`{+VX_$a%% z_m;@-(V?eWYOpg(%6-*R3n>7zekJD{O59KQgC&h`t zl+}bEk_U!9H>xf;8~+D6>>R(}B@qd^vk}%IH=++^JZsR{L3;)w***^=ej|uq48FluY0x|jJx6uMH8Sec&|Q(BQ2Jvq=C@5q~%+8)j9S;q<| zyaU;HeIvNGjw8B4^|I|Di+eCvbQ8Nkd;0Xp8w-ZFdMQE3Me<5x7BTTf^i$(+RJ?Jj z5L=y5|6#Ni{)^FMjDxw7)?L)?7d?_1tKnU%B7HtV)u`NN2)#o}bYk57(k0z+0Qx%c zgjMb#>A{QD-8HVYWe||6y{Lr$CgjOPjyWlDC)*o2suCh>nZ{YM)|mxz|3Xd#i%THN zr+(qK@S@efUu<1=ev2(3Xyrq`qc=!wkow`ptG)bXkNw>C?)UI8u8A~F4hq6a;2%VV zaAxf>iS8CbHdo@?5_py1H6!2Z{j|svt!hjVy*{G&D>%WrxAKLQ&|B8kJo7+qf|5i!p6rp+lMaBpZ{s&ca5T%GhCAP~H%Jm;u z)=x1keugCt{Cn&^TTzh0L~paip73@`DH*a`2r?@1tdvqcE=C&Nfqx2|H(52r35iZG zBSl?!w&wqNVsh>+Y1lslQ2qh;PuDd5ecu1o_wUGblfUvzn9bC*Qccgp^m8XEO<@dc zy2Tc(N6BZp4aFa!4>uH)!&6qIS4j`L|KfW8Z6ui*#O_mFv3B=rUq^XLOPwbMm2PUt zFk4IfbMal~>UZ}K52Vkll?CsH7=)9CWpkV$kp@zTGo z(*LLDgjrJG^nPbZXp5TIDxJ$>-{TsL-XT5GlgElKW~;%4vLwDH%LKRG!>t^x&JlO? zllZ^{!K*m~(m*9TJd_@hzSL`Ny3(R@O;N)Cw=u;_+wX2p7Gtil!+2aX^L+?z_;@5K zPdG0rmBNzAELeH^h=paY1$ik1Ysa*;^eVgPp~Z&gm=tU&mSW?NXYR{;GViM&ZXDeW zv=tfH2ee!76Yo;`qU!T#YlIG(G|FaaOa#5jR>r--!~r3Mbo1H%00?> zR30TW8HtV%Ov)THI)&e5#-naHt-uGC;BVQf48i__LZZVP{r9q0LbP26(eZ_pJwM3> zMc|jRt9e!wN+7#jk+vfV{JyFUD!*MOl}Qg<s0ItY<{ zdkEO7Ksx@U|9rgtXy~a3b^eS3#GdLM-sLB@Rs~xET4TPoH6QHQq-vW>SXkKyx^%xF zY~vT?zn(BcRnnZFVr_uC32fJeWRJ?Y-6p|71Qnv^$corh<{QM*xkaNsyE%HWLdogf z<(=~HgaNIwa}iw=D8AIqbNp#@AN_f^W%(~=?Ns28yIiMzu%&?8W_aGBq=_@UuqAq6 z)9_r6II2|n)vqV!F7i0}O@?MLKl#9N$j{sUf@z1RLF^);BH|Adg{d`yho(rk3!yrX z>TxR`mxts&=)mW;RcoyBgF)$|TGy#b^}RH#jfZtNQL<#dELfvu|Z#&TY9OFMVJ*9h#@0A?6U&O>e12KyBoA@V2pY*_rnv z4`|q~>KO$_ZGo(~9FZYMIhl;fiza$N)62A%jjdSLiOsiuMtJ{uux?4!(%=c2T3Kl) z%r)5NC3;m=Aec~5DG&2a(_H}g(MkJeBurgw>5P?o1D#zy@_EZ7k3O$e(srb6*!?80xTt32QH+Y^3fUVoI^j)%9QX9(S)km7lyL7S?VTb-hcLW1=ZX zwq!++xbRR|4rzNiI{&*}686#De_jimvZPrBDYee19yfevTQut{VGgQP-FV-x1(pKU zZ()kGf4wlmnktj!U%9f>l+(@d@?5=9tN=wB-st2&b?BVu`-LlC%o8BKt2YrJDgI(E zc*F6Vyd>seNv*}M;voOKmP?QB8#z?EuVH}rTrzeNEH;Eb9&YSF47!X z*|~Njo0bR=iT<%=PC4@^CcVnoZgt8r2=|`*RAR!2(x|b4a2MyVCupv*S|a4*ZQ=XX=0S6bbt1(%E{0=o@95@(*xWG&%B$p1H%sfxK9=C7J7w$P zNza>&VXg-4mOPPfi&NS;@4ow^MvSF#fqoO4%AE6uuCDx&CaSCA?Ozj&!9-NeNVu4| zI+xuld6wLo+gZ=asBvo5e!6UFwIi!g+iqi%-YKO{s$8RI8=wBbrD`VoY$D0Ys!Y(- z5l06kurH_O!3O6zx4Y&Mvz$PP zyGvzFB7?$+WzdP6@xI8Q)5rTZC2fIvF0lUzXs{O?h4^7{Q{N3La}LjaQ~tY5lBud~ zp8?I-K5X=0)HF}dr6I0W#T;lTb z4iaxemrEms)_osZ4kD*EW~gz?s#ui)gXYLVi&HY|v|5-W`~s(ioMpC!t3fKyY4*Oe z`)|Ra^sb6M_D4zv{#}ryQMqp4z8yp1(i(*cudVC#akMMpoHNt^$iq99_i%k-Stcy? z!8mr1wx^uXCQfXz%_WPO?hoJbM@=8iF)>Xhh|HE1Wo)bzi&0j>Zpg4&e6GXx%-W!4 zUhY0mg3h_nw>=tnDu4;()t`B6qlQFoLpgK$i(G}%uXq=zVq*pOOiSf%TWIB3@`Xgw zP4u)hrhE0s>75?Fj~sbzxyr0`vN+65hL8?gzH6zISQpW>SnW@4GRun@`;K?A+!L5( zTlFGQAeDsv2)Uf5@KbNsCz3LZs8p(1PSBPzT=I zLM4Vr{4~vXHul`t!Fkm=+sYE|!qu>T{K1N@7r1?(pr1cgLdTpP_zv>Q!TQJk$oi%C z2&$U{g9y2m2HiewdwKnhNJ~!u^S3f*WE{lJuB?jt_ z$-ALBk@;vABrpCOa~f#0xIkVa*wrPTfkG$(BNMj$IrdU=1Zm;TAmeV2s+?$T>G#09 zBV2g^r3G9ym7e}nQTss*H88RSemOB9NHf@$BAyKF2btD z$;rtylnm!1CHg(MF09ac?O1i;@Ebu9BVIz8EH_j)Ffz^Y&BvEG^BK{!$Wj5^a`Gtz z(@LNd3D(5k7I7OF`D}AwLEnR7L7NO=7>@$EvPp+f4-2ENm1(~=XSbz$fE1*lYy_DO ze32pn0JXnExC)h~rx8pFx|QUQ|MhaOBl1V;@ zU}vAM)Akj!F;yAa5I9-IBC%%Td&;;I+?i14a$cs`M%T+#fN`%Iw1#61;)!@+vF3(Y zSLaIh7pZ9W^4f$?tcB5?ckSLtD8@s`D%Pl?pXFs|-%%)&hlZvEnc$+~nYlIyRj4&e zUHweSrIRkhq#W;&VoI4okF@BNnsKFnUX=kAXZFfrm{YT5>4E3PtZnWvFJL7rY^PK@5F?&U|-fJY(`H-D#R=)!_q!SJ(`aocW=@sCx?R}LN;O2bPaI9vYtHk&0?8C z9s=HQ>mqtu9x|$*(4uZk@0r^IQ|SoI|*MUX^&44TsBRN`S|*VD34I>*+>fSL!XMf@{8ZI;fC-K8n**g~8~QeD5HQ zE(6l%kqOCS{LNel*^uIm!3$V*w*RM#cHyj4{DUW}U@`mJS8R#1fw7at6vqTq)0qJM z-{3|v)#Ag(lqVN2{faz!bbaJ`bO*OHoBBF~#af)M!TpA(0Q85?1v#z^IuT5k@cQsP zU(!0eFHku?lPEmE$)6xQ7v?0mG*djam&Lt*!{$*PoOJk_fSd@Fv_)3-?JH`{FNqsF z$c9RZ)}1YnH7?_g#S@T+GNIj2+Xp>Xp{}Zk-zd(A_1Zo)JM6dT%Al;|^880Cz*Ry% zEfD~l@z8Fx4ewT}jp1p_k>K{3dh?mXQTzSKmH=^x<{AGwyttxn&EeOR*rdmuG;gBU zLGPU#bDClV_})90P1Oci++|Igv_!X-2q9bd45&w}3koysJW(CHN>?0yX3#vSdZV~t zbBk{+d$V3ch|jycwY2XdoL!ErT&RYZJJlsy=seM`6tV?^g zoc*VYj&I=B!4AJp$R+hGup|qty+xBt>(-Ma&wPNZOp;d=;$s??R3A~${ZZ4E}nKe?)qi>MUJWR3Lyyo72LfKw=d$YAKEz>w^m$( zzmQ3?M@8?EDo7!J1RfL=R3_A<^~R2QNJHG32f#h1Mhxo_0o7Yb8eR>PC3d)5Mr_Z4 zmp7>K)0yUgS<5#TM41ZNq2u-$>L=dmSqLa6)y)dpBKjL@kJH6(Bio0*o zCtwNs|6m9ISnC8^{r>=qM79ZkNj}xNF};x`9b#2EB78w@MSS2Q{iKlg=uyKXQEBg$ z*0MRznv6SWu~5fGaO+e*$9RJ{M(|uv{tK-9K@hcxWy}$`yJbJv%UNLEHz#200f}jo z;_N>)#C#paQ%u|LhN_o zjeEd6W*v`9H4?az68jNcXs0^PKMrGx&w`=Wo}beTCLW9ncv_nray@DcdMJhzyzYi@ zoNLYga(=W(fbZiv?8atIyZf|@9+L_Ww^K_QtpsAg1$I_5uDcBL&3OX69bb}lbmi;` z-m@tK;bW7tWZqgUem(Zpp!TMRjR2aSwLe zArom>*+>SsOS|FZf_u)l`bQMFtfyW=-Dk#Tc30;^hGSqGMAG6R^RD*5Vwm>i!7#nt zj~Hm(0*JFw>c5mi3^g7+Kw0_Q+a8WKvg5;a6@}e(fHlPl^bRdC54Q2~5sM%byd$zH zJ3gX|p1~nIrK%|wl^HUL@y~@PUMXBgT&S`MzSS=-;W4f5IH|~UD%Sy_VonJM7i898 ziGFid7L0ex{3c{-go)Ew9;Unp7jvEP`PM~rk1shQ(?nvuo??6i%7odr#j=*ahkZ~CHoqjDjyp;C)bAt z4UdPE{RylA4XIW@ASO>wl%M}-kfoi`U3E@l8s_rjIl+9-_YOJr@lXzMn(=kFhLDf@ zmMK|r9VLeqS{6y=?lda;vvMhr-!&cu0sK_ua-?8ofcHInZhdXM>8x$Sfe7desI{0; zdChKdkv9!zsv*PMDMg&cPf{H|m-Zt4cVDB%>HkF8u$YIrUUIEx#JLtU{(7=@_xebu z3g+o-Kt{H(urltey<$g|Tx|1{&0kZ-{7ZSUHr_KhrWe5z&&t>Ep3p|H7B);1!mF@i z-K=C=Az4>?V(*`88!J>1Uzz_sINk#(kz&G8KVwm%7Wmg z8*@6f(1w{f289T&cec-AQF_R}6gT$i_S*R)W0|Z^XJI)bi604P?#xH%U54o>gDR%^ z9)SJVz^acD{GE4$vz{kkv zIk_zHRb&Te8GbT4xb6EaQxieB&SpJOMzTohoI0n)eD$X6hdOu^vE)tc^gTr`&)QV% zL$RrOyftEKBbg^2FncJ$J40n}!ws$($xxTelwYG{@e~&kmz*q!!MPVo)k@WlGSsD0 zpbWIsv-lv=+AWR_sE&vOWvMQ4$?S-vWw$VEq$5VVxIHau!bhjo&}LjFFFO2ShQO^I zXMGSeB3yRbgugT*U#(+Q6(v>6_L|OhxO@4jlq>; zdNw~Zk=?2_3S?YoOX{PqXSv{M-MhJxb;)$?cCn$*&HZ)Vy4JRUVks7%vaqatRn&YK z1+s>{X8(UPqqQa^)jf4d#sg>qmK#wEWl=8$Ys~HJLAf(xs^h?2^$edMMp6|Gn6GRR zE%K!yB;jl?b*m;X`ElyVGt4KXka#TKVL3c6;^VvH?{(fv=A(m;K-O_pEI2AXzH6Z( z5&k_dm8J+nZ*M}~)@Upyix{!y8X{tf7_qebt~^Y^>j`K?Ey> zSBZhLJH=LywQ?_`r)=cP-PwVGy(_VtVR596ZizCj=V|R?*=Y{_a}_5Met>p{Pua1{ zFvLuHZGX}!-LA=c(&8K@B#voRcUhj~I2r>+q?!jz&WFe?W%0K{?lPyQ-ec9(n@2J# zW~;vBX#@y4KeQV7=z%8Z6chFz#P(HZv^B^?c-hBKx7#l3r2k)DkjG`p_9~k zX8{C{x-r`;GmDa>RPbnlI_i{>D0e5>xsKq-{0`AiFP^DWM<5i*yIv{O82T7i6l-e6 zth!|;j5WEB+gc(Ay{4Aikb^W=fOqN!q(*|!Q<8cgUk*ZWp(D-f5@G$c^=b@UgTY4y zXv3cFV&3Uct~ge*w+w1%U$c4~vP_u`HsZSqr`WP_=j{2*O5qh3%CH zRm`)sfz_>C;bdKsGdVJ9=|4W#Kn$*+E(j*oi69d#G-`H^t&8J~R9Pq{OFzX^HYPTr zf*Tdqj5dW#uQ1Mix&>tP3~o5dH^WaX1RwX7wbfQ=CVa}L9Bq~k*maxS2nQ-32=jwd ze|I>*F897v5@@Wl>qbc4%%U6oj1p=_+HSiUcn9Q4QPto~)pYXwB}Z1X6wo%=;ADC| zp`&^dI3jT)4|+%H^tR!BzVQkn1%cjG@LgkS&wq}#gx>V8Ukj#>;*#WCWapbRLv_Ro z$vK7br8g4J0rX8U^lt96a+hr`T^BE}56yER;x3K*OiMtzS*&;!_pUEH5KgPYE`d!s zN>{La2?ta9Bw@nyj#}v1<-!wTjPP=q5GyGH!z;H!N+F$bxf&G(+LsAvqy1gSF4@Pd z187$~&yhDgp*`*w;?JkQ7%#0hb>H-MPM~;nW~QJnWga_WVB^kU*yXb+#CviriQD+w zshAkNojYRz)wPkC?-i&kUz_NUOEmUKeWW-VD|kqR5+X$7BCjhMO z=7I$&OMYyHn9()VZ65G(3*W-EUI@FA1^_wNPPp$zAg9@9qBUjeQA*o1)0!4O#(oM% zgVF8+i~5#%8@W*|ePOfeg_Ww=ZbLr`M4ds^0pnbtFE$G+YuWRfkp=q-Gc{LK`wkV= zLqb7({^K@MA!;yXflSq$KkyIIH14N`NeSjigE@B5fr08=!hc)34$U#>H~?3R4q|cU z?V993Fr9_7*d(>-LdL~+gqZ&r@K)JDSP$wQIPT`FN^=!2%=d9EejjwycUluHl%#Iv z*=5temubIFvDv4jS<@pIOetJoz^0Eap0nMM`&}Vj-p$v1Y*II^KUR!CNKA#1EKK@% zxR^JTUs4p@`5V(>&-g{1(%@IPxdXR}il&$>-OM@5>8Bos7I3TF)f|@c`KAn<>D#>b zb8D$wz_PkCxg}0<>oSj%M*ev(pE%QCfmBKOw53fuUoi=IliuSLSA*xbBT%tGz^{1A z!&6mdcXi%c7PQm~ITz{M=vhVDEWnrrfcuIXRf#+5&Z+&_4^Y&ifStc?92c}zL)~25 z#C*(H*%QLFrBE@m0tKb{S+O~+-_}-Ka+n^e{0J5*zEOZ`B3-tXBLNIH7fa(Qm$)}0H^lUE;eU~e$s_Bi@8|rG(YA{$em)GpF^d7 z+?D5LbqxCo8!m~w>r!dJ*2$q3*bHvwo5wn8s?NimKI|}=R3-);LN%K|K|U2*oGYLU zQ~-s5RqBb;j>Qtj3EdLL#eF+x{+=e!9ST}CQ2B&vml#)D@bdD87#s{WMJI@;kzE;= z3;qCgZDys!M9h6!F1AjRYKdw!WZx&T5Kd& zdy9W+S{KCL(No45Fs?+l(s=?SpouxIyVdIkna1`nVTlS8KMpJ!kD}ri6D(2|)qPT6 z?0Rynz3v2!^%usfhIMfNHxk3&tq}pvJ~j0AyAZcC_~^Wme6~RD%YEMH5;H1ZZc3Q_u_I%~{G%#-Rbpdvevbu%^TQ(zFx?C*|-N|;SPM~KY*IJ?$C9b&M2W?aUWEgV=xJX{mlEW z;ehxlHs?RJIF}fd%1ZB>3g8yzUIAXFwIPFx)H!!_aU*^iQ-k~tZt)c-2+gm`b4}hu zRkIRRzx zjvT*M;-1D{7Yg^B1YZ)84n~g&4e%zPCj@-Dp?YN&(Q9b;9QS>95KwoQeSE^|(e*zK zFxMPIF0;X8jPbZ?C7fhp<=2yEZ}yD&ic8T<+bU-fYn3hyyND|(ezVHq&xP`;fC^6V z`MDsfdVGwx&^(K3tN}knmgqIGTG&<7v6Z zD@{~ZZ&DvX>3g6miPFyb4$=i-H;h5a9o0Dd0X{*+S#Z@ziBpQW;*BVmf4Z?_(1jeC z10<>brH9qks{D)j>kvX-RX~$GN3*9~xWI#k+0oP4QmfI%92Aomhva1I^qi4c--lo zEOm?L)uJ^JLRtk~)d_-fHG*6PyytoV!sA0U^E#>{>&=1ShJ1@#_#_~+CrG2*Mn zcjMMX^lCr$@Kf+lc{j1>VD?Fz`0p;Ue8$ApH7Ut1damKV07E^drVOE-5c3X(sd5(WmatdJ1qFq# zByE49KRzVt(tGK?g}=#M?z?ip2b)ZDzq<@QEPoZI7a=dRvXgk^XOqFDJ$E3{`ewc~ zjDz@1D;~uVQE9s(1)%0PG21-N{L(Qfvb|~N1ByV=#%1=D>rC-!3nHGqZQpQ?nbJhhVakK5p}&N$P3U;36uVxO z*V4=CzpzFjkR!l9kI6s@Ie$*m2+&^);^N*l831b6bE(dTWt~DM>RI#;#b8A#L1M3G zXdqfv*)SWtW&6<1WNv^&n48ks1oG%wKkS2A)OO7OgcIvw2>SpZ&rW+$Iz|mlbf{I{ zKFZ^kjcGf`hUa&&B=#+snuN`6$zB7ridqMZ@Dsh zV#OIg;geDU&oJfusf*XF8>b;M8Dlq{&kbhriu^vSmgiCqv80#?qbVCXwB6<0iYo-W z2u?n;^e{tHrPpPYh_5r>@4v3PN+K8dKeym^DQt7o#1fqH^Y2vBg|c ziwW^MP6C&FW^Y4-xq?bdZZSdpCZ7_6WIfm5%NMSFLVX2iy@x{F$k@^K`*smv> zUAAf3j_vEA@OU>%XW}dbHSbl;Tenmp)-e=Up1JGhVnSa?#D`Y**F{znCOIfBh}y0M z#xxfwXU_h9^t5)X2W6`jJ=A8Jya>)(8gSDs5vm*rl9rZYubv_JLG)CmC4o*2*-~6^ ztYW?=HLY{WDpz1c@ga^K?i&dyRBhdt-KK0P*CFQE z`?S)f>7`^PxXoqLNh;!JxF6!V?=AKEqD$#qD@fqm+Xkoe_92AzfLLXln;>Se`T{Md zC3G~2`v7}+gZpvo5Y@bEd!gH%@cSusPYCv*^B}xNrES8tVPpENiG_Bw=aU=f_wif$SAwA`Z zPfPMW_E~}PiU#nh9W4qkb2gkg)Gk-gKsb$$=rEwGwv8nrsXDCl7U<- zCkJ;asx2H06ItbNJ`$N?;LfV=a*ME>)tGPlGC)ip{w++u;Yu=I%h(FFGpEWDXmHht zjYQH{Kj`0gLQYdblz;!^mqJ$W@QseCH`CnZ(kv$=cgEF>*_%|aJHLq1T?3YJI^b@F zD__o;x$ksDw6P?PZ?y+Qj^z|}tTZlB;LdV`B!?_tdY8vAy=!^!*3tZE-xN_0DyIbx z$#{$MGd?0D@#)}4WOavTeP*=C*7Oa5HMxq(hAE||UW(6u_;(mO!w(ir64W@>7$!W~ zg$t68B)b;MMg~^j97*l&U+}?~-5gRkw@LU3Cp}X!n2LpC7#(wQiRWRExTM1_wqzm_ ziThX@n2*TMhbZkl1sh8FrImAb$QmYf8@icPCJ~$(!WA_9O#yQ^SCV~b@J$0n-tp%NG#+;R^QF?C4lLdM9J2>G7xW!p1t4Tc&PcfCZ2O;c4|d{ye+Tq%Kc zKP%b!MHFW3E0kymaA8pMmFAlCM6!%I?S-lG`TTo}djWhO8a|z>(*HKNiAwYhuPQS8^?Iq^Pk2#XSWy{N@NH~r(m@9l-A-Jvds&VVx z8AS!69>(HNPNlkN*w2iJe6ht9^^E@W=EmY`6uRq^@lDyhpbG@|0I02rq*8VEkPwNU zwrp4e$cPimc4`TuINdds*86x{M$c__IO?MPzAkCU3dxc%JOax1Q9uKbe0nI`-_X{R zK2H9s4pD==H>uInwEpcO-M9iAW`6Z5fH%VWoHf6oB;7+Xj4Ql*Y^gabUu9G=<EWgnA#rP>8ik-zH>WTr{R4{TA2U(s z(9iUTny90sq&gfu3NjvUq!rQhs9S4fkDt=Tm_bz1ss@~%DxF0wM1;>cz(3zh*ySOx z(efHOQiHbb8XiHRAp@uB>dn)|sWZMYsN-eB>Z}p4{4%6&@Dr-*T0UbhdpG>l*PmdN ztrtxolK%M_3QqEGY^c7E{1JR*wom%XuDlB}*c3lpe5xqR`WH<;cjt&Rzv*IZI~r4o z)7a&zZl>hOZtu+Ob-;j|I(|S^3K@yTJ=>&vmh(DO@&0pJW#{mY#2RXWJ!Q{-9*gy=62>-5p;J{zi3=+8JJzOc%{qEi)X~N}jc^C)9dMfF zeLZmjJS?#5`v)Z2MpN(z{Py#?Lwd^>RCBZQt8|KJ)uqs;Y1G@%8v)J_X2LKI0m`8ONR_VSlcWN&jU^IY8**A4E zOAx3XMfY$_Jq+)%qGskday_IpT%lbf4$^23`5G}OO)a3!W5~qPe~vA+K)7Oo^?-SJ z61DnrBR^WR0Rh}~<2KtDj}D5WVf1;By=;dTq>3g*Har|@Ua{ve>|(GXO$wuXcl4*? zp7|VT#tbe2|M{_fnoq^L-QJCvDd~gR5|UkeV{kR9$g%we+hdpAw!`4hx9fd#+4kS3 z61;=^=<~%fexGJkJe;D^4W1s?k1H9ZH-sEdH8|4dSSJ&PUmntJSxB_+8i2M=%)UJ$ zNVUQ2J~yskj17OnoR7fAG<@9jt4pP}7S>SHrS@(MQgUa$pWt> zS?3B&cHIS-%dr@QaOd)OGK4aQl4tu{o(6Ju7j-f0Ek2N<2^_pTGa0gY$shw=V{vXb zo^5t?9=cRW_VVY4QVywhx$OD5ym$p3-6&VjE4ogGOiS*bq^F;qZd9IkuV%UKmify1_9SX0_OfH#Mx*54?DFs-zPT zxo!F2&{;s;W5nz^-N>O{E%VXf>Dc^Tj=&}ll<%sUFTZkeXB;)pFk)R;m~+%L++kOH zJk}T@95QLoWY%Q+_}lD7^^qIgVrvXz+yIxO^MqB+&~o{PAS@*|4K42L(F|9i$V05<1qhW^SowfO6a%|_qX!vDkz zV%rPthQ@LdwL8IDI zVM2z0TVn*OC;5Io5I>i(Vi$E?}@b^Dowl0kfAUNp_W0nE0#xj)}!&UP672Y=+gb;Q5bKj)JqHaIf)%8eT3?Ks`qg7bGHcf0dNBooc@OZ0&ad%q1-&rNK97M8M5i0}Nfpcnq~(nGky-cg#NoudWVQdn;pIT4wp zTS>@XuWB&*JEYP}0M1k!fc9U!rPd(gAbRsrJ&l{{l^Q894k#Fyg=?mw9^_A|j&pLd z&s14awH%0K&R#D4AKD$K7_#v$wnye!t@H23py}A6OCEb(Q)3lXBZrI%L1#twm6PDw z9VNglvTyX=B_wR%0FF6WuB*6Yj=L5Az4|m)Bn81+U|om1q=~OUCig900;jF!=%DVd znX$+i39Tr?Dxq$sZkdRj&H_Yq>&-|`wZfViC;F288`a($0_ILefr7v7pW&xa~wfB!95c~+dCUE)?v;=zfw$PMucevr|6F~CDc89|;&$3W!hxYMX}A4<^cD>38{ zGbKIg&W}FB=_qM4gfWEC*)Jng&Ie}&g#D@iI1NHhN@J4OH9b)-B#twC~H@k27l z@_QN9Ur&laxnZ1DzhfCPQxXh1eOHcu@)|kr(fU*1IW1NB^u`4DR0IGVULNn3c=|U# zyjK_ayL9=A-PcdNA|4wb`k}-iE#^_SY+H$SL-CC8SyMb)SL|QgiWu&U7`zcU1>G*a zDe5Jj{n*yG*+c2ItnG#m-^@%9)X*Mp#3!m4ky~v(S0=dohX_#|pa%)IsArRWp=BNp0GW?A*t-UQx^dNzr`oLi_du4Z2$Ll zvU<`iw{I^Auo_Do$x7nn=!r*#E`MG5dMlKsB%O)KF90Q#rBK7Sem$Z5Lg#Z@PTSZ6 zTVg(qJBBmRi>o-MF#f*5pte$5l&QAd`iAj&weSBbSrpN0oHHi(yo@ZwtT(m_{dr5; zo8Yc@;r2-*ytAjDttnynuY?ByOsnDp*_VUk_(q$u(>LGxzA|!*1Fl2HXTG|s{n7se zdVqIi6?BV;dWH;mu{W7y%B1K$@Hi8tr9~KoZD&KrZmWR&)n5*vx#~EJ^4zz5` zaC1zw+@yWPi4Io;*|IVQMsmaQZllD0mhS)TQBu{?+Uis!B$K&y89W@=YLwEwh7*Jx zzImPWM+Qwhp4Y>UGth*p5|_x9kwJsuk}O&-u`{h)0Or)l*M|k^dr(n)WO2gKT(?nz zXd2kI=1x(BiwR>-jZYDXWarxViuoT~;&^If5iGn{B|(PqA~=}++sEyeZaKNl7u|BK z84dACsa3V-66l-ATPi7_ho!jNPoGJ!N<1VLlXVxfzwwz5yIqbCvN=dYINm( z8Zf+SVT1G$b zmgVjy0l)t=upVu39P9FD#VqmP=dPy3$(-+L2Yo(FPB0!x9}aE!&cNE{disIy0M9Pq z2Bat6Wksyy88`SJ1ee9i%#!e6gH3U9II*jing!*#%-{gsk?8V9iLvO)Z=trLCwbnf z>Ty{VvTWX|1FtQ#wU=Xmj~M5QAyU@uv)tw^pz>u-vXg#l)z$f;1(vYcw6sbMe|#mw zo8fK0cdFl=r#>Eqa9*7O-UzMZ{LDrf} zU&dBAh5mV>8b$u62vZ`k_S5))vxMDSU%X;BfAi3{cwyeF^3?!IG-Dn(>ZV7nZDnJV zio#=)Ej>NWBl~xdYn&p-~X?U5U0lGD-S(q z!B}#l`_kV}L$z~f7`cejQFp|3k5b-uSI(_%-;l&O;QxAjrQjJNp(;VwpT#7)$Gl(1 zd3pJ=lmFG({d$-{btycR2rEA6klS-?8@3j`y@-5}iUyLEHWA|WNp;7)HPcra04^&L z1x>T?TD2?7zXlL8$v(bSv8RZTzy%VQ@Vyhm!M}ZB89KF2F7|Jm z9G-Q^jM4acmzsV}cmt?&Zp{!!dinfmDVll-Paht>ljr>d)Y^9KN<>r%Ur;bkdSd%tpqy?b4PW2eVw*G#aR! z(Bs%hs?|?h>E-s7VVeA)r|QB!lXtx8Ky7rv@Jk&@strCa#Q*^yvIpvUETU6MRNxO`OYeAP+wt%v05MZ01z@YpCkqE{My z6!%CU8s+pTod3Pm+HKOJi>&CDQI1eelv14787FUiF-srAU~i@3UlCeE5mnvsIIZpo z7B0gVoeK3IxW3YKP~P`Ic>bfRtu%jG)%w7KvHhc+QZX(<)0<_3_H%?5vMYevXxo>7 zoU$^f)3xC*_Am(|o#dJ>E+lDo|0#VM%Fw3$4~aJgfoJgpn=IQ))z@)s&y)VSz8WBW z3&+^)lF}`zZpf2{brGxGDR#5!B)_8io#DTC{&V|Qz^e(KucDeQ_qif$X$K+wj?0Jm z?~F0F;ZnCwabFy55%-qF_q8eqq1G{NBnKh5gi;60wfnHHo#jsE4SqoFTbzI!);^Che z5_YI0E0LHfh|VK6?b;u=>fs|Nm`Ah)Jkw_^IK{a&XbUsvd!KrA5hH1@Es z7t;x6#kWy;`x@)%7uv!LxZU<7<5jfBkb5yrE1%Y07>#WkDkA*Ve)yG2ubQ!K@3v(u z4Z+~01Y7!0qBFk%x!>zVJ*TbUH>Xwh&GGb z?6RaKktNkRon}FGRcz)TH0=B_w9InR9IW}0=XmZAh>uixMf{hltETb*&H$!*(YjUr zQVfUDj&p0QgpaQ)SOi!5vS?A)gB#v^0}M%%LJYaaoMX&Qg6C(n!)FpV+R|E$8t2#i zRMC^=y{;;+N>UWJs>Y44llYr@#@1w!jY2J|oPY29*OmfPe@6v$LRyzG6?@^go8uZBlvan|a zdMc5$niwXpynQr&bPyOR5kYL{vFT0GGfn>Etk+xP9e>Pc$FS3zo8~QKvc7{R?F*-E zlrXhlm|oBPeN$Xwk1;pfP2~Em> z8>I&BdZ%x8sc{)YwEBrY!W2;PkX#M&4oNcK=thj)jvYF&e~b@C)bpy8}bdE8`7oAPS?e&;l(S`otx>P zD;B46i*$y+clLy$`-GyuA$5eJzY2PvC9R$?{=Gv~Ir`0gv-u+mwN4^pFuak!kBN;; z^AI{y)$~2Pyq4aFFi+L=+UH}3d=<=?Af{Ua>qLD-q zT)$TJ`)3@H@ja_|eTB|0yV_ZYd*AOG{Hc}m@quhID{wTZOaRy1<3ROUo@$9gcH}^( zIa1x976$#%G0)L4)IiJIrN&kdb=B(Afn@d&aYFXNsY=426S6BM+K^=~Qe?}9yCO^& zGa_gFz!Yvhifnsa*|b`qHIjejp$dFft-a6!4)?hF7NSPn8yK}?$cyikA-CF}M+z+Z zV8rW5A^o5FvvOIQHIv(a{@$5ZBMAMy zL*+rt33K@4;DwI6Ja8yvyNADP{psp8k0@R$9KV!NzFs*wXEceq)v-Xlq7kyKyI=Odvx2Hn`8eh+)LGoAtCF^y-esn zs(}sJOYXrSShy@s?V=kT{54^LMlf+d5G1Fd1D>Vv!S3Tjws=`fMs?F{`n^2j4>y_@ z1BoOLer)vitV`o6ITr2=JhibAG7*V*wvDf0wrULP!{q$G$c+HQB+zbJs1U~w>C6<+vJ|IQc5OgLizc$%Q~k0YXZ7skcGNsnwoiXm$QV6v|Sp+$|LP{ zl|+-+%Rq1KM6a~{iDgitVTNu! zN5~^Wz?CHFFU{M3dInCvNSH5U>nCM1YO_+`#+NB(-77?`gK)K4J zw6AICPDyj0u%6ApR);u8e4X$2`|qiSWt|=4Wloa-lCdV?7^E3y&J@Tybe5V*bKgDF zX)#Ht%4O-4&L4#rjdV*Xz&hjYSP1ct^cpC);B3D){ywl;1bF3MVzRID1-fXJ18?W}nMexrmVdkCAAv?VqSj|7f!YgDO>nGETQnuNfLgA)6H20_-;T2ZlZ~?qqVqk4ckJLNEN(-m} zom0pqm2UN!-e}5`_e8AeDtLr@u|JY^q|lrd_*;bb=zv51kUJunS;jYtiW{+@LX(y- zvxSZ1iWFF!S^aB zPdn0ws~~j1c1fU{VhGK_D^5piJ6X#0RBYJ~1+_p`39F^c z%AiX*mQMw-n;QACEJR04xBxRUGP!vE`ATqvgZoD`i_UMuOd>!ySq(p3J;>)n@4wBgtaK_iTGW9k%BsH#NRty zn8B;S&u1>7uUEBd{Pve<_r1hpUvk;+Xg8)!gWgQLgR%SA$bbb=q2{$}6oNg{NP%5$ z_pj!{ucTp>rLgx^J~ z+*HK7ew;af=9&w28qTo9g*mg`0JZF}g!|z=NUy_L{XSPkJs!nQRY-i<+;83}GeD7q z$PHsogVR>gP$6m>Si)}y_mEzvs2gH$d*pNFkROnFuVkCm#fL374=M&Zz-w2mqsBbs z#tZT6ll+ILgu~rb{hG7d^As zG#{eD%gamtD23;<7UVD_I@lW!&fx~R-dlf|9`0Y@xUs9pE9X)Lfu0uQNp|(sL*c-xA-iPNr~sW? z!?G(Pl}?kxIe2_^|4j@--!WC)|67Qzl#EXD|2Gp2H~MC{YG4(&bhI~jnf_L_NTeDm z$%5fvXBhWEqFJO{8VYVD0-Y*_P8m4$E76{!BmH#e((&*%{rmqQ4Ke%ieI@MrHqt=-i zwvS}eUcaKM{1x3u{n<=y5D%>AiCr6r_`gdqe7b6MdCV5kv1_s>D7eD51A|3js%yXR z=0rvJ$?DuU=^GO2W%v!f3GYnkYriJnGw4|D+j85Bc82nVc@npS!EW^xh1tzG*uhGv z?&%+ADh`kL1((wfO%ZYsZVbq!yEyFpC1aF`DY8HLI#PoLA;~h=tDV2M+EsaZ0&3?y zqj=08Y>n0F>S-J@cfg#f(zs7cFmOz#xoAA^&j`wRd+PW7i>ny>&y0lN$A9Ft9f037 zwqNyBpW6FKvZ7-vib0kp6h4!3$-a|)jaIm-i|egv3>MXDu>-F8NXS-hFR`YGmB z7&oSybI|%6OrMp}P~kPKU<~Z(7)&tNFJ9}*L|bB&vf!}bFy~A0Kn(nYtzBA9>A&qO_Q^iZ8j=&#@~US$qKh5qT5{vEe@nLhK_5_N?S zE>>-(Bk4_Y=r^gD(uLITCcaAQz(JPfxj+AryI{ZVRFO{VKc-JDpJff_GX9#@ZDJS| zcWLtNLRl@_M2IQ;<{6ZS=+6xGKKtW+k4d^NkB@|76}*((^xZzcj3b*UOU;Hb^q&5# zIG~UeD4)ea#!9%&{v#b(%;&Th9eB;O*2t{|000;+LQjFqJW{(u;EX6{))7(maTKCb z?bvu(_Mb};_l8$z{2yXYZq!~Zzkna~SEtVfdf}9v)Ql+6PGz_rILc<`#{`z%doe^%QTeegk(gb50^t!iq2EY$8lL0A zH%1crC{`sAuZzxl+)qNk$bUm%qt^>nLdta&hMAm72`G9L4v7uIMkc;`=gzXo2z`P! z32m2=T|`k?-I_-Jz9O&rd*|;R;>uM3w5flakNJ2mUT{OlHhSIruT-|LR8GV1{kToP zHg(@og{-(wMwGSuh;I22!TmDasl)F=!#vb% zEhjp}V-!=*-#bLfxhwB82|A}sdS>caR|D_MfI-#~wT_6!Sz}V(NAHmG`vSYtieSvJ zpzjVD4G#RQ+3>jl%^6SCEc>^h_!8peFYHAn#ayBo3yw#XWesR2|yCX9WWzL>He5cAnns9E%l;BnS@6zS0*Bg1Q6us5iDeDwPyEW_pp;w9j^ zV!gMf-J#;^7})}uv?~2*Q)xbK4L$jlH!a;I46Gf zMl?}R?aWY%zT`M=3T6bVm#*_LDW`f-usJw3Ti+~Ylq>UOQMGl0_U%Aq1-If1NzcF~ z7K6d5GTI7JL{Ns5ZACYYNT;f*^gEe+rf{cm zibwqKipRa2iM1&l+F4NpY-)nx{4W*^H6?ngwxH{P{>ZwF+xp9FbQ-ETt$c7<<@I7R zvZBVQ**{N`KmR1=D0}O6@dSy7jx&tTRFk0xE|{VqqxCMKX)>gZ4^3;($@01ATe7<8 zAeV6F_eLp(D3<+TQM{QvXis`m?9_vwNA*8)liDcw2F=4>@D%A}VnW#)wF(yh!+H0-NEUPd10jYWqkRbFsB!u0_xS{XDUOo4Avs^N> z#r!CA6}sgN4SS!TNT1eH-z0O>?D`20H{B+~R7Qrvz=Eu~A>yvtf(B+5V&L5!T7__qY$3CZei_hKB!SMwQu`RO&kz0jt%( z^pCPCskIdcNn6C#zlLxL!nNUHQTD(yIU<)5zsi1@I~qm=l1Wc9%A79-bou$bjw@Nl z(Jz2oOZI1lzdTm9{nt_tz|VKQz(RLf6Y|XHz3=kVC?jviD(Svk<;cC&$@(mqZ`TJ~M4L4;?Zxqx0;B z2(^to3ui^gNz+J0uGnmpHmDyvtrz>Xh32d`moi5dN>8tC&Hc@`Y#S=g15L0i>7# zX&AcfX-{TYZN+ho0$6omuiG z?T?B3DQl7w^T6`5k2f~E&~-e)1dZBt(usL70>i#6;s>dGJt(!I+s;cu-LIBB<2bWD z3A5$1o*2mQbf~AMf~-ezj;jRgO!eJ<4g>w72&3~jK=?~2#3$a2nf{L*Q5&792ey%( zX^>vSO34|meYo(BKl`_sAKwg#k`Z+&_CUGDSiIPZ>CjfGQu#^Y{4T(-R>uMz-&mY_q(0R-9u(?n^`QF|hLP4p2=el*7!VE16+jAk}HKPQ}%`d4mp^D1(|GtjNn5p^I_ z-AzMh#JPDqGL5&3SD=Q~^!_*VL8VG6ae1429@ZW;ymlKbU)k4a=_~7W*O?yjx zHbTYlFV^|Q^nN>Z{37x@^#2nKhYr|;2Q3IV@ z@qV%j4j%uI`bc)EeRRyYy1-{Rs;Uw#sTH1`h zN-uj}@mZr&DxYS(hqLq*Or1fRDrX+2ssbB^cdj1y+TZE&6Ef+8l{mKUEH1K|o$Nn( zAB-Bf-^_Q1sM@t}B&GU&P>v1oSyf?dfMo&ti{U!}o1dsoI{xz6ws?wY#NLnoYFey^ z$`9Fe@&?5%;(;e552L)x-cjaMY8Aoz+{fs7(5bt-*1$oUD}m$ra>=)#p_(v`y+mAA z^K1_pV+gzB7mY7fy?rQc4x$O;3qL`gJbPJ6%&)o^a#cw)Y9y4S*}~nVU?)08N#}uc z?GfCTh4$-z(L7+pLA8oG9>_$6nBVX-KW9@`WoPP=cBeUDb+!^um;az9#K}4qcEQEO zbSU@75HBMFR?FYvJfZoPlY6Z!amQDbsB;`@~6$y-_5Vajm^W*F(y&OdP#ras9s zXVlxbbnX5iM=SZ7v*Zo$=ry}v(Q*b0~|3F1btEUaOYqGF)kyyo^a0eQrt zre{bFhdLDqbuW}P6Ii|kz%G;uV>PUJFSX51D2oe_%EnT0E6wE5)om!xn2gp-q! zZ)|Ic6R-Y&uC$ZGH&NEa$xb4LLQN_z{qLR1cP=&p7Yy$ev|VhN9xZ<9Dv`{*PN}S? zeP-2B6y29l@mRk`u(XJSXi3-+<9$TLCe_CY2D0_M)ih-LhwrJw<9_v6je505hlj;1 zR(Y`7kp=At9@ECG8U^w9ax4DmA|tuyA}94qVkLE_(2p>iqYLVgq~~v9`08gv#73_( zS+aP1+OlLNoI&vABa=#6VT46Doj^2#O@-X6NaZVSK~Mi>MubL~$4}uE&7e;jqZzm% zmsxo_h@bBBa;F21kKxQ`AZmzs$U8NGkDqQ0MA{#RgqQq;Yjx^gFnIgCRKP46nyGqw zlVwbci|PawekpQQ8R|uwmc`)rwfsA(nkWNcmw5asqFcI<5k2)RO!Kq7efK~I?4990R@-n_pa9|S3 zG2#+OS_wE+3(C7^G{`Lc>YlW@v`V_r?{N;z6*FQ&ZFHx%%zPKa;>X<2_RaA;bDH1g zPE3RozJn={3)RdqwNmtNtP5s$7$|p&&c>M>ieby1VDeE3KZfV2^)|k z^N1Vx_$u+VwmW6CWQ7`?DbD#=C@Tw!4|=7p5a^Azky`=*GtF|xjsl35#U$PZ&1WWK z?W|*6x&q-AB8l?i`@hc|w;;zeAqIcJ4(~j;ioQS;oK|p95i1cYh$$!d?Hf$HFS*3U;s28UZ_2jy8+&ps)(1w#0=^p)L z6^*r_)tsDaBr|Wkk+EUk;Rd2tg*9eJgXoN(2A)}- zKIX1_2?=%aQH0%pg;|9c8){veDz_aZ=O>IMvsHwXe_;S=YTbA7U=OFo!Vfu1c!wdL zuCWBkDI_Cd(&u&1UvAc-eoqF<5W=?T^yYnfk>FMq3j3Sxs4&iQeBMDeN8M z+RoJe1#)eS=L>(G`zNE2{kf}Z((5fF%bfhDx`;|KzDSle6U-tdO@g4VH$)e24J!4? z%+dJn^V*as1wur+e51nAaTJ$<3c(AIAG*xhY8a&&jK`4iu(`CFPgej`>GP6T3+Ic}v? z#Zm@#g`HOaRQZj?7C2TFob9XX!w zNaTJ0*>;dEB0>gr6PxeRyW3kCT5-t$Un>S0vEwmGf;EOFf;7Nx@T$c{+h8%Feb{mtvVJ7LDFiI$qxU!*r@HbR3H0nt7F;Hq?#hXmN+)?X zZtFToA&B3PHTbHz>kuL~fm~C}bJCd+I!uatW;N~qnG4LROhd!HuM=1TS*JoD<&GGJ z&_tN!$Bj{rbEvcr-H^mSXDwy>wUWx{%UWV%ah>T^FMIZxpG04B0UK;`DeGi0x;PV2 z5D+qG^=y|_fp}#;k{mc)ql`@W{Xrc5&rGHC_=Q4cG`|nd)&4-!_q}STM%7hF^`np0 z*#A^1P2@19o5T#2m~N^Vw&i5`7sSZJdQQdZS4*=ky!NiXX^(=6da^f!6%(s9Of4)U z#{YaYw~}(%3!r`J_G^Oju@->FkFPJ*w?f-+U{OvVGt&3;Nn6FfNxc&2D8##Lj9aU2 zjFI<_7>qS|u92Yk+^Pq=O^!xkvJR@aB zQe9m?+;I6+fm0t5DmG5C@UV%AZ5fX%f6vB$^!N>-mv~pQdN8BJ+9!A3k;zxdeSO&- z=pa4;Z~jmZOPi`tQ5$AEOX~N1zdmuj!lORr6T%i+39&+FBPME-*Ez#byeu){>GPHy zmDZr8=dsZQXATFRrE50qU8H#Fy_L=``-fE0evFmE-4uS=s>4pg)+z(?u@iVDVM6BB zrn-EbVZEZ52k6SVwlPVE7)|rI=hs{s0H0tIu9UX|7%}69XL40T3bp zD%k%qNjNAP-I64ooydb5x~N{id{)8!WJB%LPmR|!RGXf5j=3dOIf z!CgrW!k%w%@_eLN7(%er^!X$H)K<)*=Y!1s2mus2+|G%Zf8vs2QBTs{TiM>9JykZg zFT8&c!p+#=;a7oz?Y;-v?yJ=B%}{yRx+5vGnU60?ixAzQuDNs z{oAkkmC-BxlH16q#0*_Zk9&3tbz4Zw_!-_?W!bnn#<0-Mq;lt6Bvf=T%CcN^u$f5H zONjenx0bx%j3TmFbcNGRf|&NliWZTUQwByv~P4Fa8#g_U%AK=T#rtyI>B zKE%=~@Qvmh#*gI4)e9*<{HOhab^lQ{Lt<(2p6w(Kik#CelqgVDI~5m-$!6w``JmPt zP>pAmvE#Buyi;n@>ohA(ir%vB2pp3psne?vj|(vGERsrObHm!)ZZ3p+s37Jxm8CsI zw26X-*IntbY}5A%)%v&hAhwfv*BpW>VzwTopA|#==AP)|6@pbm;~Ct>_^2wvFcZsM zRr==wE`m8<*jksk$SkAu7g@9^{ht_ZUMCU4*g3ePsN0Q@op0_ZoHAIo?aR)ht#iia zvt-+FNyxkXR&4DB68#g&5tW|*eLNY!TVGc+hp9}QIH2|9W<*QmLg(}@Qn#Ar{>SmV2{Fwu;h5N_>cn9J^JlL1w zzOI^6D?@VUetbBaC}R6`su365nEf8+*+VVLFtL~$Ug<<-`gYDrn(a9mzikOK5_gw< z6G?Ti$|>XQIy>um_@w%ax9UQgHw9mMIqA7i?`K?-u@L_G)|=U1@ucD5C3iy2b5=Wh zm1o0BG9*+x=n}0zl5Bp|$B#?X;4Z#tiT`;#&TSgH2E2?D&z3S=k(1L$*a@F-(lXr8 zwNv>_Yc37w0T<6a=+T%y4*k70Q&!BD@}y47PC7Ea!^0%T zBRkO7bKt`N&!ON5UVetz!k4oxR_G&B=i*PWX~(EpAcf6a5tY*++^cA0L-aBbCEYvv ztF<>|MZli5rNIFx-f5Zp-;Ld6AarT+^=6uW=Cc&&UR-V%Mn#t=2^JQSi?pn>TB&HGrN zwq09$7R6mzQ-wzsE~e0nK)>&lT+|x&0H?B9kAkUbr(jeOc#w{4=;t`Sfp9`A|19`| zV)EM*j8)5OUd!PAf3va7qm~S7lA`1L=5L3t9>wBtf@&|5m->#!O_r*b`9{j;1Mgt`md!$ca^DqWazf16 zkWo*?gxbTz0PGvh{Bckj(0NFOJoR9s`9kR>^|m(OOHZCC?3tkipow`%fa44-(#C}6 zdw+pb_B<5a!VW^aV}fy)+O!0F57@Ze+f}pmB1=vj>{D0@=v2%g$sHB1fz7d<0DpZQ(#L#%kxJdnYiy0HX`wyf2qCZku!Fvrd7~et$a>Ra`?qzTYr7=dgKR`IWfFb|C9}ODMPh7L4yD3woZ*b1M$%Wz*Ckk z#jTmI$LN>HXm>u27&%G!wg-PeYz@@`x{ji3Bu%*`mr zAmhvSo*Pf{u{R)ClNnKof7Hw!=aaNXH0aTDfw9TRZpthIRx2NnhJ5(DZd4_8{?Qo+ z{a(m9$079}t{pQsr2&8zo8P0-R_F0L=ZSQxAXmSBuMej}KNc64q6VM&-IUrebI};y zo<GP|6uVHy{M_tp zEE=^jo|k#3lE(A>Q1Y1vBFr*K+!2k8-~OPNj$pw&Gj5hNkA(YuL1*dt@<{6lCNwP# z0~x!3?=+VxFs0}V|1LkCxvRK-{jMAtTl#TDIA=B+?b((k3nyt1fjloM1~F0*oR|@t z&_x6Oh!91Wt+|sG1JZc~Yo9Kjy`guil0SkTv)36sdS2|a5-t{v$z`3!SQy3gm$F{B z+h(Dz&RHi`3R=3VZ)kJZt_trBE>vI2*b?nIlAIt^1RqAKT?UHCe&d5-a%$7Jv8>C!~@)C>Xbg7flVq`KY0P}7Eka^ zG{5*j-o!WcZ`E5x|94-Aa%=G6eLtp{wIdy@&DOm+0;LJArhBl8TFv=gj;pIud1nbL z=|hN}uySTL5aLf@aJakPsKsD{j{oC`%5(Mnny4o@H)FQ!St%;*PNqLiV)RA}>UBj; z+Tkt17B#@-MWlT-l3~gbh=$6E0Pjh~Va!~SZpI^Hr&MEi#~aw%jifwtscc&5I?@cmwT-|t0Kewj`Rf2jQi^?qzR?|Yj%XgU1aI^m{YvW+;ZQ=R$#(Pvb_a@ znQryHvcE?=mAcYuW>w-_({G(@I0cxv-ArSFaE)h`RW`;_HenyJ+L#dR=(5E z)*Q_dwrXB0OpcbsQM*+)(&<{6%OOv&pZo{It1%B_mtls&Yw8ymnW7Q18MyyUHv4U) zH&p)Vy3y%7W(ZC?1Wxn1ZA~8&+&!A#*A&W?#F~40{!qz^-eYQoAbf-KZNBv$jUa_)I9O8XN2PAWiQC!ss zU9!>;j-p&#Qb2rCrS4|@4K-4_VadmWA)!2V!5+5u#v5Ff)Ufi-K&AOF42)+laQmU= z)iFXb&!kL&eME|vCx7qEliS^`Z+HE8`j~2E_+um7pF!f_Y-r|*l~fT^PFwraDHX$1QlctSUJ~1VIF6X4>~c$ zAx!0cKJ>O(9O|N>U^$=urmj3ha$$xg7_Xgx%%l0n+DYG)q=+A^@PA~LUg>H}{`U@| z?7HAx{^IKxWA+1%H@w!!lJLT^ea~+T6=9wY%G{K!ET0-A4Mo=Cr6-_?`Ys)nOthQ> zQ80apTmf$kUde5_7wfrHD1XtJm|<@(wp?(xG2*p+j+|0-INMYu}^ zuvt7%Q#>Q=m#Li1)BD6Dm5X&~EKMySDQEX%p<>MDJ%&M1&8$CLk-iQ7)-;*)p#Vb5 zPXId=Y|6Ky8jOHz4B~~`UP|*3(VU;!%rN28kf46@CQ`kGInXZm9UhzdIiVlej~|4C z+3qvWEgznGkJ*^?`^$%Fa=SO)m26d|47=pKwBTUpG5ThC^H@JMuVVDA6y}moMuUC2 zo|66xz;)?S086ug0Qa_GbhCkPvxKC`$stHn4+A*;Z{QqL-pOX6c(3TyC+!ihGO)q% zp-Q^bOQ}cwZPq?sB%vd8i=a06uueuwdS|QJ-Z~4uP+DB)p4CuF{170E7--Y zn2S@Jzs5eEQ4dX~Tv3T<^vSicXIr+&#Hn5<3E%5Dxz&2nqSnH#ejEt^BU*Dg_CM(3 z+La@iMrP@AvdB$czN5S4_`OfagrG$sSfli1fu#$$QG-Dc(&BiQm>A%~|(#_CE4dydK zO|y{#9e$ZuIfEd+=ryk*qchgtan$ON+6~=a<1#Vx?JM>Bj-LD7*9d3Ju(>GH4DNqQ zbea{03pPMBQLT~|v$k@}jsjdHb%{dz;@3~cot@oA@nB%4qhpQp@Ia9@d!U{bON{x4 ze%L1E5=Gp zPAoX~aCOK_y^IQ3sKIp)!D;+e9#pPUbkKeqP21ruL!R98<&lVFf|n3)W~$@#SDcWo z2|}O+_#f82++umx|EGtvcMha8u)EH@~a?6THlj3+f{;W57%63;}xUx48#iurw4G#_~v42V+uc$LQ8E~3&`epEX z>_7kFH`p#o1_s)07S%6ez2(Rc4tyuIVYl&r?>r4mCx|E9 zCZ2O+4Nfk(gKpCgImr8wAkKK2yOoK9GvuoOuDF7oKt+m(&r3l5OzK+RzHcn?d1sSb zrTq+ca041JDYEk;zbLB1JrgRIX|4TgSOXONY$}54LNQJ^;so!PmUJj2b4x=|BPb;F zf+XEtViJAc3mc6t(dUGx#b-_hmbsY0utssJWRKh50JcW9qvLpEqR7IT7_nN&7e=`? z10L@{NePIgXx&1XIE!(?d+HC`ygFO&inQte$Y4#@dMpWkBD%u+N80GPL=~55=|xjk zC+I1pXrs_d%unpz^Mu$DYx_hUB=D~0sz%CadtTW)N+{6ok0}Anh!&)4jQbk@QZHuB zv3TY(0zSZ&#e1lxu?y@w(%PEI?=Q)`AaCT82aC{1WOl@eUvs91GLs#)d*YW&kFI3t zjFy~y98!HlTKNnQ&HFyf*Ou4u)^k2!f3|q20H>;ffp8s}pc?JvN{J9>`z$R3vX^w4 zqU}q{9=b7)qx-r_cuh!y#U=1g0lR{!^P`Ee2?=wXE{k_Lgh%&2@O4FL zewkTo+4p`+Ct=E44$girG0DDnRhSkw8K+H9i5a|Gw_4?Ht`W`Cgd0nWhbg+s`Lf)V zu5}y@rRQpiYULsC$=|KqEMHu&U@zKeYA4%rE+6;`NKAYe(9G`7_k2(jqhPD{1v8!1 z{7xdto@dtY)mLUK@?p_4ZIgZ-h6w>r8;0#Arn)bFd`UWZ0S?PR_r6`WmyXal9-op{ z$-BW?UAU z%0OeEP3^AoK6DBWV8=uFkbJiAh1i6c^w0g`0@?$!+!-k+TYdWh$SbPPqj+YoS4E^2Qpb@-4t39z}dtXDy>jzu9^Dg-^b!{IaaZNcWsac#E z{A{QZaZw-L)V92;;I=Cu{=ZPUosz*OdB@QQznHCSSf`)V8)`sNZwSp3bHGx*N z&*X;MXVL8%?u&+e+!>n^`z~aKI2}Co);`uGU4V-$Sa?Rwg&eH0A$f9_ZQa_Rv%%>5x;kc2BC<(5hA?Bjyf! z-qS;N)5LEIbV^4JkCcDBh)^r<49L_=x4XPMQ&j%Fa(d{4!`*`iNYAch@-WW#=Q0*4 z3PNaOF1%8bA3OC{sI>$yh*Thps#R3mFB^US*!8lEN|mNS@NBeZx>Q(k}%lS2&Ih>J=U2V+~OROylhrF(FpUA z2_j~G&m95*ac5}?Z0rDNv-4YYjXPz@6hOcJ-5>XVi859bWRgmlHVn}oZyy)qXceS* znvlsk2M(GGBr34PJul99@XxQ5ewMh8t)osoww09LX4H8fg@OWw|>d zuz=(OGjNE@s)ti1PTT5{^jWGp>TR9L`K8J74$O;e*ALh#bCDOQ&yFqPZd0XY@gZ{#n zST(@jcXS6XY-3EhMJ7FN&{(1%6NU~KlFLM z7;12M{ox4gni{D5kow7zs*7z>?B+O55X z9|pLd2If-L2Fa{axjVl?Vv$8Jq*(UYszm1#vqsU#0y#QF66WW2Oj4^0)(njCh@{q{ z89U@%i#Y`(+VbKje%r|CW@ZnzfS8xU)8tfQ0#DV8Uc-Q(ef@(&A!fsjra*-?OHNAv z#ko~ydd&Obo~akGqFlee+#=MzaB>weil3d_H-K~`iIXd2uwM{1`^=^L%(@cO@Jn+s z>`Xknwqn}xjh?t~isz#7=e4a{5+9qC1?ren_zX25RO+RHzlr)6OU41A0QJg3`n3BG zV8HV4#H#oX>aN30^ei9gw*xg2Y}2AYFt-K3Ue#gf;TJ)i%upYi&cqB%UsE zy?Y}V9Ho^ChfT_<@)R?OoYtA-5ZR!jdZxA8C5V|#c-?%wG{sVVV4PwpYu)fycAj;> z%PPxmk5@AY_){bUg32QmPHhix8Gt{i@{Kp2w6ECkcmDct7=erLVYWAIkRO~mIQxP9 zk;dGysA2na|Hkd8_BV00s` zj0OqmkZMQi(so&~JpKtm-Q5HNAGY?4N;|>RDu0t?1;*Z*obgobt{eXNC^ycu2&A ztF~q=@5Vi&d?97&b2SZwf3Y(TwN|ZbLTv)*N7YYX2}W?i-D#@b+`XtvbnImcITOMM zBx&4nM~C+&tnMaT8m4*cN(;NU&4ZH$$12(=S}2w(x$cRpTeX2X%entZkz*GL#&gW$ zhHY3^AF$UHX{WUVeYR-|FMUpOi8;Y&O{t0L&mv$1^zF8GDvTO*d&rQ*_7r=s18!IGrS%HnKhrhZ2Q!ML6>E9tN3S` zFs1UTGw@@dwwdQF2qmCoUu3RuZp(hQm*LyCGj?FE1PxA;ey920N@xO*TXb(^_Q#I? znolm`;j+A*VD>${1p_Qqfu%C*_8eG3wVra&R>ywMKzmRcRS*>8(Qqg!SQn#zyHb|3 z^6<|Zn*raqbjl4nSC3@p=0HRTFzQu(d5WN)yUb~>QzLKsvFym}SF91~YW=-oZah?e zxU!Qti)UQC)QpalSZb+;e$jc=_sj~0JVkasAr_tkMOm&k%MuA-{Q_GSf<{$0BS9pA zecsVoK$xP8nHdRs%a}`GZcI$j{Vzt7ejCRUN?*%7@)uY}~dNHLZo1#?$ zb=5eMX>@Ic`d6sn@b%Omx{4#%$Ley6juAUfw@{|)lS^>Zg2Skqw8b*RhP2;YQ9qI+ zb(n^npF5-${l-r0+a=4o<}ON7xKA+F5vwgfVLqRHxwStrb@S|Yj9_)0nzh+*AMIL2 z9fQZrtlJP1D~=)Xoe!TXOVPi}|AQ z$lF{YWddjaQpOOY?vk7Vjzy;K-4mYyd?puFlh%aiKof_kh|I%WX!edW{qZ1nZ7<{5 z51VulzvP`GPQYxT@gt3_td~*M?6q zjjrH|QTij1Rf`j00$secnF(CH?EEgmb9DRdV1nfMmJ6yal1bdH=F8%;4rk9DhE%=1 z`gU#Els4MT4CZZp10UkPAeP9HsW1u3ecMspw!Jg0ml)xZYdagg8hF>>e1LZUb_<>3|voD>s8?^eJuQbQr7PF2b zC9zfM_z5;aZ@uoKdWw9B+{HU?H6p&Bm_}YwY{_biMdqJFzP$KAL+wvcLx5I)wPEMND&53NpXKi<+&#doDx;p2)7K* zHaO8z@l+jbM&Xwlj_#J!GL6P^7(dha!M#n;8gstGo!HkuOkffwZ7lYB%wA{mYe)pJ zi2N2N&2uML`;%tZB3g6AUX5`eTfi?>_;hgYC+{wgcjr`V`Z;|MrZQJ3uPF6*@L5Up(~4=~Txu z>W`%yXNFbtx8!WgIu$Gf+cs!K|7;szstvn7$Qg3!3~UU>2z>s|;J^~lzC|{clEjsD zF03)(s0?i^U=SW-_V7xuKU4?{h?LP`5cK3`0b>V(NA;>Xy0bHu<~~f(6IFu@HddLi zMSEVTSy!QqLCS{HTR53xn7?Y%-hS4dHtn@>@< zNW}0N@Q&e2OFk$?LwDU%qS6xc$B3qSE}M%plXmul=3EO?UCM1MJw^0_wAd@t2|v-d z49vm9Tkv9q=YJft7bSg9e16PP?4kL-aCNh3qvYu+KS_49HGi+lK`pJ`e(_F`L99(1 z_G&%#Py^m6;>*|u1wE{m(~D(pKT>_rZCqG+sm6@E4Eo{oglGi^bQj#oasx*LEAdWZ zCDW9=`kbs!-4YSE{>*iV!V=|p?WwDOzi?O!EUFPn;9(<$y!28IgtehqA7LA$VQURD zUV?npLvoi&Qyi#NtHm#@vJMaL%1S&5J~AUabVi*~lMWY)@u!_`wQ%)MH6L3lnj^Of zdHg}Esfw>21f(n->*ubqhGZuTi{x^i^2-T%iq^kmWTbjgSj9tQkhrAAM;j^sXk>wJ zF<;*CT1|Og&?_tVH&Ckb1Z~WBQplb z1fneqx}fscn_};$C*-1D~3cmWTu% z8vPlXw4Fdczx?^x54y|)9sNfmaP|pzv#;NIqIqP#aRVuSFuzfEoaUi@EUEjIds!k( z`9YW=siqF8U0mK9Asv1Y6sw#pBG&ectqO_tOBuv^r^g&#l|?&S zGwS((eH>VM5U&=LlEf>>qSVefRpsShcY@3-`ma-P%n2&LOSa6CKSqyIOZC-54E6lK`8m-`+Nin8lBJ+ex%{KN{}rIihVH~JvQ>6CT`GP-G?tDqO<^hb}A*4uaxI@Fmy zKOpGop<8Ja91M&Dw$(cLS$`v8$n1EuV#H8z8H2Q&L>mfa{8Bfx7<+iW!;l@kSMAwEb9)U6E#mZS7`hPEVWR)-oYa`T zY_P~RUXE;hnO%NM{EbY?kfNk2b5Nyf^70}feOYZ?S9Kkf!IYX$-2r8FN`(yCN%qen zRJmHspK-W#G(@r-R;Lo34zpHnqv`YR{T+r0zt>xUjlZ`YMFu$_r-fh4QnvRpcXj*c z>7oJ{*g5S{nu4t3vI<^RW4<)Xhl_ShcN2phSou|*;D6ky-NUksh9JKUHe(A{5ebiV z6y-G~21079jqtgvv@sn<)ldGhBni6y+Ujn75C~Gc9cdIYdjVu?h{$%#L^kk?HqKf^LoQaIrrccTBOLcce z7zeugf?FtaBiSsP(iQI!uZb9|;BP6JGTGf6g4Ng$wxXF?XB-B@gF}LgEflX$M3elt zWnpG<3I^6bx~syoztY@Xe@G;In66q$Ey zv5EYCx3}y%5qc6aiE#v>*R=Sk5S&6!b)}es;5Dz?OB}b)hq664l~u2XDO)y z6rdHMsq&u;o@2=!N#n+hd3>}%RZe%(JyKdU&{7#KN~9wWs#sd1>`JN+RJ6T$nveLz zc9D`fyvZW3pzFdK#cFpu(0mAffNk33Y9r0=YI7=I(A>wjqFTB~7Js(i!#bb!&^ntX zP!6%pLizr$z!*WQ4k^A>5SF`at z4W2tgSF{k)Z;?scB8>G0pV&DO(#hF0>i&9;+Yp`1+o|ItXIixTvI`=&?Yy8$z09>4 z8I?b=Zd?jGi)pC-6X@LLiGYiKG_q~TFZB_7yFw|QQ*)&nTNUg0-0v>G?Nt-$C4u(L z?~B*Z6t!WpP;JH0QhK;W4Zu{MYi!s2JC$Y_8r6TqYxiyn5oXjh;em_If`kR5$42gy z=6%B?BfQ8D?{|8hoyc5vahd<+=jwfPa!|Qu%A+gx^PZza4}4W;OJ-U`2dgk?^`&>R z^)<|tQX6X zq`p)9B#Rymr}(5jl1!A;N2~o(?S@TecOSB*?)K0a_Ze3E=Z2t6gZEMfV9I`ii;umG zE#2q|=Nd^vQNS@TE#bcB&b51wvHl0iVL^F+q7`Pe$f|!yX$NYut_{B;1I$qAT1N6j zOOCw^ybv^AEFVs2ez8;3&i7f)ryzN%yCD6c`iof!|2*S&fz34ex!voj%d4!_)vYyz zRSi51wFPl8$kQSgWpEcrYsRhK3iDC#CZ8$j#YY2rN84dXQbz<`otOaFd`g;OIa}Ag zLO{jCJCnK}(j$~4vKeG{to#v+6O0$Cj5I6e5A$m;xI^0IT&fh^LjUpV03IjfK+3hu zD#Go}rY$Z!mo{-JY&yZug{+ewg%p|qiC&-=GijCRWj>#lXM=&nZ z!*a+me56N{=$W_#pfC3F_|##+njADz^v5*{9hHGR0~0#o-|ktz^qc)&Ia|(Wa&O~Q zOhYbjM!r%*qP#Z|%P>3D;;&k-Gxot(vc+oM*eH#2hB>*3l_ULgATI{QYaqanXQbSI z)6QZw+aw4{s#Ba-RBGQD$n@Yv{!BK-y6F^dZ^uZRr~;+8`8tLsPGrIWs53D!=5cEI ztOqx9Y$=}1eD6#jX;2Me0WP-kF+O|Aq9#)dmi@_c<6M7^0>U{c+B%or=sOka_?5ytvA>vL%RXP4T)o4!I z0G^TyVA7mSY7gyvT~MCL3GmDR05yOru~@onj(t>IYGk&DjyIeZ{<6|N_##=dsykL6 z>fhX4Df98ee4^oE4WA_4CwJBKaB;b|7fa4$BN)s;;|4GxewLWMp5BfEC5zMr_wYKJ zGSO+*a3 z&ndM@9t8L76GbzfaeZDZ;1ug^5jy7e7thDEKeP9|l-;2#GXeZZLgCGjAP~@dTVd&s zid5EEh}sh!r?%6#e*w!-^Lg$;F5qq$vxgjDZsm;qQiO4JSBQb)B+FM2Ezb|vi>;O^ zYfXxzjZ>IZV>$u1nL6uzQB-_JEu(>t^#8Rd2BA$BAbVYOwoyjwd||Y0d6PSxYe+_U z$Y;OyeJ)R69ZE2cN4uBAJ{C>@EV>f)?2rcgTJ9P@FG>%q@Og@S~a{kmSoCyMi>$E>voHe=SUTR$=oACY4#gvbvzT4KX z^LkQ1R{+`k5oVy(+zD(0+%GY*(;Z6QA|mO<0k?=mdLonl|B&>zNQg*!Z3}=K>|R1{ zr3?{Bf1gOCH~&8(Js_rI_3OdZg}`Za;l^b+?j~!saPnmJ@XA2TCI$uy#ZF8M;7_y$ zFhL{TuiRHJ?mN0vZOq9RqUQ<$;F-uAt6$#qxs}*w3;#CRB@67h{U{)QruOpgUUThz`~JIIO~ z{PsT3=rS*mS@$urDT4P?GTsiKUlfE4L%RFG`VO$$7@JA=K%9WWn+rtAedAZ7>AU$k!^ECFC?5OfwPE_`L_K#9i=jq>-SR__6Z3Lvyr2=2C&@t8d zPI}I+`co4n@i5T`A=jdVoE41^t>3GruHm28IH0OZ! zS6L%rm8{Q_k!#hPmfCo2*at^SfOU+DOoA`=auxDnZI6-xxXNghtvkN9|=<1_TA zl`gjLGs}ijfY!OE(v1}b-cn;RVygoyO}fuoNU21g8cNfAAHzcS=l;2TaUfat{f$Fr zDg)a0z9H;IkLfT)v7fpOFi+p`KxQ8N<<^7A>Q%Eyda3w6ErSvmhykfGZZyY~EHbo| z1EQkUIF~91kV8YKerwTL*|3}#;z(2FQu!2Adk)&bZy~CP2Sp)%@N^4k$m?*)%~Xlm zFBlYNN9Pwgs~kphrqm91q1jgY*eGb(->>b3W)c0Vx+{dlm;ua}z(F(x$-)u~%gXFU za%3$?T>diaKvMgI4=Np_@6G5kp@!54-e%75v^&`So)*W!qr?BNB13EHdYCFvIaEBl z1P}1e*-)qIn%)8uqqlCA#t%nqE!^qS2E(Mi!7R^8a>m*&QN_=S3uRwiM{(dm4Dj>R zH3GX0Q~Ecdg@(=s;aU_wT5R3T9%R{{-8jr`Cb8{mZMHVuR-@IPYW*H-FnS9Do zr&O<}_*d$A+31=sC4h#(Qq99AJB~36@&~$-z*N*WL*khLwg2L(EsLZ|>hxb0yBKnPSn6-|G96cjc zH9!3oqUkComh(`@!$g6U4pO)P+B}aeY)A+vmk!CU?8|&^XdLy+9v+=h@T36x$Sn%a z#ulpe(kWKo%hUFNyC;G}Zww;#I8WjBlwnkkv$t0a{|PI*^EjUCsC@&<@UMK#?ta^c zVOM3ucewLCws2W&A9AD2q}EqM>>?XiRqksqSL7YC+WGN78vFF#pMsG4QHc{eiYskM z2ompPDzN_dy8`B!wo2bsEv|2;<(9=Om%do}s|5B1 zKki$RSz)1a#em#p2EC^=V#x?M@o5zj72L76%pbw`GaQu*9po0qxyfxDElNjPnBk+d zAp0S!M3{1}Y-5}>0G4F_k-98`j+cRr-rYx%*{`v_(H7>Zn)h|r@c_v|T$66uxM{Cn z%&dUjjn1Kg9#e{R`J(cKQotIF*Np*7Pv6i7g%+5McGd9{lp*Iz(!-AaHemf z12?lzk`_9bEFAhozG^FG=~t;00$Z*QE&?BC4Wwet&Q<8{_pGp^*-Bq%5bTL`?0PNT zts-r*+e3Yp*VSG@U};GW#t2r{5TpJyneP5}kieUCL2SrSXLv}v2@=cbwY7#pp(K0V zE(W|C|3wMkDKf_X&6AF2WP>g_PNY4wxp7yLOhBODee-?xo;46G%U6`S?^wo^*fo?H zSUdh1gX9mu|y)~|`UJ3q#?lQ~qasmrO9P%aJY9=z10K(&u3;n|kwF|9Z z?E2C-Dm0~sPE{_WE|qhLDSm4$R0S{o$_5?ZI!p@LcPSqIf;rV7tbG4AVkIhdk!ZiG zp)BmUD-pxvzX>s;ChnI38RmOR=D_L=8gX~XDz}`&3yN_p(YPzrvxva?4 zE8;yx7asE0ONN`n%Owm`AH2z)S-8S}lm6o$q?Src^0N(RsQlHaSDQrtbakM|N7Ne{ zrlXoqoSBUBZGq-m3yu@Y86^D~fHAV)UZgIe&1M53gPDv3v*;A+*~dKO51oL3 zm%;?NPx~&P`D?Uo$gvnUCl7_TA+$F2rFMHyMWG5$j!$R_`JoEG3+^Y=b{wpgM*bt5 z$|(>VaPh4ltl!w(Esht4QBpr3ztI@vN#kJa!G*-2@b98XnE9?Y2{B)75p!48AA~Gokz- zsb=Y1MH$9vYZ$n3;R~Ozo|}+SM^|&f5YUG^Q8uf+{4Yz)1RFXgi1}YeYHc!vBV^YR zrE)_#693ytkH4reH8S9ANTNu#|IrE=C9uDof%3^CP@R}NDrK(mozk@Ma)|*QI3R|G z)0;~B12#RrGrUxU-Knw;m>d?F(y0}6J1O}mt251CLssUM?x8n{G=2;HeWBs{uW*hD z)dv)^^RT=2GUgKhk%W{Iw_UtIFzFBJB+}$fxoYeZsHPUXq)>StW3Z^Wyl9@YvMA=| zSVi~aNpd7Ru!FIbn}xLP$I!&nm3J1LeeD!Gs5)0Z%xmfbvH&(^rf*(7;3M_~zcWKv zA?qtPbi~ODO7`mO1&YvGc|?dO#wR3MZrpgixbl?Qi`s=QS&m4Yp5UNzWurED8M!m$ zu0&JD<{+~VS|y_~XJZQ;kS4pE`z@48vB*%G7vOLGrC3ueQB@a2t4!Q%-09{r1wa$z zb|oi=?`P5xQXU8En_Pa zV7T-VWc0oi%y~=7rVoSVD?egz^1{%+irSN#PVnGHTh4@vTcW^_+{n!6I_>`9N8QG! zEo;q-hFrE5_Km1N2!%DIhaOLN5BRP7dDibcbq$L*V;k?ykVB;qyfJ&lrXwq{2%Ir+ zt72mRc~IalAxH&-?N2pl0BQ{sSUkUs9HUaeQaLn)n}{s#g1elPlb`}moGL%~ zly!C->B0B>Q?-ofDGvK6eQ&=a>^W$R?3o+wa&)Q#T0%{z=~txzp2{Hw=}IC6mHsdz zLqUHp0_EpWx+fSE>}6A#DIiL}VG=G{^&g2`qm;%}Kbo`c+s26Ju~Wfzjx`sC)%e0B z6#eeLlu!YSc(e9da6XKq3p=Hyf;K%uKNggn1nGQ6>Gd%*c5KP~IK^ImB#K^Uqq%8M zy5fK=o84OaP}}mja;>!V`^`emNQh%U#8pN-yPrLiyUys8Ot8u~v`|Th{@yPUs{KGk zZ_y$>^U?tfckiuEwk!5Ep_VEWZtcBxD97jL^KR=9*e(Q_n4nAWZjBlU_q>j zzBTyd+4WYUkzEr+szh+?&!SJu`5nx-u z;h96*68D_-RQHAMiKl;a(#cfuKvWK5WiV%BBAu9!QFMonqm4u6-4_#;Dz!r;`50bC z5AU$<;mv2o{J#rLtMQFdX-wDp;nMN@(Hs45W^LB;v_6wJ^??m`U{6jMy8rTid-DB< z%S{6rwauO9B3Z)=T?Ah7@rGSMM^gRfBSP^W zPv(eF6iC?k4bU;=jkHXa}=gM_l$1@ zp`tvK{BJ3dk7BY$nk9n-Yt)&3Bw{HV_*oGRNl=0AW3CTxuLe`+$2hWTwmfbbFSQr^ zE%;piqX1IA@vm_GR2h+U4EiWN@Vk)n2&`z#(aIt*eWe*E(1qYO)yz%%64ylJ>jDa1 z$kCgFJa#>r68r#L*E-8^XIi|Z)GlWdO|p~zNI+88)1r)hf4Mu|Ri8pB#UlB4eKW-( zv!pXmG`Wh{Ak$mC5>uC&BfFBHdcdZSIp;2lN;GYP7o6{j-HE+%Cpv{aF!uJP7w1Y{ zqd7u-CR?MLJOpBI>8yI39(gc&F6CT1yQ!sreMe&N-?YFDNHaoH zCZ!qgsuUtWvX>dbotgM|gSa0Plk`fxqzEfbBi~c`YPs}GLqipcg5p402GE&`*ZAZ0 zbd&4oR*{^TM{W67nVAXF%S*p0L#;z98Baot%T4wZtT_P?T(LcL(pF32O! z#KMvyyB~D*=4+?Y!|$CzQh!}XU~Bj=6G$eq4Mf6I^!Mfa8=*h&?ULK%|B*yf$tZVE zYs8bK*9R^(#prET>&|gYXT2nPk6e;Qe}qaC?zGz$4pBw6)MFSZ+|Ke>XMZD0lEe_z z>x4+W%V@CcN?*uL$>BBojb~`9%<@S-MR4k!4sM{$cv|9rA?Yyk>AxLV+(v4->QDiCQi9G47FW|y<=Iq z*&Vn3aeJ5!6jvC!dc_d$)V_h29$fp6WJmzh&H>nvFO-j�N#9(Q*_Q&z;b!nao0& zAjiIt4Z`~HD1q)$Ywd1a-!Dn8M=uns7CR85cpJ@9%_}dUKGX&#E=Y|(zt&wJixN1Y z84Z@ois>77ISi!bCL(E1Y!{9tTcAVf)HPLfL#LE-wz7X7(ATC|tp)PE)&IDwzIu40 zbrIh`FP(d57?Sbfg#h>QiLe^p@)O=JpUw#1$`bTy_*uSXkrjN(2tTr+16bLbTxUiG zARVoTAvfYPbFC~_4BuyF^;eTFPQl$-^DDnA_={di9FX2NebTT&Ttu)xOu%#-?)71T z7w4LqX?yE&CX@Hq7;I~+*s)3V6M>=-%6D9_4Qa9S zvhG&&x}D!EWNrN(CUGEcNw9wJ^4w8sZ?Fy1JaN*0D%%`aKX3(6iMyxbf_5>gbHVFe zSNMR;hH+Dd$KwByShHONy!xy|4{=Z#=|)>q(l2Q^(X^ehnG`Vu;$yi`JOj{H%UKIy zc}0barz6`{A7*}K6*Yk8-sdV!OOn3xPH2I{>n4q``)HT8ydEFQX+BbiL;%pva@R(G zNe&8dExU;w?Q>*v-g*}u}=noCmbulcs4 zJtZgL=8lx{?{9g!W?F5AjO`!at-W|fm3+}<5EL)T%9j~0N};XsLIjw@{)Rz5!KWfK zf%rY>zQpmxE1^~Eo1U-514ObuA}~XyJVwhcV9Du+U(M!bp7R^ScW*@^zD=ud{ztN| zH7L6|>p59?^2vFLAAPkBpDB+khM&a2HAV?6B1m`h zd#sS>;$EWfq;bJ**^kXEU2ez7z7{jrI!XDY9}G8^f8g zRZ1~}APH?TWugUL@#=EV|{2;ft3NitRs=4j+qY zZ*a-cB*wT+(Nwbr@1px33CoRIW5~v2;fDE{p}*3hfz<-AbI!TCq_>`v_Qrc+o%dZo zW_?s9rd&d{d*My~u5HCU8qAlHv`kp-Lfd)efRt;)N(ftP`N@E zdTaDtT=z>r;~}PsPfmgn6uehbY=krCEYgt}^s;WW&)@72r%w{BpnM?=J2 zLbibS310kh50-B4d%&3+a)oS!zf>9Jr!#fi&RO<8$22}fN$rDQO58ALQqW$Iv4=Cw_jbv_g;=2tK$n%8!%nM+@nd5(vbzI$At>_%kwQpI7CE!2+!$ zje0`V5Y}KPB1AgZuzJotQ&<6~TDpb5SjLFgOi?K(h&pIx<*Bv^?K0EXj4!0UeLxFZ zYfj;ETpx8N4p5A9dxP!>9%mX}+pcg&559i+sTz6GTx}bQ0~asn=6DYp88T&P~Q;BCUha z!2so^Fg#f{C8nGJxYI5%;i^07)0Kq--;mb<4_CPfnjc43hj4>I4Px$-Cw=(v6a1;x zKs7_C+l7#MO64hAkeKG&kLc|BO^2MdpPX;Q+2}VJriKvd0pa_wQaPc~xJMPQFCX|u zr%#h3&>!7X$=7-dAvS;3uMIPtAjy%}8Z{$D zK9h-nLUq3(qB@1g-l$%pjw|B^v(gE63)bVHu=3itVv7Uh`qlo?V<|-TVfWSch=4vQhPHt;Ao+#Nf>IU2gIagtO$DK)Q z--y)E`7n^LA^iI)6Yxy|Emf!MVct!dzLyDKIRAND6Jx=ZQ#tW71wf1SPz1%M*09zv zIn@+$_;7Um1ZY~lzP{HLdDNkBQUTfQ4wcY)(C*%9`3Ai#7Y{k{yEwfv;>xZttx_Jn zY4I7Lm6tTVHk5miDY5&mOmYcNX4p=v@$POi*{70?PLZEc1v#0KEd}42shibk{#tlOS@v{&! zJ^M2uRYJ)-G6X}$7oqy z&E(72<%#ncytu6^lfRw$W8m}hGPdLf*j+0rXZ`(l`Mw&-I4xx!=2ucwVkLq$M$3g6 zv8HfdKQlKo*Eq6ok(7RUqzPpCy_%zySwXCY&}OZOnw8~r_E4<4bt^So+_vyyS6T9D z$`>~K=ci$MEw>h>{vzh=OaCLG>~Je^wBa$a(#NfB{nRC&J`O8UP9w$@63?Ac{_lz( z$HYIu_u0_cX}~x~w>xHQM+B&Ut$xupb47zB_GmFtI28c_xwa!C4#!-fDEY&OmQ}Hj z#BFEONf-S#_&lF0!x_(}(#E+7aXDJ4HOFN1e6@baaMqAk%{31U>9sNZ(>dL!6_Vf? zD^Pq%wj=EF?8>1xh7#-^TIznKq;NI;|HJu`{TKS%>&NK^M(12uz_@N1oPEAC%dV}n zQI?HoID3LGM$#{-!Ix=Jjhd$wFBYiP$8bF7@Z)gnSX|%}%wn_tU+N@nPCl(c|EF%H1z4e%Z*UtN-632`?5by7RG^5@ z)t$r~!l43>z7)0uakzSXK)8ufB39nl%3fk0apo5>0B_)JroFvqAQE@dNz(Pg|;xfaw zrDT5!L4biyU>*_3-G#vh>ms_9LzzV@`eRv60~vEU`kJb>%##(^GO;(j!Z9x2<9drP zyAI>&i8W&B3kZnX{UnQB=_=6R8?%vvep~3Z+lQGTi@27!WVohf6J;)}rV)>|m-A9R zRa$u3;IqeQLqH&CLL(Z45bF`9U*&Xs>Ak>e1e@|D>hj_kg9~)| z611mTxZ4#EQ6$banOZb~Rcn(soZw+0qcAXsw1*GL-p<5Osd*JEj`o|&mn5fn_F7~Kn$P4uf_#gu^Wr%nUlFpm&-csT*>~uT;hfET? zwyyIeY1w_pUZMZJu)Y=&+H@qU9K(e5sYs4KrL6-X_q6*JV&B`77Iykmo4A(YV}hzW zYc%|AQlWd|GBGT}7GF)^U2HX39s4K~M$w-O(}$8p(W3KH=wfALkqUGc4m z&<7f{kP|xDQ(&m2m~%Dc-|D_6r8C}T{IL%&o%8~RWtH#dwQ=m=z}GlhIh+0>TMQ8N zuX6I=y$Qpg@_hm~Rerx4!7j@s3-mi2lMKW9ZvXrW*c?NJcY9alB=)QAhtFioex4(B z4-B?=v#9^xV^v!l?2I5qUQvOw@TQa9leG2yGssx1GqC(Mp+QU9 zI8ajEC)`bLR`sd4A}S7Y6#2P8kM_|itJ84qf~^I#eR9na?Xb{Mq#fK*4qsk>sVpP! zWigp7Q|s8HVq0agwQ1oaf(d@_!aw6BUjIAC669Zy9|Ucql4yRzOz){SgK4)a7b?|) z2Sk8Si9|%7Wc&W6#-vYe1L&>halmqHzarVrb6>(d!>YVX1@%C5cTm!D@NeE1o~XXH z(&T?RUZC6W|5>Z$UtqW(|4>rZimJlsUwBD`LGZmmV}3H!ruP zT_~I0emfFmhHCYV<&VJ@Jshqx>(jY6teQ( z!VcOtWm{|{3dRcyQdNcM6NAtA7Z#O7ExlGNcUnq>Su9Vz*shXca7VMqLz^;5x z4cX6CxWSN~)%l{7Tz6(j6MsuNQz(3mO%GH_YTeSkYPABi(uk|q)a4|$PA`w}eXR&} z0#Q-Yh*VW)**Ln^M&nc~C_rv|Px41{7z1an!figPnL3kb3F?xbL0I!c{FwdN3qz_5 zoFD?GAQ=LTflB2t&jk=vaqlO`XSQi`4hw+?h*U?2fVf-j!f?QBIEJRqc@1`%PSt=Y zd(_$dt}iAz-h9DXohm{5HE>#hq`vYWYNcMnWsZ7wUBM?clQ3#~+ zSe|l2@-D~Mie-tP!pXEWZU$GMyNG-ceTM>R?@dbTPSpZnJ<*Yi1rjddM^kq0RGP zti?jq*6*`uGQKa^?a@j-9YOl~$mSHeiGMO-n%Lzuo(9t~0_ZH(Zof&Y@$o~dEQ~LN z_2`Yu+Tt{*hEG8_=|*?B|2p$xVXyn(5Kd{amua@^>kB99r;h9jSl`&2+G#(B1e>Uw zZ%Q>aV4Ze7joc5U(@c#q5t1S(Oa4KUWrbVk1+saG>}}i?%!q+1`yJ}g13`AbCj#~8J2uCH`d7^W|rP3+vB=+WgVMW#l zuW&NIdGdb~Ijfx@KbA$)wCg=yw!bkpgyg@wr;=eybm8whv_6ncKj zx&LkXZx;Q6ujuQpMABJt^-j~h^mPj-E71#{Wm2q`g`t$FKUDEbq&Ie>=RXp#<-xy^ zz9ap+Odid=xLu>C+Gm~yFM2C=$(;!h?i-Q%0}?NbQs{pqn3W#zYn5jOA%2Y1s>NyM zO?8dqWQ?MiH;pM~9hzK5Xt7h+X`iiT2;Xoxdk|{c{nTYHWR2q^g*BPb=$PFCrJ@?- z9OP2bHy4i{k#b_#=QR(1Svf(VbBu;_KE9;@8`qXY3i6r5jzK(|m95sDD ztXn?2Bp=w^Ha!JAZBb&5S^!Za>lv6oV^j%goaZ{AMEm()aVWbU&YbP-gq(vPx54g{ zKl!^{1u|<(K5r+Vlls=t6@`MTKjn$h>522Vv6X2*f1G&hF$>)XC|B@(^_86@_Jl^e z`|csH9pB=t-^zA`)FIZqHsX0kVEV;bX7s&jyIp~u?N~ZN9sXDR#)?l+xR-d4fAZFD zU){ziRr|m4*T9u=;o7OM3J5L6P=&$bX=f4T8_^DC7+8S~B3ezy_Yo&1z%_{K27&tZEqZuAdK%DR%b#iNr+ zn%VYg6z5PW175B*Z=McGF&6xg{MWwWtT!r2o1PKE5o;^}KZXLYe+kn< zkk`^_yWPXYDWZ?GV3Xa!!L0xi*gWI2J26>(Z!bZPmf#574lnZUnO0+CxmU)hOBh55 zfqAOkY(#rCiD4bh`Y^H5VEn2eywnX7F54hA3Qtw!tE+CL!YOBVpDKD=woj7=7vKN> zLP<#hMG^R2yz`u=^}z?)rm{LVj({f|9(58$fwY4CzA*5WS~;@z&{(b%Vu05s z$shFCch-8BEPKC`j#VP4@%7zL>zwyiCX8rx)B=oIn@jd;h2|tSdK%CEu7^3GvuWm z+Up9zHEOrt* zC=SEHcwTk&0|Xa*;?@^)zJCZV?D`g?sGEtSBM7^128KV*d-o#`qBMdl58Plr>HlKz zqLSA>_{TD{+GG17Gt?eP#;%)^cY>0-+|wUL3nlCfC(pQ&y@K77SVIc9 zH_={BF3>tXt+M~+wXk)77vC9XpzakUrUEZFi-owpaEi*}i=x&=3elwMmF`cGZ0}^ekrrIoE-Gnb`14=InGKVlwI=Bfxjhry%UZXhA>p3Dlvsuw!;63@3)`9p zUtPu~l`hJQKX?~_0eouRloJ0Qy+eM-Xx_A)rD7YcRv4l1pqqz(J%qvomEth6&)2NY zoCp}ggysJj{>Q+JKlJk00rz;*Q5~a!2j-a2yJJIMiQiDbC#PF83yfRlMDd|g@lfBS zL!{>Hi5TMJcW3fy;H=`e8^|*2fekP>#Ynb&zRIz6KtNB{^=R1lKK z=O-RHu!!JNsjHM=I{s9Uo(RxfU&AxEoXqmAbHAiX4qzm%3^{nMxQqMqq%woE-stf5 zRZnB%tlm_RR?8m9er$ngUMU!vw2gJGom85vmC&T{?k@=Pd`{8c;;oX@fNh8z( z5;@^@^o)P_VbgUEvykuNhkKkc{R+aTmtxPrN=lgzD!kd;wwcx}J4=&)<@2=PEX~u= zGzr%HJpw$agoOS%D*NyOH!6DWVLAzmJI`u5$x4f%^w7=FwzJ#kkO=A7ds zi%&3| zQGTOcGI;IG{I--uZ!~jX))v5{Gf=9KMm0qEqis@c()D@e zkhp-EatH&Ia|5-W`+y4gMhYmqsb*=; z{x?7yWqlLcA5UiFfXb$DgQP!`HB)?%VawaF?7USh{@$CzhEwtFdrh6$&B954nT-b! zW1U33zZLTZ)a2?~0v~@a(J*5+h@DZwqPg?hox_$7i((v4RIk&CH%ta4{pdaJCnSAa zusBM7ilkYvWs7(S7@V;CL0m-fZ3~QDCHCU1=?QVX9glrx%}TFaLWgM}A%8{It#7R2{gvV4|lb8}P;VtcQNk_k>eZ0_8vmg5*59EL9E z-v&W@#y*ur^44lF(z&l+nC6c=nvQ0)_#1GUzUw#S$qy$*^L)WMBn|%P-_@{0+p__E z3Pf!^cD@x(EyB)Pup{9x$Y_T$GLY<#q^_PwpLhp>0{lSK^v#mM1NtIH^g1@toWbI! zzO(A3eO(pSI&6iE2~B$Az6 z%bcn0IJZ76%mI)AF%LOC7|@8MIWsAE=!1M9WMq489_2kG-vls z3USnA%FZ9n?SL?CppuEE&?;dkX|Z{G?>7MnYT0+!0$+@7tlhTO50_Gp+ps}uAxBZ4zN5p5R z+fKzBf{oq(>2|WI35X87qXd`c(;7dqR>Quq ztGL>3oHy~k9NiLoV<_y`xa8%XWErPRL7wYM=%Jwa>sEjES?%r$;plz?1zbNUS?Qu5 z=}jOY*#d^5=*N5x!Ggg5P7WpQXnr3RtG$#&^92Q$B0;|7VSA)#P{az>L}~RfSWE@5 z=MJ!@1*Ouj%?jM7cNW5SCfzdnPgq4dkw@KIjj_WNGTs)OwIUTlH->4g3ttNX!)1Y~W} z5`h*ZPd5M(^PdBFFju~3TquhmY{PCeWCMzG^ROtBU##!9tAmt zUO8Q9n1pz1OVv8}N0CNdGen^;2)x!YrfHt@h-6y8EvvruadWsv<&LJ z@k|Olw1|DkpRAs$%4u}=w)wpfz&*)y(Eipa_kTX#12xf2nAicW659V8U{vi&>3w=* z>5u*vD$4j(_%i4eaC>zZ6berRWwch&ZJ1gBDgRhbN8X(phy9Rrj$`8aok+EqykxJXs%mwkJ8eD2j>wuC=9pZSwpgE;mCXfCwI%QvTf z2r9lH4pk0&=ks;6_@jHg(fD1}`}tUv^m2JJ&SYgnj$zC&Qnue^4|ibM%}S1bB9Icg z$sZ|7%~*~P-DEKx9{U<{q2Ok6@nf?Xev4W1`)9gAi`>-gWldSJ4~08y!PJ0Z z`(02#03`*)7eWoR|IZbrR0<`)tV&ku<0?pV$in5IB8UrP&rCCJQz8)mWQaAqYRFvn zilfwCx@1r8NGhDa=p_DYKN9fi^pcJ05r<2xn84J6H>QGep}IbPWy2)MRCT9OQ;2Em zmw2sujt*RLM*n0i?SwdbL`OoP9-=BSAA>5W-oF5#7A;g+yI-3j{1|@~S5e6pE5Z)( zJi$qYrSb?8We8~wtQ6VRNwnX(IKjEfn7TC?JhowcGjLsqZ|V8=U+etUfLZ%^!ZnaphAYF-&cuSVjO!_-g- z)uUyodPkTVMaE)gL9V^*?Sh=5c@JgxKFJ+gZ65nxHnlymXMXR-D$wk=6B!cUe%bD0 zXwlB{WjCRVMjWc>2#R@pvXJ<4t@fu2pKi-;=P!=kG$L&M`1YUskS?WwV|yfh+*5<; zcoJ&H+MJF_@znVK{&_tW$2p_=u`#;;Zm9?Kt%CI5os5n1}xH>!aXc6EoD#L;k)A%+!O$9znD zSTH@q@U}c??W>RVg%ay?;-r{82!xEoxj!+kNfdO$2@&;cfnp}I@yBAI5HCF%iBg|U z@mVgT`IJ4ye|Z>s*)H;$&B3(Cygk3+AK?QFj)`wSI@VpToyfp}uL^9ZZNo?c)V?Q`|3;3hAt66Sdn+)6)yk>PaETsIw z8xcb|nHf=ws&v-@%IyMy#7?M}-eEPv@VeR_{AjA5Jq!`7qZ_tTrZP&tUYqymNl7`g zE%RBoCiwd)ms^5=(F1Sv!oz2dn1_1v@mRNI%?l;G69QK#33w{?jmP*B##{m{baVBa z=rM?Ac)U?HiN-TjAWfjVZ5$~=S|h$7`_Y0Z&r7snz#3)D(^SnJ!E(~Yg3e0;xZ@dA z8P%iHy?my6rNJoz>UECJ_ADBz)>Aush3{;rWO2Y#C+A`psOl9t*ZxmHdTMXmwOY;H zt#5gqa$`8__JNyjcNDrZ&LEVRYe#5DLSe5;2MCc}bp?}paAN4&eJ06blE}LbUZIl5 z&VzRs#XzK^EX8DrPP^X@6XHLpT;tAF8@}*lG>d0{tF3fZj6Nlq|E&C62uU)ZjYs;` zun}rjemtK|uu7Fp+K9&p6cjPO2d>Ho1prO~i(nXtzsS4#URk!v#8j`Is5bR%L|T-o z{hz|IPItrYU~3PPl4=3JTbP84Zr3XwUPRelfBhI{K=Cl*31hCSEGg(YyYF)xc5GLw zTJ;=m+&6DaCV9D2uJje>pLN z8X%FiG+vO=#TP;GWeX5bbIMQ;u+f|n+#>Ef>%ehaReSos_gjBJ7+pV?+u_21V^)># ze98dJ!oofur_5g(8(Uf-MlW)XoKr4n*k7AkU{v!uhu9G~Qmv~S6$qqwuX4S*;v!0Bi8|TadG8tz2xcV=m~!u^lg2$s}?3AQ#;Z`MC|FV$O}9&B5om>xlx{+G_HI0 zc>`3VotFmMXM=Ip?=BVRkAJH#;NUPQ5Lc+I&Gy_MN`4!R0Y|irZ%O6jBr@>y2~iw! z5&IUDRlFXx`$vX^z9RkN_;qaL$3i`2TcrIG16Tvi_+lE+yq66XcF^k~eO z$9(NjreiNa)NH1XM#l;MA48+?iDg3yuP)Su0Vbv+9qCD46M=vg_bD6SqVEJ{#=aVLH<%F4VWbk z>E#3Js7eBulFdD$>K2|A8e{di^8Y$r&@ z!t;4e_AcBoGuM za-@7)Y`hrBc2P8d7l$@S+mesc^o~F9i_z$B7~5>T0f76X>T-O5gD92gn_(p z+0{{rS^JXW$}K^hYpnUL_Rz;z5y_dbQ7lB~lL!(Q2VAbKMZT7Q)yT3gpe^dm@G6&g z-zd<2D^qzs$eHapkWjoX%MnEoC-h2Z#vdmym!UUhg=g)QC}mdF%McSlq{r!su!$W1 znL_PWtX8fuKbIp@lgyo;AU*ByjT%UtJLZp7;79{FZ;qw)N}n(??*LzxR@1-7nP(?GGqXpf(|Uo1X&L$z z8OfA3yN0xYgI=*eR|p(5%_5$Q7xyZ`jAn_y(2wo6qN|K2q{p2ewC}_D!`fLcI%Uvn zY-qyIIX5z@K2LCYAOB3r=d`WAod+YGh;<|wA0nJp8d`WBM;vlYW*QsJmquJKqXHUghZyg`XS_+>oQuyl97EY$>ppotbD=sb)L_l*+e_KWXX`fML*4H~m<1yf z;637b{?FQ0ioRIjpFq!ZPQQzz`SC!L^~77gcw{Neu0uy6-;mdhO!qNU^pyXrLHzQ! zzt)#L=1uzr;y9|83V5#PE-5dtpDK`zWV)o}^8jXalt}(dJ$|WbHK}bEwd6(-{;oDB zrF;mT$hEwa1v1f2rs{9Qx++f6c|t2pPSrBk-1-bEc4YP=PfJU|5px+A>Z}SZyfUOb z3=v~$Vzu$R!c4!ct=_-A92+RxJk4H92QLfOe?MM1o^wsSBdcHEMw}D>y8MkT*bP4D z&3KSk1=Lrn8wqi{>Dqr=V_@jALUHXCNlBV-WaGRPLllasUq7BJUKQ2(!m(B6o?h0< zADG$^CCm31AGC#XCu2)pT#8L;?o2;E;P(D82sW!X=k~V{1Op;->Ko(a0+*OD$|R z4UpE0-a9tcT3IFV^m2oOlxp3E4S!QiEqi$`U2;7*l$NuOnq0MkEarLapRT|%zGld2 ztpmf(3SxN8Rc_SODr#ZZPjz5uB3bi^s#AiU20!hZ)om9J~?$Kd$e_BwwUo9;XJ0E zzw-tL&Hg??cv_WAA4ptU2jl_}3%^S)8X`6JMr|1q#9{eUS(uJZ=I~ic+-*4G(>g1i^J&FVtKmaIF4b8tEwR=QW;0|MoT7pC)3k{ zKAQr)<5lZ!DZnzS$S2mL8vVTA9>RP1?BCBVcD1D&2{%gHo${HK6w!gq52o-ZjLQ|r z-X$H$J7eEW1w_EZ&{m46Hm*>^;cq|TH1#a|u)Xgw|sJdE6SeNXGK^2{4;Y2C}T z<`ne9AGkNFBcb&GZKn1#Qi`n4&JFWneW*tYEkxGzWz`_pGtOHAGdfzJ!-L7TNOSbuC zEMI*dH`vB!>MR}7lYPUPP0%*GLx#0ivgb*ub>;i<(G6G_j$)!;mNHZuB#~`xceiCF zC@oj$3M_dArZ~@b8ZnjS?3w^8us<}|nsg1lUr-pSO7YDh!x(>iw}+!Bw}aV7-9>Db z+2Ft%{pYS1JZ<+F@*ul-*wi&JG8VLBt*^jl44nXrXwTM4DQy`B&v#b#_)KcdVPy)U zuM%^Yt*zntU8NKesp2=LRGH>}TvoOE8!J%pQE?ypeH5G1y4QTTr5oZg$%wadJ+>T{ z7=133a7H3_pvNrmq$R)H+#k2+G9Vr`2v2C3dtGFbC(ExB+Zm*5w7aWw-CY%6Z%xb@s(yjx${56+l+Go{W_l4qdA}o~e!{dyvN5>xf^2N&ebmTHovK z&)GaFLFaas-~4>4gojC{)kA}0w)D%MI(YRXO1#LgCjDT}q^}}Q>+JH`=nj!>p$~E# zduT7=*3#N#N<`{uDyLtJSr%#L{WlMd4(2Zc`h z>`X5gSkUR-cxKev^5wBn+QqPOwT}(6BVr~@E&D)hC65yNa64&a3nHrOU*wy4%h7sx zANLm2mr19Dh1*KKq1)XL1-EfoD~}Uq)aR( zIptv_ceXau%D(k_(p2H1(56rwXH|FR)N`4`T~$k%*ifopjXOjfQEj9;>vND+?`2O_ z!8iUaYRi~ue?{yVTrM9k+E|7hRGlB3DUm9{kUq(nJNeM*(ahx85R|F5_ns!FhoiN{ zeUA96(s&~sn#Qh%0+?xg9qiN=$-)Em=&oj-Hmjz2Ck+d3ne76<8^OLE+6r#RiUwe; zavS-M7mHnUg&ZA}hWu_t=i@cZVUa#ds+p8pVWbrwXD7LM=%6 z@z}bMaRKGf`7k1~C7UGZ`lP&3DA&F8+d4Z%=8L^&{qO9E@>C8_E*~JF z*wwsL@fV9jLF+Ekdn#5~$xbM-YpH_R)Lr|$Tg`Z)7rIeYIC4i&)qLqmD)+k+E0LP{ zJMHrNb(KQ(EyowK(b4;r?8FqRTE7iBUUsIe?`C(d+tOqiQ9V>&`$t6 zM2&^h6F8g6()o8Qn>GC??bt5gjoKdXUGZN?7P+2z91y09G^lb#-2}=CnMfZDc>^2O zwS}j?1_YnW=#ngB($G4wKLml5h0AaZ22{rJkiT7$q`ZE2!})DKxm%{q_Jxv1_sc%N z@^Mr6o1OkO0f)c6pX-2nny{_e`vz#ThSEEDVB2nO&@n?TC35ZRR*{|rEf)EN&TH>%t5Mlq)C0%m z6C-mmWdQ(PFrR2I>F8CbbsVAsFd&k&d_Gf$GIDBA&E#PO1LD(rTbgC|`)VsL;dI0w z!+ALFxi+TFbR^y=pa26i?1`zXEzmtskP%mf;uiTcxvQ3rbG(;c$`)LC0=LvEYX87- zr_6EO-lEpCiaP}43#Wlk0gug~`~MjFCEb|mG~jdV;iTDKW)WcLU@uoXaDq;-RP*R` zRWwij?R?e06w-hfy=c~Hnt>p?-%$FNV|UvIO>wNBF+cTS z!ZF^iKjmj!Zsn>OzNuJUHbd(F_IQ6xPw>vXy7Qyc<&f8|x{=2ea(|ni1L%%$;JL1t zM(#rRRMW&2C)tj{%7WxQwE+Ko*FIu&aY^-xh`({5WlWw*A95ZLg@d2D@qvm6JBM z?>HYapIbS$q>pc#*()+L0jIUEK#m}1nzhqV%G^3YOZ4n5<{i>YaNU$(w^ow5^@qU= zl#EPi%az$|nKY`$tIv3-N81|>8E2XaP}Vm{l!wf@oUFF0$77G==QDzyzHQNJ@$O7I zK!Oa*0(aDwJfenhT2sk7!|D4~)XAzG?Il^H+;!nzH_r}f>oM^#gHbWp3=gh?Ai$pJCkONd z{iXK#Ca7fmGCfd?24;^)!*T5d`O0LXIE=1rWMR6L7NDm-NDBIOh{5nA)>WuLL9^=yO5!2zzU}#`GJR@Ni!2e^5 z394?T_2@?Zq;_S`={d#ailo~5G>;2)cs%xa>_V0DN^SH-EaS-ZSxlV#!1<|{cMg$! z?CQ}S#6kj=!^EewhZIq_#zWMKU zx1X@^m`H6Z&WQmeyL6XPAOYyuo*OuTFC$ZByiBc8K$)Uk2F$nEO>-;5)C=zz8)?U;-Aw8h~5Dgy9~DvZdx63KsZ>nhn*#{oU} zcWk!cM787Rcz&uL9UU?oU@J*MtGJ*Jznexk|IftNM>hXzTc?@?Mk zDAU@s_wlj{rV5tr9xf*mA$A6QS@I3T!nbmKCy%N#c`TT|h<~fR$Z!soW;|8`YE@hE zE}J1bWq4N(LVk|llb{Q=ZjyUpASon#XiE?fTB@f~@iycbs}2Rpk)>xa64i1+m*5A< zI^2;Vh`stU6Cz8Dez(wt2KMC9iq< z-?+qX?B}OAx@tt*?Ml}o>=f%SmUfu{idG@7w{bP~B^{`LqQ8Gq@Snc98K49dCg!=UBl^3rk35UI#Se2Zd zew2rmwo+Wwk5LgF=)4rlz2TzTey!SuzxK!@%JbI!+;8B`C_5 zt6zU0F^*}R!o?ky^ut)LGb=78RvKH-Sj(wgo1q2$`C-&moCw+b(Yp4G)%oOLT zi#epKG7cp_kmB>MFWXjM9qSBvw4zX2f$VVoej1|PT@>eke_ZhepF)oP8ya@{w$M zlC z6_m&4Q@9hh1ufJVKER~8%oH9`b^^PU4(u^vXnJABoYcjL?haYRPbD(ms!maTQ#v`K$lyX4G(+p5t6sXd5%jyD zji`{8+U3Y?X7c%ur^^5&&9z$z44>(}qI^)jOI{wMp20hC_j4<}9Rl1F zss7;dfb#t#hO6PzlPrB33i}_t*}G+hK-ZHQx&R8z z3Q~-l3pWX#!deZ4w`dyKpHFb{)o^*UF8|@n(DiH35QUyc2{ln)EDD8OdmR4eM~yk} zh$vt{P!!;$TeTiN$6mE3$Z7E|sqf;GqZ#b4<-d_imgsvQj=oi6Dn^Q;e!O}O#{hbO zKFZ-Pk7);e|*4vUcLG-r;uJ6RW1+Y(pZw86|K8A=Mwi8~v? zqusw8G1K=q64pm`3BBGK8uu!#bXhSjL2*wj-yhAR^r3V9FO&n3)zV$mDCl-)UL^f; zhGe0hjS-zi>PJKPm|!KJTY@SH@DK{b!eTQR>U;5-acojqP#}n}(H1OWKN+I4Ru9iyWmJuA&kpeYa0xKN% zl05ek1(p@lA?GYBV_Q3#G(|lk4jkIAeh5Ht_CgJ;h0oAb$O!MKy!H89R6JO(Z zrWh8EDy&}>8lWGSxh*O3fLG$W?2k^XoO!>n4@+mGmB8PaC*n1yVGJ6Qn(*UA9?zE@ z=-NFOVV|j~ufocSA<)y)-q8|q;JCoUmcs&moV0bUjyPRJNusninPN}?WhaYXKqAt~ zFR5p$;lS?gz&o7DzpV#k*#$*JX08`>1`_HNG?JO^2td_WFhfQeLX5}UT+7&k4cza^ zqsKilqQAuin5@bqa&uz`Pln3OZ`p*X4Y}n2J`=fv0J1i$wWRqqS8|WlwVInp^!F&A zu*4Tv=3=YV+A3Po93Br+xFl2&$uNJh*%Q4#FbNn)5CRUVlAZ}+6%n+^M%+w}cJV!< zPJQUFJ1g;Ok7FPrk|Nt2Xk*rfaWpIq7+`J~Z&ji(qK+KLIPOh|ex`62^L*-bur;BD zydDPE{f=ON^Cz&8JbH>}XJ0Mj5kg>vWPjaOsCTWSFhiFx?^YEb*mGz;dU=o+2ZhOy z-^aK4-vi_=K$$BSKpxje0kD`V@C2I_LLWMUqu~ zZGpt&0(l9=yNxL2aIPc=&=Ow+zv++}`7=ypU`IW$S>}Arfi+j3Y{Uaoux0pSBT=wL z-Co)}MHEwTQKZMJ#Y=~XKgvzBu0}WnKC2PxETIdaEyM%9!r_DE<`300o^gD3+8ja% zHSrF4h-0fCGgJVrt~I0z?G-hNm4>dnhcnuNeXk#lbvwK5jaP4kseDO){d!BhS9Eq< zTfKl-Ynn989JhEj>WTz)wOa3(g`T(B65C+}ADu9ed5n zwkQvl&!p=jH!=Bzbw_p|E7|0w%)jL)|IYg%KHv8@e_O3z6W0vmDD_TG zkHHNQES8%I4t%H@qwvh|$l=vPqB4<@(cr@Myr!}CueC_MnsGgWxXo?wdwvpd0gu9j zUA_NU6w2FNaXayz!Y{;9Ww6P)4sApbL?3aOn<#s%6LSj4aAN7d);RbVd!;kuN5o#0 z=jVeu*1JPlh1FVZw8&mSw5u*al)MvcnM%m8}F>P8lv z#ri5G56Xyx7NmS`?#9I=-+WQWwb@);}_B zr{ihopGUgX=yb45H_5Z+y8;svd(y?;iqLcJ#JSMxl0aIl=CX8yxh6O8+I)UF`v+IsJk&~GWY zenZU+Qwm>fP~~v?<(9)$Rt+n$wH>hKx$9b3v17ppHGIq3s}8O|xH0VY4rd(?DH^QG z0&JC9!&SPn>5C<~;&upTPqk^vvdrUCx)tfFarnN?3&glaf~-dl*5!-&878 z>uAp|#-g&bQGEl(O7aV$_1?c)M|X?Aa&sfGNkI^-*P6wS_P z1-G}hjbr~aB?a%Ctq)8f3}ysm=Wbcz31v5mdB&HA7lNQ14|?odezvWVpWS#=+7^HN zBiswZf2Tj%s{FpE`VE>0Q?&1nc9+W`51^uTk72o)6fnPM?KJ9QKPm5MtgS41y{d7S z6`iAZ*Nk3P@@DcOJf&rd^!Db>62h%mbOL=|qA0|i0h>@=8O1EI;^f@FBt=%F>PdKy9;kbsf@j&gR=1aWME#PxF>FxnaJRb? zvp02Ij(RGlyO7b%=&zA{fcH%vQRE2bD>ChG-e_OilCgV~nENPh?1`FrhrK{~E_cfh z@BnjKPR*rX<=17Kub$&4PjPuocjav{@z;60LEno^d@vF*zF(p=7F|N-l$$@Ey@S0E z4jd<~!ux!);)5$9ws(7r^y?fF(7*Q=v{4JeNtg!UQBK4`=U$VDcs4o=JgEnN_}bMJ zCX9S4!pXjAaMl)}f@J3yi8*t@I3TwDl6T1wp?#=sVa`0FJ-vvBxg%ZaCrujF;A|>tBVrYD_afi2i?{}|BcW1Pux=tY#am*Ad& z6q}nuTJ~*EHF4Rc(lgb;W+(+pH(`|5ZWMJ(zJEjn*XiA0HZz;$hq;*sC(lx2MmNqHzP+c@7 zQ8zYEC})4glr+P}!VHJ5+5;x}p3_i_-%~~6*vZqQ~ z@=S7m{lWrjJ=kGdYmZ8b7kUfNPN=9sj`_VhFdh!qIs;0kn7Ut{`$PL zc{2`DZZp7fS`6RFWutj@-^R;aR4dFci$c@^Tu&F{cpgCtW_8sa$0P$?L&}U@ z4R%QD-*0M*`yU{sK2t+hu$0*RuorP|RroFDB(am2Hochl+0ETDnvpQY|9o>9uLt zlk(L#q}I2EyyB!epVBcKZyyB{M5Nvt)M&}Ck3AzhXs-EHy`Xw|epTam`^@(8HympP zOS=`Ne8R(~!{Q&q(_M9~5C0hCI(Ob5opTW)?-Mj3?9`_ z=Q*VPhunrm%qq_Wqw#%E-PY~&YS2}CH;ipBjQ4!c^z?u*bD$jyPhmE~%Obot_;5L| z$v;V(MPB5_y32FbI14SNh@iTm@@cVq&ua#w?V=?8nHaNm{a=ov7R)4z#8ZW%ZCDCT zB4e-70s=c|5=uGVrb$%ZQ>fIK_lG;KgYd{{%H(aI-pdlMSXAeSS*|q6KUr4HJP&4! zvm$P-I!;*knS7SVxV&CpmHEY#fc|2A{!=@bu7h9R;4lQsh^289iwv0=lwc|i3YG8f z8+n=Bd0io5+CxyE$Mx8o33TBte`c84schpNAvAE#Cx47Qs2&fGDs9>)0O ztT*dp2FZ5fMir$zFdGq*GX*F!l&%Sj_%30$r0flLPqn5oTgR-B%(ssef%0a|`WK2m z3zO9U$kj&9y_k}IxT}8V(LV-Pv$poRx$K1X%e|MrcP1D5A@`L!6qHv4&?;?)AmtLs zi$9s!E=xKsxEhGy6sirMpG4Ww{BRqI!5<;Z_q}VbJ6DAka@Rf+0h^D=i-sQ}QoE0D zZN7gWHZ&fVE4QvY_fS{BXBQkDIeDO;)AX$AFW5zTWmDvh>03zT_3Y@;jpXP-#llBuSGXJy}kevtau1!2@!XP!1_#il>_vJO!kX4_BO8;+RR2{)Wi%2~hK(;oNGDw3*Ly0(nCEX0ADhq}Hys z-c|~a$1uJhC9EhX&3_4rm(6AsFfSrZmd z#+t_vn<&nYImUL3vyX_lPuWz>kAE9K7gIuQ>14i-d5hx-Ka=IOWhPxe3vvP>#;+QB zlj<<}VvSs0{}{CH&g^MNpmgn?UEI;ur33(s&jks?C9-smaHBoznom;IrvS=bj1{W% zzQS@%vQn(=cH2X>9=PE22}QLknHQYL)Jm7_!*w#L5v>-!+1e;FCY&bgK7V)xqvCVJ ziw0^k1Y^GY4!8qaTiH1H^=p0`I%4(SMkVD5Iod43UT(T*_K0R!txYs4{~3kv%A`2R ziaE5U6-J-%V>NDV#s&j#hgSzHza;f2Ej?}w-jQ4aay{P@I7VInDo57!%$&FYI7{UE zb3X1m+UK!si$ZMcsH=*agkc51gM0Wnywmf-klB}`?etvFT3oMOG%-^NTU)V;uUyqS z*aEE-lP3@87?D&pxR}Z7W8euiGWifJ)SQub z=G#|}0ESfJbtExuzhLZv!BF^%q>e;xzm&ff5ABs*RNn+An%xK#W|RuFcKeuo26B)y zQ?su3h#7K)MBhF%7x60`eLo>Td;eu|FvV7JH2biEbJBSL^`NZk!aEl3A(y810T;Wc( zf>z#Ar1MCV{CKmlC9u$P4wmQf1;S&o^E^jp3ymYO4#KuWBTB&9 zQMWEBf@@r-rQkU3xnj%5r}g<_5(u%{no!n0)LVcAUz?7_uUy8Q%E8BlgG_l9`XxcQ z@Ae*iEe70R7M1c}e5-LT+%>?@;%6GTDXyWE_kNx9an~Q?76*i5%*X!FfM$BR=@k_Q z=>=%Lzo?%|7CWM9U&KFyFFD4@rl({JxX1R2Fy8XC4sbMk)b_hK9m9(b2)G=V)oiml z02ljqR4%ugM*`5*;Qul7xLodjM1wNYS6EI|jj{ZKPJCAOffmPgX`8#cyL8oA-e2~* z;bG@l6O#*b@2O^}hoQIJE?^p*G zEhF?4jMGRFG9n;be7;ybmB}k)WSa7n!<}*c6G5-9i#=asE7<29VOkW4u;0fpee)e; zvX9y;;opPyvDa$xNwLw=ySbDn>gWrc_2`Ky!(_Zh5;(M#fK zjJ`Ga=~MAxt=k0K+0SVhp8rvF-tknw{~JH{Je-a8qU z-EoW};~Z4BV{eX`aZns(oH9DZ5tZ;sC6(&?^ZWn(-}`>t<9c1!^}I3HGk%GmukM<> z-12@xiJ33o@+*75Ri-0$w%(U#&E*4mHmpjw;Qs@-pC%t&G%LNKOdm-3``H^!>6~G5 zWs{4Hwq&Z$N+J4H{@eK_IbA1ws8Yf-QQ!*TzpM8hlC9ZgZ`i?WOu3%=Z%HCEcw9*3 z8*_ylfvMp^oNyAelzAv45=OndlN%{@iqG#7<_;EwbPp)7SLPPk_4_g{3smGSy$G_! zxd{4FNGjZTx_3lv?d7Vd02RqbjXdw_^6cYpu>Psgy%5w8oKJIscAZxhI{dMf*2Nai zd{CTo*ja93fn4j)6=^FnvrKkVol z?Ra>Rk#gcZn!r)fl?U5@iwKi4%J&|e!2aakjBVQ!g{J&~jRa1U+PM+kjBsu!7WJm6 z>wkc|a<#gg51%Z>zw@yN;IpHV>%8bh0yTd2E6`B<70kGJ<{Y4!UJ_x$$QP_E#pll10?+yk7yBs zu#~*ngSK@O2_JT9Wu3y0H{oYHvkOvJ$VkDieNU2aj#eX$%*IImEm$?r7Wk+GzFsk* zjrv%~D1?YOPd_fKw}ukdB7`ZhT+O^5SI6_p9-Tt4e}!}nN}g`}5IoC)(9 zf4M738O|dR!tq+2g170 z`Xc9BOeeoSs&n73PKV<+A~oX^Dq8o-3v25?@M)^}qAp^p3RSzG8?n%V!_OT{XjuA_ zjrC5L9{u*sydY?o0ihwk8+Y8D5`zSm{>tXcseZatfBN(nmDv4FxCx?K=K`HKyn6C? z^1Za%ubSZjKZd3 zKytfQGI8GUO(W@fC!VArYI^18-^pdpYCq^rTr830&6y`Y_{A4OLceJma-~ox$CIU3 zl=C!6da*%`Rw-i}pB#Ut#k0M_0fx+eI+)fx->_hs z6~vG}=UY^u{W}A8rIL8}a~;tb(`XSCk=F72Hv-S%?EJ&{y07t(ssH}~$)gf1`e$YN z0l-u#x7@D@UaS@Tze?n<|I#^a@ahA(lPW7$|A}2w4US{}<|Tq7zvG1GVIjgXRHi$k zYMj;hnCT$mL+W?dSm?K^XrVn{WxLtjXts&0V#Z48GzdNMja!qVfxIC(rz!tUGLF#d zdc);QC}pH>(_yY8lHENqb!NGnLk$Mw$+8*u@*=W?aT?TpJ(2_mi_t3B`Q$;|-is=1 z{{#4m#2R1%gb24a6bw9SZ9}U`;b}8i#(M&Sp3Ils>OxGO8Ljv-b9u}i^=91~DdD)l z;=|h}BAnqa0-7y$9uSKGWkT?>sH!SK3WtwH=pQoz*y?AY$?NdTHjs>Qv(zyfv$NX( z1ERz>Eq3ptT%dwny3kI{SK3aqZOr{=6D(d(h`EIk+cDZiL^k7W!+Z|N6X}as`>OkQ zEWpC`Z{63b>T#;I&jcvvXtH?vK7*U6=7fbKyQuZ zH9EB_3UplfMSvLX|63+;#kloQ$J!k~f)= zQvo%IzeY?Q1I;H;m!=oj&M)fZ72S|%xF-AT8f)w3r$3z;gHZQ-d$@Hq(qXTuFuQYK znB(t4kM|yM_SDJ#pN9fr_$FRQg%Ti}TefmeMd$p8fHvC^5bJs`%2;lbPv%n-$8O2r z2~Xe2r$M$s$bM@lTYJLDmsUMNXQHCy%>$GF8hQ=u;+$9PvKsP?CG87ZBW&u|>@ zlC%vvr+#%GpO$zPF615ly_oa?^mq92XsGaQMiPN$^0~0#B3gQj*&!>6(qUc#{(8X@ zRK4V*!p%g`scxrLY;2U`9?E8lu{oPD(N+XLNH!b;BC9te{=K3z?reUD&OtO_o-##f z=U2u34>0uM0BZQu_uan}XpG?dB%AmUIO@+uY$NZhyxBh%Tka}ObXm}vY%NolA6sE8k94G=YK*`P*?FW_BqvPE%j&73POI{{mC#3 zO|lX|r#>r2Ab=ig{^oNDDJ>-K+WlacTu`OepC$+dG)5`Y{}W}GEJR2kRBTF)7qZM$ z0q<)(|DDDBSe-o;C2vzYV;5arJa)6vtG;)L zNCX4#9n8?L$K-);saBEi+lIN_tuy1cU4Ph=FS0Lh%PgGug;;z6>E^5Q475=l5iL3X z@`5~c^DH7wxz-Ww8J{#0rq^wi^JmucA1Grc%C7r}2iiCl26I@P_y+3|v-*`XV)1f@E&+AwbVMnIgG$zq48$=M#Ie7!aLV zi2lrt?4| z+4@dO9{SlwtHPk*_!F8Ac;uZR}cLOLr9qW;i!M;2iI>XM5OojLjzud0ui8n62$1p^hOpPA+r z=6~qp5k*Zsnv8AXFZ8ho8)^X~TU|e_IA_-c8dLHf`Xk#^{@z6WLhg0Xl%%l9?Ilh7 z__?hfG9rbTNW#SzONax0=a<*Ot;av$7~oQv%skQho4Do|B3L;NYG?$za-&w>#*Pqu zh3#U|+qkqDTg zTmmV4*ZAnSc9G*)ueoT9-|c=DKimE5B5dbpq@NOeUVZ?>eg5srUVqSH@UyTQ7iMA= zq!;~^NTCV>wL-tCig4=CVn1b>|1~`{H?zZ^)2i~1r66af z`=AsrwWaZ%er7puZa)8QDBOnGH!OgFV^I5Q-L_bdA4@MLG`5EH@PE zoB*HE;mjM-E8VEn54hBZLVh@Gx$yP4P~elC2CiD4B>`@)DpRjXHJywSoLO9x^_H26jf+!73h1xsY}oz*tyxOy{QsNnHtP4 zpcg@TQ>am*k+<`Nw+q;^54qY6P2MvfM^@WoU0CY;lO~iCbK1nEMgtRq?55Q~`IuTl zhB#c$_UxD6SIc`9fw!cN33e%M-DpqneR+VwsN|Im{@})>rAIBVp0)HoxG8wraax$7 z^G@(Yz-xk6R(j95{9@`H^T^j_$~K*E%N+Fq)cj6!uIdA?9$kkzuzdtGZ{i#T``!Ke zAXBFI)liuJ72kV5+%@}{-<=4@;lk_=)v6ob7D%{*H^fea)KsayXIFusYGvIqE?xYm z;1B(gg_7I0s-s$xE%!MDdIMim6+X^7naF%(dGb=nE#HavyTnR7V{Q-V%n*`bSj zOpqNW<45Fv{b(Ff?!J@2;c8RrH^`crdi%S-Mlz75{{gOoohKuF`B|bV166BH{|U-K ztIpblgVExCv8(CyL5tP0K~klKvW&An_pMzvJgu&op*7s3*5plMqQljB!=!ojEmXhg zz{=!2Nf4`6S(Qk_*dI!eZTdB3WE2+N^MFY7G5t@iue3Epm3!(lnA4cz6NyzvvYm_4 zxu;LQQHDJ&krE{be#c(ESXU|0`0_c{Q-~wOmiMXvS($ECjKWrMUAO0}_==!=fGq`5 z&p94Kyt+DVI}Mww(xt@7$*#{x>C5QxOG=)ug`CU$QN8Wj`YFw!1^tD2y%~|i;=1d{3S#Z(bTj5+WxOjsozIwJs;dy(qPGT zGmd46M24KDcwFlSiCHx~2}Q{L>$l9IyR|%M%R0Xh7`m=nd zwN%y)m^4=K{OOs>Yk1?JL+f|5Q?Z0!I&v!|kSK=!<8#`C_+RDtH zof~nirjOT#+v{gJr#IFB8jyvmzf#1nY8J&0x>70uatosBWA$_qR_*+P++w$2+Ode! z=%M3J-u@)^s*DRDn%d6$4BZ9XTE{Un&)fcBLCI+K!tL}@UUY17t{8$tCL&JgM3$l` zp>L_mZ_AUHMlm)iGel@sD5Z11-qt$GyGPzCSQqvE3kes`pc+Q=WGo&DR!Dl$p$%@* z#PM^ZzpRtFBbg+tf0wjfIV0|MTi?HoQ|ZP_!keWLkJ9^#g>KCBh?JDyeqZghxb2wtykBI)tEg}PWEy2IDY!msNPJH? zw|h%BR=l-Uxa{#!F8$I)O5<+2kBDK^IJXFcp`cyUaqCw8tX8*PUl5OFCZCSsoBQF^3_Nn>d99i?^ z%Lb^r5EQ?Ix*xS6`ziDpGNQbYv5l9_*KwbFjH38`{avz7q9}}WoN>k{!g-EvbiuEZ z_21>@OU}&QOyA`?r@45Zko=~C^Wi8Md-~LZSLQ+^)aE{nT(R@ z-9xryRxM9xKT>)ww@fE^1)tWQ5vhF zjPIBTCZI0H=eYKRJKs649lFG*zq)SJvZREWdP=yZmhH)J4dT_1Ih$0WoIMwP-g=c~ z@NcLs`(CgHDfHbJ++{38xc1q)sfwseu1`n=7OF+lVPA4->V&<=<&!U*@Ab!)T~TBq ziBLno?24J`fw=AxRHBsxiW?Qfhajtx8!JkohxUr@#y&HuzZS5?CB&G{FQ_UgKbGY} zz*WN=K|{85VUzI{F~^NpwwJhFj|F;ton>2dJ;}QBMN*Ts<>uI6oo0cWzR|v8C9hY) zvv2m;yn=8c(9I!G0Jo5X(sPEV(36>8xn{aAE)x2l?*SUecD-btkCROD7_iA$As(f6 z$hKCDX=?Z92pxH^@o#Lm+@IRLhj9KFLO07<^-@?1}p>LVq7y@ zRa+#cWk6Rh5D+#D753r@zDa<}x<5uBl4P!$c4`|wMEnOt0Q>82s#$E981DI)Z$TMS z*VOZQEnb@@oWO+?r7V1GzCKwxuq#}+W4UQsQ=-)cZ_|Sgy##-v4yL*Q4qGdetG*Fk z`qYe8w(0T)!8O#+O=Vg7QAR70GpQVUWSAcVQXZwrN_%4 z)0%lbuxs{gzu#g=oHZ##cHz42d96| zjX04Fx!Z8vSmB@euvfSMp+j-%vo10oZLt5~{9kFTf24cP%rvQSP~ocDBiZ9f=Y9>% z1EyQ48FgGPXPsgjkw3=UIdB_ia;2%h9`U1TdrOy6Wc8)b43RdY9T_Ef__JQSOlOe` zP?IV#7D7sb@Gp`$r{|2DEIXX?;#T{bYwf@nb)Crsqjrk{gYS8j9pOK5N}Fm$^u>3- zOS=LjJ8SelrYN;+OJGGj%n*`duc%F)$|AX~!BKA>Mv;lu13Ii7DT9R*!jV}q9huJ1zO;L`;rOGyk&p@$CoWMNaBb#jURr7^;_N!+Nj z>T!4h=O!qJt=c+ z`A|RdQ?{eAqcNpAVsq=zdFLnIh@aaBXE4mltYQ;)Zl1G?#qbL?&GrR_V)U}yPYEW} zN@y_o_w$zZuHkh1=st&#!7)&i)H>h9{%*BcxM?l3P-3v~6D^1Y%C^?ipcxiPen!5m zV%E=OZnshu&x>hvIe~$J()<%wu@R1oof@J~<`8LVL5m$6~H|t(8(-k9M4jDz_{V%2vO!d<=V2Bg_>5Rvtc8c1` z>_{NP>p<>%SkIo!mLx-S8D`{j$K*{s?den48qb(UVK>H%qQXOeXX15ry8f`(9xCnL%TYd06;|^LNim2LeN~Ojm0IKVnkw zEI@}Atj}=eUX65B{$)_O=u%4OjY_zky8DWDmHd`%8L3hr)=@b@9V2S@BFs_K)V{$2 z5BQ$wP1G22TjmVPDxWzsTz)asJfPN#}vBQ5c;{hK3qM*mM@KnO-3I6!it%DSJDR*iSfyLr`|Ls z8FDL5OtWZocuFxPGzi!n`dwh@PO5J4OOolJzCq>&T!dp=z)@BNYCY!3s$zdVoS4Ju z#YMgzHqcrdbChPxVlD|*xX2KGWv6{PQ_mr*v8Yhv2^JP6+9%jfX4Vb~+k9<-L51G% ztr*XX$EaF~N{+gfqg{YPvdw;>m9av6>2qi#r{OorfB>7t-i6WceSCGr0X{%qE4M1HqVgFo)Cl3RV@yk zQS=Feu1M1aC+q%flUW)Qb51nVyRvJL4Et}~=H@~2foc8b)txT$k=}OCfpuysr)U(^ zXlV58+4dtPxC-19Xk>~W^T}IQ85yHQnN-&ut3@T^zh1?a39QR+mUR6Yt$2DBhMIgm z_LkUGxpo|8XfY1*=k>~ zw`AHjZWN5qhFbII`H{oc4*JA=Su^~JjU*WLV{d%~LYS*P4)`l#Z*YX%t?Q$yL z$~Qr3i|!bN*N9$w{HatCvK>ygb@(L487*azow=hbIajm-QLt-VhlzWpU-|mNdEQ8T z65_ad5mu81?0m~WkI&v+NZ;|RRbbIcQ%_}Ij-@4zzh1Etvin8}a#q(I&!@bs>N?So z<&~_nQN8t?nmmE>2|<#vuR~vJHCpUH^=B;xRHw?7QDnQ6&8#TAxhKirg-Qek%ElJ0 z+PRwj48$D%gL#d~s#i?z`9AT@l_ddKPn6lK^wi#$qsiI{sR;6IzACmrLc!S@sX+1k z7!5Jvr*eJ0L^Ji#|AmJmzE3noIW-*tiZk8!v-&%swgHV6lyCx?>h*`>@2>h~j*` zs3Giz?0Yz?>$?1lHf!#fUpPb;iR!Z#cGT@EX{=32QH;;529~B$Xx~%S->xG*x;Hfj zG%f7JEJZaA>BS@xwS+&=u=*ml4z(Li4K8($ zpX|KXe`gulfrA*tvg!qR&*xlk!$jiGN2m+n)V|&(mx|W?g;@U9oEtW@x93sclG99_RYnE1xYMB}=0_b2`}eC0PA^^)SeX<9w4r)jkPFGG>!r0m2HtOzFY zi`KI-)CwOupkJ0M-#X{Ro<0k`YiLCfm1b0Xkwdj^&vjr#{1Qw}KIokptYpN0gddCN zDwq1wb@qHPdP@>^hoqo|JEY=p94R6&pLv?G)~`n5aVI4jITcVk9TZob%DI5{}< zMFDg3nVpNolJnJ>@1v-^zOl{B{{Sy{AyT*X)cHvU3|?gR30JSPyx#{=I_hWwf!xE=>jW$CyMsMWC6Ca6EP zA#jE#+cjw-__0A@#>NaLx@x=A#}wtjW@&6=r1L9_(}ko)X1GVh>4MVUiZm6uD~}O< z1AaARG=C}$MDJ<4?H;O0Z{Qg;=jU&BRt}hz)g)$xUki}|s`Ei{|E0S`>H=1^F-scN z@nyM%?>I=P#)4ZN- zy=*c_=DE!qLZ>Gbb>>4<2#%vG`shY z^H+zASiE{EDH&WT9X9C-iSHfmdTAyT?R9vQzqvf?7VgaqP}%wUnI_A1sI;dC1ZEYB z3JY}%xp)M5?Q*J2($8$26C&9PeCX4xe4F<)-NIllQO|gl$Zsm^MO?#c)e&hsPC{ok z+^Tc1Ks=*REBQWIKd;!Mz(t-}Gjt9{n_%sUB#9uttcL%U^RAT4Ot`uIW+})ks&`+b4#xNcB^k$)#Np&UO2L~F2lXD>jiEgB23{uff{Euw^h6mF+B!P zG86EnsLTpZwm&bDmRs<-Wn2`W-0=n?H-M4(Q@?#Ls?Rh%x8Y@e#iLv0hUf|4rX}Ad zND|pnZjK;^d|G}1%y?;dm2T#Mg1ycOSRz{aYqr@~y1qJrZPDj`m`{0~JjJcn>2)O# z-wOQuU2O5Kd8`dXuD94Plc1gtV>`eVYL3>_T^Se1ZyskZp_we710}Hb$8u<$!=z-H zxMWA#XN5na_b>q;{W0r^X^cJ_bjvsNT$z~ucPQ@}_Z`xCE_NT3sZfupySb4a=hGdFbEIaC`ETY!qNEI#^yhO!+uG3Rf!vGZ~9U zS`=*m&NzR)zmZ&fp8-*INrpgj;h8@o*&H4Qp7DexWBPA8W}GSBWpZ&=+Y*#L1*c#< zwWaT7zpaESsp9n$qN&^EBk{fO^Jc7em{`ZXs(=M=I+LEaHJZSOWitOWDp^v3%l5Yx z_7B>hyw&Iwb!KrOsqzGej26~q+WBlIs|G`ZU*WOjD~%ee2_TG>i2BxVlm8-MNlb-; zXn~UmEwAv;UGzGSbuo`D@g}&S!rvYBZsU4(e|XA}l7vb@p zI`=xB*gDNz7nH!d3`&}zhA}0eAlpE~#NEx9g%UIW)Ui zp>q?o;3(&0^hO=jTs0pwviQ0MF7p~OjL1v-0f(i2)E}ubix!bOOA_z+4^h~p6+QsI zHQX3vGe|kJXew!0k2g1F8GTH$Z~&%PPG!yNhI)n2}LiMwE~pMS45DJ)FIT3#Qvb4;>E@#?6leE zvvce_HCGf-s8K0%IW=nSB|ugkQ$cby?Ikkp61<&gcHz9&8}>RR>xnptpU#FXVc-8_ zB;uq)%7T~uxI;#F8g3uv)=j%`XI%-m=w2_Cly6pbUr%_l=ny&KZ)+(gHso%6>lL}G z{u}@3V@bhk@)!1BgjKd+>p{sWX8jkSpyy$tWlL~ih5Bjk({F4sl=+tIAU~rO7SKcN z&Q7zA4sQ>a1R$w%kxAu6G(bB2RuI)#d?(V&S3en{AbP@Q@rzmKCje~5q4Aw!8qeo( ztuL?c7136%88iru(#*q4ZOH7-_j5v+>XjWS$AHr3Z~A)37NcreY~kbXMq;izlRu`d zxd&7jsTK{&FYg7XTXpT@R${qn9Y2kW?1ehH3yA?rLk5RC*2^gac}jl}ou5yjZ71;m zkSvZsKNd|U(k~I_Dz}J>>l7TCUGN9pWO2pGE?<(dQRNz|oS@1@qxDB*<2U=jk(5rN zzg^CdF{s#4QG!vgs;aqD@QFO0KbvL2=c`+JaUQzk%)C~hYI^;**=SHLnZMX$&rU+F zc|Feao9OA2M+tYBh%0x%dBTw*o#nKCz*T{L=Tn*MCsNzDJ^QCsYFUw=LrITS^l7hl z1+qu>oM#UrIBxB!n*A8dzlGa3?I7x>-))q6ShtNt?9ge%9TQs%zd^u)oedNaEh_PDLdkra;?vrhqwfjUu zR1n)@S9^waPJRLx_fo`-TFL)9U3x}bilV;o5+gN0<}>{mC0A6vQyCV(S)(Vo8lnou z&h_4p+D`UzCm5~$#I+c#DuF(ja#NKCFi!A7<%kpJAL11TxfMdlGvq-~c>ZZ4ODAYg zo7?_pMv##f^+r_L)Gl_s>yGt%YkO!P>q(~pfVVi6SN+B=)UwG`+T02XK@S70bcW9Z z&!q($-Um5in%I$gsfWVnHCUZ25iBX@JWZ#Qtb8m_YM~+8Pi2WWcbXftO9*2jpf?I? z8ZaRULqv?1w*EGZ@t|dmQ&UO+8hVy2%-Rr`9oprgANXXeQ&6 zJ!XJ29o6dUCV?+vGfMH@b(K#cA9x0OUpO=*d@i3zW#lE6U|f=oSc;>nFj{j_ojGEa zoMcJ#8Xgagi}41>1L4*E!74LST}riZ;&tF{o0-(r&0U2Z4cwPIrm9Pw41LUh{ZF4O z=TcaR(CE%!Y>byX#cyp0Xa&eFQMDLOEH2|9w zs1xx%y_gMDD6DP;Q2e zuInQT5`laKX@Qt#F+5=>TlqrSRqj~H&iBE! z@@@Z@WE4QKhk9&qCXlRxpgp2LE6-Z!% zfFBa^{AYKjW+Cd!?$hF)u{}3qGqV>FfLec?CG@2&vSkd$xx^Y+==d~>=0M-YY7g|A z!@38yX!dpo%M?J+QSx-T6IB%pd3<3hEwdys0NljLb)YugM1d~{RRylg9o^D76CnShK`}Si z&WM+fFaOT0%-h-D^E5?+jV9Yh6o&S^pI3juE8HP0evg>sy&CvZq?7A_7@cFbHM7>0 z)&90*%~2~XQfOLEW>JWK`-94ar@#OTA%SEc6MV?RL)+R5^rovX}!vzc`( z2eBYXcd@)Lnp$$(YNmEfL~;x(4C55KaM=oZLi0iJkk`e(T;b5#1>HR>*&?KhH!O08 z79-{yY&hJhJY-#CVjrA#tf982BxseG;YRo6K2RUP@j9gHx_Ei7PdKdWWXrR+!?xl{ z>d0F2!Is(PyNaT|VwsmVkH_i$QwEOfU&W2Ps^m@RG}tX6qj zaz;p@zipA}w$C%%j*$eMJU4QPLpS`J*Lpb8k84u6{wQ-NL!*1w-i(FTG7)cFaSIh= zSNJ)7Olb6Mi-=E|mmHpD*FjJF#!)^%7ayON2#Xvk+l5C4rcMaivj(_;P`cu&murG; z3tI%XV6O?qmzK0Wu*5eU^<)%Lx3nU=uOYo?&tTy;SAN$)dffUSt4pp1zEdogRZ1+G zjPCJWE^`>l>PryYd_^j>ds9zk`!1wnELS|&w(WfF`|AGI;u;1k%alqO>imgZvFLk> z_D7w!Dms=PI}rI`na0+bQTN#Q7+WXjKB7(GbPa3OZ<4&g=ks@L%4DF*yE3-1YQGZ- zMY>W&`SOW#(-@7^IqRy`_OHf7bS2=TT*F>ypl)YtpiZ8mj0ZL&4K`*%z=@~N)cL7M z&B-;9=Zr*0cE`-7Oe!Fir$ z8^qvrh}9M+1vQPnwIgZU&|~>d>~IPKKejnwjpH|DBLN$t<7Mx$EUsSH;|}#hYOuL) zb`FZd=LdEjVSo=B@#WF@8`dGnNghe_@+p!DQ`0>`+=>y4SaPzu-=2s!`?%ho2;W@u z+xZSpMVXqo(jFm->FfjxG6G@T3&$iw4}5*+)>8H_%3!n4C}1IVJJQjej3WDbJObi!p+#rW}NR$=TP` zh~w3x4_)(KxK1J}oVfD$F2FN7Qvck<~ktUXeLe=V9|KV5WU6NP?%=|emtEU2YP+CVx**TY!iKBTkDi!abFv9t^QU&^fmXz$L@LH zj8r^)^Up#S!Q7!cr6swB)Q?Z@B(23wKRd2`l)WHlPWKCS>Llpqu+en~m(^g3lKw_?)%LcpWDibjq`=7nr!l6i*LT*dc z?Ca$SJYj@$<-S{mq&uCGvu<_=rh5;3+=kRwnurH$GN1QhGrnkWLB_Gw*W%^lsbS_s z@_UckGk#yhJs4F>+47J-@cuPR$uZJp%UzGb+-WVpPiY#`j1=Dc(X>p%#;= zb&`chCpWS|;L$$X7LULJ@#tvqc%E#s`P???W!nx9@$Y6S?#v&>;}rHE)Gd zGvSbM#mGH~D976h6o(g4PHjqru9;qEW^=Mz=PFgqyTPzJCVk<Ctsb&#k;X|7F%UYRxfsWTpXD?VI{w$#r5BV^!g9FNq@2I(BZxJ>O?j;Mg++c+K{^qv8PK2g9Hc;qlZnVw<=Ls;MsT z!&*Q)Z&x!tv>JU2e~$y4EwE4L%W^pZr_|2bj9%)B7SL#EmrE&rF3M<1vdZhj;i0t@ zFun7mf%kv{o_HS3DUv6fG_JV%E)^}61~^OEkD?vMNSuY2GFXAj6l4IyXXTHTv%Hxe zwH7W^{vcw;)s@ecD-XziuI?s%t$=NbZZh>Pr37KrKdb$sKdGvY+wp}Xww;N7u}Iak z-%2rRcDk&D1LV&_F8rBhi13UA9k8yWDemF)*{7n-Q=W{(qXC~TZn zW@S+>Q!8Tb+!41GqpoU31AuxWzUAMf+)j#o8z@2h>OV8}fT^4ZcB4p3L=wSRIWWb+ejS-y&@~8%Uf4DO~Z5~ny3)y z8g?K^<}qizdBLW3UPZm4u){)pDhJO-oFE&I7PEv>CMW$+d@ySvN$#sDeXdL+T5 z)$4WH$b6|kqe^W?FIt#H=IUgf_1M#Fji7!u(M^ecAhKD)`;Zj-cXIXO*&&0wLl|-e zyZrlrDVEZD8Z}er5#)g(nEKIa65ho@Ue<01cs(~zWApRJpjT1WZd>3J$T?a55Qg z9|^fFe5lwV;zptT&q%B|b&aRgcE|FWH*k1UR)u%S>Suy;>qYUGerk_=|H(MJCTwc{LL!h|NNOL#km$JapkBE z**PH;uC`HICHx5ULfzy?icg#D#n}3{)PD9`$SA$vd0xUCAPCFlregn&oO<eNY2J)Gc{`PfnD9+cj{KUjzK+* zi+@ZqnLhxG>=DI(nGLvq2%YEnAHetRn+grQenz&TClcmWd@;s+M8yxc(Q0e2X5=Oa zV{EtSmY^w0OKb#ZQl70L?fJ_)6k!)YK>sg7<9{?OP}mKJKt^_I=>6f5k(tm3(FC)$EJQ*W_*SoVc*v)I zM3{WM?k$wZ`I|VTEzhkk?*=CcT&)*VVw_-?7_eiXw+3ncU#*2rVL)5DOSwe$h~W_v zCdnd1&~~fx5-G~-jMwWjJB10KrMM1#R3)Yaj8x9o0Rqy3yrmFVL(Pq;N`lc_0!IOq z)ti?ofx0xK2!9C4h2E7y?aABu0-L2fTnzR(iz>f&tYgAFJz|fn6Tpb-AoW@*$+IHv zc2(&2mj*jgYbF5U5hxvNr)&ua>Nh?8&7I;Za>UKVm3b+0O3Dc3czF3GR^ICaG0f#e zsZRPK!J>n}0-gLo&a)r@EN);_PR&zpreL@RJ9khYWm-h}DV&VpT~TFXv2`S|@Bv7^ zkI++G4L%oz?o?8EQ}y-uED4nUoi#Xw(-6NQ*Xl)i5AK z;~e+*o<862@#o=bhK&AD9PDpJT&-Cfxqx) zg<8{j{%B3hAf*BFe=V}X1b4Uil0X$6l#DiwH)EPCad{>OK>-Yl2nTKE1L;Pw?5T8N zxfd}fN@{B9MdN<>oZ%Gsb#gKO1d0vNQ(C?TQ4MJvFiUBJu|nJwK%e%mo>+^WrC2RK zBA&ds9@3>)AEEG|)4Rk;4Z~ng5_6EelvOp(c#UP!@z=~|>9+{hg7trS(Cd*4e&-W% z|MiUpQ+w#8bTEf$G*UKiM@a-_67caNR$f|4L1D{9bgUxRpO^o;WmZZg!a#w!+-R!! zOckNM(>_y~f(l1_+9zDrFV9SxftNuN-sE!Fu3m>xa(9=!6IGO_>jaeLKM}yI{xPFctUhG>*EVK3*NJS?BZ`*zMQ=nJNGmFaFoSd5b|3x68 z6S)w56Qb(F;~x`K>soN_Eql(AbVcA7Bk?QPy@j1vQO=JO=zmx*gnoKvxy4?Yesa^* z+dPFcb+^OhXp!_9XP#GZ&J)Ra#cM%Abeqr8!W_^c#QvYN+1M>iw)RZX4Y|K(>@USC zp!u#^=l=k-AC?)YXc(eIptvr|YF?GJ-Yb+yor9{Hu<9D3B=^k|eA{fHpBi)JqI0H1 zl!*uLG&9)^!OU;Yh@g7JRVs&ytGEIbdgxO8Ibu?hvShh;e#|9}$<@ch@LgBj?e5jHbd>{|wCO0cv9jF{7=J7bG$iSwm9q1%p zl$XvOOEFS6YEYnq+~x)ac_X3QG#ljqRdnu;O!ogDcRp+mbC@$B6Eka@vr5j&sbS8C zm_s?Ov4jqCoXx4Y9X3=BVa}&8hvYECMh8<4t5{j361k=B4xg{@FV`RNzJ9pg*X#9s zJf3VoA*$*$;TA3id%|7!eun!FTd)?Y7g?KWA)X~A-#*EWRU5CZ-zdhB@Kn62^9yQ2b}%b{6$m(^n0;f1_%+ z`v3S+#4DuO9|E={Z}Ry6L4-Wg5r}MleBQkD(*E)MCQ4-P7cl2nx1xy!ZME~5S2FH# zy-k8H1?B1Ix57m9JGQLH{I1^+{;ED#ikf_^)ve$KEH}wlldBV7x-Jk+0Khy$L+O&5pB`H@#KSGxy@fL&q_aoJ5V! zJglnmr{14s-QONg$9T;uyv2tEXCqD?ZA&oW)PC4uIydoP4M=n^F(xwsyGTGQB5^+cGKH)l+=TTennh;-lXxt^LdB1kyG&1Ifb-F`ul8X(d+!x-~f z*u{T1S4rJJE};PYR<$Bc;g8hZw3Uw&k5)R+|8}CzKNDWJIynPEazD2aN5c}A(>9xo zmYAbQWUmIWJqoevBBfXQ0nvG>#jZ#TVfkTLWGPDMnd|J44!X2G&S@_!-Re{&=)DT z*yfyVv;`bHnxx;k;T}dmR*;}HvCeL3>&+*%#`uED{BO7n*h%EH95A>WZA9(c`q42<;GfDjF7L;WCG$5 zoo`m=wu@pf$zJ?3R+?BzrP*;w0H?r$+X4=@CElbr-DG#O09*|TqpJlboZ*;bgs%X- z8Jm<_XWLwWB9ZZ}QP#Zp6GK$)ruPYYTLa4k*4+_ce;9HUwr%Hn?i{19yoQ`8!<8(B z-PCzvcJ~Zg;si--@F>$hfJ+}Z!s%J=7(7^n8*6S0?vN5`kSzI{7@6XcF)bGEDEjJh zK1wl{U^mYX6HEGb=S9)k|3DE+gJo1qy-upZzO=9p&d*o&*?Mi*f<|erK#b zJXWez?1K~80TW*qA0qHIlHO1gc+5!u&U`Z;`5^Slfb zG@^N5R6~|oVrWBQw`$brMRLVbGuQveCy*G}uVK5Un&JIhJ7hD&?Mqm48l){mJ*XxC zxUC9|RLRU|7~tV292~seTn$=C_qAJ}cq|==#%UaO;=rMkha92METc>7mWkv!s=Y|U zsqpFWd;C=u`k?;~5Xlk4dhB?mgu#k`D_NJHFSsVdxo`0&7y}|$%p%*M#2d?P39}RJ z_s$5f196a;Uv~W-OlpcP$G*m=AZKbgK~3x%CYt`(GN@iMmoDd5$z&)=`Co_rsJKAM zHMFZd@(Je2;jIght^ehiPM)JldBq*lK{{QHorup1`@4ElA1Y>v;Klb$$EXs>U781ui)VbB<5~dMpN5EJ1x$GlASb21*WNOMJqf zc!E@wv|3h$xhj9$j_?n%adBVqc9GJaCM;m>lIbGQtwyXFUSdp(ZwM$BGWYgwr2IEo zs?^oH^lhyNT6@RMjH9HI;Zn&mGstWY;#Sb;Nht!CCnb*0s+Qeq;QSiTr`QElZwGQ# zTe&BMi!SKuibGFnc1o`TA9->fH{p)4(1(I<^&D%3R;wL>zJeq>X%i72FU}eHqK&v$ zB?Bia!oE^-X1Bl-6Q(Z=NTrlw=U9ASRgk@R@EF#DYQz%Q3C){fiNu7c(rBsLf<2n= z+_Vi;x$)6wkvkB8Z^YbXhpY3pD=cszt9}K%`y-T3ZG2``>lSAgrV}u(3S;o!*6gto z8+GRDzM84#sT{h7=B@E6Az@_SRrK+aAj$HtgAvcROgEm;M1*P^GO(@XT2TOFU(|P@ z;8Sx3(q9ZYsTD!d<-L>a7TK3(>fmIKUPDn0vkuR6b zkT^^aegQA6&9kN=veC-6%}S8I&~>I@Sc0U~V3uOyru`ghD24Gzf4V2^60*b(7=E!&rZO`u;m3c0+5#B$T{ zbsWZ|eG2|>sbRPNW3J#C8;=sU8?LSJjsgEbLd$Vv@YVEkB*XFW)`M|7Mmug>jZ6eY zmD$q+B{1$Etf^7ITdbdXenqU0XOS5r*V4zI6trpRY8gz!C8>8Cp82Xz2boBgJo+Ue z(}rihP2S~C`#Me(QRW!!q@!7-*thvKNy{=B9$LIACbWsdKffK`e%s&+_%ug+z9=el z?|AdQgorvWF@{_h%Rx07E6G)#dobC<_gIK6ut$>d!#?#4M=GfeWdr_hex@uo2PW&u zbC37_wnOeyIIR@nQHUPB#3yE$|X1~^mkWhxKYdWIre z9St3%i}A_m=J}GjpCoNV592q@rSjQB|FzV;o@;tMASY2*7k~qH3oG%CWE&Y7Nn}64 z!#<`x&s9`YqBZekQY)=1?__tg1)i+&8wo0vv6P)oQ%a50Rq{^~1hY4VjTj)wusf;N zqe{n)fMNskf?nAu5j0c=Lysdhr6gQ97hg24VqNI!n8sA`pX z=Ej)ChPGDG(WeQfZ;v8*}KRxr^6|pY|*h6@sS%XcBkRP%9)?#`3Qb`f720< zahB^%5(4vhPME1iC5AsD?ct5X7-mjptl56_J=6p-?-s5GTRl;cunah(t~*@e5vX=#nRfkoTIhiCX!f?HTwa8V;hB`YPe9zSfO9KY<0 z%g=YDSBMc!LKY}o1GXw?sdzFknxM-j`LHt-z-QcuCuJ)v4b2+=;S!D zB!jvz6SWE7#M~>%fCs3e26gvCsuXe@l|>oqku-zh6ekV8q{m_1+F8{W)kea<>~yuc zi${#a%OI$sm!1V+8f9a-$LDS0xpqYrV5pxbJgyTBK z6CUi>ayjqe`B;rrxp;VLXuXN~hVRZnqfg}Wq_&jgH%l{LeJ;mX)#sh1UXlwfE$?j( z8+ed%(RrAyC(if*Gn1|N!2FEJc49Rb+mwq!gPC)WE&>HQB}5iP6BdtDQl|QU=0Hsk zzHv4r z*jkg7NwX}!BE%CWIUQ3a$1S1;Xl^5z-eiXf7fXxuI^$l{e@;?q&oWX+*V&HRV>{(i zRm88}yC|!tsPkLMjJ&)jN$Pk6JV?2yrc*16QR7Q+uR{*=JYLsZJ4Ud&O%5{dZjibk z38ukZnX#uSQX8~gVCTN1TVYcJn~CTypjkpNFT|6u4ciDm9<;7| zS3>L0G{{5Qy5EVEt~x6d-;fc>VzD3VB7f!#uVVrO0h-)0P{w1Yg z^YI_1B0Bdb#d3xr%))7$^TNt#4iDuRa9ERr=l?kLa(Wz0*ieb`bI&zz9cZFL^Kw!O zmW42xEd&c5dW%He zB7X#bIDcRnPLrtgRrYf;Lj%HtwP?O%>M-)uYQ#5+w%yG^K~?PQenDV?W9G-@YH8zd~-KIT=e=$$C!gw@s1q%7}I zXzR7;STCh1Ru)4y$dSDdV6<)d_uY7F6!Et)2MYpk)w#Z?e($;2?+ofIaLFm$+HW)` zYfNDwl3ehG6*Hv>5gQ|*exq*8B0F+YWSX)qpsW$~KRzI}CT$l#@qJ3#mjiCd!00E8 z5sW0%X6lR~;t`x18h&^FV;W9X*?V1=Ftt@r_|HP5SrtKYHS(|X^u0wjWMFIeS8`{Gha9{Wdsn@lQauYc5I;s!QJ3umRITcd?;jgGSAI1Cl@uy%hH#%J2O5QZ*uaSV=86q348EXa;_&KZ)%E)GG2x zu;3Tzq~9J7{zd&nc1aBtc-Ph|EVaR};7oxe2@}6DG|dNH?2;6(ieq4a}5mC2)>Az>MA_$ipZx; z*~`{>g*Z~iXL7pQg;E=1)>mM1o8`qvY1WQmdwjuTAq`PpM!qUE{2*qoEU~fr@5VzW zw8=yo&q!{5lFN4e%><-96?gJ7Q*Db1p0|C`bSeq0DML<5d=u^=q4%M@r=tP;c~N0w zbhBbGV|0@mRu|atch3hbjNebB}GwOpQ}59r$L2+=q38vIG*W#L4|jr(HQSC7zMkO zaOC2>h`_p71lk`ilF`Q?P^*Oxl=n0R@%FekTgY}-{$zpHsL=Esb%$}mo|YSbO+nE` z;NxsV4Gke9u$qg73$Ar4D!PK4*`z6=kE54z#0;8~)?8D|USRWcZil6E)?`cjoIG;U zbdP;Oxoa-XDsI_Dd;-6bJ2_hQ5gAPB!;pAOl0*ekE+G#P9=n5-X zfb<>T75TxAUSe)bt3uu*nzjevR_71jg%c-M63q8I+tud;&!86iJ)GNyi4Mv(0u z=?`Ds@_(W96k&fLar@S5CDS=S&qYf!`1cCHqJdBS;nu%V{ea)jo!kA3d}pdbU_qk4 zat2}Bew-*dBa;yxxaHlUG*->jZNw!{I5;B&hRgN@K2H|lER?fPMUlLzj1kZ3~XiGm=0{Woeyi{7|ePYL*-Q&i8$*VAO%i=%0+ zf=<3-o#PTK3!!CTGo;Fuxdnm&(V%_oE#(uz=o*yrk_ZtSCN9YUJY{jTvr3g7h^(j0LDWi``aZtVa z)`* zF5;hW^I|^uH>cNNUk{ z*Yl|tfa2KTsqncZ2Z$*)p-GmjIMN3S>XVH-S}<4u4rq>rcUY`iY;FyHAp zIA4GS)I7gRdotkOsPqW&J;Ns~40B;z3E~iJqM8hq(J!=bbvCfn3c$U^wP<&sxuPpV z(Wx01vkb6&d5=7LDoo5DvV5XkE~)$^zU;j`19xw9h$GvrlmFEaV|tQS_$`QG_Q}+5 z_dwp{Lu`A`{h`Z_n%kZ+Moo_Jt9s#r$t|@Hm638^Em#s0<;hk`Hf^V=-ti?{Es1)x z6*U{jJ6n+8IXO;CxpaaKe7MMJk09hMAg_iah$8geoJ?ekS1GIZ@u_FL{^1OHvwN0t z!1070uA+8jh=T5!JgSCrl5c4a%r1@=@qAQ^Z&r5qCviOAMBi3t zF7|I-KI|VWCsMVb%+^19Y6-WtAm(Iy##+lZ%+&2X=-Ki&2XZtragEc}&3I$J51L-v zR(M`JfJhF=MX*O}U?L5n7Vwn(K&`n1A*LePzG0!x$9yLyQ8|Y`%H=jp{MwyvjM>QI zfRoE(%B)nQGZIb6^4k8SRq^(tgI-j(a|`%fCk8m)yltic}}N$BmE292&Wr!|=@F5l`N zyvc%E;n*aB`c(uO%80r-*kok3kzukcia(GmzPmY4fVf-Fnc9^zYo4c+AI_{hlVv|w zq-{Qlb7UzKeR~NQtWB%&oZ)^VOMDfk7RBE^ibZoxIzc!7xeNJBjFMQI$WZ!9!(+zG z6gYEJNN&{(Z2-gUhwksGB*y-iV_Ll}xn&HUh-)!aO&6M(vI#xhC-GMf`ggJo2lu5^ zMxyGq7ROlXxir#>$DKVHX-fv9CdF^1)iPryfKn^6<#&yKNfC5ia~U(Ljim6k*(XYc zF})`vbP6o>reJ%hxT zMq8@AVkmm+CCS&;HkV44S!5m-u6{i+nA7dSV3r2p3Rvd>`-T^iCXE#!CfvycgIQ54 z5rPHr69;}N%?XsSzBj77@iIRsN{$*W;(rA*tnKk63-JcQjVfd$LHEq7kT62?h%+}p6)%mv4@}{sNom$_6=^ZK2rY8LJcdPD6HKk z^0EY+S)=7HK8ESRMzretEDQG~>csHcr%sowt$k9>) z2&n7&0`ksJyVG?1FOto!3kr@0s6`z^?Lpz%3iH-O_H{~8d^(rp z6%*Gvs_-CRvJ9wc(6;`Zj*Sv5n(WT?0waWZ$}ytvqEt^zIj@sK`Q%d~X9hckPI7oY zaTny4Wau_o;`qn|k)U4BKR^Divja)}8=2CcH9bRYMX|nzHq$6M^yfeG{^(f=g5GeC zv>DRQTPlpZH+Xpuzh3TGutGoSiE-G5>`GWiod?Thjy~;}2K^oBAXcpyt{vd$qVD{H67E9#e` z_Pk2FDc;^ey1uofyeT4*(?1=Yt>mAYrS?M)dK?{B;R_GZ3Mi7%yzia&QFtz0C4C&c zn>v)mloY>cT%PS+%hL^Tk~((MdtROZJdOv$t`Wcmrs3Bl&Y5@43V7nYd@D0RB9&qE z?O>}Wh)tbj$>t=8qjgV6EKtq$f+X3jO~A;%yp)~Ndl=phbepDy;XtjWUJ zbdjj3yZp}GQSt@fB|Lf_g7uhE8pi`;PqG{Sk!jg(IDY0q97zz9qY`RN^+?Q8V@z^f z?XugZ|9zSB@KBgi0M`<+$nxCq)dMlrnR%4O6hE`dil zfW5oXu%ssJ`hhFCO6W~&llX2oF?%AT)TgCREB8^|E!_sbX6MEY+ZI)|7(IP62^-dn zhH9QBI2p>ZdzX0@b6^4;`!$6r*(O&t%KjM_MR8*3YZUKKh$j>BzpHIq4$RhP$sGi} zWWy2bp>aJcHFv$%Tzpv5NtfDpS=Ik9RH`p5Lo8E}AP@%}F{`+o)5_SVi{0ADcu@GU z5!`qn`>~}I-<`Pxv-#%Cs2Mnxxbad)pU3yJa$@2WeR&u7WLJ41no^@A5ZuCeY2H!a zJlNQ)#!O@s$1Q|^Pk<9|IAI%CY_2}zBZ^9P>2?uBP7P7D2WjGSnyTIDmM03NKv}m0 zOT@8>4Pl{Kd7;zI*)Ovs0&Li6uVq>w0phS0xaLF(-5h@gE(hq1`89z zf#nHLKG+N&H)V5wu$aDjXWrnyvJLn#A!A#D zRkFF}Nl;u1Tg0zP4$xMz@vU5s>kUpxzi&=5{<{%J$u9=9?xA{rJFl%6`=f)8V0X*KDhlJj z{B=c@Tj2tq%`UUG$m5@7PXr9f&YANJ)92zxwR1{KD0+K{sbXlvzM+@*gQn|tnIR78 zJ7%IUi!@(s&f)65AY7Rc?YmKatcx$Wi>?!9W)clAbC{%x1aBVJ1lF?)?=R&@o}9cm z8swyN0DY`b@jdfJL8pn@Z9uZpOK*YB`=x060d}G&r_}$YhPqAaj@<`k{JA4mlHp@r zok9ux3O9Nsa6*U+=uec@sR*ku?9a@ueXv!7*Qq^=oa?UPa@QCKYWs@dx4mCYn+K;G zz^(=&#~3`NA32gp{c8+Y3L7x8S%p2{oMjQ}+5KTVbe$EFgs^7wS@LAeh;PRZb@N!A zlDfC79)$cQ*Irs9)a!1;g(H;yV3VsXATL$k1$~Y%>yWl5Cqgz2dDOLQ(A zFgPR~d5y}xX_i&vCm@PMB>|jAvP?@O(s+Pj6PGL#un@VFnEpRLgqKVrggK{74r99? zLDfQH_K#31E(SFT{3`D+f6G%*^*xYnCPA|SzZgHU??D$Yp%vq-^Uq!pGEd(-tM^s| z4v66l8T=?8_GZs+hb`#x)1D<$oTnEc1$DoiluKO$DP|&u7= zUbJT5b(q$5}f#ua(u)!nq&z{dYDvK|}n_ zSN&FdXUD7M-7%dBR!HdT1yHk3W$s69QMV~;u~-=ej52*K>cBuu5OR-!n@lVSiS)CF zUM(#&bG2P7==Dwf%))SkY{r3fX1+qO1Eo6#cJ@(C$~`@cqvr_P>$MOw6ahL-&{vH` zvlan^C55k(S(Uik>@pfx<_Yuloap*JCj|y%`8Io%?COQ@Qtr1K(T#Xd zahjW4v8RDsUVVlJyHHH0=iLV9-Eu+s)p5dU9e|Kq_Y=9q$f$^H8|SvmE|~!k_^Umo zn4j?VZ+D+@5(EAN1*{}+MTY+qTj)AB|M5<3Pxh+)TaS|%Z?9C==LCg^ zlLHJP_#-5IOUaO@811xb!nS_V6e+MjwJzI{?=+*!geG@ z&LP~G<~`kjKpJ93ZeQEtqn(RTu5$V#&+!MjkM5G z(F@n7HiJS1w5~PzmcB#OdgE*=)oxEcWF<6~f3X941RN+{cB{kiHcW()-`k&-X4UZ7 z7zbC;UG;z2wI8AE!I2e|Nv`?zp5MQSN=)Jayylj!bK_{$5<5Xs`US&z^o|i7H{q>BC_R(fy`G^k6&JQ*Sg#Hinv&7%Vl}kOW^IW@ z{;hs z@q|UGSt<#7t!P_X6Z3HLAPciL=gB~ zed-%#%nVGDU&<1T{2}YK>SD7Jk>IIh(i^e4Er?Al+0SBw5ju9=CFVo*F&)<>Ig312 zHV-sk;MvS+)p)#p%zkrcFq~}yc1pV>yLTM5E7HT6Gf0NZ`0Ohp=AsR~C5%u(K*d|q zh8pVD9QeG$G&}Zkl5w7vJa$*R-Ck@DoD{@x(0_I-M05tk#pcYF4e)?vl1k~~^Yd?L z&HVvyWCX#o9hIRh7r*Q!IH>0A^Vim= z5QzqxM94H*Ok9LXhUuY?$Z1`ENkdGfE9aZ8hO6;NKbecLx5Qfq!S<-x>IK2L7Fa ze`ny|8TkL60nspY7m`?iY>)sle8Ywfl2Vf3Atfy(en|f$z5e*=zYm%9$42o(_J1GZ zUkAS^1^&wZB>mI>e*gdaiD(4q`U|4B(DsdzBq>)(iT%)q?GlpPB}B~60DgLs1kLp1+^+OuRPn^^_bz0Z(ywL??6H_xgdk07KMJH#^ zKfSJa`}q0=1&7=W4GWLBbNAl;*ava(Ny(3iDXCAMrsd@3B&B4;*y?pO|6y2KYB}I zE2;SDGORJl@M5%62IZnoZVB-YHfT#Zvtr-hTzp-r#pc8oFLfdofQZ z;n71?VD|pA+sd+9OCB;G&9{84W)=-890)eHwU!DHC@_!bRHL9Ja>zti{Irdyf}1E&xXBfOf{UF?%5HR%f<>qPEa0-_%`q3z=CE@aq=wA`>s4$_!xf|mTaOW^*M9_O1t+PV)bpBd&u=_{ePT`JB z)=YBC&mD**|0%AXm5!h~0yU;yUy83b;l-`lG+|j zt`St5s|XruIb6#7-D+3UYMh@O$L!a=dWGa?2Ud)>b8>tr-*WjE7kCwG_RrNt(6wUm zd-J~y^PTs_T66S;5{w&w*2 zchEHPUDmDRw9#lDH(y{3PLogE0xsbvmjt)Ri`LM?5&(VFo23PS53}2%<31 zU75pnw)m^va1p{iLMgM(-s*O7+k1t%XERE;|!P$Hn}hT<(EJ0EGb|L8}B5wD#g zYZI=@#r#a& zMz68KBo1=oV~F_~|BnSU7wdA|(Q$8?zV{BO z@}*duPA~319Lug2XP1)v@hA~AZwktbN_jsI{R26VUdicdO3MjTv#-Ux@RMU;g`4By z;MT>S-MGo<4-S|iTU1)5t4#mgW+Sr<4fQwZ@G0r@u%EN~h6V+X99$LDuAURK>CyPA zpBYB8Gi%dxG||p@tNCQO+adK0r&V)K`I)IhMYL+Uq1>zu@#^azKh?Vj7*0molY4Tq zB-?z zMMs0T%p$b@{?m<8yk4p<%^T~|Pya?)dWKvA%dqy<|Evv^ptk7~5*!I;3 zn*;W7J(*75UOsBJ6+s;ut>(MS3*m*}KF9At>^-i(iJ;apJAzf3#=OeI&fd?85hyEBSl4<2Z({=|QtA@~ke->zRs2ji7f^UYyionnX31 z%`A=a^}{KHSK`g|hCk+sAdlN!CgxAPM34houj{quotl2s5^1!ikDmVZR=+WFan64B zqRkw!0vmFXamynw;lU)h1jc7U<2j!N7x5XM%^^1WrppMd4a#y zp}6P~(NjY$NU>^gM`4QxS{g)9x@uH)#B}#1ALUNvVx6|BhTz0G;slG@- zzY9G#oz+^}-?e~@SpB+KfS_wkHc)B#3$aYR%9q@Jb>RRg2d|$jlCag`4uqPMEaL#> z;^SmKHJfQlnIzs=8L>G~9XlZTRSCoTt6C~8ult794Td>duf1tFzSTjw(wNoN#V#Sd z{@dIxywN^5@_I$TDak^OSD4GU#F$O7`S#jw;SQ-ao-7$tRY3)gAB`9a!k4GiVygPI z&CQ4R@})v-F`!}|9?ed+PX{DTlQQ&3*cW+;wQ&|z1(ST1>W3yn`S#r%Vp^0?xPW>S zQLNfGvOnTolJk92f4Qr{kvq*yuLxm77I{?vPZW=IO9X`|1@S%cm#(&j2wQAlQ{ZV@ zX}Bsp+y^Q{1mUXk+qtqOy4jhhQGkAE$_S!1^`tJ@EZq6Jm*xjfp_^3<#vb$>OYF&y zch3aisDG=1#Rc`&f>j`7UTV|Y4o*ggb#N^dv(QKL15@}Ss%zASMXnCc(vNFk6-7}- z`%u2IpRgJg0-6Rvr*qa#nlFWoE+AA5$fZx(8(`C0f|7zWv5X?Vg=fnU;Ut!`bpz{Q zb10_1B+1Rwd!$tI$5=g?Vm<}8OMXr796txmr1Ovzu38htENanfKks_r4a z`bz5*xZHcv*)+yL4C`QP`jVZo)+G`2mToSTX}onese4~_x^Ct<~Z*qP0Q2x(2KTadY|mOKWWNc zb4w&2s4~{FUo~zsRt`}9rnS?2;dpdGrB~~5Q+4j4$V)FzOeDQJ`~w~d1Z7V%qL<@C za+9pDOkG3=cq6}&PgTwkN1WEmJ{aKFnJ8YJ@NUzjJ8e^#0P*33_NNzIcTVFXaOaN6jEZ^6N9i7*NQJvvjb&nW~2=N3qvs* z=@DJ9hoe^TkRGPqY;(52uD8l>UJG@<)=e2X0<@Q~lp6P!0ePFRF}T}B(54;&>}C&E zL@qLdk&p#AjKdASy&=iI;)}#S_ki^hcBoqfmC8$K)&K7N+@!>ewrJnuEL^O8`=RDx zds2BDl4#8hHgV4gvJ*#x3Ex%KdN1_hj z>T#J%G#9?A$?gADe3p}eMu#0vG!`CrNW^_(ZTzw7SzOX}l{w=f)Sdm$z~vMximQST z>m=*rTxK;cQaG5&I5cV@Y$merCK)1mnH0<>;Xq>e^PTmvaGd7z##ReSE^(!$i&$i_ zHGF9ZAL>@qY{lJVj^qcT30z9OnSg#m_$&L=&icwac=G11KNbnwIYy$GxbwZ6ip*Ojz>MUYhe1| zlHs>;&J3!{IK(v7?a!M%_r(g4Z0it_q#L@yOg-oC?Lzhsu1KbsbWbu$?$o5RpOAm=)_gLjuVNnGaK?D~ zhk@3kwY}upo6j%6l)!qLl~A^X*0{TcmHD#^e(w@Iq_#qJ#0cy%l>{oB*MR?%qV}$+ zy`%iKC-siNX7kyV&gp||e3l4W?V;>A@z5#fO?VEUC`>^tJD@mf2?YK%T<5Bv`_@+? zC>|)hn=cJgz_B6-D<`N0uw#LmCJ44sJ{Pt=-&()iSQ|dpU^$o-8Jc(!#cLNPeWcta zv>x;3k8C^hjyHc&Cl2nKAQx6O*k1m@by)fHhQ;MD5p=MfjgsIH*uGmb=kT}dKdXNP zIwb;c%263VVTPZ7-Me<@duFq5)n1NQqRPsF5oJ4c!t7#|d5XGGAcl7P%^ghD8Crgb(fg7^HC~5|-IV=YBMwf^noGzaM z90R6{KbOE!Sg{R2+E-GmYAHPdG$DA=f)IGO0J$=izOwh7BTl1-7GaV}0YuJZD(kzzYn{hw`i*vl%K5%cNtm`#9#qeMOMe*ipG2kI8u7Mj8T5!BZh zp^H_rWP8iZZPc8rGJrv()|uPJAhjIjSxY$-WcX|61KJ#;GZDM!(DjmA{SESft7^t8wCSX`mmyZ(z&YF@ zCquJ2WN`8FO!6>}p6_d_wn#sim+&+@h>cp-O+%geM2Z{8&)S^WH#?9eE(3c9LahnR z>K>2XH#dFv$Bj<6Khk`*_4EP&uo1^CiQ%?r2dsKsLiX$GtZmnH(@djCY2(O4a}E9r zZ!56KCFPnjrtXwqun2N-lK9$+e5&M{Q2QoQ1Zn06r!c6ecGz;=1B?z(>P!AcpYAvI zJUMXz(1O%GI!l^8QFZstT~HjQGxq`rs?P^}DE&4HeFHt{LRa6vJCp)z(vD*o?QeY0 zr-bFUHGRMfp>cgNhlPDfO(A1|lUsdHYJB{N48Fi|yakth5%YQwGq~*QLYhg~P{2 z=8cT}E}c#Q9Y)9q^$qA*yH@+TA0eNEci0%|>rzksjPe7jDVuK}ETQ(4Ev+27q@k<% zOcqgX{0EMx0A0*^0#Hv$!W3ZdA)j(kgfS;$7i@YF`9U!#v-l%@HsVEii*HS7Js&I) zxT(TExy&3H0aX|s)wQ=ZowSyY*QmD*e+G11%wZQ1R8}T6>tI*rZ24G8a?WH7 zAqdT(cqqj*s{O@?3dx~}c+X>?Iq_y0A9Y6PG;nH;Sm-UR(0o#Qy3eWQx7SuD8&nMA z>ls~ebcE$oMZUu4kmrf{E&O(#%Xhexww$C!gxk4q%;ABqq((AF(SJ)?;m{A^Wb`&u zfoEqY>TYy@Zi`k~oyAVUiU`8PZutGEz4{Pgbz#rCie&JY5k>E|*G zJOw@c0(uEKZ@lsuv6+6IgLcAmQsy$>y;*ccudtU@#$AWpi?^WduA0HE9K^~Vm-H}v zH2*1TrHkk5dP+n1Nq}!2mEjc}oDo(|u!bAUsO|Vl#0M*mle^6Q&#(v@_b(KViJ)PE zFaq71C}aWc{MDM=Wg-k}wq}KxV)B9ICz%ufttD1a$zLmkJ$r22AbCJP|M>ub2*u~% zsoHU_?pOyAC4qBEj9EjeDMW(t8u-yZKGSp`g)!X||O|GhxD0~jSSUDM96^?mRv><{825tvu8J{*F zPEp%MP?h(+spO_m)FOHi+f#2haW6J~tQJ&Dj~9|$CC-Y!er!DQ*Hk`pRbiSp#MfaJ zRr8SqodJXF6<=4^&vPcW%?pbS8OlC>k_2*r74**PUs_h`?YI1eyC z=mV*r5-O7c5)nUNGssKGEkJ?G4+gCuFX8b7*3i&=wt>L)H#!gdY`}2+jRn*ig#vO%J4OZ9uVey~bfKi7LR_^}h$^J7+gH6Kq}T^4E)zld z_PFXRsPCnkN6dPChYk6ro*tsq8rY?2cCc*A*L-^Hbrt{h@&v)!XGYCUZn9?Aub! zU5z_09O-W;?BKVz);wg#x$L@u6V}EzW!!s)sV7@@kC)4t!wV4xsnb}vU&d+X<_+Ou zV>L%k1R;owSI-XuLnn;L(s>(+8AY{W&b_ZfMT8BKmkCv+t?Ab?7wxIap@N^XY6xw& zP~VDwq)>e9Q8#h6U2(vg==w@~hpLgAXBJ28T>1U*o>bn#4iO}bCZjlg)j}V9RpC5; zoE(FZKS8-Kf_}cb=Yt3`Pcu3ADwv;y??v&vFm$CGii;v>I`gRj{|)dgqJS-e-rYof zPk$lo#cy83`(p30HVJ=Q{I)t#ELx2=XSoNF>^59?Bf3nXg%SW4nxv)2gPUXILuK$MX-0ee_9W|MPKx*Gu%fAGe}C>XLal85YzdvbDO4%;EbaCw;I16=$ItdjB&WXS; zfkK81bPCxe1Hlvy`;Tbes+I;q`#jmQ@-EhF<>)l!)*1guvc~Z;^(7wqFzgHXO9X@P z=R$7sqC=bNs!F-;8M5XTP0LaGr}FD3Nu8NypA*b_YJfLf`?kT>*g9{WJ;;H(w5mNK z1ORk$dvV!hUIIcpwVhEUnFst+kJC}@8M21%HqwdG z5Z{4((oKNiIk4ulZx1^eC7*DI!+SWE*h8BAT8(t-&Xo<+1$RVk`3*!HZQ+*x2{Hkx z*GIl}4PYyJc6y;L3r=kbJ%*mzmaWJ$in4~B9ef2RT8HpkLmZWM0B~gf z;`ybNa{GSf*z@I!UHM^QcN!C>(O50ta7tjsga~qSwz*k;tg2SY)TR~qq7LEA z1PV9!WT{KIflD7S|9XhJU(RMW()hGmJ8_Y;w;H$$@S_`m$Ih~#TUr1a!31uL$%zM& zBmNQJTIw-?q){yK>{j6ATL5%Z7prC{4+fEd4ItS$F#xq#MY$!ia!>jJ>3Xl`oZ`+r zo(Se?YtWv1@?hoN!IbQz_^ANR^0Gz29Zcqd!a`>+ecdlo6h=FN>-FFDDHg(3O0K0m zb;;iWWM?SJA-~B>6dR$zlG3d>_gUdUh?2sLghzaWE}|MTwdr7Mgwn0e+3Ke|fbI;` ztx>u%2uvHZud4=+p&|Fa@aI@F-A(T+{4aZ^RF#p4z{+{E@5HBbfwU#GDV9C(B4E6{ z$-EjKk-7HE{P8y!9j}O+v5HH2ncQht+#o@A1z|oK9Y%@>ZfQavZ*+9?`ZjDR(LIhZSwQ z_0CD9RQ?WtQmnk`c_>D!FpbIubMy|lcbDWIU@8!;7Uu7C*R(>izTxwILq!ndGowrB z1mdAq%4}J*rR1I2~h)&@l)>z_xHc;=apf`GRde)5!50Z++aJj+no}I^0tawb%qoCWz)`d=&WYp z;X+J%=52x1q#o)|{BvFS8n7$1qe-JfyD`%>5y_k*az6~}Q6Cc;sJ?E>>k zPWE?y)DGtbTIHX!aGPddZ$3^#*eZgQe_f_LSjg`OOgql8V)7k|uc*K`M=Wn=qbQgg zL@MiX*TlDB4PJxwU*RupfIlQ&_3p(}JG#NzvjGBJ9kP6kGK={5U-1X!$)f4K-@EMz>-Tr|a}EZ_MTcgg-(iJ*^7c zS-PijOhCspTEf+GTr8_|_t64hc&4%e+e0p{oZVy7=IqFJxU;W1@U$jKg?fy2zLlv@ zmR;2qZ6=L67iYdS$^=<;l+|?bF7aGxqxH6h&tzg zVt{b`sM@k4@mZsnMYz27aJ}}It9Ttm&GfyghiGBXpdf_PQWS3Bg*T_wWX9yweOW^8 zHxpt7rulHHb=XaG^OZiU(ss)IpqnD7=Z(MBSoy(GtAlU+H*r4svVQR_so*oIv%(9g zNLLHWXgSrAjyV%|W@a(urqKAwbBC+vE-rIXjGk9olfZ)Q2a33L!KN<>o=d3bwVpc= zqH3&UdR81DO6%+PiiaXY|DzDaYstq|e-7Rv#y0fX9X2+twjgE%)|%LukP1fmx!{>q zNq7aw7-(H;%3$ccczAz z(E@u!-XVghYb~`BJ*Ud=1HRuR^s_^}M{wbnpnLLzs(F^g8HiU4iuYVSAfe!d6XH~J zbhicmPzcd=P=Djl_uWz9p^NOaSUo#6;ur0FyT9Y6Y9Abg`+bdt<;AUtCFMOm3A)f% zpg^cIE8#V=uJ{lt%8Ms@sH^Lo#G5S%8%QeY`O`&SEq{jG!LmmKsDIQ~26)T$%kG+Ytb30px;v&UG zg?DWF0T_?5El_3NZTvxl$tX=g2DZSl^$32bU;~ANjo$Qb+(Q3A`nh`HWUGKLjwuR6 z(BO_nK^P^}>7@}{cp+3cjxUWEx`)3a!$k_BI6C82cktU!VD67UCDAOZ|+{n1*q<^?`5rybS5ZZ}-j)lWV>{Vl0;i)NTl?>pfn1tBn2qMKvxe zf%4n&Nb-Dx;R1g3b7RpmDsC+0cs+vA)42H|L&u8!Kv=(we>6L>OtJZp*;_L|z2ewq zU-|03Q+?HIMlTFBFs3JUzHH?RRyj;dPltpOSOixMQp8Rxquorn2Y-bUzth+GwvYCw z?!3$oL|6p}Mz;Il3%<;w(u0_)*`Io1urEH5Z=)og z*lmmQONiN&q^nY_4uLwqv&{VLPGe!IBP)IA#m@YY2n?^8XMH?k7s3A#vEO*>l`tH2 z5shY9jZi;(`Xiif<#>xNOAXBj^@T;rWjB<(C_3%4!0<`8Rx?B7L$0f+aOazh0lkpG z9t_3CbsLDrv&tPuokuH^*~HdMI=yAiIHEj$u7{x3nI}d-3zK?Mnl7YL+*>9mHXtPe zK{tXd&}JoKk6kSxuV|uJU1D}1AG{r~upnc(r{)LjjD#eRFw7dKPks4`NEFa~;DwvJ z81GTE@@=|3po!zq&d&0ng6U8AYPA@^%~h6h`C0=D=?0VdBO++8o;31q`RMM;KBJTh z!XD5ua+QOd+H21h$NQ9L=L5OZh*39udh8|_a-oAO(Dr*Cf=RlH(5!hPt zAE!Dc2B-{RKmtyplk*q8!bs+n(NH!4zEtAdlj$C_ z!&q$iIu>xjX+yP>(TDWNn)yci8UuhY=y30n8t90$FPmIFP*NsP_!N|6oB5ikD5&qR z0^;YaqUXc*L1&v5elzJti?dBDzd38`!&8*d_%*F<$Wb-6W?b($pEx_@iV3_^vn4_? z7F2HZ7o5zOE0n%pV>y~_^(g->w&5?SUlG!4zU9?Y>E3PbDGr814yP)kj4Sh^Z+&mr zqlGj#@$W8CvwGNGIi_h!xlO^oMS7bEg0{O1Is6Albl~+D&Yr){CDtaI<>LBtV2u)H z)~3g;vvw4}SP&JW&+e`q8l1Zssv7`Tp&hBR2aXx)2qHW8(dv>;qn7G~kO=zz3bFi0 zde`9I2}!~4oS-eK?vg8NOKY=@g1<#jmw7mfP7ua3=&)pck;kJIcL}~3u9GH*_qV#u zYkiB4|5*fO`OESjcBcP$Q4e6z|Dy<+%|r1HjlQ{lqT#7R7voBw7VhH`16$toHf?P{ zG0q$K@3rI-%2fc>dq2=#Vm@?6jv)z$hXz)y($0hA;{-+UGD$4rx3>ASob=N8Ta2V1 zVH1cDhhUJ$E7f!Ua<=Ll*rP2T6`=z$&< zS0`@zU>7rFILWhiHnZ)S-Q)hI{tCc<|0n{YMy{u!a`J(=*GV0GWe}s;4~R4Xqk0s=9fZNU;`0g^vlVZINJ|sj`SRMFRKnMdmIV6sC(oRKvoLi6C!IE!u zfQ*pea*(y)Dc0;CkKM@gI=G?4_<6{6^PL>Dc@7Xn<=1HNW%BP|7NUmlmix7gby;?! z`txrd8mP56g4Fa1PNc@h8I)`=JmBs*a5WLfsL{}Q*jf6yQl_0z++PL^82ZUmz(Ev~ zBXKpbw;BSH4@rFC_&C(zZ`kkRB;!YxoJl2x|D+7GBK=7|T2sd;Ayw9ag{xB``2rBD ziz^*2+kxfT`dG|?#7RI*3W#C9WccXH`iSSG_N_;7@dRk2p4ngqj>ym22m%Kq*H>8^ zbTih;+wG!xpW%+lO#(XnO7FBUeyqU^n~G1wh^V8`BM#alU3Y@1W<2{D_*|o_peP?u3%nFV{Ioj!ih$d3u?g}q< zNd;&MXm+C7dG|D4t5_K8G6YeLuiL>)wTSQYz-#Ss0fSi4On05vqeW;ck2-fN?WiZU zRs$pEA&^%+We#FL_?*<^f9&U=7;qVtBy1>rrs@T_Bx~bKJjIm1#F5sGpO&BiE_bW9 zh{RxL$%3kYwiY)|sb_7>EYp4t`#y&3;~Z$!y0j$`l<5aF?AUQF;5Is!t_TzYb*KK5 z1WMRI%(}J!l-^$H&wh>IqIw$ecOOGM(2<_C;WTK!%aSP+o0#!X#D7B+31Els1WWKh zLIJQmON=1UJ*N%GR!a32{M-)`s`c!iOvZrNFEs>x9(wcEL8&B@Nk(pw=SP@np%eib z?xURP>+YBW7E!{BQt6Kx)5-k0&IDwwi!x@hr#40)%@bJ=`5@mUgP1v_ExeD^u>N>vzK&Y*K^1c)3Xs0fk9olbBzmBgksY;TRk$!@%qd z3CQZwq!`pM`0ppc<W0xk%`m&OWZ+^5ilAEz5`2_DZKT8U~9=(M8Gjp}4QEOlxbu%@ymCZs2EHAm=9+;R9#jK3oU>I~EeZ9wi7Plo(Wny_Fz~^7K)2g;PZqh1QZg0rF-VLFk-(9MKkJE8A}S zsjoMt%piZ32PQ!G6#q*g0`#A%iX#?FucC;_Q$)+6i?oBRVfR^1uA zT1RnS(R?*tt1gn=0o zwA}jOtlqpVB%HfnYfz7z&+S};_h6HMkk56m)#fDX4bdvQvmbIaBSxw1O?(mt%FRa$m26`U!6}571AkrT zCiZnVO+(ca8vD||45PbV#KLl8wkTYM+#R@@UQzu zJZ}6=On!c=-dLX=D-`mCsTBXN+rQC|iXdO30AU%OOI?{tWw`}TA-Ge_<G5SycZ&OAl0IW<-IWi_pXtCeuT+V< zC?ldMfpu~djEm=>~$XSi*j*mvJL$ccKDq5MhGrqJ;k?z_o&fK$s z1Ojei5@;uqSwO2FzYOp;K3?h~c)5RIH?L?MG$*Zy+t>0*YinZXb&6|mb5;tZ=??K^ zaatKI4_ta+gl-kc8v{-a?F6bNmhSk20akDza3}1^L&d`BPbG=eED0qG1n(X2bHKN& z?_JUo@_`ZJBjh6*NH#!ZyQePZ2kjd#bgsd|8aW{)H(I9VZ^xX}8ZR%g0=DO+!4~$f zWRva%d>GLGo{<+`ko}hh25#Z3Sbw(WV7-n%TaVOpn|06AttitnO707;zes#$ zsWFO3=4dtx&ZauP_lF+~f7uIL&lN>Mr61|CV{_naPR+^nfpc}cNsbxFQ-a&J% zsAz*4{f`m_OWl8}d@TK}>^_h&dd9XV6#zD$1B|fGQaamli}kc|?wU)bGs4f;eSiQQ@nib=3<=f)jn`dk1 zce$(FSEqd{qen*|v;bP9cUf84EA(I(Y;DL zC;LC1n9X_3XSOm`-taH-G=RpQ^P#uqt{A8DpZZr+QnML7AePe)s{3i}m|YdHKk~it zQ>J`s8S)#K*y>sBu^}Fqe6afAo%vQu+d^s?JZs%EyJlwxl12-%zOH2crK~6%UC#J) zMw9Cg7whc>{CWD(k${tUCA_QiWbE)-9vJ%K$MN0!)vwt?}6%z?g^?$BV})A&06#-3WcY)C9boo)3zOGHU~xg(d1eWDW?~Y3 z00E|e6Dm_%>+z z@EOaJ)i^2Kl#~JRT4Iw3QnJkO6?^3xAZzrqpS7_$yGz4JsC!F%bvH!%)!I)0ze(ma z2-N(X@0&D6p)D>QTu(y-bqi1-FROA>*&&~#kV7dnI6#F}LY$EZM13zwyh*wV3;^}h zA4@!FY%=KBKrx98AO^hWnKk-?z>Z^}vwd#ha~p2(FiUQly;Wf)PiBonvxh*}!7SpQ zaG$WR|JPWru;;PJ$FGP<_B)ABSSLLW|uYlh!GM`Y2s{TPNETI_oo;Luz4^?;&ip_b7Qk z14Zfy!ri*9pE8#paTYg+m)WSoO#nF&1Eb#X4Y1V)yzukJ(<_B{LXfgyNx(POT|>>D z3<}?iVB_cT@G!LxFSAr{yduf+8>s(vtn+l?3idsBVr6Se4mdhr1YPb>BL;z5p^xuI z=9vR79sUP%Zu*HF_MQRZP9?T@B03xXS@;gWt8@`3J0sjnskh>o3e-xzIazogGX@b> zU@JB#K#i!#>lzL31|Z9O4VtvZR=n@c>zVou_b@h2k;f=+!OjE$B4~xygx}eS@O>4b zb6;>H&uK*UUd^Jg^9H}GY8ZgK)}KjxpB#jz`9wGZ*NoFiZK24FRo3A%&G9OrZ;Lt= z4t5doRo2MzziH&}30s;rc%PG(kVh^??a=(Me=FYGm86>hdH{@pSz&8@?u$4Ov6}&* zu(~8@I2E@8sDn;`&Nh&4h+F)`60-qdnRMQ)RRJK7K?DB~NcuCe=D$m~rJmg>Jsj~Z==xIiEqhNvyMH%6`+5c_>23X@;HAfH{k&KWhF zDH0Ht`nsuz?78PxeckScjPrkr431_1ZrW!$kYC^H-E17_sj6EygSDS$_yb*+8YA99R+!*iXmnGeLW#OKT5cS2 zacSrQ*l(4(@cI22QVkaQRP_d`v2~I3Be0XV+=sfUOsQb0{ z>Ep*I9(I-_wm4OEIJX3;}+TS#~%oQtdB zVY_;5wN%Wr>Bn;2+I1qR?!-LU_=0t6i_;|DfiIOOjbb&uqVhezHDy!-r`V;#)#6zL zaAd${n9rV%W|UMLEUbq+9DDO`C|B58ox+pM(rBN#dVPan=bh|cj(S2aFc2if-Jgc6 zBKotL1K96HGdXq8Aw8fZv=lyX2yYBH!LtVKRFL|^YEZ&W0YMe-6N%YvK9rPNefeT_ zg?`NnPQjz(9U4&`wBt6i!4Wk%Ros1U)cl6{)V8Hesm&auXwtE$AaS67JrA9N#dWofC6# zRRe$Ays@OvECZhqvl-y;0%=m_6j&BHz+j4iL)v6^rH_uxFRJuro+jcbS(zSqYzzc1a1*fLc3;8(8Z8ow#R_2jFcn<}Tt zJz*#b0Dy8`VTA}_96fq64v(1Hi6Bx^D(DDY>WVu=@k^-ENC$`tdT?f-yyVXd>_cG3 zB(Q1h0VfnXMf23f&p~dfpb?x8Y(%IC_OYx!3_AYYV^l!j^eSaCxfILp1}xIidDG@z%qsH^NT)NX&o zwkRj>iLFO`yY(JE(q(GpGYopYL-!@RiXlc{B@M~-!pt58kgWp~FT-Uhfd2|nI`MTYfP{t0cFB)Xe;B@4lONI)1MitcUGDg`iJ=k#`6`z$g;`1QOfxAd*_&X|ZYj zz5_x55^szHZlLphD<s=#- zmRaK0|J>tzYG)pfI21%EUiTm%*W%n1 z()!kq(;d4+5Z(Wru46QXH$+W{IiZD0cw?b_$RklR{iSfzLKUZE(+AGA*nqrnnh$7< z*D1fPq9(97zQmoL9BC7hgJyb79F%o?wp%x)X!CVuCv= z{ID!=?)`Oj>HneX&Euim-?;Hb?E5lX<0M=$ z1%BN@5SMRLG@d({D%@yCoH6UCa@3o0)gR+z_XuP90&NGlDXzj`S2u|$7=9`9MFv&V zH!p?Y=3-gC)Y%#*S|M_obhmrXShlz2sg zzv6h)#=+_uh3`Vy^`seX(p(r;)Il)uKg5mjRj(9dDR96l>|N@SU%xo}x_&X}vp58Wx zj~SYyy^If4B`KUS%iat=p@0VkFi5?N4|q;9xB!P$%s~$BFX)s|Lg$=|HSqYv&U=bW zy$hh;Zv*6tI#K?tc~rbl^f?v&&_9 zowGel85rX+be2xH(^T4{bE$q*2i<6uWS8qxZ)wXYm7Ciu8BeasG|eMB89Ad0({dkL z)m8N_<3nt@HN*od#<*?gdHK&tw_i+1E*`^qSwL5<`^fhh<7t{PZcDjp@C6e73(f8H zoI20VH2oOq+BSn5hFpOf2eQ$S%1;(zV)8Y@T5QczdFKM=_n19Z|W#mAV) z=~;O$b3^Al6fYjO#*o`IOHAd+ZVF}*7q;erh>Q$zHF4T&*NhDSoo9Z0>dXsYD-BP$ zB`I}poVW6ZUTsWCtaDOE(v1bnge7{L^b_fw6-J^=##>_cUHtI$WYi2pw3z}-RyI;y zN>BG%@vSE9u67ce0SFNmd;2ZOUHv9>+~3r_8IOv-k-{d@bVFgJ9=yQAmf$Sj^2_tk zChwAyy30?rCG?E+wwnF>pu;(tsOkSogf;s97p#klw8A z|so7vQw|*v#K~o6e1_TaLff#dKQpx7j zFU*Bj8Y(5-5}v3cEIS>m{K*rf0eO;qOD`9*dG|J(AV&om_j?jwU-E({`{1#kRi`K>R8dv5nNu~fk zlyx}`n6%j&am9G6iqVT4xaeGdVOVXA%Z*`nc^6uI_BK)FnDTJMvj_>n$0fbK*wIAd zLYnb0Lbvq|nJl6}Lte}%vC;v|KfzMNnYhzcg5@QOCb_dX55p|&jnn#|n4e{~^{f=A zZ%j$o*GLg%mR@OuR_wG<9)2Y0ADno(Yf|~)hWUt*TT?4Kt#ocMcT9|8ZG8ONci8Lh z49!oy-WLc}!|SwAg|i)7jKk9SpAA446&dp5s-JQt{D4tTDg|u~l+FK@&ip%i$#O@C zKjBv~X*pIY4Wb+6f4zIdjLmuqBe*T4SZ+`+Aw){FyHxRGK}#lM{53F*^FNj{tSl7uYoSvL^)YjtXzV(}^9+MA*BCgaC&fZK`u6 zCq)gGW^=kHYaInWw@)L!(o{aU{|SyK_{N6M)A%|@qCnh?LBr!l!3p8Rxvg5$q>W?! zXCXD{1u~#yEOaL43W||3Aj`Kf@=L|Jv%S0P%6&U^Cu3XJ0JS^xebK>5bezrjDI+vA zTIejbE?F_+dRh0aLr6CEhu@IR-C62MAx=72=4L=hqseC!OjJ zbUnul(LKKn3CW3%#4cW&pEWJb_FYd!1~S7MDy0B>Fuv1qfn=bNxZZiXsghsxY9~9b z4mu6#i-I_dJluvU=fc@#Mw$&5RN-j5Gs7$RZl+!Sj z_>uDN$&S5;B~-xAStC;C-j;VN^FHitR9bTWh<|DwbLXr^evp%3d4REu*#Lo)Gjpn2 zj@32Lw5Njh^cTisNSB;R?ui5`$|s}s2lPKO_Rg=Nr{xD-C0~s@CmiM7v?45Adq(N8 z8Fh>--~t_A;-uz()nnwt@H=OApEf9?gnjt9QMPwxD#``z_V5$CG(-Y#Plw9kqsX0z zM52S0WBZ3!Z4O!gX*Tv`$hmnmup}RQVqE3E`(Le$bn!&TnS#m0`LXk+q+*b z(*%pJ)yNxhNuwcmYh}tS@O+UC-)z_mVR7Ip8@23*P&NovxJVv^iMS|f$du9r@gtCP z^+ue!B$c;>Sd(t2<|P4!?H0CZS|)(VPlf2TA?1-}B`A22kX|qd&0q0Z4`b~@XZ4=+ zZ}8V}k?lE;82H2@6SH}*s_!DUWpq)-G48%^Bf5%z0uk*Ho4AM_cdeN#PMy=;c#&Qa z4~CzBNperB{>FwdW8rl!K7kZq7${FIBP=w}{@~)Pf;X=D6hUh76 z)~`*CTme3 zqi}_OaqvQXdVWM>3kgG-{1t+8QN3c5uV$S3zMd}f%8e^=x_T_>6##MXL|?;yVf1Np zJ=vcdc#Z<>!c;*vp)YnTu2;&W`*AVYFJ3vEu433+MM=p2_X@~p&`S|{}iqJk19aR#XcDI)6nP`&4r#F_Jg3`j1KgsWBKW?yZB? zrb?7e~Nh@EOTVbUq&Q z1bC*c7Uow=R^zgvIyq`l#^ZS-|D46~qbM=mY&+g^$FDn^b&8?ut_DgK3S4XHeg=#u zdlm(q@b5&K{_5uUl)72O%Z_mVy{9TkzuQe<2myE{PBeWr{{{K4-L~y7{a$~dFzf&x zxIT3;W$uB?^Y)kC<|ZFYz4F^3ZRZBOi#4ueq{)#&q5u>TshPCOCyv_ZoAx1}bqdFB z6BPCFGAwB0(ha9l7q&25@_Y;zR1_L2Zq*9Bnn^|5oWDtOU+_Kse~Z4*W1edkhl^u~ z>v;DzOcXa9bE;P2YYLzGU*{4ep3UV4T^7v>LqvXvi&;nC>?iXcVdRz$qNvjU@ZI~v zdfyc*un|q9s*Gd4xH}Q&+3l{jl8PF32~C;J=vclo>ka_z$59Vr zE(jVo0)QKuR;?6qqS3Br5}sWbxF#$NL1s~FgDFJ)IZMhOkNd7rl`LGqDtI|ouGGp3 zAU(KeQs@vpQ3oFpgydrEqM&^(wLwCwwWvs3cK-TA^w&bXk#(}UVb;bg4xu(WHA(PlU=hkKe5DR?KNgkh zW^qfWO6lJ(6ojO?as@r-7JKMmXQV9Nc_SXl7EQgMRry_yXH_+ReEWe~2oM6>g^pL_ z>X)}$o4UyC6!aS_B+5=J6m1N+YZg`KH=#P1saL;`UcpXl*5I$rOfb`$Iwxk8)LEw@ z8Y`*oWd!7^OMzr)^Wo}!dQt-QR{GWCT?bBnSD9!2WR%Hked77+UEa?f|6cPk(=R9> z`dVE5i^LhT-Xwuyv<`0PbZF`GCsUS(-Swr(XN=gE4V{cX|7qlSQtI8?gm1yrZZVQk zf3QSGiPefg?2&|4_fua&8EE#5M1%Mwc#{85{Xh|+6Tn%GF{gDH9Oc(x<~UnMW6b25pxok^$YW?)Kp}j?t%2YQW3O^4vrGO;kIZ#(S1@f)cqL9 zSJ5jb&xPE{BBgO0Sr2h@<4U3@VT?LF=VdOtbl)Olwn>p@u~YPW+q1H}XYxDa@Wk|v zQLgf7I_?_?};wd1vgDfTk|$#PewWzp-xU>2S?@DcdXf(C29sAL|i_=ZAt^ zS!u_8^^WP^gY$fYKQda5iPk#x`>-1Jv6UeuCF@4exlv0_fF z24E(7W`yo3q3b`o^dmLU(*}*7NCr0^^i2|E$PbbNq(~A?w^(B3LVz;3z5-N^hoD9( zn8jG^a=y`j3@^#GbVP`J*6Oe+&On z9`ITY4dDM1n1O-MMngweh3uXNJ>?5rd*dn)mRMcVZpBvNVKxi}sWQC5D!PMZMAGq1 zRU(LG02cqelJNzgT|v*%nW;5nb!3t}=!`x{>e}k_nu&7RRwvq&`@G^mG$jzdRL_%m zqiXYz`DV6n{N>q*_qYdiw&=rX+zVo#5Bc;J+A?9h9@d#5Nmut+f0{M~87*&Zh4X0? z{+!z2 z?;$-H*M5TV6wI>29YpK^t#T=m#Ei*SZRu1nA<9OS7G-EnuZx+W(lf^I61te>_%|d< z-X6e+Mt_4_*6S>2lrkRoXC9BY%?HNJ7-|OgpterY@Uce2^A-s~H7RuJ;X+|>(_{#Q z@}!+NfQY1J@Vr=x>=o=i?xO-LZ&W|3E(;@LlPNpJD6sL`HSzf)$+4#^J&Zbb^nS=y zF+HCkyH7U^kKEq!w@_uvcx911t>$VsN%~r0F#}uP+`Js=J|ePWEm9s|JS=M*(Z*Lp z6nWSH@?(*rQ;OM&2upL)wFu2$m~gg8%pWMG@oL*j^3LKTIZsvyBkFcm_Ph2hjx6IX zBWMV0KDD-p1*KRtYa;|jPAYQz_3&C5y`6O*d^9_~y!h!+eSWOp{aEK>Vy^O=_X-Sr zFZ-BOEQl>M_m2%hk$i+C=kvZl5(K9sO#iW@ncE%yU5ryWZlu|UTYlI4ufp9tHx)x2 z+~ar5#l}xK`kcHoLDb$NCdfCdFWAlXf$8QpZdDSryCsB0u5d3rRYzhc?-96wcmDAU z^Z3xury5ilOY+Oz&~LtiafNrK4vxw`zTl!Fj!gS?b8$74z@$FAx`Qi`g%XUFJ6t zdw9_*S%-wIaHHpojj}}%8R}a;wl2E=5vw(fg|}3sVEMR$dP`xR5n;nqicmY1!5Ng{ z#w8iJTZ?p>oqju;A=~?chc|RhcaBOBZofjj!DJ57Z6hzwl{25POQ=645FJ($^fk|X z?o1!4Rc;C4+htV!!YqH*&yBV;Hy}xJh3ROM1hXF8yYP@NK`Nj9{^F5i%@n&P~zDaGg~K+oF%?z z7o`TGtn!bdoDarvF7-v_P+R`!NzXTH=pcHbD!&gG+Uo;NlZ=T+9kUony85rynCH)+ zCf$D>7HhD%AjK}N0>FoUVWw`- z<^U;rAodGW^M?TbYo7~$t$9>Q+V3q;oPEvU22Di&D^+HGR^S4eg7MWu;kADi@gSD@ zPZ{4RJhg-+y@4AjDRjGV#W!rsizaInuiNc$UklnM0yY1az_xLxWPnAlh?&IRbb1I!ts(I3Qsd6cmUDFhE|;!LhA+r?4ADbSbW{ zm&45twI}m?=NeU9IeToesI(ot_y-`r*M1%?M3_5eT`RX($gCn`VIH`U7+5={J%uPl7we?x(4o z*E-mc#^E|V3~tRQ66Lax44Nf4<9^RAK*DQj zS_Qf6ceJnBb`sgR)C|82Bj$`-RVo}9Lxg{Q*KO2cIN5ao!+%}vWHF6YW2UX!~Waz zdeO|*r__J&6)ah~!9u6v;FM`ZxlP!mcL(>@e;4l{i?UtQLg|yHVa7%NOQw*%kbnJs z!=KSUZY^J9AMBm)D|DTfA3f~C`hM+>j{84?@u<8RMljt#iJEfM0M{dWVjoBSsf#r$ zx1;C=EfkThX2u`;Jkj`tdEvF{Pi&p8$V9XP7r(n#>7kqi0PAFD)ha3Zk>1jk{G*Vz zbMuL4w7jm5y4huNaI|Scj30o@P}P%Q&L5UYHpv$DhcDu@R5z7v4V76V_SXReSF=yk z>81WXQp&WvCO)I4YPHJfKOe8_s0VfI$1dAYxM*d}II0oV{mxgIf6w!aJ15FnVgP46 z;+7-7vqfl7v|{{eyAV34iI3glH6J25(mPA>$X#5lPs6BumEG|kPNuW9Idat`498u6 z)R8NxymS3;D@IMpZM$XWnnH}f2y7BBn$DVbMFQ<|5>D&#HU9s`fSv=J6*^)5KXzEl zp^rJQ-J*9BlV#kYr&n&>*J_u$Gy2$vZE;F#HSyx+pG?wi&1R0?rHPGr>pZ4si>g3| zh9^jLkX_gEJlEqsl^hP?PSlpC$H=f6VSx7T666RZMl#p&{^CA+-g(5X-s1sZQ_bA( z?t<$;Q~!|q))BkRp%bIC>zcD!{b{OxFOPihLOzvfXA?E#wJf(51{=-GZC}j)$2U%_ zyXL?%^})C_-Xiv+{-{NnojISjso+jbcz5281&{gMHjvgI^Oeb&^fqbLCqt?kIYFB7Q9GO9~q(*#A$^xgWKAKr#Zy}!=r3$QxVyVS@Gc3HeVUu z9`m@LtU2NP&GBLEQT7OeI<#m3FYYK=a}L zUp-7WD&%e}=$%!0vo-_uf`7IC2;$T*C`qBkM2Qi-8&o)X_bg6}NAC&HswP|(NO89% zbGuo;vk?!07lV%zH564rtPZ^>?-%Az5iX43thY^|+$4}pEZ>l>97kAC8M{rVy%< zXtM@PET~9q44Cp*2(MeNDbj}P6_O<|HG3g8sdM84rO9*1h?mauMf0|!dhjSRgjdB* zEV{xMNCYXRqB3Mb(LYp1r0)oyNuhRnlH|pUFFvspjoUt=@4Z$(+Lhk{VdCSZA!4dkm zF;8_CXKm)G{G1CSH9zs;TTAf*fs5~Ae;_G!jP(heUPzkFn5`5@gYQO;_; z448pluXPMf8AnEn?BHjvQ1gw#Rf%B5HgtIULPvc$nX~-^9kmz4S@Aw@C*N8#Cz-L+w4rP6(--etD68R?H z{zzUxVipu>adm$vH1bq89_xrxa+hwb=670-I|QUU->SvN%D6k=BM8ev|Dn1+_{=|P z>+ApaR9LImF3>&DmFFZ*H|Hzd@Px_I^mN66D>JKZMK6S^sUC7my6kMYO(aQBqq6ph zt0qjc!Uye-F;0=+_TmBr2A?m6)E>FJe#|7T^ML)JT0G-jXbnfyaQ0z?Pp`Be^VL|K zPH_>EHFDrZ+zLlk@`LOfIUDX)9un^|s`>M7eiDCYiN4W{C?>%$uSxIbgdcNA{Evo$ zAYl{9RzlFw=USUz)1Aa=EwKGGy-u^?O16JHjy;B(noI07o7C(`60M1IzxuNTe;&zm z4U_Jwmw>X}PW!WY&Q$4)X`VXu^JnG?CaB5sBqJivKKk zxisSmZQ@p%!JkoJ4-BcjhmK>=@K3;R%@w5T$Cfq?2eu3Bt&by-Vu{P5$UCK-8DAmZo9F_W)ZN_KoZnQ_v9ob+}ww=^{B}-V&LnH?6(!KTe%sef) zWrNkP!OqZ}LE7T!Zg_C(;JF&ZlSgQEvy=_Da+T&^7oC0N!1@jhzY4ZPPhO~Th`vYi z%Iiyi9*tWy(rbG$QP|PBV1JZ0(De1X!~W*nM_bs`oi}4_-}1IkIH()XW)OQPOX_cG zI1b|MgQloSi5_3u)U z)0m;jUvi4!nm!SZ;UhPu8NWmR=^oGhPUsoAdj`l9Sa^~fl{n@{&R%Ec_}ir)o{D2C z@AE?#_)nKd@$XZc!rbp_W(gGI29Es5mepD9Xw;InLGDUA^GjfNd!8y_3U=AKv#xn9 z8ru>(*hJ$Iov;lmCpLfiyNhsIuyUp}roZ8FWcP{>q=f^5h0`E+QXTI@DA*l2FeY!0 zu5Y&zwISichAw6cb>^h-u4s$;6CKDy(i7v2V_vNA1cD3gtvUF zFU6Jz5yo*z?7W#(OQPKu5i~c+I&5v!qX>~x3hIa7f@T||1A)-Ho-bPR(9l!JF@>-J zWzV;~b1N;)4a0{TmjPoM1^WWttedk!jiW0!2xK!0(W4mu>u*$PV^QiQKi&1uD_pEFv?F7dI+J=?w}1p z&frz%chOD*7o1RC~Wy|2JfYH7Xh1Y_L4M%i5fF5Rum4X9&L`xrf1AdEGqg#%<1dW$K2Xg7inv@ED;yhm(O&Q{{_DQ*+6C8l2+ED3Yn5}+cvIjgh?sArUg>O-a@EAW|?IM%pX?Yk&@#(Hd$B5 zP*&YA=q&vFY;RwB&!!6}_CFW7z$c{glBRMB|5r%TBn%gl1{OX`EUvffn4rbp?3?w3 z9N`jvUlq?f%R`Ir)m!wCP<-08*Oh92YNlti!7q%IL_x8lNO;SeT6AAfA)G_VC5q>O zSS^V8Y8Fm%*LtBpShv3+uJG(^FyHd4SkQ| zqEh$7q~g9z6AnfH<=bGp3|f&WCpVPBifHS4A9M32QEn$?w(=qi_t=wkuuW6uug{lW zKK8=>RQZyTo=e;AKzi@-ag{FeP~rrkUf^4`=^y6BYqk=u!FLVZuq-61=L+%$Ye96(E z#6-t#Y-=RJtXHP>y0&KM(+A=jRcYRujV9ftM8%mghwpqtov7SQ9_jDJ-FZ~+DJfuh(JHUIgB>6q#L}z&|C~iQj~@5H=%$xe+x=e(X9DEOhk$Z>T>)?%5PBWDB*+6x zkOAnDK^{heq254d*R4i~UdlBc^v%_zJDh{|CFpBRUGr)D1T(?#-k3;=>96P^OiC!$G3oNV zKVq2Zhkro#O&Y(g78!p^)_%2*H4k~@SCaWUf0=pUiAg)$6VVFOlmwUVP0RLUeq54U zU9~{kK*m4qwIdsv_a9XEqjtUn0Co9Vcx7*5% zD2Nj5h-*n0p_9j_nOIhKA17dj_-WR32iRqAgo~CrATvGvRt*oL$IFpT83P9mw}on5 z3OcW?LNU`Pgkkg4D<)k(Z=W1^+HHsXL2Klih5YfV1nV4hC#+lDldSleVL+dK>YLRS@Pv|JKK5Xr80iq)O%oDz^ z;3iN?{bJdXgVcrZq6I+??a(%RK*WSjpX%i~Txy1uXgf|zw96-plLz{7ohtT0q#$tceCYfNN$ZQ=O207M?~n5zQl@`lWFc!^ z4knsFBwI;vh&mzGTVi4vbS=NXD!f9A!2xbtp=VKTfH`4@OyMJ<+c^;u;s2OpLHWA& zo3#0P)Sl{T`Ai@qj{)%B>N2Xy{C9wXu|^N###@9Ys4fEfJ3dGR;U7^V22xsNmOg6t z^nVk^I@CV`nbC$I-MWr}O%B?YRv~`tDV6;xVPWdGQu1X zIpz^5L!}05MrhiSgcSo3G8>a9^)M2fgQ^)_3ZZRz4v6k0QBE=%?1O>e9^PfN5-lZ0 zC|5`?gUn}l;EmeK1k%eukeDXfst>u)EVk)!*&FDZmNUZCjX0*&08rXxwkx%OJ?3_!S=u*)NMbwsW~pTyz{Q^3GS;j3O{09EPBb^>qM z+?H#Y5QN*O<2z8DYPZPfp>1y0p{gucO^7s})V1%w1V9o!3UVdkG!$;ff5PiM2>z+{ z0(o~N)7pnI_{=*>(o|G5&X1^Yp_Wi&YP{q2^_2}8s`8W-11b*xtZ@wdvAn`d z?^Ee}?z2AIyJCkU2Q}qY3RT!6N z^trA!?VqEPyRNFuJWajrBf`4y-n%Jxf9`V3J$`@n^81x!6@M&qUQKzZ&+8@qlYf|B zI3XQbBT{rO)oN)mWgv6W6TR5=w_eGM>vyNAhY&&HXD~o^>K|^7I@&)`X0j>2D*yb zvo)VJ-2J&JsjigK)3GX5>7GqH0Y1+mBwCSkc04!K=cMd~UeS`$`ADQayj*)<7HK%? zoab7A#`j&1zb6G4rTL(*WeyY+BiQ(13erxDJ{p;M9<`xDw}YCwQRsIakeIM%1e1b( z)ZpFoxE^C_&8#Ds-Czw!PR2-n$oo*p30(#%P|s*`)B+~H!DLpYO+#0#j(utEY~w1N z1lQv$qBKNnGV7@2+>EJ|eLk+BXf}65ge;5*|Aw5}V+}jT*QU5uf2_v|$P9-J!O{0z zf+72cRPE`X9R#QHLTrw3bk_I1E7(i!AV(Q9=X(Ol8v@O^CK}^j`K@ZK9op-+N#D8Q zMH`OkSN~Lu4H0dRHeF|6!mavp_W+@nXe?@Puiv^Mu zFU_V)C!5~Byl?b~E;E`f$iqF?i)0weRRwr_8In$%WDAT-wl}pOv}G4xe-~AqfwyFk z8H2G#vMzgRjg*0pAUsb4UfD2W5;8zgr}>q@Owj(F6q#ZyVCaAdfa-xJ_{Dl+Y%O1o z^s-Y3kbt@}&P%dVD{>x`NYteoMNxJsVEN`sL=2u=sb|@0gpGi9WF5H9(xkyIs{Pp& z2>w=T(TlNdzh?%7Rd|{kEZ+g=Y%jcn7bM_ggeuy7wkEc|?-``$pQ*a0gQlv~BGYL? z6k*0(qVs)2Z^NT0@(!-UAi3ifwbb(sPmZeW)6k_j3to02|5ACME+{O|&H}t+ z@kMoRaR0vC>CJ?3=Bz(;JZ+59S>C^^Td{pl%Vp9`72!2@ljew9I!tTu^R`!N&~=RH z6_)N21=p#V_kMlSfz(#N-fVKXB-1p-9tXRb2!D}bR>?k_$iF1|rXa!H@fUTZvvLA) zLl*m;B&PRY0Y#`4OGrQ0IXW#(7=O2@H{C;<3=nO|7l!QNl4fXD!fc(ZZcwTSTamZd zL!lfEucwY`VL6>Rr6wMC7b>*NVE`3fFVD-EyRD?vYo%{4+%2N{Q@DQ7E)u)%=%uN$#d zcn&~-z44_#1wWQhvLz01#awb~rS!jn4iJFZ`#)nfsG)L}@{pl$VIU(MRW;dTP#6Pk z6=XIqz%sX`VbrRAWjh40q<->xm!Fc1E?M{vv=885|BJ6(1<7=GB#*`?$ttD=aFw_A#SE}hf6l@>t$Wg5#s%oQ84y)%-}3JpB}>&W zDkESOuV0yayYq1`M06e*2bD})e5`U}iCw-ZqTX}6K391#_Zkd=IdCJi;g4+Rv~2|H z?Kj`|xF7L7Jo9wq%YGtn_#$5WGWj$&Tcj@=1~yw~m9PFMWMdM4P&kn7U@j{-tBxDb zi5Mu|6}~_uY;Q<-;}e&%i9H0l9E-DkRnIc$`)=fM26P7k1_)CW3x~HX{m(YYgE?of zwWkl7R+ukb1G(R#Y?)|l8(GoS!zZocN)9ISsOX^fUXBb`Da7vXlSkKY4e4j@rx6wx zutTJr?;n|2LfA9O(;JkT(WD!*R{W@*xoa@}I5{s#rd_M)yZ6-OSElY8?&Wdo5Tcap z!w7!4x3wO_c#+XR6eZR{A3;VF$xp`bNQ&=f-?K8mCw68X*Q6hU|BbteobmAjvGN~E z8-J2%hTSpk9w3gff5Dw@Rv+CK!+jP*DS_lbJdHpksIL zqTWN#g#{0yDhFA~t9C)(29NXyhpK}+pWfMA@PQqd?f7K4(tnko7?b}ODy9+Vq{S`W zU=F(-8{;hq0KEi#O{2(0m}Yw1PJg~=B@sT<28usAn&H1n>q$*AA=i%0@CLjD13+zO z3>x3KWYhRB!(C(O#@WTP)i)fhvN8unB2%}lBDMFx;R;;%I$r+3-ZGlD}5$hm&` znO+TbxA)Imgc6FtLZLHBv2L3@s})nw3zJmf|#yU18IiS$upguE(l z6G<4=dpDR7a3zA*y_%B!&R-Ylw!#7V%-u%~(P`LZDk1cw4Vv{oV#e%7PWH^4YuF-8 z`z$*%-5nw55&YGrQ+MJgY9iG6OrDi@wH^|!7F=d&eQJ>ZUjBZ__E>_P z_m%-cy7m=6$xcRQ!?zurQn(zhG(6s7gQxudoNH#!ejjlGN!jdpgT+UD)`@gV#YTF* z_eg7GV5f!g9E}dbNE(e?=71Hx#a-DTZrCyzZpQjEI7wx6;mBu!#Ju`g#`k7ALrO2AoJpji>TwYO z6mZI+rx74LOjOAkD5o2M+IK*UDGUn`cVmU_TZjz71T1Z^Of&_711QbG!V&bO?#-G} zN;5=ol$Z{ar|umBZYc-k46*m>Az4l~#)1@37nX@!1sXubL-m9Sdf=_!`Pnspd0sIe z&}TOJY=0f(bIJvg1XLh?3QvgD;Bu=b72k*&O2rFXTd@}ee3e;#6>yIyBoutuz06zT6hkhAeJusx95dI&DRg z&?~G|h709)r8pSGw~bB~Tm`#HYHL;2V{s#RLlQ&FXEC%q!L|+vC5Ee3A zC>sP~Go>S{`}fS|n!p$zwP8P&yI25qnlOfpW&#pq`U|s6pf^J+C#(jFUV<)pt>_Nr zZD-Zht2e0Z&)wL0bLK#lK$0L@oAe8_{=m$};YtUc>R$0oChsc07;kkH}xMgZ2k$JGBdm3&|@iL>Jp0!;_W`Zj%RDsjDmO zQ{D9I`767v^yMOM_Yn@)6Bksp8Rfd`#0Ha|sKJ4K7&Z$>Gp-qb-`|9u)tF-&YkS^Z z?vKr1t2#>~S?|ci5Ov73tHyRx`rMeI0tf1P`mUktJ72E7;~7RYi)Z%fsk#sD$JXu+ zahcye^$AzEpSrtMl)_UHVp$G5-3@f!t9SIKWctl(TO?wGdt6HrhBK?P5Qf8DX2*a82E|Gr!KsTo(l*_4OuZI66oBeiG zd_;~H!CO6>je@H$1gSr#erM-1 z3rUgN+`6|RKV=4ODrp_wPCb9Q(}w|d1SX{Q1!-*2rmCs&ThcDFn`9Lp zP%6@91AY-(Md9oEj-BjxP^_Ini^j6-4|!mmyYj{2gIod4B}I;)d+9<>&OS8Vz}>Rh zfL{}RI_qO$aMsz=X@~pkB5_^T70;V}&+!^>I@wn4g@cG!ggJDt%k{oDl)o(Dblc>x zd@VbNwceh}Ku2Dk)WUz~*K^k`;JJZ2HDhmI{OPne>%aA;#o=>JiLN&0og%ng9pQDh z7jlR$(Z_5sf!)euIg{#>c!Q2~8b;l6~6LGk`Q0=nKb*NjiwP(a%#Ow}Cm#ENyBGK6+AQ@D+Q*z|Hy6or9f z5Ge|zfL>A7VPOPMO?|;4YHvCJ4B;d0Iq^HLa`RZ+UPcV^iq8{l<-SeT-=F2NK828q z%^7|?#AsJn2lK}J2<~kE-Nj7eoG$A+(r}DY%eLZXS1{9R7v3PfkpRmj~zueN}2;ArN+W6SPcX^Z2_YQt26ML%=A^41x zokXrpOOdO39iyLu+uVcX_SpWKNM0@X#YWK4jv0Wu9 zC%g!CH-BMhU%|yF3Z>iMXB~Pp*efgDY9hIE@Lq;muLk2m4?Fkcq*u{>p)Opk{$+e6 za#N|CFsXE-bC0B_wPlg=&eD9bzi&$W*HZLb@8VmDoeWa#A>|`qbq-u`cGzr`G=Na$ zEXub|L>-{L9P(ULF%N$l&(lm2XhHPXQibqVz>Mt!aviW*$k+!b6(lH08L7v}>jPYj znrxS+%|oQKm6=kwI&Z9s&dAO+)5a6H@*ekZ8zJ5o^S39)(gY-Y1h=KHo|5nf(}m?uG)my@0<8di}~3Pskm^*SJrH{T|ic2zcb3ubrUA5PlQhp zxM$uk>U0)5_3!f*jg^|`!a$?jK%O;_h7ihG1D%4r94w1K*O=W?L%q`XwXHhHW9L@3!6&>)lg2>ib(MKr znjdEAEeve8UkgYZ3sdU2Sbp`VA;dhbHd2%#}V`|aoQ)~@c(X<>~ zZ-hUse{mdpP8fX+1ioj!E9(`W8G%y2GL z#FneX$!H;+*5epRmn7p@5!0DzbFVhQ;-{k!nW~j5uYMT-} zL29@30LL&TAaP&y$#s(>FStE?g8xNI@3kk%yPw=o8Iv;E@L{U3mpUWEqE1xLME03n zxDav~lWNCoZf-X|bEiMv=ChyBfnnHlCg9K9+-A>* zl4ZolO@_x)|4`vJ1VZ!wN1xv-2+iBSjcsl(7db0LW)!M;WqsW{^)_&?2F=VaU-Yo6 zSI#_W;^#>%GpyljiuA$^!@CV6cz=i2X5uV!gT5k%OK_GU!~=q!X{L;?D3$S!GP{1J zVY5x$EV?TW&wX)y|BWdq371QYSQ0FJok%A)`a<_s#$ckD!3y@Fib%#)meUI(cbPj1 zIv=82DyE05bg?Emj5f9O=^?&a4rRN}cfA3xS`+U53p^GrOHbNN$qCJ$lT z1!Y>1_N_spR>RtPp;YK2@d@{!M}oZRI{uK4(Qr}BInuPRPtQ1GI4TNVtUY43cCn|! zd1%V-fJ|t}%BIEdL(#^w$R?z!D%OD|e8$g-;qEeK;iNCDc}IKswIQ{Jas*m-+a+V& zcrUB!+c~xGLhjhz$EjOYj3I)aaMW($`rjhFAZyax2)lfHlMlo9)C=GE0+sD*PZ4E` za-L#HN;N-Y{;Sn;YJ_0~v=@mdq3p|F`ZrW_*e_apSLD6l*~t(j+Y4%~{D?uo(@KT-`=+>haXkPvec^nP|gv3vwT?8++3aU+zY9*!CGg#B5Yw|g(gs_cM$?S$gA z1lW+>bZcLgE5GJjey(tElXX2+RH97!Ag>UVSg!WT7pnW_rnifF@O_JSmaC==G3m}^ z(+p~CDK&Qmy{Rv-9angMg!fK6@jEoWI^*T^i>&SS?L8AOa1HkOPyFfJ3wnu)i&S0G zpLj!&gTh8{abDLwB_R-%7N;`kpEm3~`-`i^~hS3&qeODG46^GvMc zTz?q^Ndz{}au4JCAaHs`)$>uZSYeC*^n3(=2hmITYNoFf=7;g$LK#s#T;-rj2`xL4 z7{V*!rBCme_#>&&$1#lLq46HkB4Bk4H1cKRESN)wQ-)n2icDowKhmKL7{!6>ToRlrdKNN2L5O4DLlK zBX7fgv#vfyoH}N)UZ6%vrSLh z$F`qXPQv$6pI+MB;c_d-N%7?k|IE@yW;;tZHY^n582DXJ79z?*KDA_=wRB0VOw%0j zzIrrMX<10pv$DERiH8%n`f*rG}M+SHO%MGpaL{mG>tnRO)7swtXgzf(4n&!4)7kY4f85S{Aq-W}- zSmq+K_mAk8c$y#8LT6eKeN~1fHv5}IU+i{vpldHC<>=nfvm~kYQ=aHuA@YZM2wLNa zWMY^hJC2UvS#+lDQ1E!oyqUD={zX`qRF31MSOdY$al zWhCrLXw{EM^4@H8_mRMSgMUKecn_WJ%}jFU)xFMIJT{KpxJ|kkH;4`Sojo?lc>4B< zca*~+VygZYu6HY=^Lb_VaKiVkkf8UKd@y4#-Bt^V*@pb~OYE@$zslDK7Mn>t-47+f z(@oqw;&f}XPoA@*aF!WpNF$}_O#e)on5QcDQEnrD|xpd2P7w zDU7^Jxdm)}reVIW)VP`WIE0yPy~>{-A(YHY@gvyNf%8U}J?XT>9DXu!ZXjBD;h^#G z*Z$-SN>Mdous*f&E>^ON(f(q6_D8K~;vP7(%u+G%djNSt#*R zjbWon>xU&>~<+6BK1&?JlGmJ5)vClKw;hA@;U1CHk(XTE$ zmv8azn9792Ly>ID4b|ROT1#!Z3X|hxx?Un@57&D}eDeIR&Kmr;ZdoqjXYA^(-`Upm zE&&l1h8!T(D6$41<|eN6PU(%iIR~K&baL%2Cd{A9uoJa50d*6pLQtvdFa82&ptXtH zJ^NMI!j#~ojGg<3YHpN%u@XD=;xKGqH@VRlKAquTrSyb&OxGg30v}erFp?3ygTG?5 zTHxp;%c2REr&L2o5Q9NbX`tCJMr`<;SLNO5uX+v<5=<@k{)TQOv(mpXWi09ilHoUut&}o=$VPh6 zVsDrJKD|nqhH7>svplK0eHR`Jj=tfBYAx#dv0`zR3_5?l?IJhfAc+Ux+(q42UBc(S zfmt*B^UVXqkAhLVhlFvRSh)HP6iS@D_^-@e#VQmwWVh||O_y}^;|Y>NoRQj=L65UC zDFS1s`vwc$IS>+yycyHBqikUQfbRDp?;}l3Y!!)^0r) zlJLgr=dwAO!RUwQ7Ab@H=9yvfOKiJUa@iYZTCC?ugt{?A$0w^V68Fr9x~*a{d||w< z7*W0R6#w$_OZ?j*Z7Av>P>mUvB=La5XvZ$P%nwIDN=MJb6qc%RqEFmrk@9te{pAR*@@j zciW7|skL}d=Y@*Z57;*a0vw)AF4O*5ZzAAH(& z1yL@^whJM=HgUL`Zc{rb8r@!sm%E!IL7m^Az7P=vRN{ziWHu3bk@lP(^8Zow-eFCi zVc)QuI;q<_NL5fv1gbJ*MvD}IA}V_&Rg|elM1%yA)QLbP6%14mq5`ssipVe|Dj))e zB@jR$GLkTaKtdK7{m%G&&wIS@ANBBnf+XDceVylT2Ina5VHW?32>7cQqBdT*+DVZa zF$K4%HI8?j`xlh|B5zq8$fR<0HnG#Uwz8R|~D5Tab}x$AZcY)Jj=)p))GyHWQv zR7VsNFC1`C05oLc9P`PgzuXofnPW~o2_2TajiQFeseL+6V_-=ei>2Edsq<{ccb{_&Oov2-#|E6#6vOkC$eLS$fL#qv6q@q*nR#l(o~5o0V^nu*OXP zxtw-H=u0>)oF8eSK<<a9emabQG!)t+!WVbxJ+md(C6hixJYdX0tn8lD&%6=z$d~ z?G-hP1!1VYpBgfSp4l?AzYb5`hj>-L6{{8#jlmhRPP~uFEhBN<-!;zKo)%dNUN!!= zfZ+Kit{CS&qa{8%ySpK4Lpyy_YIvwel4OR|>Z3LV@zi6T18}X5IC}(F;B2BA(JDlp zqV-Tqbybjyr0*H9-0vB?DxxDZ4jVp6epBW+QDbzDkQcYz&PBJL5SVKdA-^DNBpFHa zQuIxts4tkem1e^R5#OSGgP8Q{it_8IsXPHvVk`L@5MzSUTGo)wDpdk0W7lnpJx*d` zwvyf*g!hxW&WqTas-r!7Y(F`dRWr#R^4n;1{#$EUz1mtmSQq0MB$X?6Dy`$*A(qb( z7Ikf0H~0gLVmsM=9^q##W~p)45WU3BWpP2RFKg0VRNo@Sh+5QY(}2Y0q*5SH?7*0z zi+NN3^8u3`HjoI*>kx10_Kmp}Jo@`jtN#A=D8fVgG6aJT#{v-mC;nS?3o6+;SBBRBzi#f)8J9_qldp+%QGgXLMB(0b`oo4--6 z_4gw)&y8vJ2i}ciR>?=kDlk`=AJr}MYh>BCnxfNV4`fcJ@xte8ylPTX|4E}{aG7?< zIh57L}PLZ{2yjF?*C$t{qL#1uxWy4;}|>_Swl%iH>0z+)ke1_-0E|Y zXVdlIHU9poP!+m-XF;jq)A9;jX=VUOE_l=gD)gSmZUfZp&&Zf`De=X())tC(a15i0 z7E*1J!7BU%7L$9kyCoUzb04{7?U_;RcPJQhLw3Z}U2!()YQ`NTEsf0{Cg1I72JDGJ z`bx|Ez>g$xdnZo4?U`?Fpz4?yoHnO_X;tDGzt6_ig_Hv6;;)Px#`DQWdQl=w44VSL zX8LgspSFTwlhZP>LEEj{D!}ZaSu2@bdDO4Rt79XgP$3PNd1`xI&X z5uH}`%U7|qN+jh5d^obhci`kQ3f-NC-Q1Tg3|nDI8+31ufm||+HGeqNoL49AP4U5Y zKi@yi_-tY8BT|pyjDOlDiBh{oz6j?#kXDakMDHtAHlXFb81$oPUFe!y_^7z)XTr}c z+Ecn#ac$%!$rY8X1FBI*(~;k$4Mv5wXQER)omZ$^o@C-}+UE6L#38GJIxo5p(tbx2 zmqJi&9qhO->?B?De3}W-j2D+Z(R90l&ha!T$Dma6a@zDs&O1#ho+cbM={t`;fAXrP zE9QUZP0%sYDp6+tH+u#1s1b$N(V$In)EHmDSgbyocK*9y9=c@ofv+;n088>hBha*c zw| z_?*%r+u04!1x!k2cvf_2O5J08yLEO8vuO|JXQvg5r;wyg<8TQTVj(i%kK*C`u-fP~ z4C8>Ma`lnS=fJ0SU{(1DPn$=Y5w8Wq!RD7*oexsY&uk-{-oos*4jc^oRS7(e5pCrJ zzx{M{6Z8qgJo;fqgF*f}WJ3_I%Gw?G2``)+aqiwOog{BNx`9+(Op-Y(dv)k1obf+h z^RWIcHY&d?xTY?m-SPb2o?^WxQtb9l zXT4cTz++)@894x)bruo^C{pju8@ryx zJ`1bOYMWIgdY7CNUSg<@WrlGgosI0-*$Q~+xTGgT22M_@Ifojgcz@B|aW|CZC!zi; z(_alhsN+_SPLPtuhems3B=w5rv$0A;+3Lt=Asur39R}xYoYs<^2>O{hA0hNb1-%o2 zDB+fry1x8}YlG3(U##7I{~}_bp-d-il=LN~E#+2^p{w*m>Dv|b)2 zLyYqiIv{Q$@~f%qd*hmZbc9ifr{G%v_Wb5iRl`J1Z1V_nkMmiqfKB1loBjLWf_|FM zY%WcC!Z57$(k{`(N$GyJEKbfoCL)~Jsm@d5J=d3Nzx*H`@5{Y~3I-@>lbt$FQ7CK? zHHlZdI4kUXh6y5j>Ex$a2;V&IfsF%klF}PzOy!hLTO00(@qOJ6SvSKMDLVbykBn>( z(J8~mf^3=TdwUUztf0(!)-rog&I${skvFZ1vy}OzxiZYrncq{>ZBi2zOvbn}l8h_F z`A+h~dvnPVi?2)K5Hp;wLGK{2L+E67t9X-T#;qO!IzK(=&eS=Fl2g|_wf2-bgcq|k z1KLOtubl8??%&v)DY5norTVl%xEZyV;j5%t|Jfg!;-r54JaQ#%AQxvcD|Yd?gN`8n z{JbnphJ=@9*!pP*2`UZxfVd6~e)=^v5nm))RR8g7#Gw9S-2VMiRnwFqTnKDS6iCLk zf4oL&E;DuVie*+Y%FZPqpyqy$LVUu3g!4{cZ$Aq4!QWHqGMBdYw=2>iTIsyA-&en+ z98mU|HE9xZR~sEf$ip1?w%&u-8s{Bd3;Z-?ZjkN7iYbg^NlP!AqPn5us{10n+&H;y zX)BQLW`hL{275Dj-!?2P+g^_93!{o+OXglWDVoL>CV^QuIJV<0p@>$TK37VTO z7^-7-6SH_8fVn^-vXTPrYI43W;wE; z1LC|J%2N_gry5P~*%+;dHq@0>qlk{Ce%SPyQ&sV@jHC!Lh&6+19qa+CKGj*6onq>F z%5&W&WV!5Rg^NN2EA7lwz^4yXW*=#~q+?6bn+}MY<5~E3+W5wYwaty6fuh{}nIy4A zSI)S1H|Xm2J=ZR@ct#B<9;>j}leZmz+#JeWVqS?a@x0Kq?$|g1+`S|$w22as-K-41Gu?Dm2KcpMg8)^N%tLi1@rJn=hrv=mT zWfOVV{S0p_j)jqav|1QYI2q+^P%AnhI*9CMKJBH92b6` zMYXr)Uh`GIx$JRtn6OdNYdg_HotL`|r9disu8@m5sWv9|_$1XxsNa4{UqWjoZHe`v zGjY#S1EXkJ<*nOTaA|TpQ$w@%Wqcx;OwRSm=F3pm_q9oaO2V?N(mhEap>vzPP~oe_ zi(*(&Ea;v`h8Ge=aixe$k(pdx4ex2J_-0fgslt!+MKzIG-{rM!9cJF+LK=o%jMK}H zQa}RX=FRRdENS5tr<08aR~P1Pr*s8N-QPj~OVhaV8|oZ+*IzcbW@@C<9W|kY6VMY# z%Tk&}N_Wu$%c>yFc86ABaFi=nHHF^@jK}}(P+qa%eLZm|c1^6MxMP*Fj z2>*88PwB8LwB@RjZazwHaT&A*)Xivq2kzCCTAtpuc|z;7k}4lR+IFqapDlp;l{W=N z4O3iUCbI1n?mTFejJ3LSHgs~UKd<|V#Lc|c-mIvgEto+Un3TMS@&F}K!(7nxKZvqS zEv|dY#>dsK^HNmjZMmStx~!!v*I1ySqVDkzL2=FbXBAzR;H6yx$u3~6MrXrNva~U# z3!lJIxjRAsa=Xg?yXhg1J*LIq@LLW{7@Fb+fu2S%g`TW{(9L zYX{6U5=oiAAI_9R{L9qX+VJA(+5N-L>hpMNyot5hTm0_v*EDsCG7=T{4K=j7?Y{*T zK)kUvlP`!zQGIFaaWo7fBjCRU+}^pK6aIRz4zNBE0bGV z`(CJ?-9t;FdCeDU(d|j<`U~D1qCmjbLI?tcVIacsvGvoch_h^tp$+O`abeObX-0v<>`YgHHd#bmQ(O zUVa94-|{ToRisyN1{j0}i&03`e4g%eve=!hTiNRubhK*^I8B%H*bd>k49s*oQI-cWGI;`lT(n(|_MS!|Yj zxDAvvogKvJTgaREp_XqfRQA^_8e`X0M$kBnqe!~n|+-d)KO)?w0h{k*-1elGysROL@VNzY%vYLR1)~jy>FXe2KsN=Pjb}=h* zcDH?+%xYfLGff9m3a2z>h&u0CcMqw4;|>T%N-mV68bQu?}rmees4qu>K-g0$?Dntirz@H>x7!WwFa2@uzr($5-h54pAwEm?;lo8iWBM#;Pe4x*GU6tMr5-N2aImllq=0wl&>Uh1&wQ9U~6cxklsZWwD?S9lx$`x|8>H_AlN zW@VvRlB^cKD(046aJ&)FwwEE7d*!{F_glunCfdqS(ERvHdX$_g{U@v&& zIcEP2GaUblnXm~lH;W#Gyx==qQs!f423j)$|6vyf3yFe_!^9tj=gV9K?C0LiT%r`u z{t^?wN0yurLYr@8m+_aC_VlhjUOUOELV3z?(A3hedxt8^VxPi;Z$L;o^6 zn&REpuS#xJq3dWyJ2Dlhp-fqMRL4CfYo%IqCYQq(Ff5=IR(r?iJ%HuXE3 zmf?6fiV$5jyDUT(mpgzyR1DOLF77N|{^?SfM^KUd;%}`-Wfi4%!=yF-A?uReKO?g~ znQs(=jC0*UNVjyW&9_y8Q}bIVv616{|NF409%#8BS$x8Fq}f=P41sW&FlT6)C4sav z`->RWj(7@$lecVfeDtzsFC}5??MTGTs*=fIqYUe(0(8bF?j)tMYtJ~N>P=!{o?aKR zjzry4C+#AKM=F{ck|(7P>?8dbgjjb0zt)Y)5ZGr3j%+>cbW$KGBw}lHur*rdR~$kS z2cLZJR0Ws9{bpa&D70I=*V<;!{agq^j4`_dn8A8JExLW0{sqOvn8}Ef(hxLvNbzJp z(fR5c2yP}-SJK=*b7_drTwu|Ulagw7+onlLQ|!ZJpBZ}jc()V-PJzrdlTDRSx1*ed z{UZV$r>t5`BT}vnVg|ZVf~WVa`Z_AW?%A?zivC=cRodGJY?~B`X!_99F48L}OEJQZ zzf3Qoy7zWe`&t%M=D9*z zcj;$DE}>p~P-m^XCVIC!0U7ZK#VtX=-}WsK#`Zy;8^mF_jk{x@}G}r)9WPj}i zhe+hSCZclRB8a+dx7!5&3c6xO@P1~%LG_}LR8YFN7H`$p@?sS*P?PGPqnmatYgMnU zF;E|$Z2rK@`Xo6>*EVmCb)DtU+t#jEQf4@Riv{I=z|U9Qv$EGz8OkT$MkZ3rU8Kmb zFIxNDZ2E3U&TMB~#B<`*!=8VKKv#`tSu`3mkbAj%-(2CBij=0Ls-~XL%=h$>FK;vY zVwv=kaRFCuRmhu@(fbCWn7b0WBexYC-D=76OS&q4N2wp7iIt)X(nfnK>5I6q4QRVM z?9K3Io{#$^%EeczT~gKV!KaVeU@2H$_k}BJQOm|$O;5QF7;Vsmh=8-p2|A??Mvc-* zQ;zDa#{>VOR_hgZ&7=W)XifCtLDDnC^xEw@9wX_dY0w@AjAn`!fA& z*wYiESJ-CTDK%K5=~?udHmo;f6Ts=7zE{;1aZT6>E7w(+wG6~A`u4OBOqssfy;3XZ zk=9kQCeI1#V}XG#^I?aUxO6amk|&#b6O=Zxe^|3I5_Ls;8P5)zfAo^}#ncfJH(jQ^ z=|FO-@2c%)Mf)1&757zTb4we?T}SrY|2Vw4>aW_a645Cx=4KGsdf%3q*1koopqqc4 zbpDvS>DPveXKUJg#U_*NbPsZ|FSGA8D8SKr7YiB}e<+nLdP6{Ys|JW){s~_-L_J-iIG-4Pgd)EQ=Q?_`e!ZBc`A=CgEK+~TN#7A0ooZ4A-iy5 z6Jl(pR=Ev%lU}Y6&m5lTk8dFjJ?f8iVX3$mtZ5WCHMAbfn;P9TUIzokWGIEo@$Dg;_D*;8`NVq~#~ofNrv!@=)h(Rk+dg zq?zi{Jn+lfMif78nkJl?CE5qa>tZJs^xTNT5G>%XQ*S;72qu;23^BL%qutnt&>8h= zVTt7aDSM-bjIs&nV9#G10EL-4LH!$(g!1xLaQOaZMsH>48y%8HE`cQJgazs5Bply^ zLN6ngCcKzDyJA5VB6B~rrX(>&+w{rj;q-|iR2BMu_E=lrhm?~M$>VrTZ?;3xC&oTZ zZ+)J6QqX`dC=UIn$D7$I^sGazQ=VTf9_a;pfu2tP*nv@YpvXpLyXS@WgTafq8hBW5 zq)O!B(#g)ZZ1b@6zB)~PbWs!RQr*^9`|cF{dfx`mja*qcU%mG>=4|rSqSr#)X%AE% zsbk%%?9}B5se4Dnjyq{UtW5}dIc^z$$jG^xzVimmu5qEVio=Qav-Lx;}`GPSBu?O#_ptDK;X!*cny@q>j^n3kC`Efo`X| z{4ng@MGlO}hxj>Vwd*BAQj~PkxPSQ_Yow@k<3V_cpNlM^U(^#qWmAMgYs|8~=$F|; zhI|>a>Qq{K!KP%mzpI>oDiyx%axkR#W$&KaRoG}iAg|^je4EFHN$J0+wZ7UI&7?`R zHwK!U6z6vpY#hs(l6iG#n)2>Iy?NgDR}Kb*werR&s1VTfrZ_HmJHA;Uaf?5{vZU%8r`L?UkHSFjb{n^j zGL2qerJ&^Nu&_pyaCGLA0pcvOVQN?u;5cWn#_#xpg%j!4ov1KJ3CnO|OG!s?(Yq)#Xa!-;EKiQ z8$Vt>t{3-h@DKM0c$2+H*~lOxPRS(Xj;*`71ivXQl6&FKo0V8`)@7P?S+(d~sSu`t zTrJ$Bj}>)H9f`LgM;iO?**My_gZ*$vRC;WAp;Rl1BlL01N4>|J zX3QwwlV*~`_A#-Q3d)_`CX%bg_`|V9k9gC&;)bMm=npZfgDwmWM4K2JGTa;Kd^#kT zARgzewZfT5`vM2QOpew>xTa2w2-t5&iWIirel@m!c(XW^IkHC7v_kdRiYzHmdS|366#;&8EE^f=ATOXT*Q% z;~>yOS`SI|1yTc;YRDxBqd`pEYE{b59!0INZpdT zvnUz9*Ly|-VIA~mB$rw-+ym{TI;CnwGwo5`bkxvV6FSTr`$mhSxpALVY);XAmK4c9 z(9nL;EIV~ej%q5ze!u194;m+K*e8oMNrOHHqrx!L?@hdqS4N<7bBohX6M7!Jm|vK# z^iuuvGifW4jn7NCM2x&n+dDAkbP!I4r3Y_3g*`ssAV7Vg{algy+F+VqbW1+j z{Upii@86fq8LgE$y+f^i6_bgm-_#tr`aNl@=P0uQS`S}~-g~ZxUdKJ&;2h?+Vq2)< z7N(~$!F3v-JCOGD%G*(Cn2VI~&1E*8+bE$VGmB@5xHFc$6aT#0d_Xl9nf?A6!}IPp zFb+q~i$?%aS1*?pU6SC_4N5plWv%)pV;dV4MBWyy{b3Vlj1~2)!Au!j3!O<#cfuTV zck_{737M`?%QyIeI_;^I57EoJL~84fEeu|hi0~U*wTrQfIqOmeSpBMZl_^rHV;n4& z9{1{g({IT_9Hj4$jF`AQmcdf-`!!@UTjA z2KY?{gjF5_;+ zdg8hJUvrbzuBz&B1Hn+5DvTZ9%TbF2?3`e@mMhQ|<%@HYClK=UZqulkm+>*32c5Vc zT8D8|$BUNm!2N$(P2u5dZ(s@)b`9UxCun(G+qU#0S9A^@7%xUspNUBAV~ZURhX!-u z`YgKNd}QmXW?rKYuztmkJSE5USZQ*L&w@Gf%03Ma^d|pe0O$d=9{ZD;@n6-((IWL) z0_r12^bIUts(-g5KDfkR?)xx*@upJf`LSZNuz5EN(1wCx^YYB20>i8)v_~amW3Q_h z2zgTANDL4m`RCF;-ABIBPTKXsx~?1+Ki|!W$)y3UP!QIC{;(hzM;Y59bn@|#x|59t z3ra>I6!=>Fu$w(D$RH|x2QdASOVa77-z&b$KeZpva=*GR#b%JS0aqQ1vc@r96l+?H z%DQm; zZq~<)@`uw&uS<9H&rO@VUz#c0?mNV9P8zN{RJ@CJv*@TQzg&h07#hUwFGIcM{R&1% z_Yk1h7bcUQl;OYpmfj*FMR`UZ_;;bS7-7~lj?o_4gzOtNc2$^RB2d|CYOn5P^u7S@ z>cYYZj6{4`o!<^$0Bf!{REwfblLJ9#9?^uE^buuMlVTXTE-iieU-UNnG9WMS2@w(j@-%D96$O-voP=k|(pL+=ZH>)VMQRA|CyCOo5mQa2 zWgFdS?|k6Ct=2aNCqmANiq68+=Vc0qbj4Fe=Vna6S&MXs*nxjK57bJLj)QDLTj1S` z-1J|p(#LnFZf&SYWFz_xk+=>wFlZg zSp`Fi{PUF{I?M~Xq6X|W927X`&$fA z3AoYDQyT6(0h(1Ia7e!kVoe>6Y}yCGEN&3f@pvV9b3gRXK_e@K+}(nLH)t{)`)|P- z$jWY{u*{7Tyt{S+{8fi6KjWB$yn4-r9WQ?-+aov*>^HOc;W&>#2GdUJYS zM!1(W&3(jc%Dm<`pN3?YtY`GP^~je9Jn z!GuOBgB~beN-p*bXcv6II5@Zjm=cWX5VA;N5CNmk`Q!@5XGLob+PqKGYIAUAw1CM~7fxS$5JD;_fbuneHGZn-D)7Fhxhn1E zJvK@#$KntZVJ<3XW{UTH=-rrw)pzE_-ijlr2&SsAIt!~@RA$vwoy=|yAYY4rrh`aKmIK9FJyiGRHJrEP?jB(R%Wkx zb5xxtjax!0lP%12^X;tfAUDRC5)*%SN%P(GEi5G|uwsQZ!?tBBMVGc z$}R?w%oLOsRS{nyW<|GpWjM_!*{MwHSc#>~o}d#Kuk@3pN&M$87J&tQB=fX7%?Dspu8+zPo%%) z4cttB>1h}w`wT7=qv$gM>D5@cp{Aw%Xqyi_`m8u+xp43Kef3Jh7&>;8rKom2M`QHw zYQRAJv-`lSsin|CPJNZ*N_b*oBoENT6Bzlsvg^0{QxmUV`)rh=YU0gcaADov94oU2Ri84Sy63} zhk#~p(!06`2SvnHussDd8aM-BG|9L=8fj|9(SI89{3xKM8Ssu>EtR}_LDwDr?7xP6 zQvS`BfTSd2^s9Y&Eh%q$Jau$MVM5fh9WVP{!E~3CHcGliY(E?^OVrxLTnMZ(G41SDrks0s@H*xTZudI8iaO&N^Q2#uI!$kIg3j#WH!(Kx zXuq%+iwX-u{Peg{Ux{+U9$X>Yx~#q!Lw+>-cc>8^Mb3R%O2QtOud-W|xxub4VM^DE zHqg!`PA5<-Jddme9Cjb%6)c2k0}T-yFqZ?rx=5*3ZR+kjC6I;6H!?YXF+f4Nsme3x z;`jGFSU86MpO&M*@vJE2s}iuUtZj!dDGF+Hw35> z9;u~LOVg7}Ue7v9Zr$m%!P#&LJ9n^^`T{KmnW?fFvKmi*BEt^tqZ>V8jW9Rt6}%=r z@%3b()>~aPVby;+$ZP?Qih;6Xk+|*RhiIU$jI^z1^AZD@mFZs8(PTzsw-ImLAWU{c zjWLqC__?JW!jWod$&$Pd82^mvc3z?ZC$3uftP|BuXlj6i#Zx*7xOCc|fvrYqZX+rD zJO`!wQ47z^liId3f>5c!HWuIR<{e+^%^Z+t4~J!ZruUnr z`L@dkVfcPujK6wR!Wj_T!BXUg*FIiaW)7g-+UeH}e)GysKWU|#!)$c2F5?`NB-L6NQ6yLleO5|4Q%s^6yhGJcvkNouv^@XF=S0`fM%T0z5#QEv{1L=X^%HZWQa zBIf_lZo?c5?M#}S_C#(k&&3*XOr$|GanCI(bL7Zihg+pOO_S>q#xLgb7rhyKm=n3_ zN*8LA)4kOb+i;|4O2%+AO_sv)-({mcyQct>x#A1`wcS+1XX(-pn-7sLI6LKXSR3M3 zN~huPo;t=(JIOW)H{#?19~7?{Vr~bp zf9c1l=2@M3H@!dSYRVMP+lEK-y0Lxq0;`FyrB$_Gs6Q%?&D8L3iWFiQ7Br_W8P&s0fUI2ywgm!{?5cYA4hh7|tr3 ztgZDk`#JO>$JsuXgn16e1k+FX;dOc>m`Ze8oeMHWkNK+16R zGe8CkFluZQtew&MbPh5X>WzH}UMt}d-fng+`}E>UDg^Kl=56auYPFuv|&+3-9Qh&w$~&5}Ikr;YNaePm)hBZWx7t z@7xdYrqHZGS)EW*QHPlD^CX9IW`*MEwkO{tRtXIV-QOG#8&~#qH9~(wdp*y=|GjyY zLEx0nHT9*|!EQlsY*U^djZ>PiY{fr7gJO%49TXMCJ#f#4+troBJT$vzLeDZj%)&di zAQXgChnrh{2CwH_gE=6Wt2xl@uC<%5%uwZXrreYq{kwpS(T?z~4X0i_T?VO0o~w1s z`zA1kx3r#bD$#6^ z8HD-^xfwc)wlnEaeFJGMqUQTBed^a(n8)UQFG|gZ3PV#zki(seG`_mQA!ty8e zt1@gH0f%=HJ*7%1<6C!hGJ{lIe|{M|J>d? zZ`JT>F%JRuJH@~G>cKmPdf8uoQY;?4U~>5Ueb9CYTPC(ZzyP~x6LGI<*fw;M@ur!y z$#z4?8gZ}v>&-80Xk}eHQ>0yEXhhe}RO37Pa{F5KzB`lB)7E(QZE+8=eYE~K@#Fkw z`)b(Je=CC*ooX@+M;huH1r|xhrFZD_S6qH;6Y$FEj$#MkAnA^S-cRA#4Dc(yJ1tU@ zVJuhU=WVvb#nqh6V!=W!oOuJm06jWCoU(&Vo&}n=CE}1_= z16bu>ntZZ^HKacwo*W7*Tps88_TGapi(iGo*Q5<0{sQ@k0eih?7b-m0TPaX;AXvj@ zhI(5}-ZUAKJ@#?%DwU*yO_HArzD(;F=NUxY6dmz+>iEUaYDEgjQR6cMs(uN^_iWdG zb(ngOw83g%rtftfdGwf?ON^G)`U5dSXVZ?$t`D1E%FE!>7Iqscdu_O}CZs_G##S1* zw64r)x7@u2?O^Q7O?_5bysh!ri_eem*g}57-b_7Ldg}I5Fn+nhZ5my)SZCM=mbsCU z#=8Q;Dt8_^WYQP?i9g2Z+;&KT_pVL^nEb2^iY82YNKJtKCVq{vi z@^DchS^5U~L31P)wn}}Mh7cGa^7N8`o1h` z)D89S7pIah^pk6sG5j^Qm(ZiJhiKz*YGS};)YmPvmsU}s)eSeqzVHZ1O-&{%FSGf~ zZ>tM4Q0v0x_tP)kFIKwJp(tXaRO;2656F=oF| zdK)Pnd8N0#T7M*7khQoV{n871AuFUHKQ`P*>9*OVsez=ZqXq75J*D0`cMJcB6Xc>_ z(C_cOpHx%4!v@4n9w8?+UNMe|A&vo3UWUq6w>$$#z`?)vBx43@{_J;BR6KPE&8&Og zxJ~|Qi$_l`Oz?HW!rc0~PKQx>Bvc+g8oX|mo&$wkg=rRbJ*t7zDeCC%W65&c#?loH z&tB_gO@JGh`)A``0Z`m}f&ET?bw5=kONwJ))4?2kQtHS*ngKgpoZ8zRasg3}Wsh5u z;-*f!dw~c|+_pGB2MVgg<{oQ-M8VE(fgiDJhbQcG3tV>C;r2goRKO1R{nR_M9Fg%| z3^!qMfjYTwQBYdbQ}fuq9O`5!Yk}9(qV^-3vOs6_Vp^{V+fk53KC+z%{x6*=^!cKC zMU%MXH=_ZtrGT+;Zr^r(R==H{rYN&Umqf?sZO72@W9E(73D1&iS-p1j-*zYTfZTEz zYrtp>_fA7h6cs@)vnsr`gArk@{^iS&77f?iMFmu7!l5ujQX2ciWD4MLa5i@owqxv% z4DENjzlzaE+u`@hS$gX6^!w^ewBr@(IV|Pt;O_M<+K5*jiUG1Md-TWPx1?%hs};xe z4Ruqc)4r!WT7?_=U2@Ki&b~%Mw&HY(3T3Nskt7a(o?Sly2y>e8KH#18V0!tIxWOHd z6lcqfUqHW&{-cd&s~5ahg;3Br@S|sbFLTnr_kHbU{%PZSc2K{kcpEOviBukXDded7 zxu<(>y`rwvLtA{Kx&|es9nnz?;YgkAs_09YUpmeJC&63_=iGe6drnQSx93)C#rtsE z$lZ`v=g(EAJ!>c%Rj+_hg=UFAr7JYO6_gEp5_eY6-qTPijBOo=rJNX^1P{)0toYy9 z28FAV@-8%M@2do3A%lC>Z}6i4Yx3_?P2YS;!`-0-D_qxTbzCAA@=vfrPh>a^?F1g) z#M}43ZO%Fv$Cvk6@Jg-Do4KUZUpf`!a(sLU#T^ZH??2AnL)8(nf}9ev%qcKY6`-W> zX^Q+=W#kDb+Aot4H+x`h#MHlRgzJDN^z6>k>V~U}7^6hNQFL5bG-b4OV4L^49aKI1 z)io;=i1RX(n=t#heLpSds>?)p$p zyC|5OBMMACCM?tk+t30(7uZ3%6X%L2HDDynAqR~&EW8ML<@F|=@vB0ZpvHo5sjH-B zi~03mIXCuCUEmByCG3O%sS44$Mil=Q<<2f<8M-Yx7WK+{rESMI^=jF+7WlG%2J@*X z)d4arp7jjN*$3={&LVbBte@;2t`Kci;ez=|Mn#J*g7=H{Vq;CN>(tB~(00SC1HCUH z5Z0IR_t*l!+`xeASb9k~ar5z=5tXmUN*HcCG-DlLK#M}aT0o9*bub9zH1Zmb{Pfa^ z*Wf$9d48@mlq37-IPr=klPMl7B|ou3glVTzCQ|CndIu{}3*`roXI;eG)!o0EK>rjz z@Z0s9SZNXdi_C^{g42{RA}zl%e7xEYy>_atHd7a$a{#WRCuFy>WJl4L#yuhw0Qpi8 zjvV)RY`$tDEnUjFvsaE><{Ts?o)B};XZ94}MB0|4#gq43r6dwT>$k^AwI{o=RzTIO z@lb~7JCQ68Sw%x%wElFkpD0NkalP})x|gMw@ETFMLL3EfhY&N>bGBrk(tb5tg$>9ZNcvR#wDBDN1u)+Wz+BQol7^9^9nL70fMH+x`6bi7Em|+r5VH9Z>rb*!oZ8(;6Rm8bHRrH<if zSZZ^gy1@ZXF@!zbxA8u1f^J6Pbw0c2wNx`^03|+))S32k@L%RuVGR4!AQDC%@S7Bp zLKWhci=K~h)L3`R_+S`^u&`mF2?1^I|7p}a=imI^{Y^Y6T6|xZSzV0WfjomKcTKB- z#c%&anYi>URF}G@lLehF-8Ua!|6lkqlw6d#D4#H!^054IF9e3#BrNfK z3e5b*|GR8kQ*a|jLyGePO)eD_oE3>neqfAr*~dxYeB$!w3%{2CP^O2Eti!x1)pkpi zJ}gb&YhKrg5a`^U3UeGb8a(?1ta^?D^N#_~Gt}O0oO7u=6@5K7UeRf$7W~EWod%>R zG&bLEw6Q*hQhys~SP{lOF6QzYj@F?Z!8h7ZotU&3QC+z!WnATI8gasizixMtC%~>fSjn#Yn z+D^bqcleQ=G;!18{l`paJsw={YDM;y+K2HP+^62|AFiWxg+MUIy0u;s$ zdp*nX>->;kv8+Yd9p;T-IkJQd%3NHcl{rL3jHU2t2P)fQixNEfy2BT~?MbdauFQbo z&Q!#CvZ^|7?+GIJ*PY4UIUJLK{_a{y;T5|LQ~{f?j(1H*JMCLVya~a7h!7+V!RU>J zI~%<3pC?luQT3vgpD_l$&F*88sIj4L7x1iNg zf?3}8--7dB)RM~Z@}?)p=0Cs3=Yc(M&eHt62+>4aIKwDgT^tYlR4PTVHI^CLYZ9Ko zXm}ot=1+NGS20O4WDW@h$!-cUuMh6cl*^RyL$%zGV(E6v^cY9mk?=>c>y1_6u8N*Qv8cWmMszqqJ zL^!GTVkd6E*ByjYtMt+^W}vG%kv1SVVbMWaH^=1m{5a@u>vc$u_M8so)-i!LW{N5Q zuJ>)`sd)vH>*S|$jD4HAD;m0VMdutBq<>bOzqS>njLi+VAoYjNkymRbFh_oYtt_Yn zG`)YOv;fh{ewJ+Ub+lY#+URH>QtYP)E5AjR*(5H!Zn^T_>EL?-{b3z)DzTz?c=M@F zi#*`4qxhap?3UKtTCV;2aGEm@)#{hat1$vR*HUE!T|PMN7ICZUH7ft-l)4BU+52VK zOXXl>0PGP(r5?jrB;hJ4w9{N&9O;=ZP((JVX>3NIeM61J{c&oy}hYxrC;BKcw7)@e5F;bp3I%(A#)vMIxEroYT- z7p{EnPF$Gu7q3tA>umwfz6!!9&@^-L+B57Nczf)%^Sc1Mc@5xv1;uID38N>}t@gWTw;7hW_ia2k?o?iA2zYhM z73#5A%h?U+Ju@fLO5a~GyqJAKF`^|d?E}scvyIqbW2o+vVN{98K!3x)L^TMYxES9C z1HAc~voE4ocqNU4XT@l?;zn*Q-T&XwmmY3~jYczrv;Qq<^s#U;n|A-mE%jtcL4x5Q z$ICkd1b;EodPx@qNbJA8A-j_~H3DPn7&sPFiS_K?j(+l*<33Aa+ltV#1HG|fy}$8v9|4niDHY>OpvWFuo_e}Ad=n~h)=BDpO()kyfh)2j^mkhgi&O_E99*s$H%Bw%CFGat zY4}gb45~dd;`k`U_FOV%w+v(Tsc__g$pK0x*W4WCG2Iki>uCd>aB=CW^)(z}DE*qEzpbAD}K zH^R&8P(Y#zXhoA3*sx>&bO)hc914Kcy$im5Y9S~jO&!1Op9;3HzV7;MadRozsqH*0 zDhw4ic;4)x#a5}&N*NkaHtd!!;oCnyoT>f(bYt15d~!g!cL@10PxLyL!pt4}RUR+& zeD2-jJ!VR}P_3AY30L`LI6aR$TINztnCFSXm469_c$Wk#->ArKa?BOFL{xWKnT6#P z-)sG|vP*wUIf{us1Yu>{dsLI(O7@8bX8$cnq;1#!t&({MBQ9@h1y7Lg08zAYwQ9ki zXq+#nsq~7An9|`#D%!|u+?=6zbwOWe`!_?uv{kw>!7xm&{D-O+17=yHRVVjOhdmzC zUKx$vk{!pQUFevrjLM_9&8ZBxfcdT@81HBLLiG|DlBJ=eip5U0$Ce*pO3@FQBl<_{MV0$6%#`^l)9xBk#IR^;yQo+&*YG{R!lw={_{F}y*tQQk> z+k}eravXc&H$;oGdDJoeG@<6EQ&l?O$z?tWy*EhFqv1WPAvU3?36(&8)X-+}VBDp! z64 zGWs5V?{)Q$+KZ|g-*fK!GfVMf;O~qucs)nrEr{+PP?1DOx3@VR>M0%XF(#9RygT)! z^Su&I-umTolb)6yJrFRGp}333HEWd%{jL50d=H-mDfCgSFCn{%sNMJ-0KHO^%HiQPRiq_cE=r{DyT4{@wRKG}fL(b{NS!dz$lJ(J0C1xb%pu`2sc+0JzNz`w3~ zgpXB8J#N?X{qs^-BEqbz>AHZHBhNA1J#10NE^lDL;3Iz!%2B9c~@x&z&=gHVNVN&5OU={|t*IC6< zlR5uFQ$w1j1{ut{dr(FNP9~cE4<>uV=U&^aq;~jVTV2qkCQ2U%`qw6^gBL3_2E94i zS&_0`z5zsdy`=J>n;CHh5gAOX0Q8L1aDnqV)^6=gYvyi(2wwd7J1HhW?OP*4@C3PZ zXwRo0KTvF9ljv)>K1sC3Pg8JfiYDc1&>U8hYa_Bfyae0;lvQL=EiIvoVqM!DzXY|w zqP!)Hc4TMmcN2@>PQb)wgLEJvW=(t`m z-2BP*iNy$pD$sx{uzg~HV-_?;hsfZr1Z8x=g|F64yJ?(2{>}R5dOb7gfw@xQZj7KG ze`p&fzqQgm;7Q0gmO!s*@9YJK!pzeub#39##cv^oHL9-ho(I9(XkV3kw$33Shxzcc zYm0mQk)*1(15TCRke#^BO^#S|YMlE}c#1cE@6k!{HGU4s;Hz!AgyPZaYp_}F%6A1m zz#H>1Xu3>)pLe>$U$&xw1jrLgALz~c+bYVTX6U!Wx%J7novqq%o|DyU++SX}O}qe; z%C6B(KD53$Q~Z->cNpQ9`$$pr<|&t2`zmH$^9poj2$M{uEhwVahlteb_E9#d8Q)5s zF}0U=4yt_P7pE+tfP%9+<|VC?-BTPoj&9U7xCOL7e0TTlhRVvYyre4x2-GwL z>?daxU$d!Gje!TO2sipy@l)`v{=v?kEzjCh%um+LS=jiuj8(c;J>$B^`Z$^b)AB6w z`Quy?@v4)s%##+B)m?bIA)`yaa$l8PKbb0-NJvS7E(9={h_hYqub;Fi+^h?G`yv(Xif#`1b7rd8?pz`P{Dj&E zrG3w*yZ2=S6gA5`<`@29o?rL7b-PPit>>OmueV*~ZHZUGFP`5#m6?(F_qkvc2#~mS z@JoYuDtD^nlFrLEd-;it!`)8@np8$W1Jb@!v>WZc`nfRk)Z%snqpUgBA8!sm&P?7~ z<=^IhRXPma>N)pI1ayXH1rU|;T88Yc{t8p|Ug+!6SuLK)+&ux(%#arU-YQ!#xf1)) z_Wd54r)dtEM#AbI&PMaS>@`-6one-dRQQqeK+B&x0UImTyJlj2X7I=syofXfyuehW z@~xr3>K{vX0w!8c|nYB-G2 zQ4h_4v2iE+6#;j*@r)g`z+U#wN$Qf6irBdyDmkN|@m!>gWQfq{!^_&$sqoB(sEvJK zV?Z?oWZLFB&gr}$GCai~7$F}MnH{H0*(}by!r6e{!;|2xfWR)#sUC(MO9Ww_Oq8A4 z4SL92WB*Do;l>Sc{T*dqS&8iw7#MwQNGUpEqlTd;DE2NkBV>O9uNUk+vg!pg8Q#OMn)6Uz6DGaP_&3M8f#VB zqyPSrOzp%!_R#aOQ0ztt&@L(2ri0UD8Ai|EHFQ(@KS%g*0Wi=UmmnuvKw@aGpVOV% zbco?=PcNVMKJD|djZ4cU9)src0UC5g9D6}eP*?~!HS&}bFpHigheI zLyrUyMH8ur39B1j6OA9@MXQPJz#gBN38;>zu4E|l+V^Iprds={Y6pt$ILGf=1Fwwp zIWjq*=lLYtbLwj1E|*v9J1cOQZxlnYJ@{RNQ1RLIo+a~oQz|(*=Y>F))1@-Hw>cMF zyc-UWcq9>X9r{RkCFC{_IiW8+i>GFB_nbmsh|yg^@O2wy=T&dUma+*SaPu zZ`UVulM|JcLsC9XECterhJ>$K(nxSDjGjRwmfb@@y#)XiBZNyg397%G7o9Ys77omp z;`e(5HS|6c-pZ244m@bhRCcz{6% zVf_F@gU{U?IAE*EO4yQ#r*+%|{BSv0o0msUonm!H3CLbNUG|=v*9s1Sj4^gmnegdb z1vIt39y*)v0%Vl-E58udSy$se!6CD@&)W(XT6php-PRTg*4o_(m4>@LH*ikT zqXn~!s(hNw-M%lUOMkbmjwR(Ssmk=l*~e{?0`4A+I0Y5MW@JFA_@iep{+l~sYp%z^wq2rF~QsUGm{vXJV)N`jx zPg@hmhB>BD{SpRiad89smyVKpC$ki@FKTVM%-|1%DP8fM&%v-E?#QF`$c|-bwB34C z>#qO965Q8uyyj39{9}2q?8zlbqDj^vXC|6>l{CHm2~V!W_hsCe`1@XTL|8IMBI6;AhRPo-Xc1 zw5V?ul%h?XXg*G(tFwhTrZF+0)@(z`O{++qJ~wElkq71V*4L&77nu01ByJWl?26r> zD^3%@DqZBy^^hWtI1*N%!Pd+<_q(Ca61dyZKJB^&FzCofL15Lf#Dmv%I8{692h9zt ztDhyTx&c5r2Q2H+Z+1toQlMk@z@7>iX84m8XtdB66hNuGJY;haYQgNlExDe)ByD~3 zLu~P}q&>v^gNVkre;wYcoC%IaKV9d7H zz;GW_=$8&Lkc|{bNoPc^z_uYBG&0I^xo(8nrp>+NvZYN=jCk`yA#i(ul7=Fk*B~qQ z#QzS=g5V=lU@XW$MS|&WuxKXzAddH!p$|f0H#2w&Az$iA-Gmr$h=Z240Z5uu@ZDGJ zJH#1o|M5nX(x|-|+tu>4l}d^c^Bjdf#fB|8vK$rG#AoJ)MHR73aEWI3?_;vfVo-%Y}?{;buPv z?BmJQ{`7SOS(h2?oK2-iibGR%lqc_BLF3@UAZ`3CVI(8(R+i)-laXt?BQTkfIeK@hp9F?%A>HaB$`J=;1_MBKd5ceRa?5eOst>u-IE(960+%<;I%4`;>RV3*y3c;Jy1O*b*oLJrbDCBV%hU zcC7r`=UB8vTHwOBPyL8v-WM)v%*q&JP$C?Kp5w}AF)!VB4L|G|9bws_kSZA>YmEL1 z{ww9`+FaaRFId?NcV+Kgo2Sp)6Iac(lFf#}3%(wWcgQ@H?F^%cQI|700hy#V^O2_T z|8e7Gr{=*T+%pvu2U+xO1xOxAG^v&JY2rf<@k?H%$8m^1{ax>{k(Rb}* zm#(#|uP)8DR=?C{ttw`}hv|UtoYmc+O&^x%$K7sD4(~G+(;ZK(?KkKu3#JdY_cmY_ ze)@hyD^9sI65JLEFQre?6yjox6=if9M8eAFMS3wl>so|0(UnjUcSid3!kv_Y(m;js zzyu%DL>K9`R68YV5W7*zCCeB-HUK_Y?NCc?ka9hE|3`J4)qtssqF^e-66?h)NUZqwHpBmmZCdcs*B_ zf~m1?(ft@>4m*e18ys#2YAC{}JiB0I7ifb8x_)#3+8D6TWS1?nqH5I;2vk@QoISjC z2k`tWT}yul1{HT7Qk(B@ZhXLw^ANfd$$xkNsFzYvNBTMVnFKX!73N;H+*5c{p3^P{ za=>wr7a5^lSH=N~%(K<}C{{149pd)z!>e(?PhvjSB{l{bfUSllikvcUFA;`6txZLG z6U;S)Wh$PTAp0l@G2zx@4W#_LtTySc^4SL({$SGwg9q!sZB+6nx@$tWR5;JF(zWf& zgcr?*HaEq!YznNsY_wx3H;Wy?-IdyOv}Ln^J1|dqO}V&gO=hg-)TfEuzM}C9!s$(| z0{xoBotwfkYmOZ9g>t-n@z0Ohp0Vw`5_%-oIq)^7uNrEu%cK1qgr~;Pr^#Vg@8N%S z4AJ2tcTTrGlVnF!$CY~FyKV_T2LGaRhRZ5@*sgWy_5<^TWH7Wy^ayq9^K=m>j#iyD z&nqEN`5*}kQ+39M^i}J5A!w=j!z>AVKOA7)b3?$Km|GC}w%Ls2m-{tqLyZX-ts^kK z5N~jqag@Wfs#W`{EOIsyH)twdyUPo*;7SD%6wfWc-5A9}^ZcUq+qI@{Xh2zVct=Ae zNKFMP=T^PPt{}?+mvW|q@``d^#cELSYb~vV2m5zvzp70e_DB4&)1QTN@ZWg&+58Y2 zKhmhyDZI}Za{`HTqRT#s=9_js07m{^ofHn)y3dQfX zQELg-U{=*X9o235J_eT2`tp!v`wkZ+mlXp`k}VHvw-(b%MJTNwSAB9nhLPH!2wXWK zn~pI0#Qqg%>H>Ea_|ybcNpK}!Sq(v(g7OY&0p;=GX1tR4)!0|F)dPya7@V5mGHL2q zL$bf^mz&QK%99&t=Nb)<-R{IdDW(7Jf7@&}l@^~)#;Y3k28F^ekrDs4j|?CKJ2+?2 zo}7CbwZqo=4B;YewggP6`#1BD^S3r-Xw{Gz$x;xtcMRY{I37sS(#=WrEZlByXE`p61BA!XL572g&9SQQ zjPVW0x(9$h9avTkK;?Y1lkQ*USDI%Xq_1$i_iyTfjC<%s7zyiUU1?hl=#-n?o+_@K%}y0=(am!zSzxa z?&>?Br@2s`UyK|8TboGZ6{Ew&4rwNDy`f{3e6! z-8M7yA{`hAkj7Qt^)Ea!n7JrW>+>A#nZ~QN-Jvb165bjidh5@Kwf#wcDOp;l#Kqd_b0ztwgn!rixB zox$&Dt;>8dGjH~w`&SudD}%AuBvF>0#)EHG zZN8M5pT8LH3(qrIzIOWIo`n3KNS!fCjog zaE1!HXsp;#N2F)UpLCnKE*Yvs@i;@-OI0Bt-GYp#gg@kcpNSZ*Z82h})EG-WY2VaF zqe%`@!@{+p-O-8mD{qzT0zf04Pef`Fh=y?Rel=(H4Xkbqw;t#PDs6aACu2ZRPk!)2 z$+*m5GRDG#5#%zH+OQ{XSBpYj`aM8&gbQBy#|pO2m_(1l5TMS;VPA;*i%KWZs7cy) zqu7QyC)#Q4ZJ~-|AeHBv1%4U3V?WkGx^-T@Haf->I<#kU!h1pyUSg+>AXc@Vs`GkC z=Z94Mhk43dDs;_uay9PQnV<*Vd;kg%)DvCy>zT-4Xe1g?yTQdrZ%D`zNwtkE95oA~>pyeA@NyUS7A zwUt=~J#7Yn=(GfA#f)7(#<({2>u$-TqC3J@^R9=e_0* z;`@OG?b~|rGc+C;-xlDSLzZM@+^FiZN;wr$j4g1m-|#g=oStZQUbB+*`vUW#ok(vH zrP4L$%^F*)_L~j=^BnWK+XAJ=`Yy03U&Jw0fYGn`=@t?LAeoNo^n4J>JE>c3cd*$t z;yYtRhUb|1}(V$7%@`>cg2Nly8{FgNG)he zWr*eCv0_Xc>m}s1tDuo2@dFxvJy2~M{Wn6Ku@z%*2EEZ$EG)ZcWI8@M>{E)l%@{+E zTHA{)SsK`QxAOqDte8tDEF}FgE31dmMr<v(wE5PE-UBWIrcK%AXc<~w1sq| zPQj=it;neP{?70?u);GyW^6s5^)v_ucmD#yeL)zg4&8$V@VzY|swZ?D4@gFCz}F*R+ie(Ub%gk0>}{5JXoM%aKA!qjjzpeSPRe2ckVS_1O!BH zJuSJCMYvkHy;59sTuYi)hoTL=vpipN9bj(TTQ_$@11Q;4JD>%rC3+ulw>;_r2wL=N zPS7l@Cb$MdwdapJ1J(-uc>DGquo@9fNUM1z8T*@E37(DelD@OL*^dKMRyja@U#~|T zSbbDJB&1dy66_)OdNyMO5S20D(wb{R`%*<~aTe)fY~SNZ*^-5TPE!p3%5m#h)8VAPLK zx_{8`*)7XsQzr|HYqR&F6uv`VyiJF<{M04FTdJA9wU^2?F zYdZ-dH%|XKI>|)YkT-zOQg%t}1)yCFd^U8-!iunw=fxkTFQd-%68AUgf8e7nxxb^` z!l332MTS+7RfAu~gJ^+}BaHV4KnyRM6jmD|sLxNfzD%Cz9nvfW&*v6cuK_t_eF=n2 zv0i#LrNp)1-=i#P<9{%(I_~5vqN}mx`C?PeETiT^p=tRVgE!Q(I`#5_tpn$K>HgS1 z6bBpAFUq@6B@e*kNVSWkE!QvwO{B+jsZ$WMa8^y=#{cx7I{3|o&o#*9HlZKiU(jSf zv@RGeL1mi*X~rBdZNDJ4+}6xYh?T0n_!AyYNR z@)&0#$S7jYKV?+OhJk|Kw`A;%|Mm$3t^i9~baJu7zUxpFQ*grls>3F2Az*G$Gdu0GI+a5o9^;UHJ z1Pl_o&*~_-rhlb9$C`9gT2+Gg2MQ8f z6jk%Vp=WItl3808@LzNCeBl`P2;fqj*Lma<@ak|+CMDzptzp+(PF)v zxIzRdrFFeqc)E z7TyC=!9u^HjS~w$tm_lYQ8(uXO*g6;-fhmtt|>+*IhP4~;MAsi)RnyXXZ`!34ONHx z|2my+3i!0S`-m}crWbva?}VfV=?z!K{BVl`6W_Twf&=%fWolC}dl{pgiPU)OY8u*- z8^kSHO1oQA3j)nU*LU*aX(Gh2Q}R|a{+`ksjuyzaq)L4n@m~vbnR=}&vaPAARwgvY zh`@r})%u%N+zOsbZULwT0dG!qavF*qW@rd>hVXr|OzTpmb5l<(hbO25VooVjo9~@C z4Hk_$^2l)~KYu9GJtZT*3m@v)VD)I^-PVW{y*5M$Kq{)OF<^7a(7t9yH3K8$F1&?! zhH|yPidKCk+tnKDw}^?Ybw-=M=N99P#ThD(a=`?Gx*RFJP2#*$%+INd??&*PjbLUmq>EbIA)jC&aRbA@aL2$W@9DOP%U4MnJTszGRBpdx@)!0pF=zW z;q5q}|;|=y>3+E`xVtYiD_IM|(W^v=a>{)Bp#5;xna(Y@^4A~pa zc3ji2dR>g(d_fumb`g@0QO|j;6oR_>ZZWiamJe8nvEryq`bdqVe&+>pkV3ERBhLtvilVF|wBC32t&THaCN4Wm32G&v)G-5Z3Mr-ZH15)UUv zWa>y}$mgxU_JK6fiwRh4&?NA~fB;1qd#$->?(?%%iHJ1d@YryHlC=@mF#{2jnY6IJg~FRi0ex zFb;Z4=qdem@{2skxh}Z_?J}o}jS=Q#I zSXISgp*!Q{?q(2nP#Oh-cWQuF(483v>}hZO%`y~XG74~ZxtOnwd}NR8La_}}N|}B$ zeiYK0DH@K76%r<`Fd;72r3ak=EW^p9kLKYw13*vgf7>LxE!oR3(#p#vxi8?|;#PR> zf=rd+d!S*`EME5Vwo~JO+qRQOuO&jVn*)rkvrc*)HFILDXg@!!Fki{-yHhO}Aj0Z> ztv!Hu3RVo%K25`j*M9g!tcfzgifJ5pFBi{crE)Zk*_NkS42{Q+hHAAQbWRH$H8iF8 z`ii;~{#;hFUMJgwuizwZg|Md^je)aEpVI?+KmeTJTc^?ftiMygMzX#b8>;Fb|gb zmxOR_ZFW}nvidQp8}yIW$(<%ePp#=2v`SNeGYh(G`XaD~Y=Dzt?_$$I3ffPAjx$+^ z3GXPI!5MI})d#C2TE89+{y$0eEn09j{l{o%>pE>CKa(cgNmXitRIuWOz!AE0whSR9 zD9BC0YAG1oxsX?Hho%!(%4Yb-_$5PBg!G)4-;!#{_@lB#E=G3vF=iPvnVK&GC(OvX zbrZD!o+cBVfskvMO+lC2KbH~}nvhL^3`DKTmR!Ody{$|J6V3F5yW zdn~_+%C=-`OCf3MY|0DjO{B_3oIJhx+4@eyG6o8SRY6OGaQ<0vfSbYK2pLs>4Zp0} zSdz#{b4akS1xrg68GHuNdY|#nP0FlQ|FS({kg9%p(d=EaJKu#jgK1Cml)hLF&n`N& z6?N95I1=RIgWRq zWB>l!?MBsRn@QDFLkAAG+N-nxCzK9%9f5(Yua=ERQX@7cLr^l8X_C>syY%!Ai-{t{ zk6nrs;-=g^(-AT!J88f7erBbYhmf|{!*gs=>n^B>oRd2n>0ag|7o2`Z^dNJnHAT(M z*FgM)Nflu?4M!dOvG4Xo1cu+^=bAWV#)s!Hg`AFi5Giq{`L_mul)(y9!X13pLtZ&U zUkE>rMP~;^D}MR_Km~8NqY7PN;mbc4^@Vn1WKCsi$f61QF^O$2aIk*rqn7OSMg|F= z8wH!)=%ggHa-NbI3(-ltM_k=B0a5X)Kc~bk8L4!s3{UbAGvpQ*p8tEi-YSf+fGJp& zWeOcEC@WUh!QUw7k>&FZSPB<1Q^tV`W3_E=Myg~0_fN`+SlYPz@p+T7_PNof*oV`* z5W2iz>2{CAKtH@`bI^Kz0x?K?oy_)!g|6KT6UVH$^)7)PGd~?W8KzR^<@XG)nyEFqb zODogL?4f@*neWpN&vYko^xoIX2O~Qd*^}_c0Z3`XdlMNHFd%)be#{}(Dx(<<&=?Qm z(umn>aE6t9A*aN#sZa%_hfHhx1xsrQx7jM|PF!n}ox-(HK8 zK1{0oIyZQ{v)MSe<1_(S^0u z3Eiz*8>Q|x&m;fd<&`w9u@jD`PaaP%TEO@)fa2Z(UR1zdtVu}^qtSIb;BDJqePsyh z!RF((tYMuIkU!j9UL2d=U(hRvMqQ}nDTX7ZRms-!XnLEImQ87goRF_r{RI66yy_Qv zWaq_6QByGlF|qN&O~{!2xy>8X>FtXxuAJ*oA7J=V_ZE=xLjhkdCj;iXPm zMT0|($1Qnp=e9-T`kNAM#aRwT3d0ouOAwb1D6F|Rg)eP@e znE})xQ-MFOyG5w}KGH57SvbM}QK1q2X=zfszxwgOO`uVe`^SJ8R%V1oqV^E9=_BtH z=W1~4oEV4xX7&-ZTYGfn)Z^@odz&f=z{Y|ict8n_-qSFw~0t!JOHNTd=)hog3W{j4B}O0Va+w}#rN+kdU&muO9QkY#7Lcg@1=a+XN` z?A?xhTRuw_Ez|OK%d&iw;tqSjU#P{Mo zL;M-3vuWoh_fuF)@S+KMiQAHm4OSXgsL-Ui7bNIr!=kp72{6b#CQ$Lej_=w;$Lu$z zBYSW~&u^VugeYfS6VX8g$=Q^pcPUHt6p#YtQb3x+Edh~zM8tDI+SD9nLK%9*6wids z5rbK>uHY)+E+%SpGS!%`N5>s^*bP_5pHyJiney)#gk&0amTX3M_zkvDLd-r3|C>EATq6h()p~m%0XiwLz8cQtlNsjGIt#S zZ{RWaJw^BpUm>F9&`&yMWF+)PGU&+U{)|*bjDef2aVq(acaau#V!9_o9ughB97%Ya zlWzWy8b#JJ8wWNcT{*w_bW>I;6Zn#Cf11yj9tHs68(ztVgYVwPe)NsMuk)WsXJ1 zfMU1+F4$eIT$ao8`eDi#C9LX_o<(Lo3OTd%)BwGjQ7SJsZjlKWM-XX|(q}?Gv5@FT z%^pH}wJQb_<{u5U%@vsq10G>+vz6vw%YVdFf}YGrM=HjhQ$U_s0$J}G>k+BFNiS~D z@{&os7QRe!XGYb>8x9x@|K)#V6|IYFhfin64Gm_H>XdMbHkgdO0Gk9(xDTq zH=%vt6*KL;hr%|UJN-T%uFGcmHXmO{efj3zk7>G1|$uY?i{+qJohI-1wC9 zGb$^T4bB~UD=wtLrn&Cv5s-u)OECq+&AZ6H`%-v9CBExoW`)dc@&MH?qn4IQhhpYg@hdXh0-qREUiBDHm)dY)_7Y33i4xQQ=^hwfmkbAtS!z*i`()Sk2 zqdM1@a7c`rM#r8jGD?WO^x}yr(?F)wCxwkq{OBK<+&823FC|SD1p2G@du6Rye&6&@ z=)yE09qdcikW+)rzYGq1!ky{-Be~+7W~psIZCK$Zp17Vhbr%22!2;tbkcN~1HKcD2 z44_tNd#M(kvF@F^q3rDg*V;cK)E;}+4&|E+DG=&nGHF34*<`VbqTDkJ>ty)igMBO+ zwVR!r+uJK`u#@a6@AuJT{+?(+`_lpB*uX|am+u9v3_mg5_T8N1WU(_J=}u<*P%eXLrf>EIg^yD?|anB$S8J(_ng#gu`H^cAJ%| z+I+re5X+JZEpZ2>ur*i|`ptja@<85CW&gWGcJHw7wpdXiXs$kK`O>-G)A(1+T}qA# zU1wgR*SiXyt|m;hYHIzA8OG<-WnqsTSYXKf>k9K(P;Yvhl7IU5SW0l_gl_#YxBrvV zpH(-mYnEg7lhiXbU}ifC6C0Hcjq3DXEtr=<9OCVOfbmVPws(O|7!CQbz5t|sO76agOmSP;UP6U7@FvznpsS!WNN83T=j zeiOd#);V~i5#X6pAG!lxY<0WvH?zF-9RAiX+Buqp z^1o$IkMR92_{^0Rc`RN-g=at`vB-m0byIdGQQ$u1wv79PALcw)Z#tap3~V44TU^%L z>^G#`jvrsD*)-l6g!U7`h68Lu1(fg(LRQWOpQ)R2*40q@vg9eY;rdj5hZTLZ(sP8EAG3OnWshSTGZB0W$Ul| z&ovb~7LMb|sdZ8H@xBTayG+_+w1QZot#8hv3;+bwT@4@m!WfuJ>UPp?!haN%UjV;=%u|eN4j!j!;a0|C{DEpBEUSjwmEhcnGJJx^7Y2wQ_SiQIfF2#`m@y2Au zjiDJ|6mHu>;jY%c5g6;_jiR6LN_3G{JG~`}*_eO?nZ@ko>|ofN@6D~_X7M{>l;UNY z%7UjR-OyurFl?^k2kf(2CX@%sG;AEzyitycz6Pp$L<^?0x?7w zwLzE?H%HPFMV1HLG#Df;!`#TxD$ae8w*QwChhKK7Ux*?O<0a?fiRUNYgRR{Ubj=`14=3w}OwRg62k7 zXgy%a28Tj>BJV$A1r;@-^jW7Q7J3ZOE!#oKlin_J1!J|*cwVi^N~Z7Qu?jS3%Ubwf zh>=tLkn!Kg%AQ(Y$`!*WCs{7@1Tm0G#Z1u?HGpm(*a2fTRwD7V`Fgw%po%`6`63fX zd&T4|?EyLuPxJW}qsUp;;JXf5F5)gKzE{lt!WnRY>lAc>klh&H>L&UaMMVMsZY3Qf zVEajht(*)*a9S^0K`x)B$;WNbksD>gHwVn{{E_-by2Z>XZIm6-U@+UU?7;+NEs$@? znV~qSoZsVO({~5V0$w0#iJc%jr%aJyj&H71$#Dwwcz(YiFvNhdDwlzP-M)yjTaZ(S6H!Mr)(()XlbxMRVF8&1wNn3g|7|19 zE6nHhrK6MVr<2vx_`v2F6vF4c*4$z9H4U0ktP17N-<(MEls?q|CLBw|cP5r;7ixKw z`pIRKwjM9pC9&_J;fYuuCBS#=KxoE_PH05>3!1pwOHA zRd88AYPgt54QSH-K_%V2>&?B-S7%_n3w{#+Bq`c3KB1+lUFJ6ygbz+>nwb8?w}o(3{lf+ptX+wZ zcMq;?*3Z-^A}Oo>_R<77-IF{T`#1UBm|n)#IF{XKfEiR?$|k z2Pb?%xvW7rE2lRQdudXR0d6R+y|BzsIzvenSY1U){D4%UQBn&!);WC(n0-z)){rHV zC6t}g+`XnKh$>w~_%+}K|0*yt&Kj<0_F~#yN~NU|1zr1d56vGPtvk^@)qc(DNH^ST z%+X{MQ2(5DRe1ar;4I6t{tfM}VIJ%SA5V=XAbtinR>#d7B5wSg6POOYuBO5o`8s~ z$9t#joI!&-4A2)ot^?d`8Cc~6?pu3H&wb{3q`P3D ziJLDz*L`4CKK?+%vf1^CUR)(;ci?g{OQj$=Tj_!T_P6kg|MSD?O(2`AemDs5mpbu6 zsIL8{s%?6ZUp&u<2H$Zz>YBMo93!vHZJMR9Dc`N*<52oX|J!C4-#oiEUdmoekXIPd zXaM`f{pJHkAFGIKZ^BvRSnnz2Ge9;qz1fsNM_h{j8!};qHY`U*i)aT18{mx!5ATH>+R{5h5~ye>1iKHLFPR`@MIk95BajC7v84)NW;b9W^sgP&Hp z+PCahAY@M5zN^sD*sxV{1C_4NNqSev)jk384GJrsC^D5EtPECZB(~!(sutREor1( zGTrKPE~PUxysJ{zkmzAyf7%^6D@Px6F9N=bse8xvvfTa;6P>;HeRBYta_iyL2LpvL z#w-qS0k#xXx#(Xa2M%l>@0fjI*+sdm5T(tJK3af7u4F|OM7|N6jIe@zV*UQr@{F&U z?0;3wx>)kOy@K`rfs@hd-NIO%8OalE`>d(?H2t96-Yzo~>-P|=iRfBqDHIqJ&?)t$ z6AqdZiuXtpeT38ttnQ`w5=`J871wlNUEz}5?e4Tls%hw<`XcBMtn6av?TNdmm)kI` z7QBUG@2+5;haNNbu+DJgl{;_CzhE;CzQ+duD8vKoq@`-68AXx?{A(W5B8g&lo5?3G zXuUfK7L|)n^=Ujtjp30;LEKq<*!$aH{d#`5j9YDkENGf2QWS_!#%#CwU}99qoF92b zYb1}lWXxxxfY1t6>X0m4`qmpxpk~ZtJ^@(8+sh2U#4$Chhd=DK^}X~8(P-aOnbb}G zG{IWEa9-6`T9$T~+yW#__Ro(GyRJ+n$p1uO8haoP(wF4$H;ejU@qwWyrJnh9p#7;7 zYjio&Yh#z5N32oK7>BjU|4h=6M^K;&#CKEp{h+=uA#Jh=h_9Ii+>#IetVjdJ)y-v- zC;2pLCJ#0N@ilcyZcvQ;rX!Sav^ zpPXMhj|}@+2=xL_Y~~-I``ZuRIPvYf5!$&Ax1%S1D?51aZv6?PcoN=Bj{TzeIE7aQ zG`LR#Mfv{jp`&LqXDLY)RTiHz3euBGfI4(CdGCN@P0E2=Ka~uqEe?gED|9+|t{T_` z5HX0sQh_~D5XGt{jpx%8P#qbc@-_eJ?}?ApQla#NaKkc81qFW9IlZjO8$0}XN*M$B zJ{qqH#ybB{5oi&}JVwjHZ^GD8u5F^Ff1#M*k>$)hL|ufge*xp{>#zz0Xuo!wX4#%& z+5)ex>2yaun9_UX&45yM3F4t^)iNpqE|jAHf~m7wLIrj2U5CO$fncC43w<+5zA0Ex zePV&AMwbuW#UMt=*7Njho)Q+K9x$6VVyBjD#OCcH-*?({WiecH7u4JpbY@YZK&5j( z`%eqDSoe^%QMKL72qX65`enkT0aWpe2bgr85Pz&B86cBz5Rady?4ea}A9_sB(gCxpr`N_h z+Ivp%1LxJ641oe)@LTWJk5}%#E;$9Id&c~1nK5-qW;PPnBU77J1;6WTRKrX&YMr$s zbVd@n^6kVn8V5X0_Zpm37R)kV&jUW!2cXk)%_&U*HvQE}9*kb^z*>B{!GnhdIlvh0 zy#)c53L34pJ30EbqGminpeWc_r2av+H{XfFfzISnnr9?9Nse>D$@eFxRY>0#3_m)k z#gmWX*K|bC#n(y~!rL@RPpyBOIG%;9-@0?I|D>b%2OLolqb;Jw0Lu~zh?*EQtMNAJ!YSP zN@s>b$L|fg|Mkk+GLJ1*I7xyKxd>HDf0IE}fNCsJ0<<9Jz87Sj^X7re=-b(-e-$A{ zS!Vg(sYVm{T5k=+W3Gvv<;qG0soeBTMB|U-JUo!OgaJh4@v;EC!_C6n9C7$^dBN~? zWM8WnD#3V5X6g?f^SY;^iQ4asL7+^oqMr%*QbQ24LAG~$vLzZ_e0dX^@JktBRR{`< z)eUhae2{t_fch(ck3gUQ0%Z=GV<}mRBE7_Fzc;hD-%DZK<`7|+m8K|ikv)9B4K;sP z!ucP+Bi(6S`~1O*OB)`H18H3#Y1b)KO0L3}ZZRANtLM{J-G$j1XzUT2U}E{(XnWq$ z#mtKmy|2djJ@_t71du2I-AfbX)5e4HH$*7bcLs#s)cm*YE-f+zvH=}(>q?TFT}YCv z?T;aWb?NWAbB1JL65Vuh6dU28oNUt??lauxaJ@1BN|Fnk+I4EiL5afp-ix|I^$|Vi1&h)Lr24u<2Wqv!-_fUypN0^E06! zXmLmF7}RVYaa?TlQR^71nozzl6!QN#I`6oo_WzI9?UuJ;wyay4d~a!1W;Pt92)C@v z%*Y%#;g*>z30U0Vh+3alj!ym6vCUN=v_dL>`#Zu zCK6e70PPOK+p#kG|LW4~W_eOuqU#f_%Z&H~I!r|hm-s*a8S_#iZyuLd=Uyyxl$njx z#OImTf-4`J#cHHrNgn|;rGCa(Z*p$H!+r;wRRLd;uvU{YiYOD zu;do1mX(UTclyY_8|0V$DyoEWo3`u`8t0WGh zX%?&`H6t9SepCp3WUn=vDzL(qPDgNt`aJ>1v@8L+uTowQ|8`2o9Ygh1jh;)RFML*? zD^N95;xc&?CrxQSr+Q$vtl;#{3C_ajX^D|!9S0P_^0{T^z`sg@)c&Os3l@BprnL7_ z@l0fhg%VsaZ*QaX&e80Dzg$QRn1=X55bwyN9<00a8`ZS7xqNWR|8OwJ=kw1Mu|{2C zCxLJCe(1m}H~FJa@^6hNh&>Xc850d2-FccsjaORa$F^nB6rYKEH`{4_uQjS~%x=ei zLM+D|gHF(cw8w$>9~9w6@Egujr3osVxQGn8qNqz#!*z_0;YndYNC4-+14iCT=f{ z^zT&}ye$!U%WLR_?!&k}WKj6V;S1Rw;5;tw#?L3_@ViEUV%kt?n6(2%QDa^$A7Vm> zOjb(iF8P+WMhP_I8#|5B8C{Pp4b%b~h37`Y^$(^^c|TWV9>-LSFu|N%zehMsQ_``? z#^G`dNT45DC=AlOziM_E=B{vUF33+-8A;59(0$SKx+R(Vg2Wi+OqyFuqORZl=hR^g zfaJT=GCK*P5&Hi+m3ex*Df;0{T;=6v+{6H*&3OrVuO_X*`_xFqphlWxnAiHMTD$Fj zxRn+|fKHi7Wf*d(-Kfp#M)kp@;fchvCnI8kTC^s{l61 z>T`(0WKL+NvpJ$q8XG$yz2=FOO^Ae0!-H1|BNG)UN^A@+-Z#B>2Z3k0@-}IDPoO(~*;o1STuZ{C5JdYPnZgxs5qleuf zBlf;mdgJwUi~HBf&DHPkfRjAs_O9H|S{gGM6BR;Zm@2*?ZP&M>R$xW@3g~!2o_vc& zqR%H0bgxEzCrT1gd+QZh+F4!ufKWgN-huYCti6I_0B0DJ4_$73XFW^;ANtFMY`6I3 zRKrS=iTs?=e^mnF1>O?4{+|}?{u`07$XGCy3mFeEI$Z=CpYVXZhEkK8B8~27bnK66 zA|URT*(+S7ksuxI-RZ*JmI>2K*59b64L?FQefcqS!a1(acgKzN{-51!%4luusb4LgJ;AoK>Vi`LslEFGeUGQ!R+$mbOx+tYSn_klI%Q?m zx*I#KZ4s)yB7UWsZfQ7ZdP-1FD;IPpN2IONs%Bg(H7dxm6 z`9pi0wTe6J^SxNhje5Fgk7^<)u6K`WIQUPkqcpYU=MU2c;TDOmXHx06fITcYrhG&6 z)51~JC^|n1W3tphweA{?2ON(~Y%AD@0J>F5qT!nWi4)dUX&=faznoZuK>fSLnk+;yp`8V=%pL?G_KNiF{6fI~BsPYBBL*!UO03Rm)S87is zobQEO1dTc%teA)yd&BsE2%?}%f>m51|Ao6#?~?a=t6Pl_TBs2YU-N4AcHy!zaFb^g zov1OYMK_3@iEOWbA$^Pt1H1~hwbK(5#s!uCrSfkM!-rYlINlR!L0q&&&KJ;e56E05 z!6Ry9X&*3oG0NdnlxRS^OC&BVr?ln_D1qoTwkS-eb1H(py;I$VR}ZCVHEKG|mgNGO zaQEO_NpXEWkUK1LUkm`oi990=h^he_4k(pYD{FGb2c9x`Z(k+_@lVykrT3 zjlBN1l)99cd#GfQOzMN)aSLp5qdmeGRp_}0HgnJ>#`Znf?flg-3(wn9qC{rn9dn{@ zk#m^F12%yaYvLfeSkBLQlG?p8UyJ{ zpGKIwmvl5#q9*yIdOTc!$u)Vd=7#RpfQ1~Q`v7WU+4a;wcGdtuj(H9c1>l@An*fQm)$a^s#!A8ngUbz>7dH{ zD@^Mwa%7(S`Y}wu2_RagSpNmo%XWrx|LJvJ>h2#0(DYGhyacaOm=#t5{zKG;v`IsUHVF;Fb?+QMY; z{LZ?Xq9b2^w@3my3{&KKW^9PK^-a<8TkyV=>}}X=5Oag_vVO;W@DiknOZVE5y!_@!*oK2IZy> zNUfW@Q88>5R}hF7i@d@cDO!M`Ix7Fv9!B3r;LzBaD{C35MB!hPCmA0lp! z=$O3#hin#8bBOA&_my9HY*XZ~4ih$-g~kj87~#McpH`VevDp_u?A+AAt+YK33_?#e zbM7LvQn_8|V^^_It!kkDl{{itKR5;OKIMIx2yVCmamEI|A&A-&yqF~dbfdjo|O60!_ zorbJc_1p${xh?*5l_%gchL?dog+LB+3*4H$%lB^!5sP=EXV%NGM8EEu!~Qn13jmIy+6VmYR%2WRF_iE32sVBdN$h zKyuoR_&u7oM08M1_60L0|2;rQDP-8c0-`r&yzI|;n@XuJ+CM7D#uv;U(Y3NyV_>_V ze4hzEFSGShWz-$WkwR*Hb7nYRCCiYc2o@T&NUW??J;*X#*LXi|AGK#K{JD>6L0L{s zNBXz@iU}In6*S<1i!tq+Mp=EGj@e6~n&mm2Bm4nN=E^!8^^<{#^PO#`;e4=DG^E4A z{{U5I`obd|qUoK;&Wn0H&^xHe zAgW@u!9Tpq)>*vOT7A{CfU-b~`85RZB6fEL-LlC+%E>37f#LQX*Qh6g2c?0ZDkJ;! zdxNknbZ0VCkVk0CiM8I}c^45;yr-}YKtR39Dg>zb{rQq+wC@;rS!TsFry!NjvJGe}b9G;+z8m^x&qSyabLQhn{Tr8XgT zI1b_XP*aAWL&9p~Z@232v@T5E2m-Akv+k6ZItJ)-u9YwBNn=6>jCLv)j?bef%}Sd3 zu1@K3Rb|?RsaN+I`2V16;Z|m>Nce2%%t5`+; z#6!Yh0KG_>oqt=AI0B&7!8yD=2N2v-^Oq5e;2`?9 zdB2)E?i`VlH5mBwBz}#vZZ(p9;W5H^3 zeW}r6*+eoyR%6il{*u%TWjD2d4kpGfQWM~?jV0RSscA{4lmUQfiXF9`ohZk}b>aPe%v3mRHHsE9p&Ds zqSM%=$oM+3Lqw20d7ojQXbN*EwX<^=6#GeZ#~#si(XD+M5IA$Ro|Ra9(OR#x=Ie&q zQv)iyfM&ot5ngR1Y#N2tQ#AU3^r4@49U5Zyh;}?u;!G0}di0Y(8*A20HkU7Hox8s- zH-2V2tUppOyr3dtyBhU;5-5xGQ$Ee;g_YuaO0s1g?u=&I-r~5hXyD=mh0{R*M5Qj> zqiS{nmYa`Y*;?VwLkb2y?B3cjj;L7#3T5(mx8<7>`@ho?(J4}t``CA?Gg*=WCKyjH z2tvMg-WjJK5x%Y!z6J)V1b&e%CcW48EN}B-vMZo=>PWy8V>TwBG z1CgZb@=;ic!YpCGTp)^0LW4AGpBtg0R~U!x(lkCvI#fBVy;ep~(uYcaYYHs!d+j}h zI5fD$vJ}O0MmxMs6Y-|V(+4JqT2bWUVTmx`~3B%Ys2i{n$M{@sP8m*M#E5LN8}-T_Z>j6!`+02j>L6lBAviK>M_ z@;~#z#pxQAQA1E^s28@8{NTuRbh5wP<2Vz>p_V-z+b^{Bk=bmH&pUT1#ZAy07RV%! z;dOw|qx`u-D#BYl5OFl8Z$mj=1q=z0AGy1V9Q>~I>=jTaWcpNCFVH#WruP7@k^k=> znLTja1Vd@}N`PFR{Q^u@zBi|l5_lsze)PcWNTJhYevmSJN;f{0RLFeE)_<>R`ydka zg5{5%I&#rY$ZC*mCV~kL4eK2Rb1wrb;$RE@Y`@p!%jg`^nPL!?RBCWL-Rr$9oIQQJ zege#E1qN5$ccMb;YWaE@Kagtz8Jj9>`!|wuy)X<_Xgt!K@fg|?7@hV|q@dkUdrNkd z*&PR#6n7(elB!&75QY2%E2aEvIvjJw&CL6DtHQFSEpmZv7bLq`1vpfkNZUPvcRyFGVW!9{VFvZ^V`7rfVy7Qw@I>A$ zd5C-;R>}DU{{QqEf9wrdPmaEfOXA}odrHlol5ec1h#2>{2?4ySsx>@d~DnuqkSdj zmhY2n5~-YOrak#;{%;UtI&rf2kE_ROwiGzd{eHGt)%-hlyXe8qL&={j83HC;#+%rU zzU&!N{eD%i?Y~50?F#neNrt>F`Wx2=yT#=h}DO>RGR!%c`_=ioKz#VrT-K06WRH!?X z-u*1`J>@^`OZrv+Ue|15R|Jo%MqM}kDCAfWWW%@4Lv0_3R5ffoR$u)eeC5YYQIIAW ze&P~5VsV>_S(zsSa5Z`XS@%aww5DAn{jX!qv942yyS2=V*T#OS#)8DMhG*#D6QGg$ z(DDJ&yi=ijXq(SC^gCbjaOdPUpDZ8BHD8bHg;MX=l?ej7z2@wLAcbR!?Hd~Heec*; zAc(4rBKGRIfmfX}+l%;LU&j)IZ4iBS{6Fd5dT4M*46(~lPL@wQD=l&y!s!Bq1c-;i z19)dmiZ13}aEppMKPVoXxII$4Rm6N$z?!)(&G6?& z$inplWfO`MfT0spLyP<5`o49Ky|K-xriL23C$DJ!)gxb++fI##dq{IyAcGuGib1p8 z&4baBnfV^x_mJ>TRZIJNI;`U@F!2FhP0Wq7Z2Jj)APdTr(>Kr*Op0AGc9qYcB_It#na8NXnY{aBn1GicIvw3Qs( ziR`WLN|u1jh2gBM*_iYKs^O^Qb9ELknW2AE0u@jFfoEl6WM2}k^>q7<6tKC7>9ReA zvhSP#Bcv06R?`RLjm9nj%{oKX!hg0zvvtb^e_bK! z^7yc(WOT4KPtP42)2k(Z)7k8eR{pUg3p-TUY>Io2*6Q7OI~H-^O(J}Noh)(eJp+Xt z(3`h%3Vi=h;>1ixFu?||iL#kDkeX*zA1*=Otyd@=bA=R|Ia}{5D5z-%J9!pmt$mi#A;ZSAZ8Y^4QpSQsm6M>9>IOZD$p>>TNYzs z?&-Z83CbB{Bm_WDYBol1+c12Mr}_i5(8jpKe&D!Ni27`E*g?n8Z~Tcn6lh=_nKkdqpV@f*2UC}5vKK_ zA}1eKZOZlVK)vmIO~p|C3CaqBK^MUUr+$&;3moEuzha!BSx1<>=Dq?wI3mb*ZcAsoMu+qx{ryy*`imLy-3HLi!<^s-VZdA!G6}@oGRaP_M{!G!uIU8m4HX= z^=SUGDjy~b7#~fRSn>Mcw}qlSa3N>)TtZq+X2U`!Uv5N?>SqC=iwQ*)eU2jA!mv=< zjkLB^F(-1H=@(SH_)VFixj9)N>4hkl?P!SD#Eb%^TnTo^7gFzHzmO!>W=M>5E-y}| zD7BaLvvf(V(82e99j^qOZ`5xEy@=7fa1Dh{i+Wvd$OyjJ2OtfSnlYdDrENeZ#3Prm zB4<@~1R}iK7-y<;uZ(^_I|}r8m0_yrHieDC+=v1^yJMKvcOLz`?O<}&dzGCsW=X%F z=g)$LwvnWIHEYG+L`7TOg+9xHgc7nQkK^0FQ7--7=B#)|bq4%k?oH}m9g?+&c3Vxk zD&|{RbQ8F_E&!Ee{1nj`#6>uFiBJ{iQbt%WBNRSwx|U!^!3e-Kd{6)m|kMvSlZBH7sn_`|PWwi?PC zf&o(r!(BJ2y>m@kICoZ7&}V8LGl|NoTf;t3_stX32cqLOKVe^Rsx!2i4z&S2C# z`4Q~9-Wg^{^r`Vn)=u-#1-a*^f!qZEjUIP>CZ(7^c&i+VkM8vXCi~z2KOfvp-S!TV*3f(B``(s5jCz)O~0+YhVQa zumcD_>cWR@c7MmqDe>DS*w9urH>}1R>`-`>Qr6ozlEeS8y0X^yAX<0XD7S!FGk8;Jetm4y z-W%#x#SQSBO5w8}AHJomN;L#^W8{aP)xBwA{+K=qn_MMBuK_SB`? zf_$u|%bgQ79HA2MI3Jke4qB+W;PcPaZpzS({1Nmbd}`1qWf7z)FX8ot6}G`COB3WA zDUdKctb^??ZPFY?w^pUU0SOR;>gaS%qeUWEPj_d#{U~S`#yZ(&oa))v!9__W(dpko zu*_Utz#+Z8XSzZE;|+>pcv+fiFPI6^R{8XnTm4*d@C^0!Qj8SbWYZ8glkh0li@Ck+ zAWiW}{-$#_-b2W{Z0(^@1i1bjyUDWvWnt8yM88y}j`{~pYiYDEt;j4|Tmy2A@@h__pw*9t>{~v>aQK&OH!tKsVzzqS)c@x0Q39U~ z2-VRBH$5QD5V=eDv4ClnRDEIE6x8$*{QWR(tWSGb8v`TEnTBpv#nWRtc+o5T#D%k9UkE|`ua`VAFp-NKd%;1+HPb>h)pdIBip zVnJ)#<1g{Hz! z!oFQOYNPF^#bTX{Ms_nw)!;Tku=J7;_8sD-AxigBwz#$nM?y z>be&Up=3qRbPXa8pEJF~@=MP*wL^`a1-sbjRLAS~o(@l@mTIPYv^6F(=2I1MTUU6(nk@`H|e|Fn}{A0hdbpKZfZBc(_Z{yo0t6mj*+vu+U zr{pzs-0d&8&({OJ6M1OVB13=-|D@UoKb4!R@2Pd!})PGC!?7k22Y_Y%j4|`<# zj@>7;MLp`o{xjwESMn^lT2jN2V_+y8z?>6$VRmd_Fg$TJ#ze!<*fNdJjMrnYQTqB5 zd@GA@x$34gdo{aj3HyBBmvctF@~djzU{t;fw`;SQ%mqjBQu5S0rTv@fX70mCsOGrq zYiW^L(r@Jj-fitWKuCaBT74@@Lt3PL>qh@=i2LXTbWq;(nZ9kYCuy(yz`0!3PGk`t zavUAP@dH2KgKCPwrOwn#8pW+Vf%Dp^vH5wocOb(LHSbl-e(!g8(3VeXn%!Gwm%8ud z5BzzgUPX)2MGC!B9!>bHd5vq>P4(Ha<#ct!5xx5v)z}7TMvB&leNr;~-%8~!S#m`+ka%pYbz=XDe2bLWj%UMLh5b|*TZn)LQzn^T0_q3__ z-8SRrieCabX4~4dO8Lgz7e%@W`L>*oij-l_POb-8J2?*TaY>d+E`K6VoCX1#1yI{3 z?CH@5frmCfvF02%&gwr$VXEK=1g!l=P4ahO3oi$xrvvo%q~X{WaWJet6v}%v z4-u=$XGryOlY#8>!A|1^L_@x?29d zShgXbWmt8x?O`EUmXD}=B)lGiVbF$B!xRZGgRd8-dR_>sE~EVR@%a79fl2AdC6n!E zfmUbI1N5gL_sT78hxY8Qw`FEM3{cUJ0YUySPLMoVJZrt;JQs>Rlrrcq-@rPCwi|&~ zvb~1zEIX_%SU?eTiod4cdaRX28KQb>-Jv(2RsEBCI*U(1K*B&hFd0d)S1J+@E!CQ5 z2~gsod1^dVHcx)(UVk`GAuE`2Kz{Z>q$x7o(7v&H8l;0LX)Xy13L1(nmkOq_Hz*G< z`&HsH^`i+;P7js;T+vr`s-~U2`wEvnTWAls$Q zyGnw%pxB_bu`^fc#4YKkA{xW9(lqY{tj<3ap#BnIr!KZcaw(aY0opN8ZV9VZZyr(H z0R5fo+fNR7LcZ9CiRdxQ}FaveR`Nc8sdN=HUu=Km)}{>BA{U!OEd%5m{KSk4NN z_VhYo1pv3Zy+Otv)ROsv5InJ#Zl=N!#i}3=I3td>AblfrAB4Z*0nhcgMQrNkn+VVAd~>8Dlw*lv*GH>98f;rFBG9Rx!HsPu4ut(k~qcsKRB)o5mEO(RX=)6 z)OtSL!D=>AQHkS73YJ>Eq&t6PM&RG}y$5IU53tV)6}x0W8QFo@MU4b{;@{l!db{=h z$g$RH8)P2VLE{T8@W=({UcE^9jNGPyQbuWbeAre{*gL%!^vcITnb)}RsYaYuy8F`i z7_6l8LlD<2AZuk)l zOCI?8b2}o2WUP&v30s99{I-Fj#x+R^fnqRyLgg!xi}`JF->a#{@h7&3_ZwM zPj3nuIT1F9mHA<}ONnZoqW{pnl=TbhR@^vHgJCY|-TCs^+RCk+U_lL7@T0n&3QHnT z;GVn*6Fnl6vnJd@?Lz8@sh?HEo-G;%l0DDXKp_1}fIFIoRQFXZz|0hE(pNo0)#If> z1sEXT3v~e^U-&rnu^Dn>AZADJz7Em2U_O|m?q^M7O2$BEBjb%x5_VkXS&+?DWR-l% zdY4{@9zOT1*0U^^7-anN(hi=#I0!8JjOrRl6y6sQy>t}GDaKuk)n2F4s;V<6964^J z7F#Zu0l1G9wDeYHG_I-jh3-tLfs$y@dHzicn}u2GdVq$vy^6ak_O|(6bC$FFFJ9K( z?qD43TX=E7+>seD3YcSU&3B8d|bbeu=s{xM6Dvobgv9Bl8tXde$(k$ zU&Eid&iu}a-q$7zIM2~?Q%G$1uz~U=l~_J^Yp=SylQS;kabatD$Iq6{p#)GZ_N>1= zcSr^z?k`*O`f_oLlNf$osLjhk(}i0ZoNMTZQpU(zT2AwLU@CJJFn3_{uw}zNnH8De zkWF|D_Z{Rj>@QH!wKI_)M0AZ+itLG!>gP%>kEmOhY7y^Dh1FK1_o57AiJb)JMchC0 zS-7RukHOh_L8;<{J8DVCovq_Br~dsNaZz^IO3~_mlrdh!DFrSiJm-_a;q0p$(AuH( z0-I2sejrFjW&(eaIasW?rcAS8X)THSijk;CEo5~K+AgkjYYi7oaxUB?)Z$t4 zS!fSttYhM898W2E+?$ldf z0}Lq@g1O9Y`ZX}^M#y312BE#?)^Y01CUf>DD-JkG%$NWPG{v_Yx7TV0u6QO595_zR{FL=Gy2ghkV zy}(KF*TEUC)g!kY@;ok@3(y`rjX}U`p2GPU-U=CGcZ>|{KD4hQSyB;a5-kp@b-UgV zx^EKc54I5GMzUVHO~OZ`MnTqb2nH&gLOU*`vd_V6Fpu7Ou+JK5qrgY*?0*{C=46rm zY;-@g<`&`!CvhZ^w~KZ!qfYP^(O70i-WHUW+ibCcs&0d|(2N?Qy)&7$OeM&=N+hbw zQXS%AI?3u^7{Ei#pTIkKWF5<2dcpX{HL1|rR5)k-W&Bg@DqZx~tiu)j*qrFR$&8CK@$tbNbKUjmbvnQ!d!#;D+4cxMJWguQFGE{l-*IN z`WkU|gkX5c!9+37R5D}zz@y~TrYXy4yq$1}u;AeVi@Vx64s7Ootgvi!&XtfSiLS`w zMV1xbGtG=Eo+s+^jA&0-+o!#TGpX~uPLOajiuKAp{l;ey_^g261L&%wB@Yi7cj^Q+ zZ#HVaIScRaqy?RSFDQ5+N}S%IcZ{zOW??=xb%~v*AH@e1^Jf0dilUUbd~ZB$|4wp< zy3q9|HoDku$HKv&$hNj@EoO`+4)+g22ZWIh3^4iI}i zhkn301jn8o|u(c&@@ifj;IcQ|7_8-pyq<~6tk$YFI$5K-T;wGvr!-7 zU{p3RTf`T_TH`rjEWo-T!#XE3KTwZvT4UWnsgpb6f+p-7@z}beVFXLHr*u_x>p2zY zh0!&b=;4_V;(U3z0t+PL;cjl4k50TzMGm9ifEqhvJl&&lapE!F_%pf=IL^~~*O8xg z-&)*3_19|~HE|^%Z!5vlOvZ~6F+gpt%7qF8_ zb-Rq*YwW$BPz;mzpe;&HwmI-uvj!Nkr62MRzfCX|tdH6@Jz*d7H5=l0&5{HGf!Je75vD0%p66Csj+xjqX#ufA{z8neF$?>!kl&Vbr27 zCJ+PCg|n6@L$$_bJpE?y*`^_|!sTYht{hJpt9gyu2PPpgmklpqEn24k)P*%@#nZK= zX>TDP>63nM@j`|@%kQQ>kD zWXHW+%LsL{4PTZ6=IUn!qhC&%-~mbjv`J`pdgQ|XB#&hk;i3E&Vap*4e{ONg!VZt- zHJL0N=w89G(3t}Iq5$K)AbIf@u-llt_Vyj6=-59<0QX@?02LkDqzTWng}>a7k$ z_oB8PvsH8#^2i(ATVa`{1qzoJ>W?zp*)lvty8tTdA?oWli@`5y)fc!pgx+Vs<>i?^ zB$wEdWpwm~45lywUokKgwMWovq3HSU6%d(tKBZ_^Bc{H87EI0>wC>Bb{;gtP$O7Zk zMF%YoHA(6CQkwiRk~00Z7CBi8LN6JI_hfu)Z28t>s$(64iZxduLqjCsnLi$uuh*+# zR&Y^zn}aD&yAJj<2<-tTGz$82eLwp!jt6$JZF@+dme~73lrdxSNy~C{xTozRJvDW? zHHUQO0p;gA*UQ+^#rkH~gFMCFe6k9w6XBFsif6m%-)3T8dcNXUi8Hp!K=;tA6fNX)tH5xrg5iBbE zJLbXJ36xERGW1#@D?@o+iY-@v)o(x>kc40ZUrZ+mZ)EaUaLJ^ ztdl{-ez2+Q9r3XgiD}5XB$x9>)U*wrf27c(m7kV5duMmq6f!3n3T;vDJ*E5dpX{Q0 z&{lO7#@+!7=%7p!)lT&VnQh~)FWe9kTiOlEloM={0XY1LhEEjywR94Zt$*IUsu{U(QPa(QR3$V?ihvh+GX;5=1 z-EdJa&(x`Yf|15$wNp03ZOuzw)tlO>i;NOdAis-3qaU$3HWSDPdRFl~=&49Ret_sN z^m4cdHn-PkiiXs!_PSj+WkxOYX6J7n)_6*>_OaEO(?V&H#!o!f`Y~kL`lhB;w&~}J z5Mb5=FcHdzYh_UBpt)=-=ugc**ug#9G8w)OIKD=U>bqRBUpKstyppvi?X$dL0L~zS zHGTCtO1{IPtT3u4XY=7g5wC5|2#vLp^5VMq+n_m?^vn{I%8^wrm@@$e4f(*BFf0YKz1;5Qi0_xn_%`8Wf-&J8 zdzaw7=W~h$Pppf6!Q6I|8o=5M(hdOzHFf4_D5hAq#p?H7^+l&QJ?#G0iJPe(_Ky}1 z+AC6K+JD=9p8{ItS-O_$8wf-Tx};tQ^2b!y9NoI*U7zFx%bbk*y{xRLq~70)_sPI6 z9!U}~_k9K1-_(@HqxNfG*QV1E4F07S9lh1>0zy?KYAC6UKsAyYwNsbTIYuGc5$&db zlmU6vB>HN|NSpM+q0W|S&nQBTgsdUM8fLiu)s_|xkt{`|MMB0nxQ|SATHV!LVlrl+ zo~vs4QK6~fkPLmT)qf}E#(F7dKP31=y*Ym|vA7_Zrs<#zKKH1!j_M{oWtyS>C}Q-k ztrpsg^Fz_E0%04&d03f`0Ih+)`fflyF|mvNPvH$J9|WX6hgdFc2XPeUg;2F;H74tt>fMuCNNN*w4!K6vwpjeqPeV7nL^r(8Q)&((v1_Udl{#7qm+yP; zRZZ`XMv!)7&4L%P6vQT@=aL49aV(Rfzy_7HqU{oKb~z?*HE-CLm= z0A(N7ju~LPW1eUBVaK64LLaZPeFa*U#)~goy+?`y&>Hqu}?v;GO`R&z@NMvM&R0 zL7inYI4vm#XS}apT}sQaT^z5hR7bQ?6i;{mYU$+~?F9ufWLxSujakNZJ;?UitrD|t z>D}J>pDQFbYAF@*q5TG^-rZ8nK8~qd4C(;Y1FQsbK^smfYv6go+0cQ5Fms%Vq~ddE znm!n_-DZRFYqNXF027E}>@b-l(E8oiVnBxgH>?s70`#_)eI*08~R(C_Mc zE0*mKB*`LOG0ED!XwMm-e295kHVavzLjAYi~fp<6JZhp;je`=t_$q*{JgOBXN$ zLNp7!dP^^&Lp~wpc3X3Tg&;9-r-4wPTJ@3ZoJZOHq#-ofIj=KMMt3=@Uoofq>q75K zVh@Tb$!4mCSGa+2jN+G1-0RBUy-5vRu^h{0D<6nINoa|;Tv6?a^thwALJ^_7S0J*9 z-T2qWDI1d7e?eYo`v9;HSK3UTyZE1M-lOQYQ&;3$?*GNk08AIbaPj3@r{$ks|D$Em zl9!zdJFcpUPgrr-Al(kx_b$0etM~bzTEy}ePhC>`{}9l@zJAgJMCt+R2VE zkZvjbem9JFr4DmF98=gN(fj9sZO{f3NG!eWUm1z~gx13zd;lJnP|3xO2;s+wG{?Gj zmQg+dkq)Yepn)!6;okAQlzcN(v5Ff*UOW6nU179t%s#yX#N9z5SN%XjJvn4#(9Q=+ zs-1Gx`iqdGSeSPNKhPZ(S*yxGLt`j!`5{7)j-RFLpo_^j|5p5pFAXaQFGJoJ?SCVP zASCvldlh6>NCCo`roR80(0k_GI$BK`pU{MUI?6o###MZFK#iz2plYgApTeO&A^wlB zxx0MlzFxS_dWT?`vV>Zmo%ZcX@!4@1(dGMG%J_|HmqYHeKaP8R2o)^Y1Lq4eSqN4e zM2n186a~aS0HcYm15jv3C7&DowMVE++`)H!yjPX~JxW=l%rN~Lo7FV^+%>rEyu8bv z&&@2NWEv^Kh(3DOf-mccZ8jPMy5@A_yFePF!2@7_hs=A%V60w(*}dUk5s^;LHMKtY zeP&pF7COqaaF!bXD7s;;a7k|zv7>PHY3Z0JiQdF{+&tP&-$@41s4T&Y)d#~EQN+k6 zOk^~{ub9~Cn)DS+lvu{Upqc7J($%9yhfz!3WwLO2H4OL(Kd3@MKS=0sfeM}ll91ve z55Mszlph@JsM}+zgUm`-NuR;b6;49*RH!sm0?{h5iir=DT?B-JmBuIWN#;xnoaa?o93eBBuT7 zs208npG;F*+}%%UjjkQVnY#@(E2Pvd{MCh}U(~}sq+J!?bKRtIAg7zxP!}>56`o;H z3Wk@Z@Kf75&H=Y-7UfXJ1ohT^pQa+4lAPU4$^d+d&W#xG?zZAJ%#NlXFnaSujXN%> z;LKi9T9qspv9@B*dxC-?#>ifhbD3(6uysUrDaex~!2G{!TX8YK?=~17MY+vr;HNP9 z0>WDXZ;}>jpE_gl3q9dOO}rdAZ0!UFxW{$_P*Do6bBV)i1-rAd1zH0ypg>s3_H0xM%$5J|P|K**iMxu-JY2T0!!bjRP8IM#j?S`S)8Ii;3UN?|DZ4d%* zlAOhL0}u1==l)zl1;zUMr3=Dfq`hiVdnO%Dycp)XDq5%tb^SF9g=2W!wpX+?)umPZ zy)q+&A`5aam4Wo_w;xi0caXLUJmlZUqeSm28hCoTUAL-a4{D7nlXwfg!3{u368A#j zZ8P#VBYZE&xOtMhNW>kTcppxEN8niGoHZFLzKbX(KL|&W2EG&$Z@#M?qgqqWbr)fq zm&^F6vtRxZ!WVvkD2_#XMkt`dUsj5UL-jM0pDc3p>6nKYz~S5Aeb9gDD^%^N@X@-4r&Zizdn%Ws zbu2(?#2eeI8$1ygKz{k=n}T=ZPqQcl**?9-Dt6cMexuLxi=t(EZ-o#Fb&LILaAtC= zF2+@!_YOaZ49DcEmXk;vz}fnec?h>5&kbjUee4)Z8 zaND|QZ|ZaJc*@lYXG>z5$-veY>ZSIj>bf>|PUx=P==i1Ii5JmzQK(bt-v7-O!nCF_ zu5DoY5CcYEsyLKgB|(%K2pH>iR~3Vi9iynBCam>Lv}q^M6wy_&XY>7!1FJ=~0$4mq zqv6?tpCs}$lF1cZMr`mItsYGq3@~6n_YP_jwXKn&-Mf+Hbmops02;9F zQby)^yXR(TwRumFu2Qi;^agtJu)cBenp@RBhAoYgJ%g#{-N*S~yIe z+V3?yS?>@rW1(W&zCR?xUIrCQhCaw$dSj+_CtcLN98Q@5RPu@fRW>+9psSa)o`h=+ zUlQSfytw*AaGfyGP*j)TICc$BDaI z@fbdw2fz%BxW8q%30lk=(&B{9T7)X*nQrl`NmgT*wbKZLWIAkOOKLg$gqF%iu>tfg zZNv6T^+lJ?CS&5Al*{5U@{=Y+Xnv9hi76?BfDi}IsJ$TG_{(I*0*G~W0>3|Jx-v)i z1IHQEUDsZ{{^yVrfn$_ob2e;cC{%GupYH1d%8iY;XK%}#OYL2@7TN!~Ri7Sg6C&AP z*fjm;FJZYo0NV8DRyf_oW=k}?0V|n{m{p?lW(*sESZ!RFtwtKC*GK~omm@U^QwsOG?EMw2Q+zDCv z<<(zDgnRQqW0iAuLI!u#1?jZ6WhnIC8rAR>Arg-Ui&;d%wXj$6%d4j8=#0)sQ4D-S zjmrO*r|I4=7=k7c;p4m*oVi367)Lyv;tH}Tm8)8Qt{6d2GxRILUL}@g_AY9p08~JZ znMPA?+}C!?7RJ~X;?Sg6qs2mRM|Tm_TQ6`qxkvB@mFycE9+ER%b(Cdccz>4rm`hM5t zb(K{}p6B_UbKm#5&pFiu?ni@pTR=>(3&C;1(|c>e@%z^<{R|q9@%w=C7C{Xg*3K07 zt=JY$N0aM!{_3O}8yH&NIuY_X;AJ~xM{|QyC#x%m4lXJ!4VEI_!kf8Ma$HXk&2};l zKOL#}PIMa#h&8?k$o8Qb7V%oiuEWb+9gQzrIx(c64YpmamG(i$iA8?zu&~^iuX@aw zY!AHZ!g!(e=O@f9gD(yWw8CS8eG{|q42zbUNX*MIJ`7hb?%Oc&Qno@joDu`W`l>r{ zug6t8c)KHc+IEkgtHxpUM4REw#!I=-0!A(Bs&%egwAX-wz)evWjvK55_vrTHTf#*k zoa@bG>2iPPq}E-C-^s}lC;$&p+IJ)JjnMbQhFXm4pTkQxMtzpcMvDNZRqlEeVsqbz zF_mn(U|5ZNxx%=+g9q()KD!(iafjPJ*7g7R#8jNw^zlUh_qXXwdFj_eEejOI@(tkN z{A79C`X_7Vk85@9L8SZLu9cW=BR)!5{HBh$%RP?pjd{q3U;|cI|KX~x)*T6H4>xF+Y$ycy+1 ze(N(bs=8V#rwYFv{sZ;{M(!eGg(a61r*Zomni((H891(_pa&KLQLEdb+&#j|E1So} zIE*F1#@x?mUn^H5h+8t3JxdkmcA-Zv&XiNU*%?rs_j{`zC0^|gd#OYv& zII?n+N4qefBz`ybcB*n_>}U3ylTg<*??Y?cv)g8zCNZ#?^BM5T`p?_x@O=cyjVp64 z6~C*LNk^2-E#BcGpBKLvJX2>p>O0SU4ZHpR$_^DJOLsO`DB}&RWFg6o;C#9 zZ-<_7qaRvghWfEK0#-CO=xYdNc)AwtCGwxOG&#LbeTt|h$~iR|?ESoyj|vU2yA z>N2BS+vo@XEB6>wK=W#%IP_yyh?T6?yPf;wi_;mhTA!AH!8a5W%6!<;dudDuSZ{vc zNs$bSS=9I5j7XyDUHlJNjg^O0H!UgiX-~!L`OoC(uDd=oP|mz|uUfaxfK6TwUQry^LRoGR~dW|xl1LMRO6MXv(jN#*_ zZ|veG_~!D#~{BT{KAAB1CvxKd=K7znnK= zxMM5jo=0O}TCAAdBiASYV(*`WJuiO2ZE$qX>75fyP6zxqUMt%>7MyV1@sdZ-l{!Vm zGgN*azE39a;YgwT!X+NCGD0i)JT_3jjcL;>f)|c$kRN*KU>Wb2H*jD+$87rRLG!Lk zDYm6|Pjdh{S(xz0nU1hUal-O&ZL>l;*%w464ElA8p3@h74Ld4H90UxIBadi8;trZSwA7`B~u2_ZAXI?I6W( zIP56PFJ1jK2VH$Wg_hQfte3xQyb$@bML{DSFOARUDc?Lr>fwxbVW-1(jQ_c#kkL{1 z(@at20uI&@<)n{=-SQreKPt;n$%Fb@?rR*e`d)<^{|u|H6lL$4YRH!TQTj5N+~->) z3z2ls55}9S%>ZQh5(J1%jS|&@)|!JPV*>2ov00u$Gnxrs^!JOKpZS0^fhxxn~B`{!_3c=usgafnh^HDc3La z8i8Ao{_5h+ey?%*vc`NOfbi|3?V@B!YYuMBQ&Cb^metzudTwi~c}Vq*8oM6M@;U## zI?$I1!=EVEK8(TgJxI>4C_3CrQx&q~K=k~!yJwZOV zxHpZWQAgSN8A?3IB$V;@);{lj{tryZn49)nKdl`-@697^A4sQ4bL!^;L4 zcq!EcaMP1Z&ClvpZhx^yaT_Ct-C%xu-=FIuCaGf0IXG=x zY5)F`&(;X-J;YgNrb?iqcD$uE9zE@MPB5YDT5cA+Ur*Hv-}0!O^80SRTcJ60>Jq_Y zsQRZB+2GhhoSY!^|0~;Cwo8}m2{6$0Gv)=wT3`D8it)#vLd55%-T%zxzg-FC_CxjB zs|H#UdFev|K9X~{;X`G9#(T<@MDFL0{z4Mv_qL4?m6LhGVW$UZ(;>|MMcX~8s!8Q1 zn8~sWH)J`Ed-y~EbD9@j3t%3==!fg(hZ_JwJxWLjvT>n42j$pj>v`KLGiYrpy*hTd z;i*MKZ=m+%RnqIYF3%~i9hHXqxV2DEg!H_O}?w#b&IvNGk=DeRKXK_kh#gsP75FqJcZN^8zz`_ z@3dm*qcmOI%j#m$+d?&K_NZY{KI)CSQzZzksiYL&SuC=ZEuUom^dE`xW6YWjl@1- zwml%~3M1cii?D$WE49u|p)ju?<;e3n*5qjE6EdOeb!V#i8J?_gTe>+DWJ-1i30aJI zoLvP?!g7>8do81T+J8?F+L-x{^Q8`w(WB)XvfxN)scs6`85c}+mi~nM;gxW~$a#9- z9OV*S^r>6XJX0r6o;V~p@ponX37x^#P*^s$A=C=S15WP~D(KR~-#>Yle~oA|HzRB* zNc6EGl4RzmZ6gN@qr9yRvq~30PJ$usX5-zWVZT3J^*9GxXL4hK_n`vsGdnB-(?j0% zt#LeojQ!G^sKZx-mi@)q>@FB}$_CUf7-1?&=XX zv!3!`A7^J&I+~VtTj7oZlY?pDdc-?mC$P@@DLGSLeFkS)=$5&R`lnBoVs`R9ixj2s z$&b~<6Gv|fB`o6i(+)d46a}C4Jr@$+U7=IbQ!Ejd>F87Dq{DF7IiB6c9M7tmw^DWQ zg41`~e(!y%(p=^5zJ4)!u+vES?w6M9UuS}fy7GYitECG+6?47fRgna43M#;jj)tPm z_HMu|tYqTcl-fkJoM6QeEmlrVFpFT2GpauwXI2WSj?NGz{hN&joh)K=5;>Fg(PYol z4HxED%2#H3HHjyr0p`_*#PK~djY>;@{(^Zo+Ld~s6h^nzj8_2T?R40+y;F#P+3okx zMbT`S)%52G9G=#}Upg(08xO;uew!V9ae3m<=FLZ#J7nfuWgU}kS@G?h3TAHwO4D0x zCv!TUVm1igCOw?#!5mR`K|0&5@gPHG2Y!e)b56?uV96{FJkfwcghwx5o}k95JvkC& zJrpOo6B&PmaTJQ6e~m4N<*f{tW9p4n(nO&bxH_{#S;|ra%UTL&-%1BG>+xMZVP>)4 z!$|w{;P>BucUthqI_jh2I{te(g@b%6FsHbN zQdLf=-@j{Raa%_j<-BS^R_)iIyU0IB?pXR$B|Wx>dF<5(jUO6^&q?|pT(ontS>ZU3 zPXG$UPYl{CqZ48%Kc_!c#D^4gIrAC^;ihHLJ33j(bG69=iN`E&aL0oTyh6%|Vh(?^ z^ht!*vFSrx`A=HU^jTZNEPd~@*)Taje$xIGVx8gTLm%Yu7y8D3F$1gG7Y!u+wHGaa z=P_^s6zdCAg$gF4@QP7Qle%MZyM9CWnbTfEtfV6#&UCvL=^#bC&N@FYLYcA?c(W*h$Kea}UQQOM*tYW^8lMzaemTdY)D1i6&Xe4g6|z+5`=lBVD?bGj$24x%#|KhF zOUjmAQ3+?`mXbpS#k$4zr+t3EY#HS8f?Qo7>pvP#YJb5GoeyqCjVKZ|pD!LA{26`? z(P@->d2vn660@cE9ifq33d>31HlN7GuNiTQfep1t$oq@_ti$B(SiJ>=yeW6v9tmGO z=X0v8JJp=`0lqX6E(<2aYiZcmOmFAO%!_K97tT5_h>uiTH@nzU$RUn5*p~^tKQv_3 z?}MEOQA@D5EQ1G0{LzW`?2C{+I{ishgXKEpG&=>SJ`3xxqPu`DhU01eCADD)-D9%$ zwh`(5_h1`Hn6PkTQC11WM|z$f9ptaRbu6=1Exifq=*<}eaF%&FSuq@TxX3*3WzRzk zIvNEJau&W?#i}hY+z4`*z^uZnG0#h4ayfK4@-s1(Q}y@iTYhcA63t|H@D=FkHx3@M&A^ekFlGkjRbc;0}c4A)|XMBI3xkm|rfhV?b9cbM z;p8>~4tdfU>61JfWc|{nzPPMt9&DR=aiAj@LnOg%e-pl3^6PI?!Nj*vQGI~)azta3 zg{W8>0!XA+^*B+$d2%<$X{zQPS{gIiMv`m4@Lgo4=#Ro9sgb+K{BtD!qIt`TD>Zc< zdCYfYPY9mF>&k&YB@dbBnc6r2>NhJo zqF@$UkI`7G>s&2`S%i7qVZ-1%nYbC;X)NR!R3wq z2BNWyuJ5Iw2;^d_YGBy|(uY{%{06M?u!6)e9)>R)%pP)cVZyfV4dfc*!CyLHp~K^Z zyT!LxMlFq$ll@ISq!S~w$u3&WM04e9V|W{^IGvE$zStbkAQ(Y^^chEk(Y+#d8w*(y z=T3bChmq$n1#`;LgMv8U*Qu4=ojdo6*1R(2ZaV59_(c_jJNttnZm=6fuGQnMwR zC-M-1I|@};+)b0Qh@+*ualOK%We^hf@vojTDB0LwM3EBqQD)lLZz)%X!@+SwL>eUd z7MH*IY#K6N?XdAxm4CXy0hW_hrWAZV|~5ViWcvo3BBgL@|FU=&v$D{ zTcVOBWk~(q!~O7moYnk5tjDoN4@d2uwctZe_*57@Bx;5NVREI%sh8d*r1f`97HU)Vw>!AANy;nUmH=8V7dTX zu8`MXx{xHc#=P?|;-cLTlDuXApdLAo)HW-HQPz@SXf;rDZTVz!&#zO_%x}nQJYxF| zjE)H+6l6%qho(=A9sL#=5KPGBMz;uXSiv>-y4;|$PU}YQScz7 zd@%!H5cvW3bySB>p9MSsj~hy{=&;yLWZ=VJ zb_zj<5Azn?HWJi)esvR&@WgXf0PPfOY7L6`z% zqF*Tj0VD@q_NAn#;!YBDX>J4#au@o&Ce?Cju!JGH_f?Wt?JXH)cIf6*=9)`?QyRQr z%e^gn@bRFjnjcK;J#N5&i2$X^15SZ|ZX!!wj)b$khD8aL*ZBkX~|)$-J1}*v#a(RP&RTMRS%FkB_G9 z+NB9D2qcz}jk6~^-m-|`T&9k*V`9j2tS{%1g+H%uJf79=iQV-|ppq~Mx~{uazbo-d56MGd{df}8!(b*) zqggJkZ*70FEUm=o0eE(2%v0gIliP^SPip%1(RdO{G!tue*X8g+gn zl*5r!BbxK3o#;X+QeiFB8>#)jPXi%-bRU~IGPQk&v{W8^!BHO@oU&O+4%!RVvE6wQ zf6vf=sC2T*Hbw=e7ne_fMt5_{w)0h$(SPNcqvo4YZ9epVTBVZ#*nsAm>7At|@zO$i}& z){JMBru(Bt(m?>F#QD|8AO3@4F)VI?bUNOmrahpyRC7GuC zue}J3DS}rM%JDQI@|}`UlX+9!qnr5tz*lDjlgd60Npr#RzUU!3?K6-2p*9J)lFDN=9A(&i)Heig#4Mx7K(;u1t5 z>pN(?cqJC)E^#MGi zhuc0^jtFxCC`;zf*l#pc?_z!{(pgCu@EEX`4DiAHuNEuz&L|;!V+8%^`(0=@mR;`wNs8 zKuvLYIT9Xc@3YLBHw1)&vu^pTCxjbxEtfMnWOL*TK+wnR+5(9#i0F_jQ7%uSx4db> zT$WxnqL&zPsAQ8l@o%@kih~_VSp#k3gg2d$hMtO9-{GV28}^pFr0xdiE6g_~vs|{q z3f6rX3_Zm5|BieVdtDtu-r+<;zF~`C;*Ci!EYGnx?F;WE%03YJDf^_YYLN*Qoflrs z;##L@&Sg--2av;#>9fR=ghUo40tVU|ad@o*{XMFnn7sAUcBO{Z{C=pk4v^dM;c!5R zt?=&*;773aX*KJ5yu-t6$;vPxvqca;sg4x_C(1q36~~Hpak{%$xEaBkU{)wIsv|D3 zf87IciLS9+Ex>EKhzM9?Nx8Z+Mw(3WLS71I3r$|r7rWytka&CDem)3(AM9-?5>8ia|{NTxMk{%&zwX$m4idf?k!N_9CQq`=hF;0KhWfLfD5$r z)k8{fh=?IG3qk9mQURVfWS$J8`5R`xprsrPDftmVCyRrAGk+8n2u2ZC{p|zOLsxTm zR2e~7boIdaZ@coAmOOV4w7OLEV1Yc;*IU<+W@Uyh<#xD4sp{{u&qTMh&furLsy_{A z^rvi?_UgdTOptokW-f|k{)3Q=CT|B)RhQE`;AMbmSZ1pB&i4v* zrzo@$bXU0b@Ko|3L-9c+oAWI5M-4ATJ!F&V|CeWWc}o5C5tdO_t)0Lu%Qj5i*){^i zAHY5gCtz3Wv+phzy;$}pGUiXvklH~@ZwZ7lCbY?9s|Ky+AwxztqZ)u-n_ZreR2&j2 zMP?Jx@Pn347NBTl19kbb?qY|D0v3r{^-j#QFOJq5X2?=~92ol7a=9&%$l?ZwGCM-S zcf{)PjduwuvmFVS3||NZ3UU?panl}chU!iHB5qI98^3NC5r71x9ib+S-RALp|E2PL z*QE4OTg)Y(q88EhK)4&KATJvy47hz?oF1~6)+7QNu9{;z*}P?El z)9q;6#4_kb?*i&)QxdCZZP^LuMz`8gZ6DAecpQD;hgqm*xaZV<7Q7>oqHpa1?7|?- zXMQta@53>NcwM;hypUPI`Q=U0B(q$tUF+F2u23zF$PmUB1IuehC25U-b3F~I5TVfU zb*9-fl7DC~MKmtPp zpm!lmPY*TyS(j&;oQZKxOVKbNz4^!kqESQ`TrGEX<|>8GZgqudRXDYWDx)8a9yp+! zNiS{Ol_d*lab7eB!rsCbs4fo!wVzOl8XXpILbUM$$JvFsa$3l{VcSx@>)1%fBRGgP z2sv7hlU4<8`LKT?Lq-hb-?KbZb*mHkwx+js{n1SucCdnux3zTm(hRI0@qX|S*$s-& z6I=`<#N1c*-G`H1N1Vi3z;TM8BG+UgRc$ zJ77)pMtC$K#JG*&O!4-i{V98BGig^LFW_;bS0j#O8#Y5AIU(=`-L|XAh#TG1eXb*u z5)EgYjGxE?s5{owa~e!Mc)lN)zLZ^MNL_n#x2SJ@7G$yO*ofN%AUfWrXox)js|o%K zPsW$ZXSkzbG@NzHcGWVz_g}CLA!<^4`BgNA3kC5-sH~Nvo~x9*iF6N;7n~e+7G<%W zEY1#qs)6tyd3wRo<1llN+Xmj~^Yja7_t^h%1CeaWAe{Aril}tsM(Wmtkr%qzVtf zKbMeP4u2Y6g#I8XFoZmj0)8I^P*IXuB-#FR<#W)DKhTt2s3xO2CkrodQ$p)GOt-p|bn z7@~n1xI*hjguo0{lG+PGP2DDkmo<9y8l4Cs*nWJ?oo#tpR8=iSk+YCcyvX$SM zUv0>`_|WGR(S&Z0ySr5@O8WQ)$8YPa3oFYWFA@U^62+E;?cs~h*3F7&&9-KaM{ruCW)OuHm zH`un;Ob=DHv=O|h%AfD!q?v0#KnXV}@dS2|Ce4NgPVIQoE>3@8^HdI|@XuQ5>o zc3Tz-_rC1LD$1|zOLm2Xkhy#oY-IqY9WX^QU6+Q6pFs`#NW@u9? zX3*395~ceg9R0zx9Q1E!FLCY*`1MT8_*}|{Ss%09C^FvWqxd&;6($-l!zBdhDsZCEQHEY@AeiBZwOI9+5b7ZNq|?59`~~2K5CEp z)UA<4k9H|fr9jR-HlC{w6^57 z$ycYGC7|^47Gl~;vs=AFfDhGO$HIng=G!2AzpOHW+Ul^beRz(4FMWmzLj0doO4*89 z${vLJCytg%-2EJ=QpJMDrKSEjO zg?Ix&QFKIU?}G{m0ho1|`j55|5QO|-^e+tF!$>K~DF?ku?3pJ15WCSE2JQ@yjAGaP zN?8{GDl~!cbp>@aWglpibk!Ka6!`zK9tR~WPK<{T21^8>qvUdwSCwa@ivE4K2vEd> z$_UW4cSzYk8{fb0#<4&-=j}xR4x%H$D@P#*ej$-f->TiS?zwOQs!Mn;fH|nJGG{+n zA9q6R*|+XF{2BPFeab;(0t`s1b1U!tYLaGhaMFV46iag31#|@@{8;jT< z)#)BIb~M{nN1zyRsqk-09dwLo z#3BiC>&yDUbPuCc|8P~cYJ=}~5QYO@$}uLgnL#zT3Y>DNYo;ixaTe1vD>JXC+YQx{ zOSzK-1Xe&um>e{ux4?Rk)Ro@w)5gKkqr`Cdj}{3GW7_y8-Mm@5M7 z+A~>fhzOy!5EEj7gYe2dL#*>0G~qOHI}q;j>wpPRh}M}_txfI2(;iMx{sZgA;DA8V z^_vc4G?E5{yn|rR1UyMj9EGzvrFL@0x!Thy2nEg%APZXV>PS9El$RmpYb4@Khza9a zM0vPu#vfunwA2v)W||gm-rlXc<_qSWu*CnQfi49~ zkef1MLw47F7glB_s6cWadGHx2&xE0ottexGlsvDE zd%@@~59xu2l{22V{^$fZx#cvT!EKWwCW zoe8A-Nb6u}G&b@1OfJoRolSNZLQHQV;)T3zagF&RI8Mz{jTRzWQD|(q9bm{4NL8W6 z148+#M+joXq-|%5z}g0aF?1opnN`eeyXp+Xp02_1`ceq5ZUAe60$k9K6d3UE#2|a$ zwE%DnV=M3|nb;NX8Nx0Evkn^=qUZU8(E#cZjV}%28Vd(PUvXB7@xRXj9{v&(Kh07s zJ@mLOz?1;$K*|O&0rUw+w6`O7vC0hcx5g-xeyf3g9qS7xbVu;gLk^S{Zf-CTha28g zc<67iMU%=6I2xlxg;Sf(EJ6|p_TilJjrta};@D4Qj{$E)-2LNil2$iWS_g!DdMJZ; zeeVv%;wZFH6>c1-`JJWAd8`UN&ZuT2e*u`V6IiG0!vo;KZ|pAs0F?crB$)&1NHdgY zML_Bo#qO90!@{j!3Slpbz#2@%uXL|t?N{(?YD8e1&X`}3GGJzLeV(Zr$S4u;mskS` zg5gbL2{R`aKzB#E<-rmllf1UlbfBi$f@+7Yra<9}cng;SpVU0J~p8i9* z_be1VH4rXFy{l+WvrYc|Z&2B}_a&^drR1|9ti&iZCnz&2)v_6bvd&k9Rv*#y@Z>tD zUCpJV-Ju$4s`f9B+}M9(ItYc+d5hG#YFT(F@`Eg+9d1AC0jk$O!^#0T$=3mchJG4A zEMLLosU1*o1L_CbuGX%kzyz?P4?5Fq!}eQ(fP5Dqj=s$f8Gqo8i_IT&3}aQ%`6A=< zG#?)5J7~|hLCN#lA|Kl)*sun$VC8d@3mb09^5a$(t1!!Anc1JKO@82AeYr1o=Ze4@ zK+WJ`!~^Hjl*lwiuLCrUegPU@jY?MX3y`$D8S}eC2a6152cIL}fjlX7i3^~5c;5Wx zRO#U9(6y;lZ{u|KVd5UE@-N@v3R#1)DJlHvD8!Q|}MIbwt1f zwK@9aXc?a^fw>yli7$ONlsoRDkq->NIIR)z1+>+eFbsz`V3wZ-iI_U{sEOeXEQ<3- zae>o~?=Bi6I70Z#TZ;48k>{2$d4ff?V)&R_kAwbz0po0hA7+r_mEP174G(!a+vr&= z0v>#h_2CieOtv~#0to5_h#GLlfTuE`xD*Y8d?Q-HHwfVvVXdhOyp=vfPPlKYTek&0;^0j}Vxj-c~DxQfIyUz5|>rbkmT_%;qKh6i>h@6 zRE0L;fTofNFu)MRR8Zhql#b(+b?e@D3aT8GOd!cg7SGy#t~A%Z^AZ8efq&YknIaUZ zs1$LpAW8$irdtFL2#;A*xH%Jf2px8s`9gv*eFUwgDJFthP+lU+bRs~cJ8&<5QhD_2 zB9;H(k>}igO`?1f5t=gEU4gUcs|F$20-jk_n9B6A4m%-4A(w$w=8rX!i%ZkgT_~L6 zMs=VzLu>R+rAl})CL^HB=uoufpc}doa|Ho%mw*!w8cq9LSosGfKXRIs0RvFp&0wy;jgDB9<1s6bqL z^Vyz0_5MWsVL%GuCYpgU*o zPOULm1`lVW)Du`26x7$^b{o@DVatG%rxUniuc0)RGxY`Hh`q*&g?R7t*^+j}A0X(B ziDmg7lAy&g)R!E;k<=t*o zhC5L-Iz_|zPy`0vt>kvWE{CKuFYm`|zZ=*O1*bn7|LfxS5(X0v9py7c*x)_3yRT@f zaAp{jbHC=?m@8VS_kqgt-S+6_XRsUV&fF=tZ3~};Y|U}yg}68fJ_~_+0JyZUCi_qI zc#Z*v#vEXC{qHNyZ_a;vi}Opb>cQZ!*e^~~?&-dkh%{MS0n;om;Kbxk01Sb<18AMD z4*NXWR|`XI0CWh8UV&}QK^@d`r~^*gcD(x6>wseJ-Y^$ITt0Uqs2obSR|`R+%HnJ( z5byP>Lb-r~6qelz4n%s-8k`$Ped#_L1zr}gTp{Oj+o~E0kO?Z8TKS<`C^(?^VW%|; z2cV?fP&tsfY^v7oq<`FmVfp+tlbfV7XAD>cY+L>w-6HQFNEK1t4!WNJF?{M44Pv0z z>KHtPQ>%g&eoR3}lL|Lu`?Ii#2e-Mi09vMmr2|oY>$+Y;1$2Y490z+mMQGo&PbZO*?%5Y86L%t{Vs`Zg*Mn8XnLc_?7~FO@IOlw@$${rGocRmH}nUcMSNrH1`i$ zv*{-0NC2p&#lUk&T^$xstpOZ8cPd>S`3imT7)j`}gJ?nY>mF?={MBdV1IQhxdsJU? zhlUM^q@cBw$3bNUXV?wRP%wsaYBe9kRH*R`SD$dgipZX1&Ow7#r4-72?*_n;8f0Qy z;$sJIm)DTp4e#3;c=c*!SSO;%Cn9;nk3rkS-m=b5fq#NUPrkJ^&a z9gxTi(~;nzK9Y`*XCgecWhVYxHsg>fq1$4>Z3BI*vhYLOyM@W3nv9b0_EFG4pbi(l zD%$VnXuQwp@cFv@g4p?$GNAADF{FzhCwi)lfZ0tpFx)$b-@lPEG?-?pHb8r-v&_oD z@E2K8@P{9=*VWzXD)R!>q-k3;?j1Q9U*|OO4~m&~b7n1|CRfo@t%BJBPwc*jM~_1% z7iua~e_h8k!uX9;x*00JzS!+@ZcAl{a)N%8=a6TfJ7pOFJ!ff;pnOv)rbsy#$LHMF z9Z5ZfoS>^wqz%xsk*$3-#v`z&#%;_W>J%iPg5HOs^v)gWW_5toq#_$}uIwJ4N0gJD zV=AJ>N?Bz$&y6ULkOt2y1BUcFmLCUd-{#HF{*hSCZ~f(M$YUcI(OagV9-ET>JzPw^ zl+s*~u@Bm$3=$?l5@u&WN48(!wMnPy>}sq5_V@3s%)deYXl_BfU$m_HK+V+RUM_$Q z{QM}B7dUB(xC~ZB{m@wt%-i^FS2nJ82zWWE*!PkL`(oAMakdAnm*70f6 zETch>r*U#-jhu^-ndyQ)pX{`B6khAC~!S!B?m;cEj{GU z4ADkL3Px_;0O$^g_1EkE)!Zi0&3ZgPw7)h2AtBrd!}6Jvh-H9`2mJ)9`tC6W|GfTx DMM>^s literal 0 HcmV?d00001 diff --git a/media/tutorial/img12.jpg b/media/tutorial/img12.jpg new file mode 100644 index 0000000000000000000000000000000000000000..dd500afba01474a84ce6229ba2e2e21583ef8c64 GIT binary patch literal 81939 zcmb4qi8s`5`1WUJjD2LC7?LoI3?lnF_GPk{Mnkp{WwMhc8f(_}{hTxBIOiG9^UOK-eP7poUH9i7?cW!`5MXA4GDDe|nW4-q zEX=Iz-0bXZZ0!78CpfuJ@(T){c34uEG#VStn7U3?0hH$9D(}(e*RGa9#*D%Ok@a1902oxAUvRdZvhbi07F2G2l#&v z2n;|N_hn&atXgpcU@!>G1O+j!&kA7yvj8A44}|Fqlvh!onNQr-Er5kzDJDz8z^+W- zynA4FBV5wZKDK*ww*1#7D^l6WBj?S zs#~fGGX7D*!U;?zzCuG&`#%Qju@HKZoLH*G6bJ16W) z#xYafr_eF=>9iI((kCo5(>tE|TVq*0T$V1Jsgm+&p$W$l7`iH#xLevNj3njrqgBDc zm+am~Vy;RS2Z5e`J+9q3{k@xIyBeJ8R>9lb8{CcKI*+)nbtv!%u z-9~)YL%5W0w2Vb&>SWXMu}UA;pht{fFyI4mr#&U@nyj02yQ*xkDH0thN|E4WP^2#x zfhk9z5f6>g+F`21etp8z0`hZp8IatSEkzUY0*X!)-y6$ZZnwy|6Ok#?sZpIA?;$i{ z_#XKjf+~fKA&c$_P#cN)5MK_y`(nb#9C9a#a0ni_-vV(&=L5*>ZUXs)>NK!H*$eJI zAlW02NRClvLY+W?kt_VI?*O{r+^b~CZ0Iy+YB{cn z;1_7dRkzB&Zqx&h5OFYqpQRzW_}7_|3~7@u*xbmcG-0WsY8OG|WVZ_(@;#yPhVn5o zW8%EK2nF}Dbsv6JNZFjj!$gH38ypXs0Ktv&_9wx3$|Z3tq;bJy0-o8yw8n4YnS%e% zapsvm*>Lf^rUym$`zwqO%n5D z_X+M>hlyU9#+f6Db(zn*)spNAC&)v=$CfNDdAS zm!CI0hZ7bXMdxF1BVRJ{5W)%9Ml>9PL+8tpi20JquEMZn0vSPN1l$Q%Iv$yr_+Qwu zysClArC#&C+2f8w%dErY65lIFBJ*fO<>&sm7Nhl;9IiQOLKFAouTzY;La1aZ5+$ER z!t!W-TVj#0R6>(XF_Pr)zBv+^N@$E}MW(t>Wiob&U52?WS-Zlr8igf0fKOO~EE4_0YyH*%G@c$)47tOU z*}{|~_06^EMY1#*oxLn=AXEJL59grIMHP zb3@U^c8(I(SYXS?X(8IOecukF%M|TRtD|(babj>XN0}gEG!tRR9KQOWT^PxdSkKVs*Jl{X@$EQy3?utg(*j;bG z_v5Z{&JRZG?*47szhh}Leq&SpAF%z`bYcDe3)o?q)ZfLn2GOv8!1JzwAN?63PctT) z{sjHX4q5WLb5<%{?~7M_pk{tGTG#3FU+ey}nsrCQQ5+Jf4in+TmBZ@|Uo`bzoM2yF zdpBp(`Wb&}`b3JlZpZ5%&wBJKGrF_JR_D74WcN%B^=syeu07&x-~20S9rNPPJiJ2G zd2=D{^}U`P5v8-a_Ie`zCr*czBv@&;A1#~idA9!6eN1`%IcTAu^R}V&px#`?-8=Gk z?wbGDv69FTe+2M8T+Np+_=@)O-4k+uoB6tW8yt%@Qn8|fQX zV|-&Gc{-K!n{fGhfy&8=3XCkyuC2fJvlb7_#1*2S4H)AiK|8!}uGQA(%Wq@ZeW0OOg9qt zpc|Hi;hN4EvLk5eA_oLMSh`{Iv!=z0fcYeM6x)qC|6ig9J9>s<&w!BGy>=Lt*j+f) zRmnAnj^$Woly)p~6y)dM+LlfRdE60qMB_pAaQQj%XfX{&D_wH4bl-)zx0*ph6C&g4 zTbHq)sbw{IWGqD-hXYil7MkT^CiVIJHzGtXD21ZzL1VPyJlZEnS;`o@r(th~XMh_S zeL?jyqn?9X1kRB*Me3q^WPEuDCeB8wH21Q;41J>ckcr&x0kC==txm66k?7tp=*3!R zy-^A*{yXkCZ_V9r9(xHHC2=}vQE7bm(vy6rCSS|s-S(BWlH{GHNcDy?y^qd8A;T_N z-#v6Mk7N}EcG6bTI-52{JN^L(p|FChpMIN1adA1KI@eDqeVR7y<61v5eb%sM(G>8* z*ZVcGZd*e!z%PLCasRZSPtaV)_=>gHufU!A$D29t-?cCPlp7S8wt2T!!B;5s>dGKY zUPJN`>Ic0^^OWZG`hceXv%wwt24DTgXAu3x%tGdmV-z=6{M93xH=90Oc(9SFyrxzt z8)wdJg3ytlOjPy`3#P5*aO&v?4m~j^+B6+bs$taBS04DhOZdws5{BrKI&E>*so~UH zZ#Df8FDc2pvnm`F7O=>l z9-t27x~yxU5-cvjFA_>3UT%}@c4ekUrYz9V5Z71Tcf_eNY_2&x1(%ICxMmxL=}D?s zXsW9)GPO+&RA11gPv|8J!Z{fKna{k|uqD92Z+AyDvx zLn7n+uYS`>**h6{Yn4%Quz(LUW%?gL*RvJgV^?cy!7@GE2IDlJQtyDPAVg%{J_kPo zd3~TM6jf$6W(?CYh(HF79sTOhU8{#U}=5Ub>AGxCIe-9UKB>xC_J=EG8^weiAa!sZVvTKpjXz>*~Wh5 z7f&w;vetML)ADTk;|Ns0w&c za{ogK-@9CAoe#>zf%LgG;d5S(L>j3nzI@hCye5ty^QO|LbRUlwbOp^*_tvj}T=j}W zE16g+rS7Q>p(odzRlU7>h34~m^QXQY52+8%iRhTvwVJjpX{t}$yF7Wo+Y2Mn2e1%2 zAPj#a8_bl$GM;@lm(;WicJKScOmW9OUB?1s+_MY$6f{91)QA!ZO?D-V_BQ!qs+t(o z5<_&9WSM!F1~mE6E2e}Sy-iXW;#EpyJm?Nu80USmUD^Dcqi`dU&Gq$PY9s*eEx>GWw2{!K z*4%LoJFX$?GPsJ0k-6ebWqxo16o!#Yvw(q^!L0g8m{=QPSR-%a94UC&bL5htJV~H! zC{=&C1=asH2z@2oVruiWkdN->Td%;+r;e@b!n&NA54G>DAidtaIGCxhRXsHS9evF~ z$-*&^@VAII#(M4ZcmBj4;ozaGcG%X{;JNc-Qcjx5I#qSctSc&9%8SBkeFC)e1+oXK zgBd#V4MkTU8@DMRKJKc>{VG-YP^Z_4`YPqTDOYuIXv3-#*=t~9u3U4+;-`PVL|QSv z!S(*-$3xiS{MQxzmRUc1c224~T4h_k?bUuT`F>q=NZT=>V<{G)IPedMV3ifwvfSe= zL&-)#kdM%tUmvM#K=+D|0?G=M=Q}TLpN6?#Z7u>242s8E1uSuT=Cux?gnsLWOT(EK z?<8?7#;LR}8N5mid#*n2#V(T*__?oN)cECn-msv_oh&IiT}K56oZh}^TJ27-WK&S| zNf(21tZ9v1m#z$-e2I4BR{guzJl8Zd-ZV^XIkIA(j)iRGy~piCuhQ zPco{tRdJ7Sc&ehn?ryd2T+t`-6CU1=!_}~*%u%d zyx72m0x8s2*_3=N2uP=?L6)&Jz(7^lRYohbpbb3GLMV5b^(Q8$bY%CKh`Vnv&M*OJ zynl9~cgdB!7x1skGD|Tyj3sX`-4z5C0%K%Y2f*a3-Puq;5b-P~%8asZlqO?i_v~)j zTRwzXX)}|VBn)6KwV@b~Yk_1>xF)H9&I*`3f85Vmz={0>_`9-xM_(R_`tURL#n;HWsq2SstxNv1`^j*H{-y(TD>=YKyK`G^ z!69@p<=!3ft>5RU4Xy?j&Z^3A+`*-?iqqDn1gaW&|NDy`v@skFe?7Bp7J}&FudPPg^MHF+dV_i+zQ&CRvA+TSfYcY8Ye!sjVn#|ZD~f;(?o4m66WhoVan zJ_Q_(YF$BRZ|oVa-du=WzicXf@!917`EH#(nbdOn#YLYQ(XSK@?PoF>5iJ=b>Wg7> z$0vr41qK%bVA>779^02s6cm=f`FfeJ-lL@sNlJV$+5ye#gd#^+A7(En@q%&n#fc<1 zNri`$FMDcT4yeU>C#mv7@PN!mSFj_Xk4EDqLP`0+C@+~FYXIsHM`rKsgV?UkK91A<0-JyW6#ixrujz`>Z%KN&i$@?}|gW+^2=7`o0Oi zvC}b`=D{>ll>Q5lFkD}tQxKW5>vG07A?gBYJ>O&dcNx?_LL39DcD`t+7gJEAxJT$i)1(^JkHd&gBsg zJ}$;ZW#ln<6l^{QyUAOBd(V!(WnmZjy7ca)jmz1WrBpeZ`;k7jK5m|>olS!wQSTmG zKJ;|cDBk1rd`DSpv?r^`{5EYolQU_oJ~PcB!8AQp*;rBH-d_1tCF!A6F|EnYmR>*0 zck?5CEV=DT4*h+T{D-^o2Y=$7wX?0g$cn47Pmhh226Br|zPHP##*E~9z3af$DLtzq zzI<|WG|x~R>#s5>k=u&rT*a-`DYeY392*RtkEOwEQsWD-^11B=_9ZaG9A`_>;0P1p zm_Vn&XT4de9jl)GS+&l3Wo2IGzBS_QGV|1cWv!y@cCil@E%@Z2D2HB5;Iw*&$9%zg zAx8hzB=WLTj*^oTP*p2(PikJU%l6YFT(4iJy3>^#PUCrk8y)_0UIoua@{4FrPu0XF zYZjK_y37a1Og9pH_A@V6e>;F{?|XhJJY9CAm*+VvD0#S5QoJ2~-*iejI_8&^i&o6H zTal+UJX%XH6c`CS6nSs;4G-QU3p#MX;!lxa-L8s~z52cslL2#`LyKJ-0 zjA^DC+Mt;-d86L!xs{SJ51H@`#gQ2+5o~1OC{My(G>f@#!L*W*BQdVH7WgvU(_{~_EE|jknz?s~`dvtaBLa91So8TpX~6Bq{joK4dld1GI=zZX~-}K!SxK zfKCra>KhiB>R}Jqf++|SgJ@!mA=#Wp(l_CU=$AU80TU{n3EU!SFhemKDQn?cAS3;v zD8c}^OC0)hJiU}VrW8={w+R&k#XLbK#L$o|uA|EV7Jwnf0-2b^RGOHKF;cccd6P`Q z7X`}`lUd{Vxy_9@R$M*i9BU7cY*PHU8Eh#*X=x7>2zoXf@JRZ&mt= zv};l7D}SaC5Zi9h!9F*U{~OmXX=``&uc6#m=h!0mK2@cZz*oEa@wFjki~KYvfoQQ0 zCyRGPHPqHGNjA9Uo@~EhJ~SA~a<$^3dwi#D`mLFEr>x7yez z^Cu8u1>&~?JvFKxD_0oK<)mF#c+YW0>fvCGlIL$}KR?ntQTMgBMoNX;kNBtD4=&!U zL+8#@UpPLpF}qYGv(d23;~rS`aI_jef=V=dr}}PDjVr@dZhWxru@{T8@>r{>z3Lr9 z=MOC01+}BY)mH@{zbrhd?-wa??G#skH~c$qr}BzN&;_o(5~7dCkCJQQFF$Yyex22o zzIU}~Bg$vJL}j_@%^qHO@zHUK5j~#V92|J!Ej#TRRIU|uMPgO-+jShc=Sxj?lMRfl zCh=?mz*Y~~)6#KT+`>}dDmg$6?y4N{r@*c(G(l`U1|LHsa-O|94veBmJe@Fz`y~^E zK$9bBy4&>?)eMYV}^OruF8s_vo7 z3rg!$+u#2H(bY$02ON7D4}Hj}-e=z%Hbp}U@EYbn`1*aGOH2I>D%kou_MrS=r8vOS zc<1j0r5x*zvV$rUqW7HEo;8^~4dFxzVT1BAY(AFF*9JIqC9M#O?D6Ze@9U!OMGk3n zmbY76dc73vmpgIA(;_hHeN*7#E~f;GJMk51f-o4X~&LhOTca+mp zA}>1gxIO6Ti<1zPkxyuJ|74XY%fb1 zT`gT4c@}nXwP)_b!b&vH15ass&9ET#**((3mJ)mS-Yf+RC4yc2!~WmWjX92jm7mqG z)cUTk`4nG&5$yk*`p)-*b5y6lWuI(gZdU&A>E15G=$!Dg$JYd(-n*BmRjSsj`GkIG zIwfCbdbyZmb@X@5yGP#}{wR;D@5gfNXFap8{vvMLF7dI)^fLFWRz`b8J{ie8|LNOL z3>0%g&Zd;n>M=+(tVv0&b%2*Lf=(X$Qp1!{+If`Y-xlM0ND@wbOA6&6jJ)+t;0X1y z(Rb~Dre3^kzzrveCY^l6^D3FfMqmU{6E`s*81WX~g^}cV>?j7e#EO}BOVy0X?8unT zRjl~^lWi^hd!S6?CdWKEMy2AQr=an)41XMFFWFIxgfGPj3YQ{N-2^(Mo|U^dW>y+; zb`UuP$YM>fm{tr2G-e9TI-O0yFl<3zO1=R%7%K)bGq43$7;P}DGl02;d`q~E-GG_I zRL)Du1+tUQuwp=L4hXR;609f?Mz{@y0whZl%9*<{%=HkS5xclHqCnfJCot|CT5aME zr$})|-Kbmyk{=Wy{qN;_}zof67|iW z{J7H1+K^R`$60gxGo3{@rC(;~{*>%^f}Xg+UoCTWN#SMP6c<-rZK^e!k<)#}>QC>_ zeNun682-Y_+M{c%_;xVu>(3F-%DZZF=T?5d*mBy@EvpC){*`j%c2C60`2yB{%lf4j zJ!v`WE1xsAab+`bN276^=y=Ll{@GB|a@3^A!zc0)QX(@HRS}1WmcYnq3?#kScg{%s$ z4C_0|$JOvF$uFLB>0Fpo72JMgQl!!$-J8XZxeI^0Gn_^CyAp&{4jy`wRuJ`NPh1C!SYm8}1C)xjgw3GbQW)3E^TVY0lmPV?)I^0n@RGG$slv zhS8Rp<-!dnFg9kMAX&h^bX_^2+?Lfi3k^pgc}&To%XoSL+1^pXpF38Gn`FQpf06wn zBQ&vMoHecFg0|t(r#8T;SfECJ9(URXc?S1}=EKv7Bif^rnh11GR;-y49D{<)kbq2- z95?g~M2tVz;1*zu((Ax{5`(ywmXo+`xbu_sOCgn1GdQ=@+cSX8C`#oMm1Dsz3@b3;J7te07U6VwDw zEKADAjG{^(d)SC`a~kBuoE1f}5!fY`SG0>2goNN$ z>DGpd7EFn?{MFq>1DYI(3NxrChf~hZ)8)Q8Ks#U{%~y#R9F(tYK6!VXA9=BTwAu?B9nt<76BISy zqbcKJHn|)jt2yk8Q#AqmUVNK{PN#t*nNe4lb5C+}=2FI(k?SlYV%cs1@MTz5aJj93 zFo;#ohFsl-N|rreIWe1|nrb#MEpkn8Ea*c@vw9pk0 zW*AAJSKV&>tTSIipqY43@oN$iL}I0RGg!H=g|z=CWGIrQ4g45T1CX$z!qXx#P!K)Q5bsMIfG0@ zW^%o|XuzCdm||mxWMbt->ZhQTEm*yQM2l`iBk>db>_Q-3KIL`~DaUJ;w+|GluSf?j zpQ~P=!+sh6lsT<1D7UBM^_i<-c-}50`o8@4dsGKwxeYu=SwP>EPsQyp2WH~cAqC_V35OZC28Ob~V(O*||){?iqPD1fo?w;~pj&{8C8Ju^WSuXZQ z$;fS65F%$)JD{_XZs*JfU#szy@P1*HQe4HsEQ;TdxTx|3j(NMhi%{BwQ;8j}1CCsu z%L~oZ!Poyhm#?~-GBad1Pi!Tde97s|; zG&Xsx3=qy#2BYIJu-G^0U`E$3Q;$cISotYn<|Z5~KQZ3|$!$XAmg27&VuG72GhJi} zR3tJ(*Et|=Hu*5hG;{nF(yE4-m_6l!CywS zgG&N2rQEO>Lt7M(|Bd#LY6N<^3s6eotuSViz*OldbH&KFT%(#e042jMhRHfB{-w;2 zN1O?)!hRP6$>`q^waSsKJd|kEDd?V!9tjz?>{0r;8k%g{ul}jxC*tV9#nEiO^SQ(2 z_X}U0-w#D3>*P{LHVlx2j^&VkO}?BCbpLhsiuW6-5*Z837eEV4Sw_U*U2eVmynE8d$Mn)RkvF)#?pxS?tAJnn)ST4xI+xd$ zkJ#?WCi*<#lF()9%*c(~M`!UBOD}a7Yf|WkES%Z*3dM1n&u%2xoxNvFzwUXtN$GA2 zEj-Iwb5Fp2gC}TUJd(ZX9P0O(c3uFdQRv=R;yQ>}=ety&(UzSf?_Y_|W-lAO`5sZL zrVv+l7TY*HzU}@(g#KaSvd6;FWtt)EL9AS2D&$&TM9zBfreU;?#^J?a@+;CS;?w-P z#n-);ySi^*$-TlTInn()?Amx;6$q;Ll%0qdxE-=i`LsJ znngqTk7A6X-rP%rC+lxuxZ^aTP`ON15;s~WL24G0Z^C}Qv`K5-hyzjPCiPYfF8Vf@ z1IUD9#d3iu)O8?UY=T0MDVH<`U`FLoD031&3IaAGF?d%k;R4)%jX@GwRgyh~o}{IZ zs7ZwC3pSf`xC%qWB>5v_V)u}Vq->)NbEO;JI5s13C`rx+U^)ZvV@M#(i3lVBKHLB+ zaWh(YSQ#tk468vL9aIWpGeVHANZ`43lAydvR^NccWPQ72eK9cO!w$+Wwc)X8<^@pv zYOVkZMCN0H9&zUJ7J@HR!IJ|hR(6hy7BtxxMq+l)8BvF2^#N88oTk~H2<7k&_dtdo`%qQLUFt0)a$Tola0sOv40m#-y2EUl5xMMd>cZ3hG3P;R^`CjLt{%H4)%vgDFr!P)kA*G>6uXZ+kaf3xV3ioz* zPj5`HZnMm@cQdp|TTd&hdr0BV(z(cl-m)3*6R94r7P=&QgY-iA*Zu)^-*)ZiXa{!? z&trObzJ?W`BSgN0w0U-XDebn0!mN_A6t5`TFANFkCT-KgT2S-YhoZ(ecZ4=lbZ%|W zAdg2`4ueh|pC8bnwNT?|{{XAG<8%K2Yxm>xeaBrj8YPss{m=gaW{SI+CzHN)obUS` zW&Zvju+?87N)0R0U6*}3YMTCCxOi1Zx_7PXBTA){eN)mJIYda>Zrf?dc;hVS*>LaD zO4j1Z?rZ3eF=*WOZTee{qA1_*hN72{s=xTc7(x6C|O;KK`{S(vg&rYjlI40gaW~*-P z(Ziszk{%0N2CyIv%gKeHjrrRhf+6->GZ(TRG)`;WJZe>W6F?R9*6BPFagrI9^kB({ z$?jlp91oWNRjuu_un$)48JN_);PFgtWxSkEr2X4tE49zg=BDAH8rN(xA(Eye z9hH?9NanuMbGB&73E7Jr9L#UI1;}PVIWt9HumViV1tlOJji_3H5C+`&0&J5tYOqWL z4mUb#q!|m15tayL3qfWYu&?I}pj55Ci6tj?Pu2ntsgc>q_$(8Ofe<@|Tdj>JWjft` zO<)C~aA#<(QENsY2eJ;-3>Z7CzMuz)Ru zUd*kqV1bCCr8tVg#B5F#ahe%r7{*HSGLs$-h<*bl8|ee1+;-$qBmDyZ%F7S8-eAK0 zgaV)yvmI&Kc^9n*b;aj+sWtD$+N~^GqUwG;Pkp7v8Rmf;(#aSWs$BY#({lCN<0r_8 zpNGj($_ZZA*bU6`ZCcwT%^7BCx=oWW2m3z4yL4CCd)qOD&qAg-Qtw2Vf@+ihQhb*( zmYyEe+rYw;r)Q-&|nv@m-coO9(T$PbM$AOna^VR{r*%}%pS3rvKgaq9AmZ9oT6=db`5)* z4E_Pxn4w+c-py^FBk3PcrI|yR_@o=N~QN5E$}^ zYwk1QXh`|%LiFxa`iPQ^Ty_>IdhrzhAB23$!6BR1^8Y4{85~KN zc-}nJH9R%(54aDXD_#ouG~D?s+**%q)ap7RZPUQqq(pY{tB)=Ri~Ws^=6wlOkw^R^ zA8rqsoKGuIQ!w#pIk@#W{eyXpRYYnRCD*;cGILOBh!7tx`42cLzIMnypHBata^l3F zmWrE4d)~77=kt2_?N@{}zx>u{o~WMCR&qL!Mh1`9{sYc8z#sFEO+AX>O$iK2LvlH1 zPfv}`3LU*yO1(vOdA~NdHlwjOyfrg|pt<3n*JT;%mjazU=@=SQlZ`iE0l!ZH0A&+^ zL5fre!VqNkKy5o?vKB^)7t5C=$8@s)=h>-(9a$ysGc<=ck4bR3OtnCJ0VNzuK!Q~_ zp)QeLoa#m=(HLSg6Hn?`nHn+y%NR38ymh6g#n|LxrIv62Lm)QbCV_b}LHg?kJT>`X z?z7zStfbORl&w}gKT~NYoXIDU!IGhZ{QLkp$K8gZsyQ1n;LAviH%XKN>_NFna=dqG zHUdoPE_R^*N(a9M3@C!&H?TBxE&$bJ1LxHtnUiT;6n%ZIHW*YE7zJ#&#}R-Hl_6j- zStTO5!Ix@}pXM_L^S+ImE)BP;Wo?R_HQ%bH9Wa&HZ>xQ|3=QA*)4tSJ^60r?j%15w z!1j>+8R4>p%M!#22x~TA1|rz{*1XA+nwGD|C;Cr$JscxytLZOUsJ^alp4IfeKJJMx ze1*Q(kZ@ZoqllL(dTA>vj&yxHLfikIy0Ko+BKO?L$DZru)Ud9L<(~>fiVwU*|8@la zc{3O0-z}TsVh^u)``IbdT3g~D!1K%L2%qj#@rCxBITylP1>7 z-o3kJZD`KtVA=S!tEQC}ow_5caN3{#4~TP2X!t2i4l6K!7!l-AFj|t6 zFL3(J+Hd*Znu(R^+3}^g3ij@%XJY`tnIjm{nbs{{LwrrFxsUZ@OZ|$<*}a z!}G&8wrw92EjmQ#*?%eMp8sm+_-W$Tit)Sr{_~O|!gi*PAtm?tlSfWsNTY~%W3YHf zo-x`pG-16%^oy5AoM(Nq2=4hEt`hljWed}`9!sNZ_7w%H{67O%HCn=coX#rE34Lpo z#rOJ~qfFpJif-esOUda&J(P^~hs28fbBpQrUupZtj_M1kU2&hIN&?b~v?J)}f-C1W z_kR2X3{U-4>;JMg#TXr+3eDeIUCJeN&0O?ZBQY4 zJ$l`Hd$c%Bv3?|8a)$o8(ERqUsZ=9zYgqZbcJ_l$sI9@>lDpfdd&cfW1=~Pe#gg((V)SinYxn_V=BWWO`B+&85Hv2(QGgo^h_QLt zp8Y1y9na@VV?E4-*E7)_n8=Q7`V3JMcOBG*v9!eC^o=lLKCU3vX=c&{iH!gS^rg5Z zO)}%fE;2OsGi-PetAP!7F?TN08B{J4k~bD8-GhPTcEMu*OHkSMmvh0)iKPr~dXAU= zAI_G0UqQk!065MFL{zqrj$mgbJD8GdaRyjRj5DfeX#=QGqCpY@$xMPU;F^1c8>6g* z2T&D*`(G0KU3!A%1CDI4m^dS#{lvBciV zWma|}P&P-73NLnkSMEQYXl#!+KSmhB+7Nn)#Y0LCdd{uDF0l9MVcrL)+WRj=tVKoZOMG-RPauATsv_U* zd6kr$e)HJE_OE5cRmD`TBlE(SpC_s7>Ru=MpI*P|WqSD=OMTpyM^}ew!R(Qtl#B^Z zD$0eTi~dM>;J?Yjx^O(E{m3_R>2^iez2B2x=3gU!x$w^Ngr9c}qI89uEdM$jVj>jl zdGA*_$zJYRD4mrt4^BQP?xiEtRocC((~Sqq?wlTu_~SJ=SGcnE&>3go>D%kc^0V@f)cT-jmn zH%%2{hl|+{Pf2^JcE8ID6=h>{;BR*ZU41rQK6x!zTcb9tEv;bF;~yXu^n$CgtJZ~c zh}zryXX3TX_;B>R{f`}Mu6D0%zmQ>Q^rzuFcTefwId83k8vFk4@uBp{!9O5g-YMC< zzgWCo{*`rj^^#q2U~%eaySlFZNRjYI#jAf*YrC%>@Gd_5nLHtrdmnEA@XHu9#RY=w!bn0kNs&Di|^~HZjIEGBMf6zy@`# zh9B`p*=pWKm7SqNQ5dQum}JMy=(Z>bfVY<%n*;$cOaKNf^o6cC1H0@eZbHd!`| zHxT|)!BB9JZ-N^ciamqMM^IeL3QdP#}Zmb6}E!UuKT07(;pjnW=U!vs{g9L@S5%i-3)knVip=@Vl2z0o?4I z3?DWIB?$u|E{^^_{bJ?>%nv$*gnt+C8e3iri!(lTHC0~YS)+SY##_Wdc(|v~*<1KR z$%vn)f3^Rb(WvRa*j{X!l}-P-``v6%dHycSu-Kj?>DxDf{`bG>f zXKN=n2kpyeb@-Jn&k6`i=JyN#_yo1H$V6S|Ah1i`&4!zmNrH;_0S<{}3yvhp;RY50 zLuSc>LJMUG)gwbshD$6p^qU`wo_}pP`8C$+^=x*^Y4h>4(At;V^ax8e#HYD550T&g&i7S1UOeeLde;(k zxm$KeC627FA$z6s%~{7RX}|sFhtYZKF`KSS`3 zCNEX~=Ci{;@<>`iCf@AT)cXCYZD)|%9XhUfZ3-8cQImz(JNwED7?_c~)lu>O7u&Y! zW4y#eZ~dX4^qj)mJ-FO(gh7;*w5a}UeSd_{~$u`o03_dqk)E&FfH*b_1N8# z)WR*<{7;el3+cZNZJ+KOYX_#pGv4P|y8X4=?!gWYnGtU9Gja9%=()wTz@Yiq+{KqK z-#^$mMj~uAUQ~@Q+)(U$WI9S;^ZG$n_A9VYxjJTjaQET^#rb{_-3$1oT)r1~>|Wx{ zbyq6#{)CoT`&@lWIXOYv9j?AdVF;&hnz%`CX%5S7gxGiz9Nv#?QtO z(}-{kHv>X2U={sxGbmu(gc@*Iz9#DckdXvVb4+RWfH9c213bV`_1GExnhME+(Zc1o zvY+83=K>_az!t^I_&^bHMli@UyPB&lf29YJnFK1g1sKg9iIGyd|M_5yKS2yFgWrM; z#U{`enZ>sko6eiWkWMgX*a%|EAkqYY%4N7{?QHl&k{x4Cf%U(05_nr+ye%LzM!u;^ zz=#$QGD6a!TT8tZC0XvukAS9mQ_5;`G47l(`mBnq;wpgA5LDfMS11aC2OZ4+m?Uj| z(0uQI{M+G%dO=K@an?973s$3aw@>Z>#6aX{O){G%8z}O3r>M8~S7w*w$0lM-R!tOV{_F zv@)}PJ?ER7^-X=L^-`QxJYhoQ!EFymwmY~Xs}P0iPxI6CCy8rrA(Cgi3EOQwP(E!pspwl~;Xyk!E!l?XO#6_Sc4CKn== z*JE|EM&DW4-&%A9j(!$TO*#Hr?MEd8E4`?`0{beBfnaW?cNKWzrQ%cNBdI@}oUPcs zWSuJ;`z5}GWJ+&y^KV2u_c)Rc*~-uv}wR>nB`ZceTfVQe+SRL3X% zzM@cwfF`G7bLc*ol@nF8gX^QVH7oT>(xXYH0`!GoGGR|h?V{|e*;Jm_ct@)CQpMp^ zq~mgkUZUxvajglJEf(4lYk}@VjV%-P)d}6N(xbuc5&{~=Hv*}Lw_^e4~bzZ&xD&f`D$z$&Z#OAmokwb6vkGB}DZzoSq*z}6a#^?<8Gab9Fy);T&zg3H4FEUZXVmwR zA2y}1gylX6K0(3%1*X-F2!%4mb70&gFo2CAh5;z007#NoNyb}1pOa+4A1P1=C>zzd zbIUQBt%|cQZg;{WpuXS{<_&gs2sjqO!CFZ_%bk{p!!T(9Wu@yt8-sv>zj5D8V9+r( zK$tt%0vHk2M*=ZrHT;|y{ViTsc3@h0n&N5DzEHh_#TP+DPBnw?x~6N=;| zsULmD)`nIj9%y=L$W2*sHo%SLXL^rJoxgV*b~S$g=`%XtwuzWI4KoSXTpd>IQ^)rd zVG%#PW^U`u)?fLHZc-7oa=EzBar)e*d@;ZJy>j)_sw#TeJrnJ#_!gCg&Ex4XmN@b3 zFG1sBw{$NkS(unsW0C50nwqz*w4X{$Y=v+BP(BFXth!6=@3~X!)c5?63hUd*f}0zj z<4gC{LyWIv8{1O_cf20XJv!5qIDgOS_ipl=;W?O<=}Jl(7U{LH7kyic3KMBOmiX>6 zhG>{`DZ3`GRg)fca@IO$c{FeDM9UvhHPbnj>)5e_hkvDc`-}9FRo&l>uZ&MIPuzTd z$ZslM)YfTOB?*`AVoX^i6EHVey-@>K(B&a#1mHdM-6AhS+(&(joC;4i>h{UYl>SY1 z>a_hWs#X~h6Lk2KT``HpP6W%QQ96xd#y4tEqi!>4-h6pdeo!Dk$z^Bw`RKE{LaE>#Vj^=Q6{j6W{ z-EXgJZEJeEkwZOmowesfL_g^K7PWf)ZUA1xJjKS%n9k%)VsalLo+R6iGM8N`#0v0Ru%g+>te6^r#tLG^2xMgsFf>F-F@8*Ji+CwotQ_E)Hz%@la2S=I2NGYkoGgj?AHU?j(X8G>PO!gz+K2xk3X1k1G$^9C7N4Di>0 zj2M8%88?cG@xB3t>0|Xb5KvzR$i-pUkwgQ~|0E-#lnA!~dFRJ6#!TZF76dVwIcCC_ zpADb>-^R)S65Lm6b1J@Gi{~uz)B`)lnVIZtthTBQ@>u>CT9#dI{LPL>&X+(<3$F$%=Px-90Bt7`1obbrzvyqxuaoF;g8lF9eA-XisJhh#Y|Edho!x(_Q{=dl)nC2n zYx8&Ivgg+Aj8wx9!`T6MB_*d72%&x<>nY#wiZEugt#0qXR&(|%xTYQ4Om7cOk8+%t zJ-kjZZ~Jj{ub=+Qc}w~Lj;gFhnwsjc8XL%*8DS#`+)xTMu*x_w7pyyt@O$B_EmQxq0GHrW=lRmJ{Ez-mQ`3kp(dL59-Cb3b7pP8ckfSX z=X#y>su^3nXI6c(aqDGJuH@sB?Q2I`Z^Lulq&#Z>s%b_{jD!iy?HH?cc-9Jj`h+Cg zN!oe}*&)f}h|kFwfkrsPfw1K*)jX1wR`QRsT{^l|`ZujIYjVVL{zDP%|M2wHQBk~c z_iHN(N+YS#{iSQ^SOICIL%Kn_LqM8ET5^GedD7Kv1^F`968xN**@|@-ol3I6A^oMa(97h$)-KgYl93Q`sX8aD2sqCLo zi@J+)hI8w|Me#Q&q~v2~blteig%PTN%0Q|rYT0-mqG-q|IlQcx5w(1GV3#@vre%zi zho$1c_#F4gd<_L)`D333=DjR$nNqBPncL=MIO zY;CwqK#EQw9UAbabCb>djytW`qgOi!1l_h!qh0~p`LN!qODgHOWyJN1=uMB8R#E$$ zoPoP9)V>OH0|naC`vNle?H?0xKYH-gLG>vUn(z~G8A*7K>T`+QFEXmY8Vh0v(d7UW zHu|7?x#BmD0}r$mD1a)C>E1oi8yeNGkP&^{U0_Q@NX!A#b%wee9P&sRiCk+Rk|5QQ z2^?Ht;}HMD7ee2>0*3QICl+y!3CI}#wvmo?5&-|n|JzGFlE5h}XA}f{;XU;Tse5c+ zW^C_S)6s*hDIO+)7@dpt7VZHX;9dpQt%j|k7SFh$j+(*gU{xH%6ZzxFZ ze(TpN^M`qSlC<|_8|bcQC$I#%f-?IRlnoPIx*4hA=Ejem<~lk18mBGK)-6SN51C!< zT*bY4n722!HsCD_2Y1Q_C6pqVPT5lbSP?=aou4$RGuxf9f;W$b0GuW_rUts%|GiXm;y za*IQ}@g8l9)q|elT10`u6R%S*r$63)UAw_C%(I~&fPoK0_n?1-Qk)sO>Ia}9z5CD2 zRGFAmALpon{q~*GN%-s) z7=n@$BEoWVO%!@$Bpw$N@jL>-?Uf=WltRpBctHSh>kU53+xy8u&t%@-|7QE{9$OOM zJx5@vQN@I<$iFh9zj{7@R zihq)AFqKD-`7?%iG4}ZE<84gY9&LfU*!P(=D}3L%Z(R5{fyJ3_dPej_86yN)#&&8e zSOWA?^OqG>QaHWpnndlw4U7UNMoh!J)^6CmOf%e4);o9(^A%kSy6asgY)untE&`vR zOA;L98GND7f7Wa|m&gZ<^lepo-z^&A(J(4KE$DKU*R*Iom)1p2oYz_U%QcZa@@6Co z8(5=Tp)N{2)Cy5!`-rBS<+oia5r4HsE4=abTDMB2ul{muEukvR52jX#`clO${vE(C zW*7>dp*Gzwc272r&aQd6<=n6cuu8bs!jT*+qx8%&YQ5~khQ7X>BYSFMIA+s&0qa$z zv3jtzKbuwu8FJTH$He~ySr`78cU)>#(Y*5B)-971GnCOyn#@69lEtQ25RK!52Yqn@ zb*y85K?jFdPiXU9D}=yG6J)>0w0l!~6)rMP(!oq!)A@fvwVdN>XX3b9wJ62c5Q0pW z^JLm->o>XKR2Wvo^~Id?+6{(rx#1-zPPUMFvX9LPq#F9ZUo8xbQj4leW%G>OsH|~- zU=qWZ{RQf+m9(WfULx2V0pkv-b@dA&ZHRFQJ+38hWs~v1{^*7mxa?zWm+L5X+>>$4 z+Fy|Ah&8W*D4tBt3v!^|kph7T?C*~-nMf57L`eNF!RFE9ND1Z#K=gkuJ;D?OR6J75 z)-iA1Xt8R7zm-4Ac}VpWc&Wq`-jBS;ktMkRIVS=HH1q$)zVyImernBzLlOqEF8>1L z0ssmC<*4@FvrhWYI-MX$i0NrxZZYR)R&s!C__!O`Sr6&)-#q|ovZxXX@<<6BydQ7= z#RRS1`#`FBN{-ikKR6QjM?ki?pir|>xMVc7d{gp>mYGz?VT@J$p$5FIw+t-Bx*?>o|R> zf2CC6h3BRM|9}Qjz^%l$``yw2TLgd=Su601OX(Xuok1h&^sjM3On__^B9jxul=NzZ zAc$LwocW6c*-QAsXq+gv{2=DP<%G6Wa2M^MZJnUvt&zUq-M(1`)&RqakGlEKAob1) zcFgT65S>!hM8G)cH!#U1C|h3e zR6g<3V2P^I<`!lA+Pv{W*Su=RiTdEA7QyG}b>py{ozbag8Tb9)&$)kE%m> zxk8y`%~15{U7s7C7;L5?JZolwr14?Aoqq6pz9{l@5=GN3_Ne?026tzfm`eeU31z`a zWTukm>+!8D1si;;!b`3ByHIa)xWT+1rGcNXl7J$e{d}BuG@CYCBG0t&PTz^pKCP|( zk}L1Y_x$rH-o~oRpZppnHL(XnLc;m6b4G-PF-e&+p&fFI;4`^Q=c>nKrm<4Yv{E}= z>cw3Ov#LbkXa-!ySmLM9j5WVir&Pu__us6_v4ASajQYC4-2*w+-8VD zQdJy$3@HvgotRhGo$@~a5$;cn%JT(+ZftzZln#D++|Lu0Hk!x_DG%{ zmGXJ*Mu-Y=WC$gmb@0Xn~XlGcpvSHy$&rJut`T}gdAOfIR9Kyml0X?Gc z2~H18gZJ0&+RiEA`OKD`v*uC_YO)VS;XhD=M5h>87;oDyUxM2s>(~;uucDtd@O*X8 z{x$zFDF@bKGQ2G0H-z(Ri;B2qKD$v!H;H_Kg!_Gxp;WA-{;P*303P$vEibt7zPU(q zmc5YH3WK@ms}w%a1DQOXe*xgjD@g!P88ynYqh>~)=%=a;9#VTohgsMi$}^Fut?+4h zwqDK ztnHy%`bn|g{<_>Mt4Q&Ft3vpo7naM9hpxKUh_BhU;gh4@VUYuJAdyTc;ap z+4ID)Wl{I^f%$B_DvO?Qqrn=hE}cc$h=S;W4w0-4bp(Z&z<67ayNVduv0fmXx`0RoWObQX}hpTCafBz;hfk{X^c)BHwpZ; zl)JifLay$bk(q@&zqb?#)!Js1*mzpW{w_BOoz6D=+OFmc3um{j-NH-VUOc&3I zu+SC6pm;XhC^5^9GRvw4Vh2)!{Qv%F1tZCbUszFvnm%y$?+=NRZ9ohehf zP%OIehblD!`dT90twa5uCkJs{AvN2)^IM0vcz4hL^q@p>?<;>h(N4_WcK*m{F0&{6 zMlQ5=mbm&IHIoiB8T3pthX?>UZGo)+Oy*5+tYi+WNy6)>pUWh>v~=vR|Lt>C^@I=! zAdB-61j&^X@!gNim9L(_dGiq9fyv}O4${20NDx%0g^Nm;QlJwpt9BHTYLLZgWK$=J zl+Zh;CoV(@#e;HQB!>lWStk)ZkOC@s-sBp91%AIrGLI(*2N26t=Tk>YN`wFt30xo| z0o=DB5Wwbrm;(qA*#9521F}wf^@yP98PGvo}7>DZ7=_%hy)jNZ|yoo+Cq#z!s z6{*FP?0WG1Dn33F@}}_XrMA+JOHi5r-M_Xie4|LNlxdJq2qm6Qh5yzqwPnwaq7tTN z{Az0iZl2SMv%+=bF;fs+P3wHU$5ydP6+$&VU{}-rDWAf`H%VfYU?IqjDfI28GZ$05 z^ys&ekwICP57D1Eaf$k6BbOv7lO&6u{ezd{a@THj(_C#1j_Lj&|AGcij=+!z`Z$f= zqvMm1wGY+Kd~pII$F!<{tOOzZ~vgYiOnY?i>*WcmmtiJ(H90O&=WrvdT!JLo}s3 zSe##=tpeIU&z;fkf0LK|#mYB#1but?d*Us;!KWhv!bLyhAtY)T_`g$4sck4@hb7d~{lfWl=V~3m~6ya%1{mKhYcIR-+`r-cg=*m7} z)TgjAwFG&Fis^2okAWArPx`I$%>?7~^@SB%XESw|3WTV+-N~I?M*p&!>D>D~cB94T z`h2a6hc~9}X`-@o-rrrDFcVEmqG<5xQn$FgpSjt%;z)F&xg7KpGtoRXTY8y8?C?kQ z5!(^{LUD(}tdWD}f88ir`Pa1;1K1W)jkJn!lv;p!qknnR`ffHp;zO%I~Da7^H+ z?&8oQwtF(ZtlIU{_4J0@Sv!gZn(0YPb!ZSwijvP}FN%$-Z|Pbb*kY^HHO=XmR$pq} z_zUu6eLl9X=;y*XFjyE}f4cszh?G=aQ%tllO7wBIN|xAq`OyjGE}>t%^<;Wr9oNU9 zNrfZou5Rbs7%_9NgjK(hUQO?=-wmSMaF#ZL- zjJ=_@qx9h!v-TXXGOG%|&1~;dOwY^wdc=gBI0J7ZO@Jc(11_$#>T|N(hK|2;*yFr- zk~77cr#gW%!}Q9Qo=^tRgvbD;h;Rx8ZuH{|e< z5DU`9s%~Z0uaky1``E827EM;JtR9_m%{o(xA~}*pFv$9~se{j7uV+`j%1}wxUiY!- zYfnT*`dA-(-|7|#Id!=h#W*(@N6FC>vqg!{j!aa{rpi;>?|mG>EV7+!eTs_0^I5a2 z$oVPaW;)DW1|OxgTj{bk5Ffz41PI(2+g>d&^TTtzYs?EIU8U+G4Hc3ksz%e0&;O-v z?ud=+r_fB|I^^hXGe?S@G*o%m@K*SC#_) zcAIZC)DhGE$bl%%vu9bSm4(xA#o)N=33yx$`QqDZ(o4p2tX|qS1Dqvpp1LDPk8ly%d+GZ!6yL5-qMaIh|@WK-0`rB>lf zPvg+v7iN?$&cx`E^D@b2lJ-!;h0gSKd%wS+Xj#|ek329^!G`(9rp~G4BdW{3$z7xv? zo{b7ML7{1k^yrZj@|Sm1)V@ki^wf#(yC$(72Y|6 zyb*rTkLptPyva9Xs`X-v^7@3DNea|o^X^H$@dc6719)Wta8mf84qQEQlt>6lQUFL2 z0Gsw65FlniI151a0?d~l2Y&@fw>Y2)r63~mg(L-#+R!0hnk_G(@vN2VhY?+_LC)6a z9NOzkBsLat>PzhOw5awtYU|ZF9i)6f(X`lz7f+Z?r(wa!rC1$dXjYXv-%4lAJX%a+ zjRp>W*}Gh|Om0w}suRdFaZU61nrUThbbBoi&C;Eqf^w=m6Wc06uA3?kor<;}y5A2| zK*|`f6Eu@z1s!ZmgA;(%$t8>~9uw&vr46 zHr=8{iN@u6xvITb5Fk}lbOT7Ac0C4=y}E30LUHE?$9k)?^B+ES11OZFkfp*{EfTW5OR;1&;H!)o*qJbHl zt4r&12VYRyuWUCD!8yuY*-kO6OU0R-!=j|&bH{2Ym4rnpN_0hJS0$uP8J?H}>MT({;r`qpv*4bW5J6yQ}|Bcl&O{g|F{jr%1Mv<8(`> zRT2EK>x|z7+EbxfKkG3|<@EBP*{*)By~SP69=`|AY0g~D$@1)cYv#CJN?$xX#VoR8 zW&6%p7hCCskKVAgV6CfKR(=o-wdGzxmxiTM3%a^0sA-n8o$}4{U@+eN?j#N`ydX)r zX*)&q+XaKk`(4J%icYReH$DM+*IQQim4%xzG}42e z?LqQQ$3)-g#=&G39phjfX*(BH1jqIJ)QiH|VosAR@S-R)SjzS-xQW;G^o-loH^r65 zJyxG;_GIZf=d4LZ77h2$Dqhkyv5Mt#w;JD3M3XZ0zBG#I=a`G(@OrkIT9mQ@0yb7A zKly%t^D@)ywe&IgwgZ2BwmX@HUfBgQTX3oQVYC*On zfS?TEYsgFH>D>QPEiW?yv|6ulh-$w8q!Iv5cm$9;KtR>xAQfK@xE>^d@&JOcLa*~e zV{pPALH}n`!KWi1w19vXd`|!uzf^*Ro!oiz^z~cJ3m)h5926wWy-ytQ@~D@wxvsRj z8w|{;k_Svy|AHi@8{~I|x2pFcuz!C_<`!Uxs$+YKV_GHQNR*U~br0=?TsBMu6+#yDxs?>RmI#KM*o-s}qm1+lhz^;5_~m zA<35gdc`T5ckr6@Px*b-2@pVHCTu1M`Zl2e(pt@X#QFez(Gw2Q&dso0jr-!2D7$KF zIp#hTkU43l`*{%89nyE>`!k7qP!0O4H#-|fe2Ix(7gkbs;Ls^|%r8RIgtgM--8}E> z%5Ro~ai?oImvAN?rxa1I zw%_@S(`Knv{a9E7)k3_J`fdCW)^>$q6r+!TPD3)lrmeHHW50`+eE!?2DNmo3FN?ve z%6M9-xo7-DS-gol!Ru_(wLvE{wSY>NvUVvsU%Rvi4TaYacQJ6S3N{K*fzytSiC2z4 zE3wZlTuqfJb821@3BBCC^j?&yXDfQPk&0`D--e;$$bj027kjdp+xFUTy@+(VkE{^^8 zFe!aFMS|zV6(v`PSVp=&heprZ&JrN9>+clBPMj<#b+g0F;$uC9JK2XC42&E_@;@QS z`8fZ?m0bK{WfF-i@!;9OwiJ*;Q>AV-lbq{f86E1XqO;;?E)^Nor36|$UL^Eve;m?~ z3>-KyTWMvD-exI%rxLksF$sV6>@e1^bZGX-(rzd@SjYvEKNHF!Gu?b(zp(Oz!9P6I z#z>hsRc%9xtH0|}nN|M{>BZYF*Bwemy0v^;POGcCqHxUFxmN&;g|vpb3@wgqfC`J`v%Q`bz#utlZ6-Q^Z=cwCdVEiqK18uApe^8Kmwp=|FeMu z0mH2O09_&c6RD}{gaWSA)bHHu#7_k|_5}71a~}C}uIfe;9V@0%(lZ_el>m=B=$|hx zv$9kCafD>HHLroR?zwY8F0^ zoR=$DFw6dB!}hii-~sVsB9LNj{xWw7S;kyp4GO5Tk6Wm_``|gmI5p%i2y}#1Z`fu$ zf%{vkL|s!%e>?(umZ$AkYuAZ?LC?6IUkf;A-8%%nnBrD)S4+tU&zI_L3#*$btE$w)zaZ|w_lf}a`(3nhZTe&JP-g4iXqxuY z+KsQjJeA-6Vb?_DAFI@=vu_6OB>~TpFo6AZ>>ZrlFX684GD-L8P643Qe0_ULTb4@CtEh_*g^UI22?f0ik+lIBQaOOOIF!Yc^ps!4 zka0{Y!1BYT^LnhMg5rYll}_#Cg}GqJ^-}wT zlTR}LO0wa(<%iJ{hmrU4&CIU)PsC+?Ni)I#Hkb^&F8zKJfI)=r0ge_7y)yK#9`s!7 zgqMF`-?6Nq-a?o~V@0{qd5QZY!e0CRJICP^Q8@>^GQ1)s#upbB7?L)=zaYc$tBh1jVeiYUt*eZXZL{K0Y^G&? z`nFr~<@s!56N3`v=d~>q<@c_J*KSrLpY{Z1*0B@-9?FFK=-uO>sgVbtAf7Z51olMb z+@cWZ4~5o;!2luQ=|!(>jRbe8;IB7G9j=wlHQE{m??8MD#QDPKjN7R`TmQP>acnEY zrB~uELy1Z6HlCL54gP1LyQWLU+d*G<3@$7=Dtf=Z*%#S_VVqb!G{|gT^&}Bk9lXl6 zi)*5E@Xai@)n=58@}_KY3fOQ`il(L?RWMqodZ_gR|2$Pg$vh*l6*|5(Sig!!;a+{` z6B4S-N*TtFYEhmI=S?CkNslzBe4CNZah0tdiB#A<0ahn-X$OX{3W2-*VbK!&tC6|O zHNLpNd~Z7^sQ@A%#%IO&e$}!!KfC9E`r#?1q_V1C{KC%XJ1Ta^B5J0xx=l)f(3NrX zFtDAqd%!NjaHWdU4svg~j6_h=hE8Jz*U!!8*-v6L&!{C57cWeC%)wJk5Vu?b zjWMJ}IBa*qRxTQM&{plOk?3=aIs_8Bq`t_IHLT5AFoCKg>&?wm&K0d6{{k@RgM6qxM?0Y$@j)=mjQs_qd<>JQIkgqlc;fhhXZrkn$D<+7r&U!mU%<-?R ze16KnC))DFWPk(8)56#p=V9&!T46IsX2ylda0axpfZPY)`W;tgh62qFxx7XbgDfiA zvfRmb+a@bo%2dw6QAcJm$7Qaa69cs)dbd#zxaKik0qPXI4%MFW$199S&~=7rQ?Y|- z6F4stHGMwln}&}Zw`!wOI#oXAPk8(I*(JMCbJDHXt!|h$_s}gB5(LWV<5K6T9B5CD z+D)PVj1rkoDxEHE`-tla`mvn$96`J>B|QJIttvvQ^nhB` z49nj|7?`$3&l!KPt>^E-Ddte(=cGa9UfFd~++df!!*ExL5!o=1I;CM$$q*;G^$=7r zvgA!|chQb{8G-i{Wnv7nWDPpvC%bCTY0y)sNSXqeNuCZ}$_j%9M=eakm1=nZhpKrXbqpK5=_mFe46iJ+7BxRPr zD`M2{HJqYvY7?5v9774oapX0!ri?n&g&S!bd55E`P`>D-o+$Is{(~HnsN%l#)Hc&_dI-$t^v2BmCSqkATe!89d2IN z_~R7s>U(=P{r7Z;^#03c>LUNy!R)-YWJQfG^_$cc!>;z*hdxQF#>9DPaaJiYkfS zQS%=-ebGI%(wf8E`T%|&_w9E1hVt(7ao6VxAmN$l#ddzc(GN-c(zQ=?^>xFuC0PAk z3hHz7;zrkJ6>fjs*!Os{aSirIW6<+wFuUUanCJ<@lyY7L z%h&Z@M04IUp#Io;MG2*N zt*D$|s%|@Pzh%RtOb{z69)cHrlM$lizUvi7P*`^~?YgBydmc4c0Es@F#>;*&iW%Ip z-^`NpuB79ZrWW_smWpXDOzL=#1Xui=-u^VP?mI$Jx3far!2^Ru$dtc7yLBO|9LCj~dE~UPzIj-JVCquI|_^E+6iM ztT^({rNEw_dP2~d^oeQ))2#4-E4G&I)Sf5Hr{&M!9SU$yZMbw4tq|luITm@qG&?^1Jr< z*e+H^g%s^nOl*jm$d zP)$D@_R@Q+2R(f4BFLe_8DZitAl9=yw9O&T*vEV1bu4@S;R+L0=PFI8-)Jn}?8N~I z?7IqVKd>(ed})Tgk~J9h6%pGn3r6Q4UmLo>UQMp}1TdEL{SkoBkY3GPQ9sX?*Iv0{ zj6b1lG>u``1y8++23W8T5=^D2ufxz=u6W14EswSX_2}z~@2%PJR3xmf0e- zj=XBYBD9u**`#HU|2yXh^(DY}$}OVQ49Nf3>ZM+}zN^-`ZvWgLt#kL3&%}K`V_SD} z!Go#y`kc3)z06-J+F4(7wQ8n`GF!-gvr1)avFwr~QQ4ioMXijefIPt_%McgAYqLAd z|GJpHYSZmP%bmG^z9n50FZpivR(XP(kE{|&sU%!Jw8L04TzVdV9m(9NKEpOq&YlEo z0sky|D+En|8*mG6iwvx`ra236e9fZbMRPw-vq(r-sC8Xqhw`NpyR*#JWtAiyuB{Ga z>dm{x`OQp}S)`_Or0M%B)F@-8rYIIRN_CO;O1yqU6K%ucc15pH=r!33zJfB_zW)Ju#!m&_Tle)PC!gz1aCWyno*=NmIE@Bl|MXE^a@JXa5C> zi%_TdQOFm2hJ0iS3}B9p>uF_kJKkOs-~GuOqe7~945fM6ov2Zq7~>#m05dC~!=4ML zxqce|eZ>2HC7RS{hc-D~VR+&A@Y?j6HbK#Y?MO}Yh-rT^?Z{%OEZ26Rjl-v7$lINp z8I``jicDl4KG_noK^6zBd#?xVqJ`|)8(l614h`9cAj#LYP4>F@&h~ZH?9xmLERG$h z0w-u`TWXK)Ej)IJY}JN*%6Ze-&aR~nuX4#Sjx|nooDVy3Q>RfFzy%o5YZ#(9&At{* z@=a#32`4iixF-+ycba5a*ve0>^i8XW+o!N6{IEQGXufs7=M{X2+v5!~NPnjE((070 zBkHJBd)Ksq!dcPI@PSYhNn4>tA=0+YzCDa`0xv3E1K z2qgtjwRBP~{`wV!=k1Pa9hD*T2Z*BvzBCsy=`etjiErKYdWR z>s4E}!1c-c!&hgszHg!gk>+(QR2aguc(}`G&&Q`%HKKRnjeF+UR-GMQ-Om^=B*{+$ zzl`8R^4rV}`adl@^*&(<%AG~Sf`ycsoRRB2jLHP_n?BUI{WT~8sJsiBHnH)__m;Zx zv(2xiq3w<9CerRz^QaB0s8L(+v~$Y(je(p_9o>3M$7qR8&Cf%DuMNVKiO3=q2Jw*I z9TTuiLb?siCJukSX9w`PsE2YAE-#2j6rp3~RN4WLDPz(JL|UsHWzBr<$*;G+X9mG@ zevL3>-{b|WE*TP$$9HJxMH%mA2}5q5Qoo*(H0D4EsCDzGh`Dm4VS6of%u*R{6~64vusWIP*CFC{IfVw3uz8$``L0y5ZfqQJwMG4c z)E|;GSOeK=1C%bVYe7;yIauR8dQA?i*A(k*yoq=qZM>RXb2J=`9+(OSHw5Tl3b8**Guvr{@3mQVB=M7J6II7(lOwyxJFU%Eni)uH;Ny)|id! zFSf*)hUDY2-;2B1rO3$#iY9RNqHN&(7jQ-NYlS!!c5@0LuriHT|HQ{S0|TofRD-;xgI)k;ncwEGmp;nbUb#ND=mK)BYl$;H{PEDm28ipy1tse8v@7El0 zl771Gig5X(02!?ZOOfTG;?KaTF>X9q;Tv7In)x=ti#_csXzdP4%AkwCYKpY`*Nvzf3dG<@=ZX?;W8{qv8a^U;~u+_ zKcmf8=pw#-o|K;~I{0R%`Q{EGr(6IeBGpMV)!`=NFn_Gs@oN$}m@@!o!PVgC!u1Ap zY)28X$>^4=t(9uD+8wif?2Nlce=C434W(}h9-WbP<^Tu}q2 z1004dJ@I!`c}o_%ULXA?(#Dq4i(YGHd{~M@{>g5cZb4?KB#77dJu~*<#z^N6?h|dq z-t4)iSmtC<6Cx9AxjLOJCQg(y?ZpBp(#0p6*Wzj|nI-$iHE*HypY2Sxbv91c9v(~6 zex5X2baK#u`@n8o;`s$E#$-Dkz?Z3Y+uBsr-fn#?ELsW=Zk0p59P^BuQzugbWrr(u z-_i`xrtncQeZH~rX?T7lUBM9>z?SfhvNTXa3!%&YBG9?(BIG=ljkM^6xafco3wuXA zz?m6e>Hh`T-}^Ns8QfjAb9tZ@44175>t2(wk=7?3WE-36 z?l0Q9aP>3cRwZpka69)+ zM*Zw!sU=+8$*^!ZKfaaYif7pR_{x6Q=IEH#rA9wh@8!t*j))5K_a+I%B6!QPZ;Lg7 zrzT1abg<*g=gdacXr&m`UOg|(tZ8E1e%X_5)U%_V26s{P+Ouqx`{0u%%jZj_OqHd8 zy*>e7?d;i)Dyv~)s{;B3_h+ZYvcFNhXeBh8SiYBQ{mGLhL{owMJqh5{*Daw?bl`XX zhcx{1`-WiOoLKPrrZZT(K=%ZA8i(95EkU$we70!5*)GOFGy3(Ea@ zGuAwvO^f=XbYUFUri z&xY4A*i{oVBKBta0BgW127A{)-!yS^Th+tPQN{lvs^FOhgkzjCU5mVq&W!4?2U=by+G)hW3P!^Dd ztNgvaV|ztNlOSoba>5ML=gPaMl6JG}wX~&cT&hKPk&(Kee#zLk>7FS~8(S1e;>uW> zxi+(giO?&3$fL+`D;7MNS%0jkmdt@@UiK4FDf<2TBFx4IPHo_P?%^#)`~_K}R@Mua z+`90C1CLX!aQfAn%}GCZcH!mqvL27_XhX-0^N)DR8ZSBJ+)xzRn+?X-CHO_t%DEYQkih; z!ZC`irA~fOd5u}@Po{z3Mi~Z0?3ySVfahX|1!M%repeTWoCC&)eL<{q@SR6 zeFv;RVaBU&H(!rlwjoyG>D4#yz#=EYocDK0ixitF5nnk?y;*BUQZlI_6J$RR{T?6< z<43OBD)Wzmg^qed)@WUSW-!K|JRs;hD6SRUDM)XJeMx!usqhthjG{?sCt2tHGQ({#YxW?d+sCosWryB$ul1SOyaBv`gnM$77bM_+K3LsW6bY$a}Wk7!yrW z?zT(`b?P$MjvWd-hKcRK&jL2LMEW_&532s4qCPh2VitP?%wt%^QY9Pjf>(v|2Ha#>u1z{h0|R8cgTuJyRr2=H?( z2Vu`CY=me0&_V3|N;ummc(&m3b%}UVs~Ey?8jKkAvLYYf(a4VGMn3!_9=+%J*=}_i zH9U=mW!=2&y@0}cM-av17US)Kb(3<=&IO!5S7FN@{vp&w^jGF~p*4#Ww#RZ#X$_>K zOB!^iEp$s|rp*@6q8Bx*sX%j-=?b-JW~ke1m)4JdEDuR%ak)`Dms`o0^50We&hFJM zV7R1F-U#{&Qu5-iy4?b%UVCq0u@~%R*ejhXD{kzr@4%|#M}N`C^@TFCZu7&ghtQ>Q za^pcOtDa0*FX-!|1N)g%!D=N4YiMfW6??xaB4^qnG0Ib(Md+ddLwRY@DsV`QBFS$t z@R{u%F4d=YEUR~)Dg(SRpZwx7#zLMUi?p=aU|9;4xaTi?+|!xa1x-8hY(wtfj^lR>M1i}^`ncUnA|ZrqmUPS^u>Jzsh0MU>QuPa`tJ&frts|r8iJ(m6@OEC@>>>V8GH;#=p-7YL&a=zr*p@mTz zCl(n7ObyO`0TcqFDqvPkS-TuPdLmYHfXffeUPqa7)hojsX(IvUo65`t+gO6#;wwMG z{&Xi!wKQ$l_13=5jTy0#>ZA1`%r|G;{LwC&`N_3&?Ai6pnE=T7iv!yPq}}Efjmeo9 zfvi9k9=of|NWU+j|r*8~Kcg zxaLtkNasW8;~)y&PokrTRSjaq=gO>9mV#G2r&llw@N`_W%1ISyD6fix(?EVgs494t zLZvv(k=tf>BxRUm#Ny##LF`%HM1L(Wn(4hUd-}{r4;ihGu}iKViNu5d#Yw6g3~U}` z3ILK&tG4(~hUtRQgUhW8EhPiEs%DqK_+4P`F^uvMw;)ylo3b(Dbxwq$CXQ2Lo?`Rl zEcCft9XLL2>`Yy`xYMT0B4zyb?r1M#;gp(h;y^opdCu`!7^|2d za=Z4Yh*ImCerH$2@tgw(BudwiN!D=Yd(Gvn!^y`>^30o7|Ciz#h?NEec6>F|8B*R9 zD9sSf(_MT_ijA77`^Z><)DL?%6$MO%$c&vW;k`VBZn#`%ImvdX5S`e z2I!ah?yt@-Q&B53_lX^*wHTxt4O{_(AN=Bqgqh>Jrz7l~cpFukXE$+jUhS!NGyyC7^o==yGbj4?VKAR#fj1`HVG_x1Vx&efmKSZB!kR0;1=hM7dchrON#RSesQPj&e&L5%Q2|a*Kd05-E^hd zBIo8B*2HYxZNiS|I%32s6w0(l5Mdy4+Ncg&k~mR((&xGflXW%O=CuYI)3ECdY7{!!uAfQ{*=h80S++hV(X zPT90Sd84p$gmgpRZP%_Z$BTD;atmV>Z*yzJ$!)ti)-JLGJ_daR6^=g`B+LFK=snQ1 z#GUI-Q_zD|3~gc$%6>HEg2N)au16k$0;eKBV@9g({LW?R@(YCBt}-I**qxnRK+1-_ zGoGi~`^}e*ZYY~QM#8H=0dp(UTi8sKJB_UvMxp^$j;7K~eN^|PvbX{_N!DvX+^S?* zpbfLpiiK!(G6b`$(B&|-9M@si!z#7Lw+Ahcl;zDn8#HW(cL3gnzB&KD({}nET6|UP z;IvzqGf2lt8?+%DW}A-q5ii}Q67-vhqo_ZDQi|;G8|i1hZkw>Nw}hXnhHLQcB`f`3 z3m_H44^0AEJX{*8ezx_L`|D}v&YM{G z-VpfLMqO1--4FHR2K3K7FY@tmIy-|lh_S)7!L6#St~UOATlwRWhYo=0E*$#>bD?MQ zk7^2jPG@_Zq>f>_=S?F%8%fEJNWBsSA(ikBk4K8t2Az_>E$JE!EnkgR*D% zN^-c?Xnv0f4weQJeLNb%&7AJ*PUHB#de>`Q@QH9}WFS0%sKB~Ie;R6J4p$*&Z!D^q zE~hZXYo4#Q+WJ@#@^S6pro@h#-LQnxU>yTru@fyM`j+>MJlyG@r4JcO7^guBW{1`l1dg zh6E%_DF-^MYQD75zGGhB_?*Tj}~D$rW*46+g{NjV-KCLr2xV3Yw2HPZUW6B z`Zt*XeB?ul_>`^?4sN#)W{|oxd=&YesKpJY>tfkLphvNX2f-?2aP8rvRvAf3+&MjX zlw%mMxm0gPuA9dm20NcJ82~$Q>-0I_k8l5Vykz{rrtAekmM=5&s(FiAyeFx?LQjBt z`%bUQiss9<;kNt^?)=*S=G!d(UA{Ih)jXWdnf*r%H0m7r&StezDS0v8R4N47pdQTc zGy@(1_7cRUbW=!{Sk8V`2$(fZ`h@-DV59$Pw|3dP&W`*)=mit{p2vdoz!a%Dm+;|T zz=4^Jq094o4NXhO0V+~L%BuY$iq~Ut6t7_64XZnx7VWuE#^5=6*Ko;CYt~hHdsYE~ z#ROu{k>waPbm80%iyX7Z7{MQdgFjnPB$R=19asfkGEQn!Ie8Qx4H%bN^&Y408PqZT z*`L^-$~Y%PIrY`2jwIOhpyN}=0_yb_HcRh~x;#8guq2W<{m&vIeeoB1xLpKGZiifw zcWOY&YDoAsq#;&5H)ow^sTy@33+U&RiT!5FSK0g`DV4_Cp;fgNbh3F4DQis|dzP8U z?SeLt;RRFa3DPs3{Nn1IWIF28kfEqYR{_c`_0@E$dJh0b9be6)(CtUovs%tWKlCw73C_iRzus;d%cm0 zAT?+nX?KWsx{Tn*x!#tyvCzTuU$(33avq&zI`+J=s5Y&!{UgJw1lv>-5?-D*>xVcI zCT8=G;PA$`Idg_rYj!3~9j6Cz-Wby+mK0~W zF|Mp=S7F{k+J97~`0X|XPLb%~5L~Klk~#VWFMArle3tQZING(!%XcJ5PfPT51yPf< z0A$PSHoZYIKli;84pBrGz!&9~*#Z~}D9UG?ST z7Dk7$J(PhA{bED6_ga|FPk#`_1|1qYod%yc2PY zIi~yIa;UfMCXH!JZu&<>;XlI2Zx!k0~mfF#eV3X*$?R ziI~Y)t}~T%@sW4>lmHcvP{L!BdrO)HQ$N5So4Dgaf6mz3>ek$AMgoTxNw-6Ey2ZWa z5qFm?lS7Z>S)~+YXNg@lSxVUm3B3#lI=<7mWlsr{{ZBceslJ~OtJH^_b}I5labMd- zp{%Tn63E9$OCFnOi!;_okI!hwAcga$lv1l^snIp*5u+ron7qMbcu}ZI$(CPc0$%XaPn`GMWsWS2QmwWzGs}8)}Q&YaafT$+D zO<9gd$`tEJSDbNpus5Nj16!eRB;;x(kS7Vfcn7yp{oP|jM|Xt zwLIq=&+pQG4KKm@*n{s?kzFYfdX3?wgTcaJ)^hmCXe7Vh0}PxH2PPeg7nvUOn0umR z2T`KUoLrk_y1U1|8s2j$b7MyqtQ%V$2%!A*MXk_{$NYV!^^ht~qi@%KT+(`%fA>n? z9giO2OHE%8V?aYy_0H389|UBdQ#HM*d7G;c!OE9GIqI4gv*b^7mEIP8rqQc1qw;+C zZ~NG>_-vyqVIgJlpdrIC6|$q=EPYt$qDj4f?Z?Ot%NjjZq>Nd_{^Z&vu1AnN_lf7Tt~RRU zc8HlE>oWb*;ZId13yS1*z(2=@Fh5(N(D4uAOxE%X1)g;&IZd=OiX_iC>&6@!?6_!OA@_d| z>Z)s9z=gs5>g2SP1FWx@3rfkYL41ieqrJ!-Hr(t%B(rrXDg(819YgxUOHQ0=hbzVCbG)TYO+WNq{x(W2vr_x

=T zDwi7m>^KNIXciC&@~(il97U=u`^qRrANrY;j|*xH_v2FL4E#q8(_=zgX^^E`MQ0ViQx5dEB<}xLC3W=F@=F!fkxzjIJCr>8jr_ zV#|)xv_!zdAbrjKAC-~_G2WWuIueTG-!tPdvVlaZ0@+ZFbo!Na5r3QLz!OtHYr(N@ zEfLD@yibG$v{ZcE?_4S23}JUV<`t;s`&%s#gr!-)n-yXeHi6i0&3`;5SRCg;>b~nP%yO3*FW@Y->XCDvpY*B)cls)9wRLf=%SOJz5 zw@&SdjT>}Qt5c-1O>CMd+&G5f@TX(xXc#WzJOqRV|LI?3wyIlm1Hb#{W4c zczkb=v^o$=s8{>4YTM`av)IjTVnJQIg%h&Vgxp$1uVB74=Wrs-5<8?B^8r=2_h(LJ z!rZ4s-OneUjzkO} z$qfFHU0ek-59@7D{8kG(*~`Una$5S&&CNDn`Rp8)t)Cbm*Lzcdtfwd2G!nPej-dRb zYEfv;Qf$sJac~kgJWe2(;(0Dj*={;~tB3}cT_CIJ{=SQj^JCuPv6{<^a|KqEo|rit zo%O23%#+m}-ZUUw-=J~$Ha`)#bgTT)$fhX;(^s!v-lb;y@a!EG(8&J#fX2h!bB-_E zQ;%N@&g~-qt#&5NZ3|-9Uz};M8V1vfb(QI*3*_&`7|xvMt)KNfn!~j~h$!hDvjrVa z>H2+!KT}D$D*A-Ia1HzcAxawX1kKBP7dC%{1SDkhbHNL`TMT6N;|~{aveCVfd-0k! zm`&z+Kmzr|Qm7lQqJa4h7AeH@h>BU}%9{x)MtT6wOZDLwX4c4}) zh|%aai$a~8;P`+xP8IzdTD;kRbUW?;cUXVQR%3C4DvCNP|8A5J@bZ#K)Wb*27uO!= z@>VA2U37z_c{LC(ZhD$WT6lCX6gB3A9yG)%OzLU95Scf ztu)d+wL>M5CCG^HUif5n1D)(P>C99u`Dk6sJ$3y6?cP3$B*s^|rd}AgXJny}rVuN5 zk>9I&MN`dH!@c>kp;|zq?WT2MGt z{PV?g-gkS;KH1*0gA-K=Z-3rqY)rQd;yXx*eu3i2KDYk5M^4|!-%L2k&b4;;*=&2b z7!ueiA7&Rj`|_mB=^s@(CMQSX)VGSM+y9ts2>~PFcf{qmdr5DhA`j=by8>*kRq)?6 z7+&ZAA=az-rN1Ft?dpcH1pCniw@iut;!-a^jLfzTYP`*{=svQ*x9PP2fA8ACNp1^v zi@8m-*ZRIr$fX$1k_fY~SnL zcWo?!b2`s=BRzD)+S7{<6zT-)%PD7jT3li;H47SSZu=>Ml#;NQ_k(tLn0GGS9h*Fa3LVk|P~% z&~-6#>mL=4ORKAR4YTa`#A$g)cW3`3Vis=MeF%Ge%o)2hu1QaDB->Yv2^W}9auBpZTAzcw zu8V!5UUscgD=VWN_gIKL^b$Lcq#7c?RynJ(w|DxUum+p%DY^tOzk3B>72GU zqbR01{F-+I$z)fS4{HwRNp!reL`-#<;h-K{V?Vh`rJ-gI1pmi}Y!j{(3z~J39ILjc z#d+I{x4V3~WKZ=M;yGz-KTWk9&x%C6BISt+?uncxU{}TQ>wQKfg-@@OG)bJO}pJ8+Tv1|Oxy5hbjcX}qgrQ(fn*s{TMZ)rQ4uM0?FhSFYbNMt zzLuO5h1myK;%>Q6gOeuoy7k87;1H1E)8u~k!u8iv>MM;uD*E07VB@DZ0i109=l}I2 zJ-Trh=+wUZEdTbWyQnWD;do9SW&zaLaH6{*{bnfZ>jYPPzG32Um_GG?qHzvnWq%|*au5<) zVaPcBJU;z1p+Ratq2S5yxe z8$BBsbA4E7TRc%kn7!@vMhX^V$K3EL)uQ>OuUM^Dl^6e_viWJQv!>?KBG*dOf<*m> z&$djbL#KR_dz?wERyvpPbbp)gbn z`RARIx^nfm{rs8k1P~+Q*?J=r4(Z%ztLFq?)8LNIFshs-&pOB+_DSndrzG9$l)-{@R4{D1pU19*3qU%`l_RUi|pGm#dYto9A>Pr?q;*w@SAbJ>6v(g zc9FdavZ%_Z*UE-RVnxcrfZ-ndIBMZkQ|==2P{Os5<=St%ATpp+$&jKYB1@mV{VgM! zc=vbxHr`1_IVw!>2X}l5h+hN0z32nfD;jLkUHRKAk8?iugtCRZ(MK+SA(uJy-EcK- zH-Fvjd(PD~I=a|_is3_Wiafbsf2R*!jfL^p@r}Md{YTY1U_?$`@8vJ|C-~qWkt%bw zm$j$TefQR_$WnUx;kXc+cx$B6%>6y0hd-d@XDSB@8F=_V87|t2qaKYY_|NEkDB@*$ zF-_4W?$8f7{~Gg44UdiZBl6n5py=KjB{SCFtV_j@!m}FJcE-x2UgvB&miz5SFhsEQ z-#E=~Zd5!XKK`J zu$oQfzcR0;eg0j;pY2QD03|duwk%G@47`QJr|Tl@_6MiL?}y}gz9?L?5;!4D@v|qz ztAV`TMr)?e7O`~(gSi$bSu%WtT0k9#VnfTPxirLhyAF=&J?wF9p*q+HxX>HA{}=sJEkM1c#ahgx!R4!fKr|cGkibLl7P#%YL0aZJ z$XKZLOG3QuA9~@p3E!i5-Jd=Js+E7pKD~MgKw+m|j$*v~h-NzK?!s|P6gFY^wr)n% z6ag$AD;DFNL%`@emRI#<7B@~ie21aPif31xk?6y`pBQ9NANjtWxrfOXx0ZwWEQIU* z1!Hh4M$aa0qp9;B)iG;0UCMEwfXw@-dhn+p#Z2Ip& zVY-zNKLeX$h<2`ZmcH0J-5F-nT4iz*$e{pYc`G<@uoy2MjMp7tDpS6 zJ7qI+|IeD!(8gGV9`<6e;a#K8yDiBJTxkN3bfXP%*Y_!nykFEf5gol@bo|Vhj9^Rztta;31Mt{rJ z=JFSoU-aP#<5riknfJ#Bj1m-(Sx5H6xN&talAOAXRS79k+DhG}ZYpM!q^*#tpLI68 zoEN(<+MuY&?$0Z>#0g`DNV`ROn0->O;6_26^Ii+|I=1x(r+2HjJ@p)ANZQFC!M8ft zlvrmLM~G1x?IUZGBVi(^j*VX|!Uj45hbN74S6)~+`2J@h(EFpVr;4X*`5-pkf~wd0 zv(+;}CUujmv?+hy(AuxnD7YKbgk)|qpY#4OI#+$Jt1+1_N$#m-JgHoI@Rk=HAb6h{ z!sy%qjzU|x`-I*qP3%3rRfOw5Zi~UMOBjFjR-^w=`*>ZSH~eFbeGHoW%gBPR=6e5= z!sji_nCDju;PX=UeJNy>#BLAK&i*t=SwYw-HsWDWm1<$;J|D(~_q2HRxUBOyD9jL4Ar5pP)o|XxF;(!$q=dbpF7UbGbNjH~N?MB6aSqwj~N#DAv+Sb{{3X_9yLR zM4-wzL+U*jYd1D+$L5r)>|WG9L#@XN;L~sWzjk4rt~lai2DpMwiDUVP5x@Goj;1Sd z@qlSCsMTK>-#g}8IlJ-=n+)9Qw`mk*dJd}n3Of0iq--}=uXmCiO0tFtEDSKXX+#Bzpt zUGVt63(nv{CP`%-CRjL4Nn5%G{V7kJtDPfndtGFE5?S#4;{~vDjotXVd63}WbH}R3 zf-ld}??QW>SBHF_gn1%KogeTVg83ih7)+Vege`6`|{BWe5w+KZ%+e7l{qO zw7lt?8?wzm%i+&vSGF8hjeUeW#SScrY8^?HC856Vl-LgL`MeHU|5f*ZEcSJy!WdkL z{;gFj4^^pEg-BYNj${2dIK~vu~#;+Oj$qq>?*oBMB!q2wrpHoB{#N0nR~e3 zuCZ_FwI89LWK+_=PxuKsUB~uEh(R+NXI=XD$18gFt9*dk66A`fT9!vrU>4?8@ELlx%n zj+oU#LCr#5$DYPt^!;+LKI~O}hu-s9%zh;2<R^(BqaXhPtNOW(ZSrotPuN$uZE=@GKv1`T8u& z4>pbI{-e*^dac6i*K(I6v9DTcdX}vhsXOo4YkN9~Ege>I93oLks1Ai-co}>8ON>|K z7{%+#**$RGVLb0e;yR`|4E{dSVx1Q`TnD_=xi%LWd=r;A2PRk z!@RnZjuVUz^v(uF!m9u!A!x~N)uN=2wCWGuc>uIg8YVSJlH8LNgVm2*6OSDa4ds^HjSQa71s1hUGRz77C&&s1e`GA! zXI|&Fa7k=q8Q5#=a=LXm!td0W*^d3AqJN_GV7XLm6q5eBIrGb=x&>`cn(e9uqx1hz zZTZyPytGG`G+z7J=kX5T2+dQ)CHi_Gs(tm#r9LW}U zEAbc>W`1|q@Hu1O(BAJZ3m?WV+&40xIJj*jjP6^IZvy1(N-(XM!P-fVs4P=x{@X4+ zJ7i%;b4{Y6seuLCLcQ9%Np~~mXVwnrBsT)OR%}@t@ukoP6;bt}F?-C9A@SnCx$FV5 z>ZiQ*9jTHKtJju8-AKVIF=HSYF;=^k+XhLFGj=IGb}$1@w|q8EQzluNAT2`x*-x9t zB2Ku#rY}ZtVDrb9enO2EiUU($uh=B|=3sMSvvIYW$yMO=pvnRi(+o1FG|fXfUcqgt zHftnqPs_Gk!A?M+TLWLziQ~nGw_!VnqUxQc;02`&CJ%KZ(hb!aEEk*H?V|`;R;z(& z3=G=!OR>g!Jo{$}a|_967xwK@#$kq(*nwN|w(g zdoi@&+|9l0z|PEV(R3}ISrPFf0cDJeFPvR6!Kg-Fb-`vi)+g8-58I0ueL}1_925$Wb%z`vmBjuY&5g1mP$Vl zoXY02L-k6C33D*mlojhd4md6oBXo#wzog;`wxM0ci6Lg;2za4Ukea1fy9=5K((v6e<%lsSW{Ps z+46kaBmlZj8Ip!3DRne z*lWLI0i%`pPA7O84LD`CqSAfpH}TfKJI{ zCbtb%S9H^F3Q&H&vhJhMU{P}>*<_YAYP!9)cc8>(nH4EDxXOlFmTJo*`c+7~#g`wg zHMr^ise5Ko!gK!IKKn_x9(NfOwa#v^Ow8OaUtga2wR~)pX=&gC$4+9 ztW(TdlH5qU6;~^&6t$WN&{L;HFEe(P2i|=lq7OP~c)m5bHBks%?6&4@x@NsPWq*7} zk5`~thMDhx0Y4?WLAusnKh7smYiUl(x_zH?77U)DyA6yOLlbRByFtS~%ZQBs$L=U4D&G>GBtKpy0XZ zI<3;TYlFVnk1wXEqd%6L6La@~4Q; zgWC>W<5j*H-33*t8!n4JwV%6rL(*F~!WfQ}BGYz2^1lExYdikkzPE^hoBbd{EhL%D zRSTkH&pyu&X(b$DWadx9jTe*D)*SCVLRqGGmGby%DCb<~Gf6gTfDB^MztXvk14X+~ zGY@hFW`=rY)YQDOFa4_*hVC-U{+PJ*?9u--4^uH-Dwd{x3%H1{<_B`dTD(tv8vXvB z=qFpz=-6vtb&5)|-mP02%QW@BY`&f0GG>+sYr7@G`rZCh{+Sh6JJZ=tBhxm$OMgQx z`El2<2=sYl`itIzzF_)V`@Z0M5zQy-A&9HI=iIpl8|>ByLgXGO+a6E{l?Nw*l=PV6 z=z3!mdO*IA3CfUC=@5ZBOKuNtSQ~6vTj!QqndQNSX&L>aI*Dn<_0!ae7E=hE2$g$d zgi~B(MrB}lYi98N1cLtgKsuPtd zH7yjM?rky$=9FXj%IuE6%y-=D}$}=?P*Du&Dbpk=`Ex7r8*``9iV!W`^m|$BEnNhE?(1AThJN z3$#3HCvh{ZHEE-=aPj;>v7 z){-a}29%xMlOzl_liif!H;gNR1+MB!*kr8KwSx$bh?90&`ESj>mc*0Ip!1_yocc<9 zu35WoS>WA;%vo*)Ewf@=aywz|oL19l|+b<^Eo{9?!xKZx>;JuV^?Xv!rH<#}+Yh6B-^)1dV4Qy@+9(3V0eJS zP=-6tutY@8v{}Hq#ek1rlgFr{L|TDu1Is?3D5n15PR=%-?(kKVD)BT6aGI)2_&VKJ zB)%luGqU}rMA|r#+x+NZjgve5g zX3M#a)>U;)ri;bidpd=y_L+pj-f(5T+m~#){Y_+sZM;eN z`dUH(+xffqZcI;_@}^!Ha?|Cl={!F^ zqU1CO4>EritAYuLx?;nUQDnXrYY$yYI-EYvfaY8nEH(pQd^t#qM(Vv#I*q& zdKin{vmJypyPPZ>DsTFTsY6rF>s)4mp(UYgZ(lX}A61AL=7KqXuz72K+uNfm+uOr1 zdqq&mM+xHyX2Eqgw)!i)9nD`EX%q^lw6wLYt2jbaa+>_wWu)hlCxL z+N}~>I@yQK!Y#F1*SCb+7E|WSypQhUN%p7x;q&y-C3~v$r;KcmZd|{Ed-G^J_*#c; zLh~h&t8{Ouqq}b0jjFN!K{d%%eV4JrHsy!+v$xd`-LF=I5L41+ADm7&AG{apVmnlZ zPPu0XiK&I_asMD}<`Y!$EC2KFtPL;LEX|v-9fDb_5a1Rm*EY!1nW2h!l>NrgakQC& zQ|er>Y%o{kZUi~t+9In4ci%=~e@^X))@V^GY&K(AY9|vC*`2!u2z3&Kt^eMMxer4o zK$l`wV|x8}!=S1U#-5&5`Tr8~(iWCGx*VlIMpk*5FyNRpcVqvj=n zEaq1NS0_?ssHoTgwDF4@Ppv+v4t;+LlmqHNok->Q^6YZj<>(th(94ZAJyJ5oqgT}V z96yO;(bql?1;x_$z}T!V547E!A1x-ih4-ys)DuRDk=L9TaAjkv*V5_xb3Ku?u9F8` zw~oQAXsmHJsqR`8Cjxb5@Q*5Qr_m9rnujH>9(=7Kx6jK2g!qBUP&{#i8gG&8 zCq`+qr=?_`TjVN|<D_Y#)PYcutx(W__C7IrG^_$D{xoby?@(zBEUE?IZ;}{~GRQ)1E zBJsKi=8KS|O>6gK$-Lh4iE!&Bwh5+Ue9LXk=9+#SrjZ6Op5lX_u8n-B{zKPfo6{^b z(fz^Pt6MsO^o85f4PTfl=MB?NKO#tyUfVPZzG60gS8yr|Z;6qe9hBa4jH8*LEbA4$iOoR(ab;q7owqMF=NZ_Q zB7c7iT=aFxuPU#tJ3?Fs`YN?ey1nR&YpR70Vjq-`=Q%;or(5EYm7mBAf5~6TuYvTHO^rdQ`XPxT3>}8racYw8p8eM)_b0WTklXT_h zd9fZq$yQgM9$r3{HpenF9U@gG-ay-5BWwAtpSK~P2l&P8Bz7*ob7;a$&&kS^ zn656J%nWkL`%HUJMeUg35CJOF5Qp{KpBY5*=Pz*Pu&!{KI8~7@5GrRF>m`r*d&^^; zr-7HD{I^G|HYZ8BmlE;DY*toWp7SLAk-u?U)HT!XPIywovvhvvqI<4YXYr|K#E{3A zqw|X6S5t3trJY`WZ$QiZg~9gK!Ocqo(lW1{ujVUbi6{5I2{YC-yWf2Hlvz3FR)b^N zx&=TG(B!2Z{WF%a7sfP3d%KB%@RRvBL?qbJ7eD zPx9pB0BdNCzk=wg6?L(qRHnitxaA6489uo+c6;hvyJL@G*6_G-ZgWnDJdXTjuFE9g z*mprLhidePygi=)Ch@Re!AN4c3-8UzfO9%6zLY;Dt0ZsmtQUXEIkP@sbs|hB!?Y{< zASuun?Vceu;C#Ao^eu4631H&mwm zFifQzeOeWFoT|tVN9?C)&##;W?w;2u@MYGihplOfb?!${EoIK+I-%INteFIMJWn}& z<97Rk(Mwo3m#jhr4{#nQkD~l_+GAAoKT5%jF}M;!SNuS`9JW;%5u+RYq{Lw~Fnp0L z&uK)AGowFvHW~@WPS>$nJ84*jRwP|(=$O(z_L(;g=2j4tfsPK5y_W|Y#9D1emv+`M zugrF&j)kwEimC@;@*QbsZ}xMolb^tk&^f5A%*8M(P-67pGuSUnb-7-W-Woq}aFYej zGun}7b>}>ZVU&x}dCPEIQv?4^!a{pEACQ5e$uyPhAT8jy%FRmbWcL}iFZcP@;w!hKcx-6g-(tCqc+r`oMrQ72nUZ4I zvD=N!mwlKtlZ}=f{01x%SwrH)eR`C8#$3C^Otbtbp@9mxO^dj&^0@7Vl$41E-z*fq z!O)#Ie89hW_-^5II}RnukynA2Z&P_B-%X@aeaeIbGBG>V_ck{$)z0)$mM|A{wjWH@ zK!@T@&Ev=3fbm&Z@e$2(kM|g;?^!$`$O4goiwMrXp57m#X6)P#xWl4~@Dq@db{)!TUbyznc#( zQ3Y-@AJQMuA`0j-fn_Dj5czSf-w}Mbj9n{Yq%h0^!d1rdS^POD!fk8oEE1JobMXD|BjDjyE4cTbzU4K)DSt2@?(M zAxB*88tmK^n(5~%SIL)VJvjdD!O5!e%**H`6uGxESuZY?usZIasbU7PhY#&!9a5An zPu}exTf_`7m@->Rx~Az4UJ+?}vXm=Qt)KlM-bNQiP(mn^e#dW5>$onIG3U$vqiW;C zl#7Pfa99+yY$j*XZdpwoi@n?<6mj*#ck^1Yo1dLs`RZ*X=AL)) z`#<-|pQvcpjwAAK(&%(4C)>|3I;0Ta@Q@{~gbxJLtAyIEZH6q9X3`ql9m^c4F=72K zmVw7?isgGPZU+o^XqKiVJdhRne>2N#O`ysCO^NqOAQ-XXEOFwUucGVR&p*Sv0(Kww ziRJc|t9U2l)jZQ*<`#!Jiis zZKls;%G^jqYv7<1yB!p937Pb=3yiV`*Vjf&p6Qh1JA#~?y{ zc=I(%B4HkSPG@n5#NSr`q?%+x5P|R6^bTf_N_^Kz3tLIDcXD1e zAyxOFG9F@|%lOgwU_mmcLgscbdM#}zSiz`%4*deL&f{aFpH(a0p4O`*35SlHiboLl z-l#`w*ji@!9|;F>-=8ykU>R@^>(OI(WuzM+sjDWg!RB!R(bc%IP_ps1S}s- zF!4`hv~|J+*An3jTCBwwLbkhz|OfAY%VeYg9(ttt2i?Dx9Q;uIOf_DibxHs2nvnGT$lkDHFc10 z>_4hTn?=YtcnkAfS!gp^WohjEKE>%op%XJLPWl#!Y=xZn0@6Pib!46UU--DytAA85 zlY^!(%=v=_mF@WpAXSC5gd77bqJ)!=BUO%<g}n4I8;g2*aMUEpP(YZ6{5TmvwV_ zaH+sS^TFbzlrP(JY$+! z*0mfTA&IgNahv0}?ufX6KUX{|VtD{y1!tG7;*G}a_N2Qr>?cb420<-kp?!{w@$N2R zKj#neIzBKjbPe5`k)`f7G@sCe((7GpepPt^zWJ_f6k`J~W6ei5S@ zkuHeeof}J3Z<7YgDkHA`+6C}NRYsM17m)1v=13(l$cSRm6i)Z1-gshb9)X9#s{Srq zfA{i0KI-$dB>fK&#s|C~MA9$6x*An&+UZ-aY#cy+kCTw5`;swGR>sjCJ!ktX1^32& z)93+j8FjK^=))WCSKGeaj_#`Q>b-LB@~`*e-dF6u@q7Dd>?!g}(^M3^r`SLX2N#q< z;pkeuThM$J)tp7vrsGnTyNa!XAuK~AO8YEevpWeAuVcOVLmRjbrT!dJe28$VU0#r1 z48ON1J@=ctKLSyBCT=N7qJ-GC-=Vj<&8OIWHanpg%voFxJoJLW7d$!1XAflMyMn9Fi)8k>PKt)d zHg%6YyE0RVVZLk{2F47Qai#+A^g-*E!)}!wED&Y;$CpL?@?*><+5D zJ}LXhb31<0p_Q<ACxBVj#`)Waku2n;dCb?8+|*Oo7(A7>)Dg?4RRP8vXGN~$d5 ztu;2ebNdV(UxkzFnz~7xc_g~~u1jUGTc$_=^?N>W$i5M?o2XuD0bykSMT&v=#Z+N-2 zuyO3YlM_PI+mdSEvs$F^z#={cQe+~+=hEzyi-(`P9x5tsLEx;iYn&m9Ux;J=Z37XS zV9ATc!(ms_g^AA#Eqgcn?lM!Bq5VEM(@GgQv1RJ>9grwoJ= z5KRGjUfjY?{LaI)2|x{Pibzn;+X^k=Z8g|ZzdQTpfLukcD|b&qz^#bI+ipHz9@rR) zV%`Z#AKrI&ols&8o&;g{p8S5VZ_sm^xU6(v#M$_swK`Ku^yP)m-dhu%ew@w;#$oUG z#>3#|torvLycI+2Iy6F8^RER1l2B2S(RC^*AFm-$te@Ih6!CHlQ+?+iVcDvO6Y{2u z)BK3L6DTScpuMmPr@@8C6CbQ!%etJawHZfD1jkMmekeN@T4b*l1b;S@M(e{#0T7KB zcW4eQVA|fq&s}xuUM)TtjaAUs@p1f8#oEGnUE>(`wr%Diy{QjDwN8}pTwnY9mh#DM z32dqpi>?TLu<-8ic#!Aok(ZT0JJsV@(Z!qubm4ey;KO#Cp+^!Y<}%MUTT+XqPi{X@ zQ;!EE`!6;B$I)2^wZU~;n6^L-cc;ZQ6nAKmV8z{wySt`_ONypwfZ!e|Zbd_o;@SX3 zg1h^B^WB-uvY~PRn`Gp+QlPAr}*i3J+ zHVW$dc7q40OiCmfHXR(zz_qnaG;(5RR zep_oS`GsNs8uKJ7+KMf}i($F43cVJqfbN>B_u8t%6u95%I2su?OTV&8=;`l$4GEwp5x@o8j~ zX%=WzX{NvzjDMx@orz0oE8$!=a1}n?9ejSe30ex%UiFgIXEYs7q=pYOn6Gl2B12Ym z(Pm2O(ga;1Q1(N$biQSot*qg(CJ>=z_xiY7tQBu${U}(avK%zX8k!hcQc`u)QyqhM~aesTYbBVwp$;Wp$aXDEiX}C#wDZ)+hgrj%5bsMekV6R&_ z%?p6Y1Q`N&ypdhwb%05!qea}Zop!#8*n4A?=YLpRrytu#cNMxcp`PTtKp0!lkvJ0h zSYn7+gcKe3`5rr|=_iZ*hXts^Y$&x?<0Wkt=vID>8fNtWGEwf*z~f`S#rU`9&u{3v z2%(VR8w5R61V(@}DJl{kdB?h15gAAtwOHBO>1LpK#@_Tu2L3bNEyIqmDe3plb*=4Y z94!oQ=#FB5V!yN22jej(zFy_}4=b5H>+(e0W^`_B*r|9|#7AH_(=7+@=+bplvuray z@*i@XU*3D6*f@Q}w~-Klt{wQh;3`b5CvA@+)~;ZIPquP1=>hGKOKIEIlsodf~o11UooOu;9rp-CCrH@4nMVnW@6)QJ`H`A-u%6SN7IEtzf? z*R3z<^ZPO5sjeY&Usf}{GiEwWnq8CW!n~XGRY}tnL-X{V-85Gt8B8luOu{;RiH!%q z{$iDk^XzH2ZNW2=o}ACoR4$k+sjgAu7uzTMB8FC|*JM9;)yWokzFx4ACtY#Y`ruJk z#&h$v37XPot>V#8Xt(#>Wu&}F4(SSl4DAuS;yq?j+mYuCuS3hMmK#;4Z<@y22AhNMlzPWgQ}%9!SqOii^4$wvlx#?*kCt_o3^xINV2>2of6id^Sa3=o^htZWvf9MAjfQ_%>zXH_dSIn3 zFKlI3NEdsw*`}3(#>WCr2r1g1KC*4ITwU)A?r{njk> z51XHf(9c%4mi<8c45wc^vIxFD??AQ`C>N5in*g$u8*y}A_S}?UkB&u3O@wA@(;1lK2&>)B}s-xbQJ6{8+`7W5%33$;vbMb zs15x8$U0?uw{B)Z&ZO;)r9%05a`;sKoj!DyM4Wh#Zk&nD z7Tqb2!WKy&zr`wV8g9@>Z)<=3sslaedY}Z)C2Tgww_FH-m^}xVeRazMGBr0Ax>rYY z*(cW=2#3NIZ-T1AGw-OoH?DPb)n-!IE%T4of;{RIM3?Rv^W*eKy&Xz5;uuUm6~6dh zpuOH6l=qjQji!kLj*;W*4jtAcj9h$;f89{RSj<4%BLRPEC;^?ixH4CAXao=SRve2- zHp@C+>DA7Sl!0A{-Mos7MS&kJ+eR#ESP|V-R=}M{a?R6MV4^~~%5#Yvjj{hkb#wG%_5(E=@D7av{nKO-;V$GPew2nf)2x!z7B|;*JU@x+qgkV z*IKgAP1;ZIgUky5!&-B&=(u41d+oD676zJvT}l>&$|KAqf+z*1+A~`~z4To4Q zdk&as?J{g)xjt^s%)dX1;YHVxC`R8qh8=MK+qw}ALBxT>kx4#^*{CE{^#F-KBJtwz zPX9jwzecf53WVOag!6>p0|UU}5wQi9VnvK8B6>_DAf1?W4MjsupU`5S-zbX#ltiLh zJ)Vi+o-l)fxGw5w6aj!)lCNd|NPTmAA(dOBb*g@3JH3^zB5KF4a!G$xxJB_Ps!Fgb zQU8_rbw)X zs~i@M24H02Q-b;DwG3hYm1%^#LB2t_MOvn!i3SYeorM_RWMBb}7m1ZMNfz#u66QPo88{ zhLUo3EggDZQ^;xv&u?FMarOQ_y;rz-)NGnL9`ibJ``A)Hq}iUu2Pyd=8!X^{$}Qye z(%X^YK^wX$^Bg#x+^uk?|X5`?6#rPFUekd>qLr8RPV+D}+e~V{(CPgtX1n z%ra2*)Lw(4y8Zj0yM7!n6`VM=C_0cgv1NhKbD|G4Ulg%i{(6pc5I$MYp`G#)+huAT zqk&wdkDbBB`j3vo82eipJCEasxK1%Gzu_HYnIDcmo(2V7o?ln@BaIB#u!9NGw_Y8Q zFzVc^78>HTgi@9cHSUnB}jSoM6;C>;R|jqBjGZV$}Y_s#5ZJev0t;PzhNI{^#^#6yN?TXvL|yGb>)bebZoP$v)wF=K-N%wsD5qvj`rQUTHX!6 zG16?%Mg`1iD2J-`+P2T>>=9I9@9NfzN?Ax90`~iGBs;c(bjk)%b_O5I`FFjAGc16I zqrpg%c?8v&tWR*f*1%s>gVMjhc$`Wb9=yi5V(Dzdxni;Zpz_+W#fpM|OH74^X}ORw zcQoog4UZ*Ze>C)UBqc_|A&pzyLSg2jqLkFzoLVNRRL9?W`0sz{7}3J#6SQ6{V8X_4 zv9gkp3U4samNAiW5BmiN z3$`r}@KyYqyf6RD%6*8S!i{Bks?bWzs@rYsss%S6P|(Ktp7S+Nh3q}sYOR0~9)9;o zO=*awb%?sCM*e-$n`{hE`c!SX?VGQY(V*T=f}-}@7oP+3lTklR3CW18qm=cc@>sM^ z-p6BJPS+-;NiA{lniGMGDSLwb{#)ZCA?zr$?C-b^2K7B8?ZQiY>1@dB_HD=iMM5cy zTQV zA-|z;?SfE0#8t!~ceOq^3O-dG!ELqQ%Fo35DSAS>h6&48!*Cu;PH0Yt=>7Z)tW>i2 zg-_Fs!f_lvZ(-zk1xHq=9}u-2_)I9lvQU~db$7_dC;!}mcxnhIf#xzLBQi6mvK@||0h^lzeqns1S7Pn27{7#2cTUvZ zgfghelx`n$xI=A5!%DU)jl3?s4FW^%!axIAC~%H^=$CatHDH>%y6i<2dFz z#o!=5hU|SevbIsc|HHHQ^7>dTkQrUQ(5Aj%#_dP$EHZtYl+CE|+j1qy$?UhW@m_r# zpPnnwLYRhy3I+q_-7X~Emfr8G3!YqQ3BEMfWCfd*J-s)r`xTcz-S1RSx}We9tqu~z z1r#^?DR0?$O%5DDfTg36H^wm9BKXj+kR?X0zW=boF!IHP>JpT1rhn}ufH(ov z=(@N1XtXnP;@5@a0&1gu&^`&5=yE7}#K_6u#=vA5hi_uw);@Gszu;QCQ%OnpNlMLz z2lxt{kLViMxh33BA+>bKrhu#=L~l1T4o=oPz^s>=jF^l=`%6qxs_Q?j!ZDW@m>*gs z8e?@i@i`CmRC(%ZDA4k;C*7-F#>@+X7;n_M;mS@3BhL){c=ImHtYZk3!ejSmIHAbb z=Yn(z){rq-=yhTA;EF2d*N_@~hZu5BWR-7Md0V;8ESKr6$fC`x&DGcq$M&w?0(wr$ zslVju=i?6(j46#M_Pz*qw@3LWjpy3P7+(lgizurC3QKkKlNJx`U6a%b6w~yyScD3v z7Rc3Dl3VBV3t5u%8hm$+HlV#vXKcE3U3PJPam49IV7M32!vK-SY|G6jZ-$`2pN=@S zBr%q6}b{hJo1T-){2 zi=ICIH`dxupQwJ7!yzI1Ou~f2&9vGYl}9vT@P0yZoIA?I4z54|*_L=8_W_@vud0;d z-IF)1tY6ehuxKRH>6cgCaderi9BR6G!0_3Z-Fk#(#(KI%=yEEml@C<5C+1$k z^ADD;p<_N`^h^Jjj_RLCunI?=X$6~vR*J8Y;fn^vB-5m#B>8csI3{B5)dZqKsysZc z?Py6HjM@-U*Ic;Jgl#b3X9LV4M>2ei{8x@-oyz|+VYBI*wD4`?YitN*M%j{+?!%L@ zQ-`ga=RY3_TG0m~$bAhTS15 zYr+SLrN};ca>8lH!77PuiDz6+GNqg|bQYZXGrPj`cCqe6n$szg#Of?<+J`w(O#~VC z;$-nTG0B2p z!>1C(3obzYtavQ)isKSmMQZx!IV*3in`R!Xq0%V+ND8h&oq}>bC~f+3=iyLyP~^lh zA=&2LSp3CVn-+xWJ~3=Xqf`7YN8>fkz`_}(-Sp9cI8x-&6sk1N3RdF`Wn?{R^n)bW zI;{W@;F_kzdjKdTuE_Amrq|ALzQW!Px$*C{l&zVu_53cv&gHJtu=`Lkm^yycK%x$rAfoC*f3%A*5msjJ(h#Ghh&-9h| z>kj27TZCPFrZ@*LF`52cO^U6QmbBfqedk!7a!QiYLnBXrV{la#e+Q%`j(no#bpwXQ zKyDNMeAmg>zSIv!AhNDM{g<%Edsn3X%ChCml4$)j)TPqAIA8dtpHV$_9%D?vB)w&r zC+*c-n}hF*eUDcHF}H@+5m3P@FA9E9F>s^sOe|UK*%gR?D{^IDkmk0DQMf&?zBVtUZ zPgo{kVK$i;^LLhxVumhCQH;;@h*fYD4aE!<4?L-{Xr>I?l`1l+zkd9z1~InERihUB z!%{^WZuLe9I)mTOT=Fw@Sb{UJVT$hYnb~}q+bcM3Z?_T!?iCEFfsJ7w#5t-)O-7|= zMK^>;9`SS$!i0vFU;DJvLyXgXc!tW_wjEMkcc=j$!Emz-hd0BF}5;9boK8SUu!DPDqN*?rr`2tkCHM7D{&52f!f zg-W_%6hBiDw!Ql2mpEKZaR>L2PnlRW3~1hP8owkOe@53*V;{-1|Gq#Dm*evUliDk0 zIVqy(z>erRrp6mUELW7=e1woTPt5qVgC3EMl__2$4XM{pM=~MBu&5HzFRGLJGQ-TPgkG_Wd0tyU*5?=wZ@ z_n;!pQv67%F`p_}|0s*y)cS>+l8Z`=oGhDWag~sPm}?VYGaSujiaUyow{!{05YI3a zjxbh?)gR9uQ6EtK%?YpWlV>p_Y}Tn`t({S{!&UvAhG|nz!za?x;TGzBqrho|?d9m0 zMs909v^|;ZSndg1KIOtsI+(^${E_6#Hqr*B*2ZmyXJ~L5d)xMN$9j0TtQUC!9{&Al zp_+lm>S(zdriJfujSBynIpi`e7wSPL>--wmQ}b;#yN&T)8~7`63nJXz><`tcv?0~ZR!AAz z^$r2PH^-9_HH}i!HcL*xG)mBZkyU8;dJYY4BSrUeGC1f0LQlgn#j6=X!Qu~u{M_Ck z-L7>_{}vGBXc|5B@A~GfhdW>-eE1lca%e%i8t7!wgOL{mPYu8NdKeG*2EL`;8cMp8 z)r=K;x86^#{oRKAhPfk@RB40vO)E~4+TiCCAfnFLcd%$x(YqV)H*=r!moR^V4Wzcc z%3t(R*^o?_e`rm@aZf17)6SrTqUIj_Q;n?FA(tn%R`=-IBW129LmQZUyA_>D~ z_J7_ojFDdwOr)X~?K6K#;A4#Oc4^%YEMTkX&A=&*hH%Q+byYM~CH(OmbYLGEAQ>|^ zHFAvCKEJ9_c{7&a>+(ECEcaC@I@}htW|}+KD_%o$CC=!yXfo$047bDt=L;Wgrfx+1 zk7h9b-Pbh%(1V#f?75nAhv*&JhhkpKjNuawrAIFrh}6jS)_k$uxA>DK(gh9vQL4K_ z%oukD+cQ`I^9iDBq@lDy)M$^=_T`O*$av*Jccj8T4VLn|dj(stmXMq?_lA=#(0$uJ z<^S<+ z2`_qw+VL%6|E|Q@de?B;p_qjprs>NnO*--XxZf8T)a?Q9`o<{woQ>L0o~2;LX523F zft=dUS(>XeQsU=|v`dU|lRV4RrbLULrJh}?O&Ebet4)rOHegFGa3YIM$TA~7g{!Kx zi{;~K^M$a4rgNQw>IDTd2GB;Smu!mL$ddNvl7^M!HZpp9_yc1;t3IYR)h?ai(Ej5> z5g?05q=ZW~Nr-CKh2?fZ!KR~L&)a(~wT;y-67Ch+8Qvgw@E#o)Q%Uo}S|b;@@gG*J z>m)lwmwk34=szqf=bHv&oe=p;mq!PSumzeEyDqNN;FzEcw8b6cr(?FbThVW8`nrQH zg`r)&CX_X6^H!{0nwggJ`@y!W(7Ogjufj+W6wgOzcUT@Rm7|Qzn z#KxHJ=?6FTr&Tt;hrl8)yj?I=0y=kD4|>-adYqGti5^>*CiOp`-G#p4jJtG1G_o7$ z;mmrdMn>@m{ zosTi1g;j%(KBQOKvmg4HFt1dwC1(2tg5n$OF}A5NI%myN9U4hz&oCMru4^%;IUqt8 za>5U5GQi&6;8~zl8NT2#$*w4j4)z_N_OYr&E_cbz@3G!<#8sV`rYlmxcikRI&Da(f zSzrpxwL9cW%;rCrT^>m#CYK^P<7-fL0^z^K6gLCL;BO7 ze@4vv#no*u4~KZ}6U&}6BghsjmVqVS9G{B6fW@Ts>ANc-`PXSi6MDJ~iPhkUo3a*F z6=u1Am{B4TnAC&r?7t0FdC+M4H&kT@$`2=?#{(s5D2JHGFY-{VZSQdG8`C*+a+Fgm zBny`7;TD<>G3Yv$y}0K&lHmVgU(-vn;bgG)`^fWv5{xB@s&&I ztt^GZaFVcSQ_H{RJ+Cz<4@+I8*Seda4X^6;7>fVI`6hSpvmuD-xs#6NO0g5!VNk-k9ibrGTonry zmRrDp#`8oNWdlt5HgTD=Qbua}Mv9#!1nCWBk8NSNI^fegBH-R@lM=z-0LvafJYV(6 zcCO}^QD=%h^rSeT*N~K6#r8QtWU4UFU7v}Ef-#eC`_Eg*ydj>+7`5YHi)_tNP_nEJ za;a(hI_hy0#qV=M?+d&3s&slVzM`hB$x?YMH_wy#_J!P6TAbwHA*``E5no8^p=%MCKs-NQ>ijFEH@OJ!hbLs>;8Dqgy@flR;8EIT6XeheZ3)YF zq|1>vjScpHbn!Si-qX|`-`5+m4h6s>iS(&zO6kLu!a)q0O$_aS z&o||x))LRm_M3*jlLI-K6|%T8CcVUOeL74=S>aG7)Qm_5P|^MFm8Pq)&Hl&@lWX?J z8xryPDFWr}CF@XxC69(XsBdBnDJ|iN-iQl}KaG>ngVrYZfrW!@(pYrGS|v`qY0J5C zbJ)i-tA+CCYyjnXO%j>S2r}BED-Tc`j*Boxwlnsh-(g`kN0_OCk;CY6qUm_je|3N@Ed zCJOs;x<3*sMe%lk)UWs$q#l>14)^1Hzx0z&xK@mh1$x#9070ad&wf?6>vS~Ip1KULWYgJ z<<){O%E5I&NkXd6@WfuAOCPtUOA%19tIG2Lslr&GQL!$O>WHD#9YPN~6DqkyCCPwfv#?5vT zm6Iv%5U3+529&TDOrl=KM6*$Fr8(Tlm5=HiLSN6 zL<3lV&>n=6$FO@t!1>fxEmys0!Whctq2@LPG-Qw+kk~nqB|{^{#gPEhONmgxD>1V+ z1{Vs=_7m3|on>8V8RM|Ok*ezFF<|DIf4M7sCj%8nbk<&NT7_P|J3entq{g)Syf@t1 zQb3STHsKbTx)6BJnC3(v#=ex$yOtq-;okbz*VB8H(YhFQrmC4g`OhSvbf$+`y+t+Y zXw89d_)!TY%Ud%8waONE48@P*Nz>F#)@?d)7)N8@x_e7W=bH)kq9lQ7JVs1iA_;rU zU~e&=bk_N*wfyxo=`8x8k=W3>AiIS7tTG*Zi~Re)1AV)aLp6C zF~VJOxMGQu_GSAc;kbRjluxc5rtkycUWQ@+Bpru|(4iO;oSWUtXWal!)&WZZ=&<)P z&lcyH1&Z%iE-jUpUFIwJo|iD+5pUO{?lz-C=0#uo+g^duWwXF#JjjeH1N4T?>)xv1 zG5PpV<%5Nr-#Mv(O_n(79kkL!o;L!f(7ijH(6%? zl4SMPjY*9{46#+ppqIuCt6?BK7_JdaD*h*ySEGeO-zRuYuJ+ROCvx6p()~64((&gk zhOWlHPGhQMyjo{|dadw^a~L~ml3!otjvSc;x9zu0;miVLD8x6A4;F{LF4UEYG~mb- zw2i4&E^tg2LL~VgdNn8Xa=YX&A?Z6c49O8ADOciGw5vnLVe(SxLnZiwjZ5{&IX+F{ zVu6M(1H(+`cW$Y+Grc74Q@7bU?lpk?2F8yX>UCajIzG+<^Be2m(k%iGeJyg>viyIa zaO5*_r>l5Rq{yhSPEVw(7>`YlIVSd^KsWbq^9rxKt8$ zDj8`1K*xoSCD?eBgepz#tj1w`^|NA*^p2#(6)+>?L6`82ANx6Sh)aT-uOniZst|)RBO5WPQjK*I^4UY4 zI0N0}OMp%A7Wf7wyP-D5(Wt(6KQGJ;%|-g!tr1J)GcYji8bIS8z=O3!<1oiHqyK>;nBNI zz$c!>mc!1Q-B9ht=|oc~x(b-SCf{Lbe8EXbY^c4~giQspiW2(qBcVP#g|W<-lAeLS z#5+}|eqwbXABRTJvx<*Jd~w-gOOeI@WaJXP(WdVmmD-j{=4++IDgL??|A~BzxLPUM z=kgd+OkR^lm6cE-KQcK+eu9I>gw<7KTJ>owE5SI&Tj2Y=apM2+P~>pG)eWDHr>)Qgr_d?Q_JX*=y`n)`r3XXN*pAeF434hW28&gPs$vL?pE<-0u z-Lk4m|lUGO^Jw4Hn)ZW6NViRx9fFZ8>DaQr<;U$ncn9J zN3kb3m4I1FSX;V-^lWc(m@5#%U}i{0O0bkdz3uewvKVq=vqM@6;iKK>xu%)vV)Lc) zgn|b?7Nx%H73X$Gw)aj$Y9g&^C}>oM9ZXQ}=8?tXRdZO>k{i5u5SZ)&U%l7R^{!eN zKS{4S45j4KtaKvny$<3>xQ$6(rd6#_SlHko&EF2L*@yd{Zy9#Q(t*Q>ilB!DsEI%`d&-9lvm;Z>WqnIX(?-Y zp5H6=KQ0E!Pn;Z3()2QznKW05S3GPO%v~6Ct;&otL_HrsQDcnp_|$ViI? zrUThCOQ708r@PFDo_ZxVt}uqtPzHydVCcEzfm)PZ*2cum7_QRa!O?~XvNBAP!}Xs8 zgc7}Rz7dD^3cu20UnC?jsip^;<9PROBP|cnE02t~xh{9XVTAZMV{zx`qWayO*HSsj z^QTY;vtWxi#~%1|XsAe$&8aZsW0Q-Iz4FRHAZguu4fiXD)TWIgO%@b)(>sHAS9s zahRIz&}P%SX+x&6stn)QjcCqf&P*W{@}akWV4jaOBLS2Sx&jTS*0bKFZ4NSB2h|oK z+60DP;u%?;)rpA$7nbskMmX26#~qhQfMD*n?Ce1h!q(Cq{B0RVAPkWY!>$L+u)lV%WZ zWICXPE5&ldFAz6T!j%wU691OLNhGktT_rH3Uq{^nPcv8lz91mw`jO^j41DN%Z29W0 zIAUw0%Oi8+s49dZoqyi3AIPaxuq|a1hIci)r05mBM}H|~)Ax`-ReP6xKETKu@Ot29 zV5A?|aVCS`h4;`mhczKwHB4&{+a>SE7{#T1sidipU%a89WpBNdyNUlw_vVH6XspMd zZ*kHncRuSX4Jbh|f%qpVa=42TS!VGptIOKQ<1|1l>gfhDIA}U7!va7}=ZtO#3!V6J z2X6vNAPU2)QA_lMZNd|;j+?9F55xzIr$s1#%peaH6Yj`ty_oEqz*%t9Zgbq9h3}S< zowJCghdJX4gwu+JAzHnx)?iYTZ@>-~0MN1OQX*Jc&o#Z$8SzUAuJhNbG&gnI*Ps=j zAyWU7WNaftOsUoSxN>^+7te{8BzY5lj(vf7ii9N24BXa$LS@H_@P38(aJ7OjFZPYe z)ScXODQ@YPX$y@7sv6Bdnn;Oan9-6?`y)(HbELWz30hztC*Ojhr+UH+;MJ}Fr_TP< zi;;gCiQ`2P$MQvye4GQGr}bi7gvXKWsjDi(7loJaX}-xnCHXpo^~nT-p2Eh*`t+9L z3l-K(L-IEi%m6QYX?QwOhI5FotPMA0p?(1@RMpY?L!Uc_V!%W=#nZ^`i75U!58gB0 zBRin$^_!{lL#KS(#$Dw^icr$;MP6bkpguKVt9B$cZ%Qg4x`tA)y2QdAZqt8aq^jZ0 z+c+_Nj8Q81$&=XK6YiCS(#0iu?4Q z6?9aN@WcA)e^?7$I1s86nQzJkXzGnP$W;jR*Si6+b*c}+Z(6K7ISy7VRu~j5{cP_l zJ4P#Zg^UyUqYmS_fgKCABDk{61LmqFy^xm4I9qtJxWEKQ9zva}zKkW43z>lb5n~32 z0fnimzqWrQ%xrp_;KEe((}sI@gtKAVJ>XE$ebZvKp3eK-O=bB41=&a(GqwFQ{k)9! zqtBI9Kb$&y#Dim{5c>0m?4O*sR9=eTg)4GzB)_bQekk&UbhjH^G+PZ9&MoUrE($(i zbYS#Nio(h6uc`ht&h=r+m+VV|JDn2$Ks(Q)8fc7^9y}NiejRm5g@n6!j9iaBoiQv3 z&nTWwIWPywgCPkRcTxxfc1N{F`md8^Eu4C0Y$EIO)=73b)$o3;>zL7Db2$rjf49aH zbbdPFwanPq7G;~LFn1)Mxp$9&v|&)2x$IGKo}(gdY8Jo}nn6hYrSMwYyZc;``}N{e zR#eqSie12`gXujm|IJTEoyrUtj=OSymeFEqE3m+nw$47D+3nD3+C@A~(bX;$mD2>$ zHovDG5HibZdqy#MMgAmqfR&Wo>_@WVq@0RQ6Fjqi5kgYNQq?4HKix~89cIzeA{;^| zaXNT_h@DL^D4?3?o^?i{n&xS8TGM5P0QoCb;JtpZlU*^q!7e&nk;CFy?_19DC3&Bpp4*sheU^v zUp~2N{!;8=1U_wLmwQ$-VpkHG=Dz-oK_gNNcEeOneBYY#SEu}V4odbD?@f)H4_A?! zzzHj;I(RrXcH7axo_e!#aIGT0QF&DC=-B#Kem}p3u;R2T`=HkOu6Z2)_6-c~FBnP} zTGfbYo~Luo^x%Ps@_bsceq=8HZdYF)Q9dJ;m@+#%RWs$<900_gCk{tj1Xa&>TichD9R8=t* zpVJc4dwbq0JAL0Z`f(C_NfT49Jh0##t*4}BRa}8NN)_>O2+3Yu^C)NjeC&e|7aM10ryXM(CZQ!c$# za!u7lu5+cEHl-QKOjWMLvT0wBB7|yV8#gUF|5$#y`#AF-7VrVG?YpaPH#_tWld<&U z9ZU1Xql23=^d7XCZ=Q6L_b_3ki@Zs>xnEmtk1BKk@)&uItiLYeH!fYVQY(vqCWsnX zjq>`+;oH=}!u&~i+3xl9iHGCW42f5ef1FhSTcvl@MbkoZ0^-q-i#X^ z{Cw=1r3n8cmB@3K>yrke`jm}Z!v+tN%s2SgX$Z%PCv6czN-%4|;^Kt%#e`VRh zcr%AUuKRX^@aHzich`}ny|Mt6yUPcS*<#WetA2=DlFb^8apkQO2HiM!4^_GeVF-JW z$wl6^Am$y?`Au8RKejaFd@3n_qtf?fgn|FE76-wr1^3_T+d~AAYy&HXmLsbf=O_T`kryv%gh9ycO zp@Ata!HFVG(SPqv=?)Cw8*U4uW2J5qA-Nj&vmIuE8?MvNH#I)c(rM8yA2zd7^N$%m zD?W*>HU=NFmquDj_VpTM{vmS=22%~o(wH+c+JrW1-*+0PT&TC2h;iq&q_#rY24 zkJ+!pg|U7ak4F)hPtlmKCxIl@t49~2U_0?Cy-R;{G}vRxT65p!ADxW)*{B)1<378K zWS4cIxll|dQS-35!?=VoeDEMJC0d5G7xqoHrC|}eunzV+b@&%5BE=`K8+x;~JDl`* zhWY#@_UOekgzVxdqSWw=tYK7K%A<4>DZASJe&yP9Rx{(avRb^LL`P$d6U{%^~! z6))ym^h2L@f^Tqar`PzrRmvo=bnUD1bU~F{3)B3BlJO1+a~zo^n7&{!mQJ+@_m(*z z<&Y=!Qzt<{aiNcZQre+GVRdX^WW{BbVye8hT6nP?e=Fa#Nmg|m)oPMV`~-DzY_$i; zxSH@VUDKtQ__19t`(`(6LHaR5{2hYHS@lm?;CbL)0Nh^2Ni`XD;4G#gZo8S#A4=nU zOBX1M7jVTtmblw;tB$u>ZOWHY6sJNpkSr`uW8TR3-B7;rr$E?@Of*_F_IOvRLQX=34TQqbm*Ge>W1%7$T@Pl-@?@DG$YuChTqJ~)s)UkXFjkI z=hldo6^)4 zFLAq>A{=SsZ(k9=K-$**z#_th<520a$`O5ea{k25)$oJrJB~LR9Z#`|UShn2cwAI? zZUIbuqhI>33NpB)7f-DPUfb3&Ve(&=-A$Oq>Y?|fRs2mbDb0I>TN6)a=GMumPNKM?em%lD_h|V~ahK#U zXA51JUKjCp3Uk`!su#Ocq2ry{IKp_Ho(X#436+A@X)HiZDHdjqE4vD=Md{Znro^1? zD?uw5_EmPgW#jrc#PzrJT)>*yhmQKK6mVa#(hZB-jJ=5lb+We#D=E19P9!mAk6o=X))E%qYjl>WpDfBNK@as6W7ny`jvQoc$q*=)F+bsA2+G~#KBTf(Nh${ zsXa~!b`-`unt6Trwm6^jr}E|tpX_JF*`hudV{%Wpwe#s}PxeKdW0HS2BroV$!Zz%G z4_Bp)GJPMIRR;zDqGUzjN{$n@Y9?DrA4J*gM=Q;KHFXx#Wn^bHE^>v52%p$kXdb-& zKBgacYp6y$7Ac&`zb6$2MUS6lvzv}3=(ft_gzrdR-Ry==^|kXJ1K8;n1G}0XAo>0X z_E~mWKClA@>m0P(MniA&?;dEf@+hx8Ot0s0Eb&(qJ#lXcKbTH2q{v)Yypaj$z2HY; z7f!`3l#K5m1KvI`rZ5stYd+{`{AywO539oCAshN1R_`sQ&T&Ha#^wY1s!3RPp`@<||lVjCdc zmZ;F;$886<;yb!go!tagfnmYApwa4L*U>Xqea`yA%wF3D@@YrgMCJYMO=RQ1Kw(a? zMsw;cvM|<;sCdNyH-lZQJoB1`f5k?DKeP7Jra8U|Fx1G@4~P=e3!&k6y4)Tm>OZzV zpA{6F8z*!I{7GeQ`KB$t5pKZnfDlww3f>=PkllrK+|_pk1}YJz!?Y&9GlR5_a|omX zi~??QQthLish$n3Q3zqwfg$1VJvvaLW#6bDsAx0z(t@6PS2#ng2_r~R>)U+87<3q| zJ9+yaq~N{}iScViG!;su(VmqlX4kBv59vX7X;ogQXrC;PJZ9PC%9C8W>=x^FzNBCC zrw++R1si`DE=*verqUgwi+0JN2-y)gb^>j~EDS3;X&Mm&6rMlo>l>de8Q$G>j*@Hc zYvtHRuF+uY(z6X0vnYYJC73w5xp={AyKV!?F=IL_`Nh=IEZy#AsTsX%C{?k14#h+B zewh<=i_OY*;DLqHFi*>Y+CpylrG(;wFiG}bc)Dc@wzsLpNE6*v$#mb2Ih`>oSTG!_ zmv!MMb{nY1tVZLyvm=zTDNG?kS@kCjU?rwo6)DZl^Pk7lfyn~lwG>v z>E=DsGG7fNj4QW1cie#I!R;UodK!fJt9{OWU+dg~{Wt0YF60;ULKVF6*tkn0PpJHNDwVy?ZU$ziGZBpgD5OfyW&7oly2E^MRxCeK% zA1dUnH4*Pu?%DOeRD!+Rnrd!K$ei^`9~6u;SL9;%Mg=Eo+)*F4cEp>E0;hAA*M(5N z^?PKHHNBum*3uvcZQs~>XSy7AZGjDl`RLgnLHBz5a`DB8>213ZDxdz~)*NcD3#|)R z=M%5vz*1P(}@{ zL)GU`%Io?m&7URcUIStx%d54M0Tr)fT|UJYZ2Pe(JwJYBMZtNW&VFhiu&>C5o4U`L zF})NuYDeRmmC6(2=Pxk?^#s%!n`B-Q3Ow1De$@hL9%gTO_M>K0u00O*y6x3a`?ONZ z!WUmmuncQBNltWrY_roXe(^q04CP_n1K;x=<_`JExQ3d}uyA!YtuD@