From 26f97cfd17a331e6eaab8a0ec55a2ed35f88c2b2 Mon Sep 17 00:00:00 2001 From: Remi Date: Thu, 3 Oct 2024 17:05:23 +0200 Subject: [PATCH 01/29] Enable CI for robot devices with mocked versions (#398) Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- .github/workflows/test.yml | 3 +- lerobot/__init__.py | 13 ++ lerobot/common/datasets/compute_stats.py | 2 +- .../robot_devices/cameras/intelrealsense.py | 99 +++++++++-- .../common/robot_devices/cameras/opencv.py | 123 ++++++++----- .../common/robot_devices/motors/dynamixel.py | 61 +++++-- lerobot/scripts/control_robot.py | 78 +++++---- poetry.lock | 7 +- pyproject.toml | 3 +- tests/conftest.py | 81 ++++++++- tests/mock_cv2.py | 66 +++++++ tests/mock_dynamixel_sdk.py | 87 ++++++++++ tests/mock_pyrealsense2.py | 134 ++++++++++++++ tests/test_cameras.py | 76 ++++---- tests/test_control_robot.py | 144 +++++++++++++--- tests/test_motors.py | 72 ++++---- tests/test_robots.py | 78 +++++---- tests/utils.py | 163 +++++++++++++++++- 18 files changed, 1053 insertions(+), 237 deletions(-) create mode 100644 tests/mock_cv2.py create mode 100644 tests/mock_dynamixel_sdk.py create mode 100644 tests/mock_pyrealsense2.py diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 038b44582..953b1e4c3 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -11,6 +11,7 @@ on: - ".github/**" - "poetry.lock" - "Makefile" + - ".cache/**" push: branches: - main @@ -21,6 +22,7 @@ on: - ".github/**" - "poetry.lock" - "Makefile" + - ".cache/**" jobs: pytest: @@ -60,7 +62,6 @@ jobs: -W ignore::UserWarning:gymnasium.utils.env_checker:247 \ && rm -rf tests/outputs outputs - pytest-minimal: name: Pytest (minimal install) runs-on: ubuntu-latest diff --git a/lerobot/__init__.py b/lerobot/__init__.py index aeae31008..851383dd9 100644 --- a/lerobot/__init__.py +++ b/lerobot/__init__.py @@ -28,6 +28,8 @@ print(lerobot.available_policies) print(lerobot.available_policies_per_env) print(lerobot.available_robots) + print(lerobot.available_cameras) + print(lerobot.available_motors) ``` When implementing a new dataset loadable with LeRobotDataset follow these steps: @@ -198,6 +200,17 @@ "aloha", ] +# lists all available cameras from `lerobot/common/robot_devices/cameras` +available_cameras = [ + "opencv", + "intelrealsense", +] + +# lists all available motors from `lerobot/common/robot_devices/motors` +available_motors = [ + "dynamixel", +] + # keys and values refer to yaml files available_policies_per_env = { "aloha": ["act"], diff --git a/lerobot/common/datasets/compute_stats.py b/lerobot/common/datasets/compute_stats.py index 208284465..bafac2e1e 100644 --- a/lerobot/common/datasets/compute_stats.py +++ b/lerobot/common/datasets/compute_stats.py @@ -68,7 +68,7 @@ def get_stats_einops_patterns(dataset, num_workers=0): return stats_patterns -def compute_stats(dataset, batch_size=32, num_workers=16, max_num_samples=None): +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) diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index 4806bf785..c949109b8 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -5,6 +5,7 @@ import argparse import concurrent.futures import logging +import math import shutil import threading import time @@ -13,9 +14,7 @@ from pathlib import Path from threading import Thread -import cv2 import numpy as np -import pyrealsense2 as rs from PIL import Image from lerobot.common.robot_devices.utils import ( @@ -28,14 +27,23 @@ SERIAL_NUMBER_INDEX = 1 -def find_camera_indices(raise_when_empty=True) -> list[int]: +def find_camera_indices(raise_when_empty=True, mock=False) -> list[int]: """ Find the serial numbers of the Intel RealSense cameras connected to the computer. """ + if mock: + from tests.mock_pyrealsense2 import ( + RSCameraInfo, + RSContext, + ) + else: + from pyrealsense2 import camera_info as RSCameraInfo # noqa: N812 + from pyrealsense2 import context as RSContext # noqa: N812 + camera_ids = [] - for device in rs.context().query_devices(): - serial_number = int(device.get_info(rs.camera_info(SERIAL_NUMBER_INDEX))) + for device in RSContext().query_devices(): + serial_number = int(device.get_info(RSCameraInfo(SERIAL_NUMBER_INDEX))) camera_ids.append(serial_number) if raise_when_empty and len(camera_ids) == 0: @@ -64,18 +72,24 @@ def save_images_from_cameras( width=None, height=None, record_time_s=2, + mock=False, ): """ Initializes all the cameras and saves images to the directory. Useful to visually identify the camera associated to a given camera index. """ if camera_ids is None: - camera_ids = find_camera_indices() + camera_ids = find_camera_indices(mock=mock) + + if mock: + from tests.mock_cv2 import COLOR_RGB2BGR, cvtColor + else: + from cv2 import COLOR_RGB2BGR, cvtColor print("Connecting cameras") cameras = [] for cam_idx in camera_ids: - camera = IntelRealSenseCamera(cam_idx, fps=fps, width=width, height=height) + camera = IntelRealSenseCamera(cam_idx, fps=fps, width=width, height=height, mock=mock) camera.connect() print( f"IntelRealSenseCamera({camera.camera_index}, fps={camera.fps}, width={camera.width}, height={camera.height}, color_mode={camera.color_mode})" @@ -103,7 +117,8 @@ def save_images_from_cameras( image = camera.read() if fps is None else camera.async_read() if image is None: print("No Frame") - bgr_converted_image = cv2.cvtColor(image, cv2.COLOR_RGB2BGR) + + bgr_converted_image = cvtColor(image, COLOR_RGB2BGR) executor.submit( save_image, @@ -149,6 +164,7 @@ class IntelRealSenseCameraConfig: color_mode: str = "rgb" use_depth: bool = False force_hardware_reset: bool = True + mock: bool = False def __post_init__(self): if self.color_mode not in ["rgb", "bgr"]: @@ -156,7 +172,9 @@ def __post_init__(self): f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." ) - if (self.fps or self.width or self.height) and not (self.fps and self.width and self.height): + at_least_one_is_not_none = self.fps is not None or self.width is not None or self.height is not None + at_least_one_is_none = self.fps is None or self.width is None or self.height is None + if at_least_one_is_not_none and at_least_one_is_none: raise ValueError( "For `fps`, `width` and `height`, either all of them need to be set, or none of them, " f"but {self.fps=}, {self.width=}, {self.height=} were provided." @@ -228,6 +246,7 @@ def __init__( self.color_mode = config.color_mode self.use_depth = config.use_depth self.force_hardware_reset = config.force_hardware_reset + self.mock = config.mock self.camera = None self.is_connected = False @@ -243,24 +262,37 @@ def connect(self): f"IntelRealSenseCamera({self.camera_index}) is already connected." ) - config = rs.config() + if self.mock: + from tests.mock_pyrealsense2 import ( + RSConfig, + RSFormat, + RSPipeline, + RSStream, + ) + else: + from pyrealsense2 import config as RSConfig # noqa: N812 + from pyrealsense2 import format as RSFormat # noqa: N812 + from pyrealsense2 import pipeline as RSPipeline # noqa: N812 + from pyrealsense2 import stream as RSStream # noqa: N812 + + config = RSConfig() config.enable_device(str(self.camera_index)) if self.fps and self.width and self.height: # TODO(rcadene): can we set rgb8 directly? - config.enable_stream(rs.stream.color, self.width, self.height, rs.format.rgb8, self.fps) + config.enable_stream(RSStream.color, self.width, self.height, RSFormat.rgb8, self.fps) else: - config.enable_stream(rs.stream.color) + config.enable_stream(RSStream.color) if self.use_depth: if self.fps and self.width and self.height: - config.enable_stream(rs.stream.depth, self.width, self.height, rs.format.z16, self.fps) + config.enable_stream(RSStream.depth, self.width, self.height, RSFormat.z16, self.fps) else: - config.enable_stream(rs.stream.depth) + config.enable_stream(RSStream.depth) - self.camera = rs.pipeline() + self.camera = RSPipeline() try: - self.camera.start(config) + profile = self.camera.start(config) is_camera_open = True except RuntimeError: is_camera_open = False @@ -279,6 +311,31 @@ def connect(self): raise OSError(f"Can't access IntelRealSenseCamera({self.camera_index}).") + color_stream = profile.get_stream(RSStream.color) + color_profile = color_stream.as_video_stream_profile() + actual_fps = color_profile.fps() + actual_width = color_profile.width() + actual_height = color_profile.height() + + # Using `math.isclose` since actual fps can be a float (e.g. 29.9 instead of 30) + if self.fps is not None and not math.isclose(self.fps, actual_fps, rel_tol=1e-3): + # Using `OSError` since it's a broad that encompasses issues related to device communication + raise OSError( + f"Can't set {self.fps=} for IntelRealSenseCamera({self.camera_index}). Actual value is {actual_fps}." + ) + if self.width is not None and self.width != actual_width: + raise OSError( + f"Can't set {self.width=} for IntelRealSenseCamera({self.camera_index}). Actual value is {actual_width}." + ) + if self.height is not None and self.height != actual_height: + raise OSError( + f"Can't set {self.height=} for IntelRealSenseCamera({self.camera_index}). Actual value is {actual_height}." + ) + + self.fps = round(actual_fps) + self.width = round(actual_width) + self.height = round(actual_height) + self.is_connected = True def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndarray, np.ndarray]: @@ -315,7 +372,12 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar # IntelRealSense uses RGB format as default (red, green, blue). if requested_color_mode == "bgr": - color_image = cv2.cvtColor(color_image, cv2.COLOR_RGB2BGR) + if self.mock: + from tests.mock_cv2 import COLOR_RGB2BGR, cvtColor + else: + from cv2 import COLOR_RGB2BGR, cvtColor + + color_image = cvtColor(color_image, COLOR_RGB2BGR) h, w, _ = color_image.shape if h != self.height or w != self.width: @@ -347,7 +409,7 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar return color_image def read_loop(self): - while self.stop_event is None or not self.stop_event.is_set(): + while not self.stop_event.is_set(): if self.use_depth: self.color_image, self.depth_map = self.read() else: @@ -368,6 +430,7 @@ def async_read(self): num_tries = 0 while self.color_image is None: + # TODO(rcadene, aliberts): intelrealsense has diverged compared to opencv over here num_tries += 1 time.sleep(1 / self.fps) if num_tries > self.fps and (self.thread.ident is None or not self.thread.is_alive()): diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index b066a451a..4e5f5d183 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -13,7 +13,6 @@ from pathlib import Path from threading import Thread -import cv2 import numpy as np from PIL import Image @@ -24,10 +23,6 @@ ) from lerobot.common.utils.utils import capture_timestamp_utc -# Use 1 thread to avoid blocking the main thread. Especially useful during data collection -# when other threads are used to save the images. -cv2.setNumThreads(1) - # The maximum opencv device index depends on your operating system. For instance, # if you have 3 cameras, they should be associated to index 0, 1, and 2. This is the case # on MacOS. However, on Ubuntu, the indices are different like 6, 16, 23. @@ -36,7 +31,7 @@ MAX_OPENCV_INDEX = 60 -def find_camera_indices(raise_when_empty=False, max_index_search_range=MAX_OPENCV_INDEX): +def find_camera_indices(raise_when_empty=False, max_index_search_range=MAX_OPENCV_INDEX, mock=False): if platform.system() == "Linux": # Linux uses camera ports print("Linux detected. Finding available camera indices through scanning '/dev/video*' ports") @@ -51,9 +46,14 @@ def find_camera_indices(raise_when_empty=False, max_index_search_range=MAX_OPENC ) possible_camera_ids = range(max_index_search_range) + if mock: + from tests.mock_cv2 import VideoCapture + else: + from cv2 import VideoCapture + camera_ids = [] for camera_idx in possible_camera_ids: - camera = cv2.VideoCapture(camera_idx) + camera = VideoCapture(camera_idx) is_open = camera.isOpened() camera.release() @@ -78,19 +78,25 @@ def save_image(img_array, camera_index, frame_index, images_dir): def save_images_from_cameras( - images_dir: Path, camera_ids: list[int] | None = None, fps=None, width=None, height=None, record_time_s=2 + images_dir: Path, + camera_ids: list[int] | None = None, + fps=None, + width=None, + height=None, + record_time_s=2, + mock=False, ): """ Initializes all the cameras and saves images to the directory. Useful to visually identify the camera associated to a given camera index. """ if camera_ids is None: - camera_ids = find_camera_indices() + camera_ids = find_camera_indices(mock=mock) print("Connecting cameras") cameras = [] for cam_idx in camera_ids: - camera = OpenCVCamera(cam_idx, fps=fps, width=width, height=height) + camera = OpenCVCamera(cam_idx, fps=fps, width=width, height=height, mock=mock) camera.connect() print( f"OpenCVCamera({camera.camera_index}, fps={camera.fps}, width={camera.width}, " @@ -156,6 +162,7 @@ class OpenCVCameraConfig: width: int | None = None height: int | None = None color_mode: str = "rgb" + mock: bool = False def __post_init__(self): if self.color_mode not in ["rgb", "bgr"]: @@ -215,6 +222,7 @@ def __init__(self, camera_index: int, config: OpenCVCameraConfig | None = None, self.width = config.width self.height = config.height self.color_mode = config.color_mode + self.mock = config.mock self.camera = None self.is_connected = False @@ -227,17 +235,33 @@ def connect(self): if self.is_connected: raise RobotDeviceAlreadyConnectedError(f"OpenCVCamera({self.camera_index}) is already connected.") - # First create a temporary camera trying to access `camera_index`, - # and verify it is a valid camera by calling `isOpened`. - - if platform.system() == "Linux": - # Linux uses ports for connecting to cameras - tmp_camera = cv2.VideoCapture(f"/dev/video{self.camera_index}") + if self.mock: + from tests.mock_cv2 import ( + CAP_PROP_FPS, + CAP_PROP_FRAME_HEIGHT, + CAP_PROP_FRAME_WIDTH, + VideoCapture, + ) else: - tmp_camera = cv2.VideoCapture(self.camera_index) + from cv2 import ( + CAP_PROP_FPS, + CAP_PROP_FRAME_HEIGHT, + CAP_PROP_FRAME_WIDTH, + VideoCapture, + setNumThreads, + ) + + # Use 1 thread to avoid blocking the main thread. Especially useful during data collection + # when other threads are used to save the images. + setNumThreads(1) + camera_idx = f"/dev/video{self.camera_index}" if platform.system() == "Linux" else self.camera_index + # First create a temporary camera trying to access `camera_index`, + # and verify it is a valid camera by calling `isOpened`. + tmp_camera = VideoCapture(camera_idx) is_camera_open = tmp_camera.isOpened() # Release camera to make it accessible for `find_camera_indices` + tmp_camera.release() del tmp_camera # If the camera doesn't work, display the camera indices corresponding to @@ -251,28 +275,27 @@ def connect(self): "To find the camera index you should use, run `python lerobot/common/robot_devices/cameras/opencv.py`." ) - raise OSError(f"Can't access OpenCVCamera({self.camera_index}).") + raise OSError(f"Can't access OpenCVCamera({camera_idx}).") # Secondly, create the camera that will be used downstream. # Note: For some unknown reason, calling `isOpened` blocks the camera which then # needs to be re-created. - if platform.system() == "Linux": - self.camera = cv2.VideoCapture(f"/dev/video{self.camera_index}") - else: - self.camera = cv2.VideoCapture(self.camera_index) + self.camera = VideoCapture(camera_idx) if self.fps is not None: - self.camera.set(cv2.CAP_PROP_FPS, self.fps) + self.camera.set(CAP_PROP_FPS, self.fps) if self.width is not None: - self.camera.set(cv2.CAP_PROP_FRAME_WIDTH, self.width) + self.camera.set(CAP_PROP_FRAME_WIDTH, self.width) if self.height is not None: - self.camera.set(cv2.CAP_PROP_FRAME_HEIGHT, self.height) + self.camera.set(CAP_PROP_FRAME_HEIGHT, self.height) - actual_fps = self.camera.get(cv2.CAP_PROP_FPS) - actual_width = self.camera.get(cv2.CAP_PROP_FRAME_WIDTH) - actual_height = self.camera.get(cv2.CAP_PROP_FRAME_HEIGHT) + actual_fps = self.camera.get(CAP_PROP_FPS) + actual_width = self.camera.get(CAP_PROP_FRAME_WIDTH) + actual_height = self.camera.get(CAP_PROP_FRAME_HEIGHT) + # Using `math.isclose` since actual fps can be a float (e.g. 29.9 instead of 30) if self.fps is not None and not math.isclose(self.fps, actual_fps, rel_tol=1e-3): + # Using `OSError` since it's a broad that encompasses issues related to device communication raise OSError( f"Can't set {self.fps=} for OpenCVCamera({self.camera_index}). Actual value is {actual_fps}." ) @@ -285,9 +308,9 @@ def connect(self): f"Can't set {self.height=} for OpenCVCamera({self.camera_index}). Actual value is {actual_height}." ) - self.fps = actual_fps - self.width = actual_width - self.height = actual_height + self.fps = round(actual_fps) + self.width = round(actual_width) + self.height = round(actual_height) self.is_connected = True @@ -306,6 +329,7 @@ def read(self, temporary_color_mode: str | None = None) -> np.ndarray: start_time = time.perf_counter() ret, color_image = self.camera.read() + if not ret: raise OSError(f"Can't capture color image from camera {self.camera_index}.") @@ -320,7 +344,12 @@ def read(self, temporary_color_mode: str | None = None) -> np.ndarray: # However, Deep Learning framework such as LeRobot uses RGB format as default to train neural networks, # so we convert the image color from BGR to RGB. if requested_color_mode == "rgb": - color_image = cv2.cvtColor(color_image, cv2.COLOR_BGR2RGB) + if self.mock: + from tests.mock_cv2 import COLOR_BGR2RGB, cvtColor + else: + from cv2 import COLOR_BGR2RGB, cvtColor + + color_image = cvtColor(color_image, COLOR_BGR2RGB) h, w, _ = color_image.shape if h != self.height or w != self.width: @@ -334,11 +363,16 @@ def read(self, temporary_color_mode: str | None = None) -> np.ndarray: # log the utc time at which the image was received self.logs["timestamp_utc"] = capture_timestamp_utc() + self.color_image = color_image + return color_image def read_loop(self): - while self.stop_event is None or not self.stop_event.is_set(): - self.color_image = self.read() + while not self.stop_event.is_set(): + try: + self.color_image = self.read() + except Exception as e: + print(f"Error reading in thread: {e}") def async_read(self): if not self.is_connected: @@ -353,15 +387,14 @@ def async_read(self): self.thread.start() num_tries = 0 - while self.color_image is None: - num_tries += 1 - time.sleep(1 / self.fps) - if num_tries > self.fps and (self.thread.ident is None or not self.thread.is_alive()): - raise Exception( - "The thread responsible for `self.async_read()` took too much time to start. There might be an issue. Verify that `self.thread.start()` has been called." - ) + while True: + if self.color_image is not None: + return self.color_image - return self.color_image + time.sleep(1 / self.fps) + num_tries += 1 + if num_tries > self.fps * 2: + raise TimeoutError("Timed out waiting for async_read() to start.") def disconnect(self): if not self.is_connected: @@ -369,16 +402,14 @@ def disconnect(self): f"OpenCVCamera({self.camera_index}) is not connected. Try running `camera.connect()` first." ) - if self.thread is not None and self.thread.is_alive(): - # wait for the thread to finish + if self.thread is not None: self.stop_event.set() - self.thread.join() + self.thread.join() # wait for the thread to finish self.thread = None self.stop_event = None self.camera.release() self.camera = None - self.is_connected = False def __del__(self): diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/robot_devices/motors/dynamixel.py index 491963fed..0c3145028 100644 --- a/lerobot/common/robot_devices/motors/dynamixel.py +++ b/lerobot/common/robot_devices/motors/dynamixel.py @@ -8,17 +8,6 @@ import numpy as np import tqdm -from dynamixel_sdk import ( - COMM_SUCCESS, - DXL_HIBYTE, - DXL_HIWORD, - DXL_LOBYTE, - DXL_LOWORD, - GroupSyncRead, - GroupSyncWrite, - PacketHandler, - PortHandler, -) from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from lerobot.common.utils.utils import capture_timestamp_utc @@ -166,7 +155,17 @@ def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str return steps -def convert_to_bytes(value, bytes): +def convert_to_bytes(value, bytes, mock=False): + if mock: + return value + + from dynamixel_sdk import ( + DXL_HIBYTE, + DXL_HIWORD, + DXL_LOBYTE, + DXL_LOWORD, + ) + # Note: No need to convert back into unsigned int, since this byte preprocessing # already handles it for us. if bytes == 1: @@ -333,9 +332,11 @@ def __init__( motors: dict[str, tuple[int, str]], extra_model_control_table: dict[str, list[tuple]] | None = None, extra_model_resolution: dict[str, int] | None = None, + mock=False, ): self.port = port self.motors = motors + self.mock = mock self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE) if extra_model_control_table: @@ -359,6 +360,11 @@ def connect(self): f"DynamixelMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice." ) + if self.mock: + from tests.mock_dynamixel_sdk import PacketHandler, PortHandler + else: + from dynamixel_sdk import PacketHandler, PortHandler + self.port_handler = PortHandler(self.port) self.packet_handler = PacketHandler(PROTOCOL_VERSION) @@ -392,10 +398,17 @@ def connect(self): self.configure_motors() def reconnect(self): + if self.mock: + from tests.mock_dynamixel_sdk import PacketHandler, PortHandler + else: + from dynamixel_sdk import PacketHandler, PortHandler + self.port_handler = PortHandler(self.port) self.packet_handler = PacketHandler(PROTOCOL_VERSION) + if not self.port_handler.openPort(): raise OSError(f"Failed to open port '{self.port}'.") + self.is_connected = True def are_motors_configured(self): @@ -781,6 +794,11 @@ def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | return values def _read_with_motor_ids(self, motor_models, motor_ids, data_name): + if self.mock: + from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + else: + from dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + return_list = True if not isinstance(motor_ids, list): return_list = False @@ -817,6 +835,11 @@ def read(self, data_name, motor_names: str | list[str] | None = None): start_time = time.perf_counter() + if self.mock: + from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + else: + from dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + if motor_names is None: motor_names = self.motor_names @@ -876,6 +899,11 @@ def read(self, data_name, motor_names: str | list[str] | None = None): return values def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values): + if self.mock: + from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + else: + from dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + if not isinstance(motor_ids, list): motor_ids = [motor_ids] if not isinstance(values, list): @@ -885,7 +913,7 @@ def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values): addr, bytes = self.model_ctrl_table[motor_models[0]][data_name] group = GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes) for idx, value in zip(motor_ids, values, strict=True): - data = convert_to_bytes(value, bytes) + data = convert_to_bytes(value, bytes, self.mock) group.addParam(idx, data) comm = group.txPacket() @@ -903,6 +931,11 @@ def write(self, data_name, values: int | float | np.ndarray, motor_names: str | start_time = time.perf_counter() + if self.mock: + from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + else: + from dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + if motor_names is None: motor_names = self.motor_names @@ -937,7 +970,7 @@ def write(self, data_name, values: int | float | np.ndarray, motor_names: str | ) for idx, value in zip(motor_ids, values, strict=True): - data = convert_to_bytes(value, bytes) + data = convert_to_bytes(value, bytes, self.mock) if init_group: self.group_writers[group_key].addParam(idx, data) else: diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index a6506a3fe..ff9cf3dc3 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -242,7 +242,8 @@ def is_headless(): ######################################################################################## -def calibrate(robot: Robot, arms: list[str] | None): +def get_available_arms(robot): + # TODO(rcadene): moves this function in manipulator class? available_arms = [] for name in robot.follower_arms: arm_id = get_arm_id(name, "follower") @@ -250,9 +251,12 @@ def calibrate(robot: Robot, arms: list[str] | None): for name in robot.leader_arms: arm_id = get_arm_id(name, "leader") available_arms.append(arm_id) + return available_arms - unknown_arms = [arm_id for arm_id in arms if arm_id not in available_arms] +def calibrate(robot: Robot, arms: list[str] | None): + available_arms = get_available_arms(robot) + unknown_arms = [arm_id for arm_id in arms if arm_id not in available_arms] available_arms_str = " ".join(available_arms) unknown_arms_str = " ".join(unknown_arms) @@ -323,6 +327,7 @@ def record( tags=None, num_image_writers_per_camera=4, force_override=False, + display_cameras=True, ): # TODO(rcadene): Add option to record logs # TODO(rcadene): Clean this function via decomposition in higher level functions @@ -333,9 +338,6 @@ def record( f"Your dataset name begins by 'eval_' ({dataset_name}) but no policy is provided ({policy})." ) - if not video: - raise NotImplementedError() - if not robot.is_connected: robot.connect() @@ -359,7 +361,7 @@ def record( episode_index = 0 if is_headless(): - logging.info( + logging.warning( "Headless environment detected. On-screen cameras display and keyboard inputs will not be available." ) @@ -427,7 +429,7 @@ def on_press(key): else: observation = robot.capture_observation() - if not is_headless(): + if display_cameras and not is_headless(): image_keys = [key for key in observation if "image" in key] for key in image_keys: cv2.imshow(key, cv2.cvtColor(observation[key].numpy(), cv2.COLOR_RGB2BGR)) @@ -445,6 +447,7 @@ def on_press(key): # Using `with` to exist smoothly if an execption is raised. futures = [] num_image_writers = num_image_writers_per_camera * len(robot.cameras) + num_image_writers = max(num_image_writers, 1) with concurrent.futures.ThreadPoolExecutor(max_workers=num_image_writers) as executor: # Start recording all episodes while episode_index < num_episodes: @@ -472,7 +475,7 @@ def on_press(key): ) ] - if not is_headless(): + if display_cameras and not is_headless(): image_keys = [key for key in observation if "image" in key] for key in image_keys: cv2.imshow(key, cv2.cvtColor(observation[key].numpy(), cv2.COLOR_RGB2BGR)) @@ -545,15 +548,23 @@ def on_press(key): num_frames = frame_index for key in image_keys: - tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" - fname = f"{key}_episode_{episode_index:06d}.mp4" - video_path = local_dir / "videos" / fname - if video_path.exists(): - video_path.unlink() - # Store the reference to the video frame, even tho the videos are not yet encoded - ep_dict[key] = [] - for i in range(num_frames): - ep_dict[key].append({"path": f"videos/{fname}", "timestamp": i / fps}) + if video: + tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" + fname = f"{key}_episode_{episode_index:06d}.mp4" + video_path = local_dir / "videos" / fname + if video_path.exists(): + video_path.unlink() + # Store the reference to the video frame, even tho the videos are not yet encoded + ep_dict[key] = [] + for i in range(num_frames): + ep_dict[key].append({"path": f"videos/{fname}", "timestamp": i / fps}) + + else: + imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" + ep_dict[key] = [] + for i in range(num_frames): + img_path = imgs_dir / f"frame_{i:06d}.png" + ep_dict[key].append({"path": str(img_path)}) for key in not_image_keys: ep_dict[key] = torch.stack(ep_dict[key]) @@ -612,26 +623,27 @@ def on_press(key): break robot.disconnect() - if not is_headless(): + if display_cameras and not is_headless(): cv2.destroyAllWindows() num_episodes = episode_index - logging.info("Encoding videos") - say("Encoding videos") - # Use ffmpeg to convert frames stored as png into mp4 videos - for episode_index in tqdm.tqdm(range(num_episodes)): - for key in image_keys: - tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" - fname = f"{key}_episode_{episode_index:06d}.mp4" - video_path = local_dir / "videos" / fname - if video_path.exists(): - # Skip if video is already encoded. Could be the case when resuming data recording. - continue - # note: `encode_video_frames` is a blocking call. Making it asynchronous shouldn't speedup encoding, - # since video encoding with ffmpeg is already using multithreading. - encode_video_frames(tmp_imgs_dir, video_path, fps, overwrite=True) - shutil.rmtree(tmp_imgs_dir) + if video: + logging.info("Encoding videos") + say("Encoding videos") + # Use ffmpeg to convert frames stored as png into mp4 videos + for episode_index in tqdm.tqdm(range(num_episodes)): + for key in image_keys: + tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" + fname = f"{key}_episode_{episode_index:06d}.mp4" + video_path = local_dir / "videos" / fname + if video_path.exists(): + # Skip if video is already encoded. Could be the case when resuming data recording. + continue + # note: `encode_video_frames` is a blocking call. Making it asynchronous shouldn't speedup encoding, + # since video encoding with ffmpeg is already using multithreading. + encode_video_frames(tmp_imgs_dir, video_path, fps, overwrite=True) + shutil.rmtree(tmp_imgs_dir) logging.info("Concatenating episodes") ep_dicts = [] diff --git a/poetry.lock b/poetry.lock index 40bf29eff..a46d38b59 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry 1.8.3 and should not be changed by hand. +# This file is automatically @generated by Poetry 1.8.2 and should not be changed by hand. [[package]] name = "absl-py" @@ -2406,7 +2406,6 @@ description = "Nvidia JIT LTO Library" optional = false python-versions = ">=3" files = [ - {file = "nvidia_nvjitlink_cu12-12.5.82-py3-none-manylinux2014_aarch64.whl", hash = "sha256:98103729cc5226e13ca319a10bbf9433bbbd44ef64fe72f45f067cacc14b8d27"}, {file = "nvidia_nvjitlink_cu12-12.5.82-py3-none-manylinux2014_x86_64.whl", hash = "sha256:f9b37bc5c8cf7509665cb6ada5aaa0ce65618f2332b7d3e78e9790511f111212"}, {file = "nvidia_nvjitlink_cu12-12.5.82-py3-none-win_amd64.whl", hash = "sha256:e782564d705ff0bf61ac3e1bf730166da66dd2fe9012f111ede5fc49b64ae697"}, ] @@ -4578,7 +4577,7 @@ dora = ["gym-dora"] dynamixel = ["dynamixel-sdk", "pynput"] intelrealsense = ["pyrealsense2"] pusht = ["gym-pusht"] -test = ["pytest", "pytest-cov"] +test = ["pyserial", "pytest", "pytest-cov"] umi = ["imagecodecs"] video-benchmark = ["pandas", "scikit-image"] xarm = ["gym-xarm"] @@ -4586,4 +4585,4 @@ xarm = ["gym-xarm"] [metadata] lock-version = "2.0" python-versions = ">=3.10,<3.13" -content-hash = "c9c3beac71f760738baf2fd169378eefdaef7d3a9cd068270bc5190fbefdb42a" +content-hash = "5e4f6b9727d67a37d1c6d94af7661bb688a0866afd30878c5e523b8e768deac6" diff --git a/pyproject.toml b/pyproject.toml index f46e39da1..119244419 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -67,6 +67,7 @@ pynput = {version = ">=1.7.7", optional = true} # TODO(rcadene, salibert): 71.0.1 has a bug setuptools = {version = "!=71.0.1", optional = true} pyrealsense2 = {version = ">=2.55.1.6486", markers = "sys_platform != 'darwin'", optional = true} +pyserial = {version = ">=3.5", optional = true} [tool.poetry.extras] @@ -75,7 +76,7 @@ pusht = ["gym-pusht"] xarm = ["gym-xarm"] aloha = ["gym-aloha"] dev = ["pre-commit", "debugpy"] -test = ["pytest", "pytest-cov"] +test = ["pytest", "pytest-cov", "pyserial"] umi = ["imagecodecs"] video_benchmark = ["scikit-image", "pandas"] dynamixel = ["dynamixel-sdk", "pynput"] diff --git a/tests/conftest.py b/tests/conftest.py index 52006f331..386441e5d 100644 --- a/tests/conftest.py +++ b/tests/conftest.py @@ -13,13 +13,15 @@ # 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 traceback import pytest +from serial import SerialException +from lerobot import available_cameras, available_motors, available_robots from lerobot.common.utils.utils import init_hydra_config - -from .utils import DEVICE, ROBOT_CONFIG_PATH_TEMPLATE +from tests.utils import DEVICE, ROBOT_CONFIG_PATH_TEMPLATE, make_camera, make_motors_bus def pytest_collection_finish(): @@ -28,6 +30,11 @@ def pytest_collection_finish(): @pytest.fixture def is_robot_available(robot_type): + if robot_type not in available_robots: + raise ValueError( + f"The robot type '{robot_type}' is not valid. Expected one of these '{available_robots}" + ) + try: from lerobot.common.robot_devices.robots.factory import make_robot @@ -37,7 +44,73 @@ def is_robot_available(robot_type): robot.connect() del robot return True - except Exception: - traceback.print_exc() + + except Exception as e: print(f"\nA {robot_type} robot is not available.") + + if isinstance(e, ModuleNotFoundError): + print(f"\nInstall module '{e.name}'") + elif isinstance(e, SerialException): + print("\nNo physical motors bus detected.") + + traceback.print_exc() + return False + + +@pytest.fixture +def is_camera_available(camera_type): + if camera_type not in available_cameras: + raise ValueError( + f"The camera type '{camera_type}' is not valid. Expected one of these '{available_cameras}" + ) + + try: + camera = make_camera(camera_type) + camera.connect() + del camera + return True + + except Exception as e: + print(f"\nA {camera_type} camera is not available.") + + if isinstance(e, ModuleNotFoundError): + print(f"\nInstall module '{e.name}'") + elif isinstance(e, ValueError) and "camera_index" in e.args[0]: + print("\nNo physical camera detected.") + + traceback.print_exc() return False + + +@pytest.fixture +def is_motor_available(motor_type): + if motor_type not in available_motors: + raise ValueError( + f"The motor type '{motor_type}' is not valid. Expected one of these '{available_motors}" + ) + + try: + motors_bus = make_motors_bus(motor_type) + motors_bus.connect() + del motors_bus + return True + + except Exception as e: + print(f"\nA {motor_type} motor is not available.") + + if isinstance(e, ModuleNotFoundError): + print(f"\nInstall module '{e.name}'") + elif isinstance(e, SerialException): + print("\nNo physical motors bus detected.") + + traceback.print_exc() + return False + + +@pytest.fixture +def patch_builtins_input(monkeypatch): + def print_text(text=None): + if text is not None: + print(text) + + monkeypatch.setattr("builtins.input", print_text) diff --git a/tests/mock_cv2.py b/tests/mock_cv2.py new file mode 100644 index 000000000..a3e19e550 --- /dev/null +++ b/tests/mock_cv2.py @@ -0,0 +1,66 @@ +from functools import cache + +import numpy as np + +CAP_PROP_FPS = 5 +CAP_PROP_FRAME_WIDTH = 3 +CAP_PROP_FRAME_HEIGHT = 4 +COLOR_RGB2BGR = 4 +COLOR_BGR2RGB = 4 + + +@cache +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]: + return color_image[:, :, [2, 1, 0]] + else: + raise NotImplementedError(color_convertion) + + +class VideoCapture: + def __init__(self, *args, **kwargs): + self._mock_dict = { + CAP_PROP_FPS: 30, + CAP_PROP_FRAME_WIDTH: 640, + CAP_PROP_FRAME_HEIGHT: 480, + } + self._is_opened = True + + def isOpened(self): # noqa: N802 + return self._is_opened + + def set(self, propId: int, value: float) -> bool: # noqa: N803 + if not self._is_opened: + raise RuntimeError("Camera is not opened") + self._mock_dict[propId] = value + return True + + def get(self, propId: int) -> float: # noqa: N803 + if not self._is_opened: + raise RuntimeError("Camera is not opened") + value = self._mock_dict[propId] + if value == 0: + if propId == CAP_PROP_FRAME_HEIGHT: + value = 480 + elif propId == CAP_PROP_FRAME_WIDTH: + value = 640 + return value + + def read(self): + if not self._is_opened: + raise RuntimeError("Camera is not opened") + h = self.get(CAP_PROP_FRAME_HEIGHT) + w = self.get(CAP_PROP_FRAME_WIDTH) + ret = True + return ret, _generate_image(width=w, height=h) + + def release(self): + self._is_opened = False + + def __del__(self): + if self._is_opened: + self.release() diff --git a/tests/mock_dynamixel_sdk.py b/tests/mock_dynamixel_sdk.py new file mode 100644 index 000000000..6d0ed20e5 --- /dev/null +++ b/tests/mock_dynamixel_sdk.py @@ -0,0 +1,87 @@ +"""Mocked classes and functions from dynamixel_sdk to allow for continuous integration +and testing code logic that requires hardware and devices (e.g. robot arms, cameras) + +Warning: These mocked versions are minimalist. They do not exactly mock every behaviors +from the original classes and functions (e.g. return types might be None instead of boolean). +""" + +# from dynamixel_sdk import COMM_SUCCESS + +DEFAULT_BAUDRATE = 9_600 +COMM_SUCCESS = 0 # tx or rx packet communication success + + +def convert_to_bytes(value, bytes): + # TODO(rcadene): remove need to mock `convert_to_bytes` by implemented the inverse transform + # `convert_bytes_to_value` + del bytes # unused + return value + + +class PortHandler: + def __init__(self, port): + self.port = port + # factory default baudrate + self.baudrate = DEFAULT_BAUDRATE + + def openPort(self): # noqa: N802 + return True + + def closePort(self): # noqa: N802 + pass + + def setPacketTimeoutMillis(self, timeout_ms): # noqa: N802 + del timeout_ms # unused + + def getBaudRate(self): # noqa: N802 + return self.baudrate + + def setBaudRate(self, baudrate): # noqa: N802 + self.baudrate = baudrate + + +class PacketHandler: + def __init__(self, protocol_version): + del protocol_version # unused + # Use packet_handler.data to communicate across Read and Write + self.data = {} + + +class GroupSyncRead: + def __init__(self, port_handler, packet_handler, address, bytes): + self.packet_handler = packet_handler + + def addParam(self, motor_index): # noqa: N802 + if motor_index not in self.packet_handler.data: + # Initialize motor default values + self.packet_handler.data[motor_index] = { + # Key (int) are from X_SERIES_CONTROL_TABLE + 7: motor_index, # ID + 8: DEFAULT_BAUDRATE, # Baud_rate + 10: 0, # Drive_Mode + 64: 0, # Torque_Enable + # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144 + # For other joints, 2560 will be autocorrected to be in calibration range + 132: 2560, # Present_Position + } + + def txRxPacket(self): # noqa: N802 + return COMM_SUCCESS + + def getData(self, index, address, bytes): # noqa: N802 + return self.packet_handler.data[index][address] + + +class GroupSyncWrite: + def __init__(self, port_handler, packet_handler, address, bytes): + self.packet_handler = packet_handler + self.address = address + + def addParam(self, index, data): # noqa: N802 + self.changeParam(index, data) + + def txPacket(self): # noqa: N802 + return COMM_SUCCESS + + def changeParam(self, index, data): # noqa: N802 + self.packet_handler.data[index][self.address] = data diff --git a/tests/mock_pyrealsense2.py b/tests/mock_pyrealsense2.py new file mode 100644 index 000000000..b9c6ccf96 --- /dev/null +++ b/tests/mock_pyrealsense2.py @@ -0,0 +1,134 @@ +import enum + +import numpy as np + + +class RSStream(enum.Enum): + color = 0 + depth = 1 + + +class RSFormat(enum.Enum): + rgb8 = 0 + z16 = 1 + + +class RSConfig: + def enable_device(self, device_id: str): + self.device_enabled = device_id + + def enable_stream( + self, stream_type: RSStream, width=None, height=None, color_format: RSFormat = None, fps=None + ): + self.stream_type = stream_type + # Overwrite default values when possible + self.width = 848 if width is None else width + self.height = 480 if height is None else height + self.color_format = RSFormat.rgb8 if color_format is None else color_format + self.fps = 30 if fps is None else fps + + +class RSColorProfile: + def __init__(self, config: RSConfig): + self.config = config + + def fps(self): + return self.config.fps + + def width(self): + return self.config.width + + def height(self): + return self.config.height + + +class RSColorStream: + def __init__(self, config: RSConfig): + self.config = config + + def as_video_stream_profile(self): + return RSColorProfile(self.config) + + +class RSProfile: + def __init__(self, config: RSConfig): + self.config = config + + def get_stream(self, color_format: RSFormat): + del color_format # unused + return RSColorStream(self.config) + + +class RSPipeline: + def __init__(self): + self.started = False + self.config = None + + def start(self, config: RSConfig): + self.started = True + self.config = config + return RSProfile(self.config) + + def stop(self): + if not self.started: + raise RuntimeError("You need to start the camera before stop.") + self.started = False + self.config = None + + def wait_for_frames(self, timeout_ms=50000): + del timeout_ms # unused + return RSFrames(self.config) + + +class RSFrames: + def __init__(self, config: RSConfig): + self.config = config + + def get_color_frame(self): + return RSColorFrame(self.config) + + def get_depth_frame(self): + return RSDepthFrame(self.config) + + +class RSColorFrame: + def __init__(self, config: RSConfig): + self.config = config + + def get_data(self): + data = np.ones((self.config.height, self.config.width, 3), dtype=np.uint8) + # Create a difference between rgb and bgr + data[:, :, 0] = 2 + return data + + +class RSDepthFrame: + def __init__(self, config: RSConfig): + self.config = config + + def get_data(self): + return np.ones((self.config.height, self.config.width), dtype=np.uint16) + + +class RSDevice: + def __init__(self): + pass + + def get_info(self, camera_info) -> str: + del camera_info # unused + # return fake serial number + return "123456789" + + +class RSContext: + def __init__(self): + pass + + def query_devices(self): + return [RSDevice()] + + +class RSCameraInfo: + def __init__(self, serial_number): + del serial_number + pass diff --git a/tests/test_cameras.py b/tests/test_cameras.py index 0d5d94425..72da248d6 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -1,21 +1,32 @@ """ -Tests meant to be used locally and launched manually. +Tests for physical cameras and their mocked versions. +If the physical camera is not connected to the computer, or not working, +the test will be skipped. -Example usage: +Example of running a specific test: ```bash pytest -sx tests/test_cameras.py::test_camera ``` + +Example of running test on a real camera connected to the computer: +```bash +pytest -sx 'tests/test_cameras.py::test_camera[opencv-False]' +pytest -sx 'tests/test_cameras.py::test_camera[intelrealsense-False]' +``` + +Example of running test on a mocked version of the camera: +```bash +pytest -sx 'tests/test_cameras.py::test_camera[opencv-True]' +pytest -sx 'tests/test_cameras.py::test_camera[intelrealsense-True]' +``` """ import numpy as np import pytest -from lerobot import available_robots -from lerobot.common.robot_devices.cameras.opencv import OpenCVCamera, save_images_from_cameras from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError -from tests.utils import require_robot +from tests.utils import TEST_CAMERA_TYPES, make_camera, require_camera -CAMERA_INDEX = 2 # Maximum absolute difference between two consecutive images recored by a camera. # This value differs with respect to the camera. MAX_PIXEL_DIFFERENCE = 25 @@ -25,9 +36,9 @@ def compute_max_pixel_difference(first_image, second_image): return np.abs(first_image.astype(float) - second_image.astype(float)).max() -@pytest.mark.parametrize("robot_type", available_robots) -@require_robot -def test_camera(request, robot_type): +@pytest.mark.parametrize("camera_type, mock", TEST_CAMERA_TYPES) +@require_camera +def test_camera(request, camera_type, mock): """Test assumes that `camera.read()` returns the same image when called multiple times in a row. So the environment should not change (you shouldnt be in front of the camera) and the camera should not be moving. @@ -36,10 +47,12 @@ def test_camera(request, robot_type): """ # TODO(rcadene): measure fps in nightly? # TODO(rcadene): test logs - # TODO(rcadene): add compatibility with other camera APIs + + if camera_type == "opencv" and not mock: + pytest.skip("TODO(rcadene): fix test for opencv physical camera") # Test instantiating - camera = OpenCVCamera(CAMERA_INDEX) + camera = make_camera(camera_type, mock=mock) # Test reading, async reading, disconnecting before connecting raises an error with pytest.raises(RobotDeviceNotConnectedError): @@ -53,7 +66,7 @@ def test_camera(request, robot_type): del camera # Test connecting - camera = OpenCVCamera(CAMERA_INDEX) + camera = make_camera(camera_type, mock=mock) camera.connect() assert camera.is_connected assert camera.fps is not None @@ -78,11 +91,14 @@ def test_camera(request, robot_type): camera.read() color_image = camera.read() async_color_image = camera.async_read() - print( + error_msg = ( "max_pixel_difference between read() and async_read()", compute_max_pixel_difference(color_image, async_color_image), ) - assert np.allclose(color_image, async_color_image, rtol=1e-5, atol=MAX_PIXEL_DIFFERENCE) + # TODO(rcadene): properly set `rtol` + np.testing.assert_allclose( + color_image, async_color_image, rtol=1e-5, atol=MAX_PIXEL_DIFFERENCE, err_msg=error_msg + ) # Test disconnecting camera.disconnect() @@ -90,29 +106,25 @@ def test_camera(request, robot_type): assert camera.thread is None # Test disconnecting with `__del__` - camera = OpenCVCamera(CAMERA_INDEX) + camera = make_camera(camera_type, mock=mock) camera.connect() del camera # Test acquiring a bgr image - camera = OpenCVCamera(CAMERA_INDEX, color_mode="bgr") + camera = make_camera(camera_type, color_mode="bgr", mock=mock) camera.connect() assert camera.color_mode == "bgr" bgr_color_image = camera.read() - assert np.allclose(color_image, bgr_color_image[:, :, [2, 1, 0]], rtol=1e-5, atol=MAX_PIXEL_DIFFERENCE) + np.testing.assert_allclose( + color_image, bgr_color_image[:, :, [2, 1, 0]], rtol=1e-5, atol=MAX_PIXEL_DIFFERENCE, err_msg=error_msg + ) del camera # TODO(rcadene): Add a test for a camera that doesnt support fps=60 and raises an OSError # TODO(rcadene): Add a test for a camera that supports fps=60 - # Test fps=10 raises an OSError - camera = OpenCVCamera(CAMERA_INDEX, fps=10) - with pytest.raises(OSError): - camera.connect() - del camera - # Test width and height can be set - camera = OpenCVCamera(CAMERA_INDEX, fps=30, width=1280, height=720) + camera = make_camera(camera_type, fps=30, width=1280, height=720, mock=mock) camera.connect() assert camera.fps == 30 assert camera.width == 1280 @@ -125,13 +137,19 @@ def test_camera(request, robot_type): del camera # Test not supported width and height raise an error - camera = OpenCVCamera(CAMERA_INDEX, fps=30, width=0, height=0) + camera = make_camera(camera_type, fps=30, width=0, height=0, mock=mock) with pytest.raises(OSError): camera.connect() del camera -@pytest.mark.parametrize("robot_type", available_robots) -@require_robot -def test_save_images_from_cameras(tmpdir, request, robot_type): - save_images_from_cameras(tmpdir, record_time_s=1) +@pytest.mark.parametrize("camera_type, mock", TEST_CAMERA_TYPES) +@require_camera +def test_save_images_from_cameras(tmpdir, request, camera_type, mock): + # TODO(rcadene): refactor + if camera_type == "opencv": + from lerobot.common.robot_devices.cameras.opencv import save_images_from_cameras + elif camera_type == "intelrealsense": + from lerobot.common.robot_devices.cameras.intelrealsense import save_images_from_cameras + + save_images_from_cameras(tmpdir, record_time_s=1, mock=mock) diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 406edeb4f..f554c2511 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -1,55 +1,146 @@ +""" +Tests for physical robots and their mocked versions. +If the physical robots are not connected to the computer, or not working, +the test will be skipped. + +Example of running a specific test: +```bash +pytest -sx tests/test_control_robot.py::test_teleoperate +``` + +Example of running test on real robots connected to the computer: +```bash +pytest -sx 'tests/test_control_robot.py::test_teleoperate[koch-False]' +pytest -sx 'tests/test_control_robot.py::test_teleoperate[koch_bimanual-False]' +pytest -sx 'tests/test_control_robot.py::test_teleoperate[aloha-False]' +``` + +Example of running test on a mocked version of robots: +```bash +pytest -sx 'tests/test_control_robot.py::test_teleoperate[koch-True]' +pytest -sx 'tests/test_control_robot.py::test_teleoperate[koch_bimanual-True]' +pytest -sx 'tests/test_control_robot.py::test_teleoperate[aloha-True]' +``` +""" + from pathlib import Path import pytest -from lerobot import available_robots from lerobot.common.policies.factory import make_policy from lerobot.common.utils.utils import init_hydra_config -from lerobot.scripts.control_robot import calibrate, record, replay, teleoperate +from lerobot.scripts.control_robot import calibrate, get_available_arms, record, replay, teleoperate from tests.test_robots import make_robot -from tests.utils import DEFAULT_CONFIG_PATH, DEVICE, require_robot +from tests.utils import DEFAULT_CONFIG_PATH, DEVICE, TEST_ROBOT_TYPES, require_robot -@pytest.mark.parametrize("robot_type", available_robots) +@pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_teleoperate(request, robot_type): - robot = make_robot(robot_type) +def test_teleoperate(tmpdir, request, robot_type, mock): + if mock: + request.getfixturevalue("patch_builtins_input") + + # 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 + overrides = [f"calibration_dir={calibration_dir}"] + else: + # Use the default .cache/calibration folder when mock=False + overrides = None + + robot = make_robot(robot_type, overrides=overrides, mock=mock) teleoperate(robot, teleop_time_s=1) teleoperate(robot, fps=30, teleop_time_s=1) teleoperate(robot, fps=60, teleop_time_s=1) del robot -@pytest.mark.parametrize("robot_type", available_robots) +@pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_calibrate(request, robot_type): - robot = make_robot(robot_type) - calibrate(robot) +def test_calibrate(tmpdir, request, robot_type, 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 + overrides_calibration_dir = [f"calibration_dir={calibration_dir}"] + + robot = make_robot(robot_type, overrides=overrides_calibration_dir, mock=mock) + calibrate(robot, arms=get_available_arms(robot)) del robot -@pytest.mark.parametrize("robot_type", available_robots) +@pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_record_without_cameras(tmpdir, request, robot_type): - root = Path(tmpdir) +def test_record_without_cameras(tmpdir, request, robot_type, mock): + # Avoid using cameras + overrides = ["~cameras"] + + if mock: + request.getfixturevalue("patch_builtins_input") + + # 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 + overrides.append(f"calibration_dir={calibration_dir}") + + root = Path(tmpdir) / "data" repo_id = "lerobot/debug" - robot = make_robot(robot_type, overrides=["~cameras"]) - record(robot, fps=30, root=root, repo_id=repo_id, warmup_time_s=1, episode_time_s=1, num_episodes=2) + robot = make_robot(robot_type, overrides=overrides, mock=mock) + record( + robot, + fps=30, + root=root, + repo_id=repo_id, + warmup_time_s=1, + episode_time_s=1, + num_episodes=2, + run_compute_stats=False, + push_to_hub=False, + video=False, + ) -@pytest.mark.parametrize("robot_type", available_robots) +@pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_record_and_replay_and_policy(tmpdir, request, robot_type): +def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): + if mock: + request.getfixturevalue("patch_builtins_input") + + # 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 + overrides = [f"calibration_dir={calibration_dir}"] + else: + # Use the default .cache/calibration folder when mock=False + overrides = None + + if robot_type == "aloha": + pytest.skip("TODO(rcadene): enable test once aloha_real and act_aloha_real are merged") + env_name = "koch_real" policy_name = "act_koch_real" - root = Path(tmpdir) + root = Path(tmpdir) / "data" repo_id = "lerobot/debug" - robot = make_robot(robot_type) + robot = make_robot(robot_type, overrides=overrides, mock=mock) dataset = record( - robot, fps=30, root=root, repo_id=repo_id, warmup_time_s=1, episode_time_s=1, num_episodes=2 + robot, + fps=30, + root=root, + repo_id=repo_id, + warmup_time_s=1, + episode_time_s=1, + num_episodes=2, + push_to_hub=False, + # TODO(rcadene, aliberts): test video=True + video=False, + # TODO(rcadene): display cameras through cv2 sometimes crashes on mac + display_cameras=False, ) replay(robot, episode=0, fps=30, root=root, repo_id=repo_id) @@ -65,6 +156,17 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type): policy = make_policy(hydra_cfg=cfg, dataset_stats=dataset.stats) - record(robot, policy, cfg, run_time_s=1) + record( + robot, + policy, + cfg, + warmup_time_s=1, + episode_time_s=1, + num_episodes=2, + run_compute_stats=False, + push_to_hub=False, + video=False, + display_cameras=False, + ) del robot diff --git a/tests/test_motors.py b/tests/test_motors.py index 48c2e8d8d..672234071 100644 --- a/tests/test_motors.py +++ b/tests/test_motors.py @@ -1,11 +1,23 @@ """ -Tests meant to be used locally and launched manually. +Tests for physical motors and their mocked versions. +If the physical motors are not connected to the computer, or not working, +the test will be skipped. -Example usage: +Example of running a specific test: ```bash pytest -sx tests/test_motors.py::test_find_port pytest -sx tests/test_motors.py::test_motors_bus ``` + +Example of running test on real dynamixel motors connected to the computer: +```bash +pytest -sx 'tests/test_motors.py::test_motors_bus[dynamixel-False]' +``` + +Example of running test on a mocked version of dynamixel motors: +```bash +pytest -sx 'tests/test_motors.py::test_motors_bus[dynamixel-True]' +``` """ # TODO(rcadene): measure fps in nightly? @@ -18,38 +30,31 @@ import numpy as np import pytest -from lerobot import available_robots -from lerobot.common.robot_devices.motors.utils import MotorsBus -from lerobot.common.robot_devices.robots.factory import make_robot +from lerobot.common.robot_devices.motors.dynamixel import find_port from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError -from lerobot.common.utils.utils import init_hydra_config -from tests.utils import ROBOT_CONFIG_PATH_TEMPLATE, require_robot - +from tests.utils import TEST_MOTOR_TYPES, make_motors_bus, require_motor -def make_motors_bus(robot_type: str) -> MotorsBus: - # Instantiate a robot and return one of its leader arms - config_path = ROBOT_CONFIG_PATH_TEMPLATE.format(robot=robot_type) - robot_cfg = init_hydra_config(config_path) - robot = make_robot(robot_cfg) - first_bus_name = list(robot.leader_arms.keys())[0] - motors_bus = robot.leader_arms[first_bus_name] - return motors_bus +@pytest.mark.parametrize("motor_type, mock", TEST_MOTOR_TYPES) +@require_motor +def test_find_port(request, motor_type, mock): + if mock: + request.getfixturevalue("patch_builtins_input") + with pytest.raises(OSError): + find_port() + else: + find_port() -@pytest.mark.parametrize("robot_type", available_robots) -@require_robot -def test_find_port(request, robot_type): - from lerobot.common.robot_devices.motors.dynamixel import find_port - find_port() +@pytest.mark.parametrize("motor_type, mock", TEST_MOTOR_TYPES) +@require_motor +def test_configure_motors_all_ids_1(request, motor_type, mock): + if mock: + request.getfixturevalue("patch_builtins_input") - -@pytest.mark.parametrize("robot_type", available_robots) -@require_robot -def test_configure_motors_all_ids_1(request, robot_type): input("Are you sure you want to re-configure the motors? Press enter to continue...") # This test expect the configuration was already correct. - motors_bus = make_motors_bus(robot_type) + motors_bus = make_motors_bus(motor_type, mock=mock) motors_bus.connect() motors_bus.write("Baud_Rate", [0] * len(motors_bus.motors)) motors_bus.set_bus_baudrate(9_600) @@ -57,16 +62,19 @@ def test_configure_motors_all_ids_1(request, robot_type): del motors_bus # Test configure - motors_bus = make_motors_bus(robot_type) + motors_bus = make_motors_bus(motor_type, mock=mock) motors_bus.connect() assert motors_bus.are_motors_configured() del motors_bus -@pytest.mark.parametrize("robot_type", available_robots) -@require_robot -def test_motors_bus(request, robot_type): - motors_bus = make_motors_bus(robot_type) +@pytest.mark.parametrize("motor_type, mock", TEST_MOTOR_TYPES) +@require_motor +def test_motors_bus(request, motor_type, mock): + if mock: + request.getfixturevalue("patch_builtins_input") + + motors_bus = make_motors_bus(motor_type, mock=mock) # Test reading and writting before connecting raises an error with pytest.raises(RobotDeviceNotConnectedError): @@ -80,7 +88,7 @@ def test_motors_bus(request, robot_type): del motors_bus # Test connecting - motors_bus = make_motors_bus(robot_type) + motors_bus = make_motors_bus(motor_type, mock=mock) motors_bus.connect() # Test connecting twice raises an error diff --git a/tests/test_robots.py b/tests/test_robots.py index 4ce3805ee..72f0c9444 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -1,10 +1,26 @@ """ -Tests meant to be used locally and launched manually. +Tests for physical robots and their mocked versions. +If the physical robots are not connected to the computer, or not working, +the test will be skipped. -Example usage: +Example of running a specific test: ```bash pytest -sx tests/test_robots.py::test_robot ``` + +Example of running test on real robots connected to the computer: +```bash +pytest -sx 'tests/test_robots.py::test_robot[koch-False]' +pytest -sx 'tests/test_robots.py::test_robot[koch_bimanual-False]' +pytest -sx 'tests/test_robots.py::test_robot[aloha-False]' +``` + +Example of running test on a mocked version of robots: +```bash +pytest -sx 'tests/test_robots.py::test_robot[koch-True]' +pytest -sx 'tests/test_robots.py::test_robot[koch_bimanual-True]' +pytest -sx 'tests/test_robots.py::test_robot[aloha-True]' +``` """ from pathlib import Path @@ -12,41 +28,42 @@ import pytest import torch -from lerobot import available_robots -from lerobot.common.robot_devices.robots.factory import make_robot as make_robot_from_cfg -from lerobot.common.robot_devices.robots.utils import Robot +from lerobot.common.robot_devices.robots.manipulator import ManipulatorRobot from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError -from lerobot.common.utils.utils import init_hydra_config -from tests.utils import ROBOT_CONFIG_PATH_TEMPLATE, require_robot - +from tests.utils import TEST_ROBOT_TYPES, make_robot, require_robot -def make_robot(robot_type: str, overrides: list[str] | None = None) -> Robot: - config_path = ROBOT_CONFIG_PATH_TEMPLATE.format(robot=robot_type) - robot_cfg = init_hydra_config(config_path, overrides) - robot = make_robot_from_cfg(robot_cfg) - return robot - -@pytest.mark.parametrize("robot_type", available_robots) +@pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot -def test_robot(tmpdir, request, robot_type): +def test_robot(tmpdir, request, robot_type, mock): # TODO(rcadene): measure fps in nightly? # TODO(rcadene): test logs # TODO(rcadene): add compatibility with other robots - from lerobot.common.robot_devices.robots.manipulator import ManipulatorRobot - # Save calibration preset - tmpdir = Path(tmpdir) - calibration_dir = tmpdir / robot_type + robot_kwargs = {"robot_type": robot_type} + + if robot_type == "aloha" and mock: + # To simplify unit test, we do not rerun manual calibration for Aloha mock=True. + # Instead, we use the files from '.cache/calibration/aloha_default' + overrides_calibration_dir = None + else: + if mock: + request.getfixturevalue("patch_builtins_input") + + # Create an empty calibration directory to trigger manual calibration + tmpdir = Path(tmpdir) + calibration_dir = tmpdir / robot_type + overrides_calibration_dir = [f"calibration_dir={calibration_dir}"] + robot_kwargs["calibration_dir"] = calibration_dir # Test connecting without devices raises an error - robot = ManipulatorRobot() + robot = ManipulatorRobot(**robot_kwargs) with pytest.raises(ValueError): robot.connect() del robot # Test using robot before connecting raises an error - robot = ManipulatorRobot() + robot = ManipulatorRobot(**robot_kwargs) with pytest.raises(RobotDeviceNotConnectedError): robot.teleop_step() with pytest.raises(RobotDeviceNotConnectedError): @@ -61,21 +78,23 @@ def test_robot(tmpdir, request, robot_type): # Test deleting the object without connecting first del robot - # Test connecting - robot = make_robot(robot_type, overrides=[f"calibration_dir={calibration_dir}"]) - robot.connect() # run the manual calibration precedure + # Test connecting (triggers manual calibration) + robot = make_robot(robot_type, overrides=overrides_calibration_dir, mock=mock) + robot.connect() assert robot.is_connected # Test connecting twice raises an error with pytest.raises(RobotDeviceAlreadyConnectedError): robot.connect() - # Test disconnecting with `__del__` - del robot + # TODO(rcadene, aliberts): Test disconnecting with `__del__` instead of `disconnect` + # del robot + robot.disconnect() # Test teleop can run - robot = make_robot(robot_type, overrides=[f"calibration_dir={calibration_dir}"]) - robot.calibration_dir = calibration_dir + robot = make_robot(robot_type, overrides=overrides_calibration_dir, mock=mock) + if overrides_calibration_dir is not None: + robot.calibration_dir = calibration_dir robot.connect() robot.teleop_step() @@ -121,4 +140,3 @@ def test_robot(tmpdir, request, robot_type): assert not robot.leader_arms[name].is_connected for name in robot.cameras: assert not robot.cameras[name].is_connected - del robot diff --git a/tests/utils.py b/tests/utils.py index db214aeac..0c4b94d89 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -13,13 +13,21 @@ # 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 os import platform +from copy import copy from functools import wraps import pytest import torch +from lerobot import available_cameras, available_motors, available_robots +from lerobot.common.robot_devices.cameras.utils import Camera +from lerobot.common.robot_devices.motors.utils import MotorsBus +from lerobot.common.robot_devices.robots.factory import make_robot as make_robot_from_cfg +from lerobot.common.robot_devices.robots.utils import Robot from lerobot.common.utils.import_utils import is_package_available +from lerobot.common.utils.utils import init_hydra_config DEVICE = "cuda" if torch.cuda.is_available() else "cpu" @@ -28,6 +36,32 @@ ROBOT_CONFIG_PATH_TEMPLATE = "lerobot/configs/robot/{robot}.yaml" +TEST_ROBOT_TYPES = [] +for robot_type in available_robots: + TEST_ROBOT_TYPES += [(robot_type, True), (robot_type, False)] + +TEST_CAMERA_TYPES = [] +for camera_type in available_cameras: + TEST_CAMERA_TYPES += [(camera_type, True), (camera_type, False)] + +TEST_MOTOR_TYPES = [] +for motor_type in available_motors: + TEST_MOTOR_TYPES += [(motor_type, True), (motor_type, False)] + +# Camera indices used for connecting physical cameras +OPENCV_CAMERA_INDEX = int(os.environ.get("LEROBOT_TEST_OPENCV_CAMERA_INDEX", 0)) +INTELREALSENSE_CAMERA_INDEX = int(os.environ.get("LEROBOT_TEST_INTELREALSENSE_CAMERA_INDEX", 128422271614)) + +DYNAMIXEL_PORT = "/dev/tty.usbmodem575E0032081" +DYNAMIXEL_MOTORS = { + "shoulder_pan": [1, "xl430-w250"], + "shoulder_lift": [2, "xl430-w250"], + "elbow_flex": [3, "xl330-m288"], + "wrist_flex": [4, "xl330-m288"], + "wrist_roll": [5, "xl330-m288"], + "gripper": [6, "xl330-m288"], +} + def require_x86_64_kernel(func): """ @@ -173,13 +207,136 @@ def wrapper(*args, **kwargs): # Access the pytest request context to get the is_robot_available fixture request = kwargs.get("request") robot_type = kwargs.get("robot_type") + mock = kwargs.get("mock") + if robot_type is None: + raise ValueError("The 'robot_type' must be an argument of the test function.") if request is None: - raise ValueError("The 'request' fixture must be passed to the test function as a parameter.") + raise ValueError("The 'request' fixture must be an argument of the test function.") + if mock is None: + raise ValueError("The 'mock' variable must be an argument of the test function.") - # The function `is_robot_available` is defined in `tests/conftest.py` - if not request.getfixturevalue("is_robot_available"): + # Run test with a real robot. Skip test if robot connection fails. + if not mock and not request.getfixturevalue("is_robot_available"): pytest.skip(f"A {robot_type} robot is not available.") + return func(*args, **kwargs) return wrapper + + +def require_camera(func): + @wraps(func) + def wrapper(*args, **kwargs): + # Access the pytest request context to get the is_camera_available fixture + request = kwargs.get("request") + camera_type = kwargs.get("camera_type") + mock = kwargs.get("mock") + + if request is None: + raise ValueError("The 'request' fixture must be an argument of the test function.") + if camera_type is None: + raise ValueError("The 'camera_type' must be an argument of the test function.") + if mock is None: + raise ValueError("The 'mock' variable must be an argument of the test function.") + + if not mock and not request.getfixturevalue("is_camera_available"): + pytest.skip(f"A {camera_type} camera is not available.") + + return func(*args, **kwargs) + + return wrapper + + +def require_motor(func): + @wraps(func) + def wrapper(*args, **kwargs): + # Access the pytest request context to get the is_motor_available fixture + request = kwargs.get("request") + motor_type = kwargs.get("motor_type") + mock = kwargs.get("mock") + + if request is None: + raise ValueError("The 'request' fixture must be an argument of the test function.") + if motor_type is None: + raise ValueError("The 'motor_type' must be an argument of the test function.") + if mock is None: + raise ValueError("The 'mock' variable must be an argument of the test function.") + + if not mock and not request.getfixturevalue("is_motor_available"): + pytest.skip(f"A {motor_type} motor is not available.") + + return func(*args, **kwargs) + + return wrapper + + +def make_robot(robot_type: str, overrides: list[str] | None = None, mock=False) -> Robot: + if mock: + overrides = [] if overrides is None else copy(overrides) + + # Explicitely add mock argument to the cameras and set it to true + # TODO(rcadene, aliberts): redesign when we drop hydra + if robot_type == "koch": + overrides.append("+leader_arms.main.mock=true") + overrides.append("+follower_arms.main.mock=true") + if "~cameras" not in overrides: + overrides.append("+cameras.laptop.mock=true") + overrides.append("+cameras.phone.mock=true") + + elif robot_type == "koch_bimanual": + overrides.append("+leader_arms.left.mock=true") + overrides.append("+leader_arms.right.mock=true") + overrides.append("+follower_arms.left.mock=true") + overrides.append("+follower_arms.right.mock=true") + if "~cameras" not in overrides: + overrides.append("+cameras.laptop.mock=true") + overrides.append("+cameras.phone.mock=true") + + elif robot_type == "aloha": + overrides.append("+leader_arms.left.mock=true") + overrides.append("+leader_arms.right.mock=true") + overrides.append("+follower_arms.left.mock=true") + overrides.append("+follower_arms.right.mock=true") + if "~cameras" not in overrides: + overrides.append("+cameras.cam_high.mock=true") + overrides.append("+cameras.cam_low.mock=true") + overrides.append("+cameras.cam_left_wrist.mock=true") + overrides.append("+cameras.cam_right_wrist.mock=true") + + else: + raise NotImplementedError(robot_type) + + config_path = ROBOT_CONFIG_PATH_TEMPLATE.format(robot=robot_type) + robot_cfg = init_hydra_config(config_path, overrides) + robot = make_robot_from_cfg(robot_cfg) + return robot + + +def make_camera(camera_type, **kwargs) -> Camera: + if camera_type == "opencv": + from lerobot.common.robot_devices.cameras.opencv import OpenCVCamera + + camera_index = kwargs.pop("camera_index", OPENCV_CAMERA_INDEX) + return OpenCVCamera(camera_index, **kwargs) + + elif camera_type == "intelrealsense": + from lerobot.common.robot_devices.cameras.intelrealsense import IntelRealSenseCamera + + camera_index = kwargs.pop("camera_index", INTELREALSENSE_CAMERA_INDEX) + return IntelRealSenseCamera(camera_index, **kwargs) + + else: + raise ValueError(f"The camera type '{camera_type}' is not valid.") + + +def make_motors_bus(motor_type: str, **kwargs) -> MotorsBus: + if motor_type == "dynamixel": + from lerobot.common.robot_devices.motors.dynamixel import DynamixelMotorsBus + + port = kwargs.pop("port", DYNAMIXEL_PORT) + motors = kwargs.pop("motors", DYNAMIXEL_MOTORS) + return DynamixelMotorsBus(port, motors, **kwargs) + + else: + raise ValueError(f"The motor type '{motor_type}' is not valid.") From 1a343c359101c7fe0099dc64c5fe867cfc4be898 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Fri, 4 Oct 2024 18:56:42 +0200 Subject: [PATCH 02/29] Add support for Stretch (hello-robot) (#409) Co-authored-by: Remi Co-authored-by: Remi Cadene --- .github/workflows/test.yml | 10 +- examples/7_get_started_with_real_robot.md | 2 +- examples/8_use_stretch.md | 158 + .../robot_devices/cameras/intelrealsense.py | 208 +- .../common/robot_devices/cameras/opencv.py | 148 +- lerobot/common/robot_devices/cameras/utils.py | 47 - .../common/robot_devices/motors/dynamixel.py | 73 +- .../common/robot_devices/robots/factory.py | 4 +- .../robot_devices/robots/manipulator.py | 4 + .../common/robot_devices/robots/stretch.py | 216 + lerobot/common/robot_devices/robots/utils.py | 6 +- lerobot/common/robot_devices/utils.py | 14 + lerobot/configs/robot/aloha.yaml | 8 +- lerobot/configs/robot/stretch.yaml | 24 + lerobot/scripts/control_robot.py | 64 +- poetry.lock | 5618 +++++++++++++---- pyproject.toml | 8 +- tests/mock_cv2.py | 17 + tests/mock_pyrealsense2.py | 37 +- tests/test_cameras.py | 38 +- 20 files changed, 5052 insertions(+), 1652 deletions(-) create mode 100644 examples/8_use_stretch.md create mode 100644 lerobot/common/robot_devices/robots/stretch.py create mode 100644 lerobot/configs/robot/stretch.yaml diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 953b1e4c3..10c90f841 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -37,7 +37,10 @@ jobs: lfs: true # Ensure LFS files are pulled - name: Install apt dependencies - run: sudo apt-get update && sudo apt-get install -y libegl1-mesa-dev ffmpeg + # portaudio19-dev is needed to install pyaudio + run: | + sudo apt-get update && \ + sudo apt-get install -y libegl1-mesa-dev ffmpeg portaudio19-dev - name: Install poetry run: | @@ -111,7 +114,10 @@ jobs: lfs: true # Ensure LFS files are pulled - name: Install apt dependencies - run: sudo apt-get update && sudo apt-get install -y libegl1-mesa-dev + # portaudio19-dev is needed to install pyaudio + run: | + sudo apt-get update && \ + sudo apt-get install -y libegl1-mesa-dev portaudio19-dev - name: Install poetry run: | diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index 50a2c6452..58bfc66c3 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -45,7 +45,7 @@ poetry install --sync --extras "dynamixel" ```bash conda install -c conda-forge ffmpeg pip uninstall opencv-python -conda install -c conda-forge opencv>=4.10.0 +conda install -c conda-forge "opencv>=4.10.0" ``` You are now ready to plug the 5V power supply to the motor bus of the leader arm (the smaller one) since all its motors only require 5V. diff --git a/examples/8_use_stretch.md b/examples/8_use_stretch.md new file mode 100644 index 000000000..fcd1cacee --- /dev/null +++ b/examples/8_use_stretch.md @@ -0,0 +1,158 @@ +This tutorial explains how to use [Stretch 3](https://hello-robot.com/stretch-3-product) with LeRobot. + +## Setup + +Familiarize yourself with Stretch by following its [tutorials](https://docs.hello-robot.com/0.3/getting_started/hello_robot/) (recommended). + +To use LeRobot on Stretch, 3 options are available: +- [tethered setup](https://docs.hello-robot.com/0.3/getting_started/connecting_to_stretch/#tethered-setup) +- [untethered setup](https://docs.hello-robot.com/0.3/getting_started/connecting_to_stretch/#untethered-setup) +- ssh directly into Stretch (you will first need to install and configure openssh-server on stretch using one of the two above setups) + + +## Install LeRobot + +On Stretch's CLI, follow these steps: + +1. [Install Miniconda](https://docs.anaconda.com/miniconda/#quick-command-line-install): +```bash +mkdir -p ~/miniconda3 +wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh +bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3 +rm ~/miniconda3/miniconda.sh +~/miniconda3/bin/conda init bash +``` + +2. Comment out these lines in `~/.profile` (this can mess up paths used by conda and ~/.local/bin should already be in your PATH) +``` +# set PATH so it includes user's private bin if it exists +if [ -d "$HOME/.local/bin" ] ; then + PATH="$HOME/.local/bin:$PATH" +fi +``` + +3. Restart shell or `source ~/.bashrc` + +4. Create and activate a fresh conda environment for lerobot +```bash +conda create -y -n lerobot python=3.10 && conda activate lerobot +``` + +5. Clone LeRobot: +```bash +git clone https://github.com/huggingface/lerobot.git ~/lerobot +``` + +6. Install LeRobot with stretch dependencies: +```bash +cd ~/lerobot && pip install -e ".[stretch]" +``` + +> **Note:** If you get this message, you can ignore it: `ERROR: pip's dependency resolver does not currently take into account all the packages that are installed.` + +And install extra dependencies for recording datasets on Linux: +```bash +conda install -y -c conda-forge ffmpeg +pip uninstall -y opencv-python +conda install -y -c conda-forge "opencv>=4.10.0" +``` + +7. Run a [system check](https://docs.hello-robot.com/0.3/getting_started/stretch_hardware_overview/#system-check) to make sure your robot is ready: +```bash +stretch_system_check.py +``` + +> **Note:** You may need to free the "robot process" after booting Stretch by running `stretch_free_robot_process.py`. For more info this Stretch's [doc](https://docs.hello-robot.com/0.3/getting_started/stretch_hardware_overview/#turning-off-gamepad-teleoperation). + +You should get something like this: +```bash +For use with S T R E T C H (R) from Hello Robot Inc. +--------------------------------------------------------------------- + +Model = Stretch 3 +Tool = DexWrist 3 w/ Gripper +Serial Number = stretch-se3-3054 + +---- Checking Hardware ---- +[Pass] Comms are ready +[Pass] Actuators are ready +[Warn] Sensors not ready (IMU AZ = -10.19 out of range -10.1 to -9.5) +[Pass] Battery voltage is 13.6 V + +---- Checking Software ---- +[Pass] Ubuntu 22.04 is ready +[Pass] All APT pkgs are setup correctly +[Pass] Firmware is up-to-date +[Pass] Python pkgs are up-to-date +[Pass] ROS2 Humble is ready +``` + +## Teleoperate, record a dataset and run a policy + +**Calibrate (Optional)** +Before operating Stretch, you need to [home](https://docs.hello-robot.com/0.3/getting_started/stretch_hardware_overview/#homing) it first. Be mindful about giving Stretch some space as this procedure will move the robot's arm and gripper. Now run this command: +```bash +python lerobot/scripts/control_robot.py calibrate \ + --robot-path lerobot/configs/robot/stretch.yaml +``` +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. + +**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). + +Now try out teleoperation (see above documentation to learn about the gamepad controls): +```bash +python lerobot/scripts/control_robot.py teleoperate \ + --robot-path lerobot/configs/robot/stretch.yaml +``` +This is essentially the same as running `stretch_gamepad_teleop.py` + +**Record a dataset** +Once you're familiar with the gamepad controls and after a bit of practice, you can try to record your first dataset with Stretch. + +If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens): +```bash +huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential +``` + +Store your Hugging Face repository name in a variable to run these commands: +```bash +HF_USER=$(huggingface-cli whoami | head -n 1) +echo $HF_USER +``` + +Record one episode: +```bash +python lerobot/scripts/control_robot.py record \ + --robot-path lerobot/configs/robot/stretch.yaml \ + --fps 20 \ + --root data \ + --repo-id ${HF_USER}/stretch_test \ + --tags stretch tutorial \ + --warmup-time-s 3 \ + --episode-time-s 40 \ + --reset-time-s 10 \ + --num-episodes 1 \ + --push-to-hub 0 +``` + +> **Note:** If you're using ssh to connect to Stretch and run this script, you won't be able to visualize its cameras feed (though they will still be recording). To see the cameras stream, use [tethered](https://docs.hello-robot.com/0.3/getting_started/connecting_to_stretch/#tethered-setup) or [untethered setup](https://docs.hello-robot.com/0.3/getting_started/connecting_to_stretch/#untethered-setup). + +**Replay an episode** +Now try to replay this episode (make sure the robot's initial position is the same): +```bash +python lerobot/scripts/control_robot.py replay \ + --robot-path lerobot/configs/robot/stretch.yaml \ + --fps 20 \ + --root data \ + --repo-id ${HF_USER}/stretch_test \ + --episode 0 +``` + +Follow [previous tutorial](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#4-train-a-policy-on-your-data) to train a policy on your data and run inference on your robot. You will need to adapt the code for Stretch. + +> TODO(rcadene, aliberts): Add already setup environment and policy yaml configuration files + +If you need help, please reach out on Discord in the channel `#stretch3-mobile-arm`. diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index c949109b8..66c7fe5cb 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -10,6 +10,7 @@ import threading import time import traceback +from collections import Counter from dataclasses import dataclass, replace from pathlib import Path from threading import Thread @@ -27,47 +28,49 @@ SERIAL_NUMBER_INDEX = 1 -def find_camera_indices(raise_when_empty=True, mock=False) -> list[int]: +def find_cameras(raise_when_empty=True, mock=False) -> list[dict]: """ - Find the serial numbers of the Intel RealSense cameras + Find the names and the serial numbers of the Intel RealSense cameras connected to the computer. """ if mock: - from tests.mock_pyrealsense2 import ( - RSCameraInfo, - RSContext, - ) + import tests.mock_pyrealsense2 as rs else: - from pyrealsense2 import camera_info as RSCameraInfo # noqa: N812 - from pyrealsense2 import context as RSContext # noqa: N812 + import pyrealsense2 as rs - camera_ids = [] - for device in RSContext().query_devices(): - serial_number = int(device.get_info(RSCameraInfo(SERIAL_NUMBER_INDEX))) - camera_ids.append(serial_number) + cameras = [] + for device in rs.context().query_devices(): + serial_number = int(device.get_info(rs.camera_info(SERIAL_NUMBER_INDEX))) + name = device.get_info(rs.camera_info.name) + cameras.append( + { + "serial_number": serial_number, + "name": name, + } + ) - if raise_when_empty and len(camera_ids) == 0: + if raise_when_empty and len(cameras) == 0: raise OSError( "Not a single camera was detected. Try re-plugging, or re-installing `librealsense` and its python wrapper `pyrealsense2`, or updating the firmware." ) - return camera_ids + return cameras -def save_image(img_array, camera_idx, frame_index, images_dir): +def save_image(img_array, serial_number, frame_index, images_dir): try: img = Image.fromarray(img_array) - path = images_dir / f"camera_{camera_idx}_frame_{frame_index:06d}.png" + path = images_dir / f"camera_{serial_number}_frame_{frame_index:06d}.png" path.parent.mkdir(parents=True, exist_ok=True) img.save(str(path), quality=100) logging.info(f"Saved image: {path}") except Exception as e: - logging.error(f"Failed to save image for camera {camera_idx} frame {frame_index}: {e}") + logging.error(f"Failed to save image for camera {serial_number} frame {frame_index}: {e}") def save_images_from_cameras( images_dir: Path, - camera_ids: list[int] | None = None, + serial_numbers: list[int] | None = None, fps=None, width=None, height=None, @@ -76,23 +79,25 @@ def save_images_from_cameras( ): """ Initializes all the cameras and saves images to the directory. Useful to visually identify the camera - associated to a given camera index. + associated to a given serial number. """ - if camera_ids is None: - camera_ids = find_camera_indices(mock=mock) + if serial_numbers is None or len(serial_numbers) == 0: + camera_infos = find_cameras(mock=mock) + serial_numbers = [cam["serial_number"] for cam in camera_infos] if mock: - from tests.mock_cv2 import COLOR_RGB2BGR, cvtColor + import tests.mock_cv2 as cv2 else: - from cv2 import COLOR_RGB2BGR, cvtColor + import cv2 print("Connecting cameras") cameras = [] - for cam_idx in camera_ids: - camera = IntelRealSenseCamera(cam_idx, fps=fps, width=width, height=height, mock=mock) + for cam_sn in serial_numbers: + print(f"{cam_sn=}") + camera = IntelRealSenseCamera(cam_sn, fps=fps, width=width, height=height, mock=mock) camera.connect() print( - f"IntelRealSenseCamera({camera.camera_index}, fps={camera.fps}, width={camera.width}, height={camera.height}, color_mode={camera.color_mode})" + f"IntelRealSenseCamera({camera.serial_number}, fps={camera.fps}, width={camera.width}, height={camera.height}, color_mode={camera.color_mode})" ) cameras.append(camera) @@ -107,7 +112,7 @@ def save_images_from_cameras( frame_index = 0 start_time = time.perf_counter() try: - with concurrent.futures.ThreadPoolExecutor(max_workers=4) as executor: + with concurrent.futures.ThreadPoolExecutor(max_workers=1) as executor: while True: now = time.perf_counter() @@ -118,12 +123,12 @@ def save_images_from_cameras( if image is None: print("No Frame") - bgr_converted_image = cvtColor(image, COLOR_RGB2BGR) + bgr_converted_image = cv2.cvtColor(image, cv2.COLOR_RGB2BGR) executor.submit( save_image, bgr_converted_image, - camera.camera_index, + camera.serial_number, frame_index, images_dir, ) @@ -155,6 +160,7 @@ class IntelRealSenseCameraConfig: IntelRealSenseCameraConfig(90, 640, 480) IntelRealSenseCameraConfig(30, 1280, 720) IntelRealSenseCameraConfig(30, 640, 480, use_depth=True) + IntelRealSenseCameraConfig(30, 640, 480, rotation=90) ``` """ @@ -164,6 +170,7 @@ class IntelRealSenseCameraConfig: color_mode: str = "rgb" use_depth: bool = False force_hardware_reset: bool = True + rotation: int | None = None mock: bool = False def __post_init__(self): @@ -180,13 +187,15 @@ def __post_init__(self): f"but {self.fps=}, {self.width=}, {self.height=} were provided." ) + if self.rotation not in [-90, None, 90, 180]: + raise ValueError(f"`rotation` must be in [-90, None, 90, 180] (got {self.rotation})") + class IntelRealSenseCamera: """ The IntelRealSenseCamera class is similar to OpenCVCamera class but adds additional features for Intel Real Sense cameras: - - camera_index corresponds to the serial number of the camera, - - camera_index won't randomly change as it can be the case of OpenCVCamera for Linux, - - read is more reliable than OpenCVCamera, + - is instantiated with the serial number of the camera - won't randomly change as it can be the case of OpenCVCamera for Linux, + - can also be instantiated with the camera's name — if it's unique — using IntelRealSenseCamera.init_from_name(), - depth map can be returned. To find the camera indices of your cameras, you can run our utility script that will save a few frames for each camera: @@ -199,8 +208,10 @@ class IntelRealSenseCamera: Example of usage: ```python - camera_index = 128422271347 - camera = IntelRealSenseCamera(camera_index) + # Instantiate with its serial number + camera = IntelRealSenseCamera(128422271347) + # Or by its name if it's unique + camera = IntelRealSenseCamera.init_from_name("Intel RealSense D405") camera.connect() color_image = camera.read() # when done using the camera, consider disconnecting @@ -209,19 +220,19 @@ class IntelRealSenseCamera: Example of changing default fps, width, height and color_mode: ```python - camera = IntelRealSenseCamera(camera_index, fps=30, width=1280, height=720) + camera = IntelRealSenseCamera(serial_number, fps=30, width=1280, height=720) camera = connect() # applies the settings, might error out if these settings are not compatible with the camera - camera = IntelRealSenseCamera(camera_index, fps=90, width=640, height=480) + camera = IntelRealSenseCamera(serial_number, fps=90, width=640, height=480) camera = connect() - camera = IntelRealSenseCamera(camera_index, fps=90, width=640, height=480, color_mode="bgr") + camera = IntelRealSenseCamera(serial_number, fps=90, width=640, height=480, color_mode="bgr") camera = connect() ``` Example of returning depth: ```python - camera = IntelRealSenseCamera(camera_index, use_depth=True) + camera = IntelRealSenseCamera(serial_number, use_depth=True) camera.connect() color_image, depth_map = camera.read() ``` @@ -229,7 +240,7 @@ class IntelRealSenseCamera: def __init__( self, - camera_index: int, + serial_number: int, config: IntelRealSenseCameraConfig | None = None, **kwargs, ): @@ -239,7 +250,7 @@ def __init__( # Overwrite the config arguments using kwargs config = replace(config, **kwargs) - self.camera_index = camera_index + self.serial_number = serial_number self.fps = config.fps self.width = config.width self.height = config.height @@ -256,41 +267,69 @@ def __init__( self.depth_map = None self.logs = {} + if self.mock: + import tests.mock_cv2 as cv2 + else: + import cv2 + + # TODO(alibets): Do we keep original width/height or do we define them after rotation? + self.rotation = None + if config.rotation == -90: + self.rotation = cv2.ROTATE_90_COUNTERCLOCKWISE + elif config.rotation == 90: + self.rotation = cv2.ROTATE_90_CLOCKWISE + elif config.rotation == 180: + self.rotation = cv2.ROTATE_180 + + @classmethod + def init_from_name(cls, name: str, config: IntelRealSenseCameraConfig | None = None, **kwargs): + camera_infos = find_cameras() + camera_names = [cam["name"] for cam in camera_infos] + this_name_count = Counter(camera_names)[name] + if this_name_count > 1: + # TODO(aliberts): Test this with multiple identical cameras (Aloha) + raise ValueError( + f"Multiple {name} cameras have been detected. Please use their serial number to instantiate them." + ) + + name_to_serial_dict = {cam["name"]: cam["serial_number"] for cam in camera_infos} + cam_sn = name_to_serial_dict[name] + + if config is None: + config = IntelRealSenseCameraConfig() + + # Overwrite the config arguments using kwargs + config = replace(config, **kwargs) + + return cls(serial_number=cam_sn, config=config, **kwargs) + def connect(self): if self.is_connected: raise RobotDeviceAlreadyConnectedError( - f"IntelRealSenseCamera({self.camera_index}) is already connected." + f"IntelRealSenseCamera({self.serial_number}) is already connected." ) if self.mock: - from tests.mock_pyrealsense2 import ( - RSConfig, - RSFormat, - RSPipeline, - RSStream, - ) + import tests.mock_pyrealsense2 as rs else: - from pyrealsense2 import config as RSConfig # noqa: N812 - from pyrealsense2 import format as RSFormat # noqa: N812 - from pyrealsense2 import pipeline as RSPipeline # noqa: N812 - from pyrealsense2 import stream as RSStream # noqa: N812 + import pyrealsense2 as rs - config = RSConfig() - config.enable_device(str(self.camera_index)) + config = rs.config() + config.enable_device(str(self.serial_number)) if self.fps and self.width and self.height: # TODO(rcadene): can we set rgb8 directly? - config.enable_stream(RSStream.color, self.width, self.height, RSFormat.rgb8, self.fps) + config.enable_stream(rs.stream.color, self.width, self.height, rs.format.rgb8, self.fps) else: - config.enable_stream(RSStream.color) + config.enable_stream(rs.stream.color) if self.use_depth: if self.fps and self.width and self.height: - config.enable_stream(RSStream.depth, self.width, self.height, RSFormat.z16, self.fps) + config.enable_stream(rs.stream.depth, self.width, self.height, rs.format.z16, self.fps) else: - config.enable_stream(RSStream.depth) + config.enable_stream(rs.stream.depth) - self.camera = RSPipeline() + self.camera = rs.pipeline() try: profile = self.camera.start(config) is_camera_open = True @@ -301,17 +340,18 @@ def connect(self): # If the camera doesn't work, display the camera indices corresponding to # valid cameras. if not is_camera_open: - # Verify that the provided `camera_index` is valid before printing the traceback - available_cam_ids = find_camera_indices() - if self.camera_index not in available_cam_ids: + # Verify that the provided `serial_number` is valid before printing the traceback + camera_infos = find_cameras() + serial_numbers = [cam["serial_number"] for cam in camera_infos] + if self.serial_number not in serial_numbers: raise ValueError( - f"`camera_index` is expected to be one of these available cameras {available_cam_ids}, but {self.camera_index} is provided instead. " - "To find the camera index you should use, run `python lerobot/common/robot_devices/cameras/intelrealsense.py`." + f"`serial_number` is expected to be one of these available cameras {serial_numbers}, but {self.serial_number} is provided instead. " + "To find the serial number you should use, run `python lerobot/common/robot_devices/cameras/intelrealsense.py`." ) - raise OSError(f"Can't access IntelRealSenseCamera({self.camera_index}).") + raise OSError(f"Can't access IntelRealSenseCamera({self.serial_number}).") - color_stream = profile.get_stream(RSStream.color) + color_stream = profile.get_stream(rs.stream.color) color_profile = color_stream.as_video_stream_profile() actual_fps = color_profile.fps() actual_width = color_profile.width() @@ -321,15 +361,15 @@ def connect(self): if self.fps is not None and not math.isclose(self.fps, actual_fps, rel_tol=1e-3): # Using `OSError` since it's a broad that encompasses issues related to device communication raise OSError( - f"Can't set {self.fps=} for IntelRealSenseCamera({self.camera_index}). Actual value is {actual_fps}." + f"Can't set {self.fps=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_fps}." ) if self.width is not None and self.width != actual_width: raise OSError( - f"Can't set {self.width=} for IntelRealSenseCamera({self.camera_index}). Actual value is {actual_width}." + f"Can't set {self.width=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_width}." ) if self.height is not None and self.height != actual_height: raise OSError( - f"Can't set {self.height=} for IntelRealSenseCamera({self.camera_index}). Actual value is {actual_height}." + f"Can't set {self.height=} for IntelRealSenseCamera({self.serial_number}). Actual value is {actual_height}." ) self.fps = round(actual_fps) @@ -350,9 +390,14 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar """ if not self.is_connected: raise RobotDeviceNotConnectedError( - f"IntelRealSenseCamera({self.camera_index}) is not connected. Try running `camera.connect()` first." + f"IntelRealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." ) + if self.mock: + import tests.mock_cv2 as cv2 + else: + import cv2 + start_time = time.perf_counter() frame = self.camera.wait_for_frames(timeout_ms=5000) @@ -360,7 +405,7 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar color_frame = frame.get_color_frame() if not color_frame: - raise OSError(f"Can't capture color image from IntelRealSenseCamera({self.camera_index}).") + raise OSError(f"Can't capture color image from IntelRealSenseCamera({self.serial_number}).") color_image = np.asanyarray(color_frame.get_data()) @@ -372,12 +417,7 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar # IntelRealSense uses RGB format as default (red, green, blue). if requested_color_mode == "bgr": - if self.mock: - from tests.mock_cv2 import COLOR_RGB2BGR, cvtColor - else: - from cv2 import COLOR_RGB2BGR, cvtColor - - color_image = cvtColor(color_image, COLOR_RGB2BGR) + color_image = cv2.cvtColor(color_image, cv2.COLOR_RGB2BGR) h, w, _ = color_image.shape if h != self.height or w != self.width: @@ -385,6 +425,9 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar f"Can't capture color image with expected height and width ({self.height} x {self.width}). ({h} x {w}) returned instead." ) + if self.rotation is not None: + color_image = cv2.rotate(color_image, self.rotation) + # log the number of seconds it took to read the image self.logs["delta_timestamp_s"] = time.perf_counter() - start_time @@ -394,7 +437,7 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar if self.use_depth: depth_frame = frame.get_depth_frame() if not depth_frame: - raise OSError(f"Can't capture depth image from IntelRealSenseCamera({self.camera_index}).") + raise OSError(f"Can't capture depth image from IntelRealSenseCamera({self.serial_number}).") depth_map = np.asanyarray(depth_frame.get_data()) @@ -404,6 +447,9 @@ def read(self, temporary_color: str | None = None) -> np.ndarray | tuple[np.ndar f"Can't capture depth map with expected height and width ({self.height} x {self.width}). ({h} x {w}) returned instead." ) + if self.rotation is not None: + depth_map = cv2.rotate(depth_map, self.rotation) + return color_image, depth_map else: return color_image @@ -419,7 +465,7 @@ def async_read(self): """Access the latest color image""" if not self.is_connected: raise RobotDeviceNotConnectedError( - f"IntelRealSenseCamera({self.camera_index}) is not connected. Try running `camera.connect()` first." + f"IntelRealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." ) if self.thread is None: @@ -446,7 +492,7 @@ def async_read(self): def disconnect(self): if not self.is_connected: raise RobotDeviceNotConnectedError( - f"IntelRealSenseCamera({self.camera_index}) is not connected. Try running `camera.connect()` first." + f"IntelRealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." ) if self.thread is not None and self.thread.is_alive(): @@ -471,11 +517,11 @@ def __del__(self): description="Save a few frames using `IntelRealSenseCamera` for all cameras connected to the computer, or a selected subset." ) parser.add_argument( - "--camera-ids", + "--serial-numbers", type=int, nargs="*", default=None, - help="List of camera indices used to instantiate the `IntelRealSenseCamera`. If not provided, find and use all available camera indices.", + help="List of serial numbers used to instantiate the `IntelRealSenseCamera`. If not provided, find and use all available camera indices.", ) parser.add_argument( "--fps", diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index 4e5f5d183..7de4bc4e0 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -31,29 +31,48 @@ MAX_OPENCV_INDEX = 60 -def find_camera_indices(raise_when_empty=False, max_index_search_range=MAX_OPENCV_INDEX, mock=False): +def find_cameras(raise_when_empty=False, max_index_search_range=MAX_OPENCV_INDEX, mock=False) -> list[dict]: + cameras = [] if platform.system() == "Linux": - # Linux uses camera ports print("Linux detected. Finding available camera indices through scanning '/dev/video*' ports") - possible_camera_ids = [] - for port in Path("/dev").glob("video*"): - camera_idx = int(str(port).replace("/dev/video", "")) - possible_camera_ids.append(camera_idx) + possible_ports = [str(port) for port in Path("/dev").glob("video*")] + ports = _find_cameras(possible_ports, mock=mock) + for port in ports: + cameras.append( + { + "port": port, + "index": int(port.removeprefix("/dev/video")), + } + ) else: print( "Mac or Windows detected. Finding available camera indices through " f"scanning all indices from 0 to {MAX_OPENCV_INDEX}" ) - possible_camera_ids = range(max_index_search_range) + possible_indices = range(max_index_search_range) + indices = _find_cameras(possible_indices, mock=mock) + for index in indices: + cameras.append( + { + "port": None, + "index": index, + } + ) + return cameras + + +def _find_cameras( + possible_camera_ids: list[int | str], raise_when_empty=False, mock=False +) -> list[int | str]: if mock: - from tests.mock_cv2 import VideoCapture + import tests.mock_cv2 as cv2 else: - from cv2 import VideoCapture + import cv2 camera_ids = [] for camera_idx in possible_camera_ids: - camera = VideoCapture(camera_idx) + camera = cv2.VideoCapture(camera_idx) is_open = camera.isOpened() camera.release() @@ -70,6 +89,16 @@ def find_camera_indices(raise_when_empty=False, max_index_search_range=MAX_OPENC return camera_ids +def is_valid_unix_path(path: str) -> bool: + """Note: if 'path' points to a symlink, this will return True only if the target exists""" + p = Path(path) + return p.is_absolute() and p.exists() + + +def get_camera_index_from_unix_port(port: Path) -> int: + return int(str(port.resolve()).removeprefix("/dev/video")) + + def save_image(img_array, camera_index, frame_index, images_dir): img = Image.fromarray(img_array) path = images_dir / f"camera_{camera_index:02d}_frame_{frame_index:06d}.png" @@ -79,7 +108,7 @@ def save_image(img_array, camera_index, frame_index, images_dir): def save_images_from_cameras( images_dir: Path, - camera_ids: list[int] | None = None, + camera_ids: list | None = None, fps=None, width=None, height=None, @@ -90,8 +119,9 @@ def save_images_from_cameras( Initializes all the cameras and saves images to the directory. Useful to visually identify the camera associated to a given camera index. """ - if camera_ids is None: - camera_ids = find_camera_indices(mock=mock) + if camera_ids is None or len(camera_ids) == 0: + camera_infos = find_cameras(mock=mock) + camera_ids = [cam["index"] for cam in camera_infos] print("Connecting cameras") cameras = [] @@ -114,7 +144,7 @@ def save_images_from_cameras( print(f"Saving images to {images_dir}") frame_index = 0 start_time = time.perf_counter() - with concurrent.futures.ThreadPoolExecutor(max_workers=4) as executor: + with concurrent.futures.ThreadPoolExecutor(max_workers=1) as executor: while True: now = time.perf_counter() @@ -126,7 +156,7 @@ def save_images_from_cameras( executor.submit( save_image, image, - camera.camera_index, + camera.index, frame_index, images_dir, ) @@ -135,11 +165,11 @@ def save_images_from_cameras( dt_s = time.perf_counter() - now busy_wait(1 / fps - dt_s) + print(f"Frame: {frame_index:04d}\tLatency (ms): {(time.perf_counter() - now) * 1000:.2f}") + if time.perf_counter() - start_time > record_time_s: break - print(f"Frame: {frame_index:04d}\tLatency (ms): {(time.perf_counter() - now) * 1000:.2f}") - frame_index += 1 print(f"Images have been saved to {images_dir}") @@ -162,6 +192,7 @@ class OpenCVCameraConfig: width: int | None = None height: int | None = None color_mode: str = "rgb" + rotation: int | None = None mock: bool = False def __post_init__(self): @@ -170,6 +201,9 @@ def __post_init__(self): f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." ) + if self.rotation not in [-90, None, 90, 180]: + raise ValueError(f"`rotation` must be in [-90, None, 90, 180] (got {self.rotation})") + class OpenCVCamera: """ @@ -210,7 +244,7 @@ class OpenCVCamera: ``` """ - def __init__(self, camera_index: int, config: OpenCVCameraConfig | None = None, **kwargs): + def __init__(self, camera_index: int | str, config: OpenCVCameraConfig | None = None, **kwargs): if config is None: config = OpenCVCameraConfig() @@ -218,6 +252,19 @@ def __init__(self, camera_index: int, config: OpenCVCameraConfig | None = None, config = replace(config, **kwargs) self.camera_index = camera_index + self.port = None + + # Linux uses ports for connecting to cameras + if platform.system() == "Linux": + if isinstance(self.camera_index, int): + self.port = Path(f"/dev/video{self.camera_index}") + elif isinstance(self.camera_index, str) and is_valid_unix_path(self.camera_index): + self.port = Path(self.camera_index) + # Retrieve the camera index from a potentially symlinked path + self.camera_index = get_camera_index_from_unix_port(self.port) + else: + raise ValueError(f"Please check the provided camera_index: {camera_index}") + self.fps = config.fps self.width = config.width self.height = config.height @@ -231,34 +278,37 @@ def __init__(self, camera_index: int, config: OpenCVCameraConfig | None = None, self.color_image = None self.logs = {} + if self.mock: + import tests.mock_cv2 as cv2 + else: + import cv2 + + # TODO(aliberts): Do we keep original width/height or do we define them after rotation? + self.rotation = None + if config.rotation == -90: + self.rotation = cv2.ROTATE_90_COUNTERCLOCKWISE + elif config.rotation == 90: + self.rotation = cv2.ROTATE_90_CLOCKWISE + elif config.rotation == 180: + self.rotation = cv2.ROTATE_180 + def connect(self): if self.is_connected: raise RobotDeviceAlreadyConnectedError(f"OpenCVCamera({self.camera_index}) is already connected.") if self.mock: - from tests.mock_cv2 import ( - CAP_PROP_FPS, - CAP_PROP_FRAME_HEIGHT, - CAP_PROP_FRAME_WIDTH, - VideoCapture, - ) + import tests.mock_cv2 as cv2 else: - from cv2 import ( - CAP_PROP_FPS, - CAP_PROP_FRAME_HEIGHT, - CAP_PROP_FRAME_WIDTH, - VideoCapture, - setNumThreads, - ) + import cv2 # Use 1 thread to avoid blocking the main thread. Especially useful during data collection # when other threads are used to save the images. - setNumThreads(1) + cv2.setNumThreads(1) camera_idx = f"/dev/video{self.camera_index}" if platform.system() == "Linux" else self.camera_index # First create a temporary camera trying to access `camera_index`, # and verify it is a valid camera by calling `isOpened`. - tmp_camera = VideoCapture(camera_idx) + tmp_camera = cv2.VideoCapture(camera_idx) is_camera_open = tmp_camera.isOpened() # Release camera to make it accessible for `find_camera_indices` tmp_camera.release() @@ -268,7 +318,8 @@ def connect(self): # valid cameras. if not is_camera_open: # Verify that the provided `camera_index` is valid before printing the traceback - available_cam_ids = find_camera_indices() + cameras_info = find_cameras() + available_cam_ids = [cam["index"] for cam in cameras_info] if self.camera_index not in available_cam_ids: raise ValueError( f"`camera_index` is expected to be one of these available cameras {available_cam_ids}, but {self.camera_index} is provided instead. " @@ -280,18 +331,18 @@ def connect(self): # Secondly, create the camera that will be used downstream. # Note: For some unknown reason, calling `isOpened` blocks the camera which then # needs to be re-created. - self.camera = VideoCapture(camera_idx) + self.camera = cv2.VideoCapture(camera_idx) if self.fps is not None: - self.camera.set(CAP_PROP_FPS, self.fps) + self.camera.set(cv2.CAP_PROP_FPS, self.fps) if self.width is not None: - self.camera.set(CAP_PROP_FRAME_WIDTH, self.width) + self.camera.set(cv2.CAP_PROP_FRAME_WIDTH, self.width) if self.height is not None: - self.camera.set(CAP_PROP_FRAME_HEIGHT, self.height) + self.camera.set(cv2.CAP_PROP_FRAME_HEIGHT, self.height) - actual_fps = self.camera.get(CAP_PROP_FPS) - actual_width = self.camera.get(CAP_PROP_FRAME_WIDTH) - actual_height = self.camera.get(CAP_PROP_FRAME_HEIGHT) + actual_fps = self.camera.get(cv2.CAP_PROP_FPS) + actual_width = self.camera.get(cv2.CAP_PROP_FRAME_WIDTH) + actual_height = self.camera.get(cv2.CAP_PROP_FRAME_HEIGHT) # Using `math.isclose` since actual fps can be a float (e.g. 29.9 instead of 30) if self.fps is not None and not math.isclose(self.fps, actual_fps, rel_tol=1e-3): @@ -299,11 +350,11 @@ def connect(self): raise OSError( f"Can't set {self.fps=} for OpenCVCamera({self.camera_index}). Actual value is {actual_fps}." ) - if self.width is not None and self.width != actual_width: + if self.width is not None and not math.isclose(self.width, actual_width, rel_tol=1e-3): raise OSError( f"Can't set {self.width=} for OpenCVCamera({self.camera_index}). Actual value is {actual_width}." ) - if self.height is not None and self.height != actual_height: + if self.height is not None and not math.isclose(self.height, actual_height, rel_tol=1e-3): raise OSError( f"Can't set {self.height=} for OpenCVCamera({self.camera_index}). Actual value is {actual_height}." ) @@ -345,11 +396,11 @@ def read(self, temporary_color_mode: str | None = None) -> np.ndarray: # so we convert the image color from BGR to RGB. if requested_color_mode == "rgb": if self.mock: - from tests.mock_cv2 import COLOR_BGR2RGB, cvtColor + import tests.mock_cv2 as cv2 else: - from cv2 import COLOR_BGR2RGB, cvtColor + import cv2 - color_image = cvtColor(color_image, COLOR_BGR2RGB) + color_image = cv2.cvtColor(color_image, cv2.COLOR_BGR2RGB) h, w, _ = color_image.shape if h != self.height or w != self.width: @@ -357,6 +408,9 @@ def read(self, temporary_color_mode: str | None = None) -> np.ndarray: f"Can't capture color image with expected height and width ({self.height} x {self.width}). ({h} x {w}) returned instead." ) + if self.rotation is not None: + color_image = cv2.rotate(color_image, self.rotation) + # log the number of seconds it took to read the image self.logs["delta_timestamp_s"] = time.perf_counter() - start_time @@ -455,7 +509,7 @@ def __del__(self): parser.add_argument( "--record-time-s", type=float, - default=2.0, + default=4.0, help="Set the number of seconds used to record the frames. By default, 2 seconds.", ) args = parser.parse_args() diff --git a/lerobot/common/robot_devices/cameras/utils.py b/lerobot/common/robot_devices/cameras/utils.py index 0f329d9fb..7904a57a5 100644 --- a/lerobot/common/robot_devices/cameras/utils.py +++ b/lerobot/common/robot_devices/cameras/utils.py @@ -1,55 +1,8 @@ -from pathlib import Path from typing import Protocol -import cv2 -import einops import numpy as np -def write_shape_on_image_inplace(image): - height, width = image.shape[:2] - text = f"Width: {width} Height: {height}" - - # Define the font, scale, color, and thickness - font = cv2.FONT_HERSHEY_SIMPLEX - font_scale = 1 - color = (255, 0, 0) # Blue in BGR - thickness = 2 - - position = (10, height - 10) # 10 pixels from the bottom-left corner - cv2.putText(image, text, position, font, font_scale, color, thickness) - - -def save_color_image(image, path, write_shape=False): - path = Path(path) - path.parent.mkdir(parents=True, exist_ok=True) - if write_shape: - write_shape_on_image_inplace(image) - cv2.imwrite(str(path), image) - - -def save_depth_image(depth, path, write_shape=False): - path = Path(path) - path.parent.mkdir(parents=True, exist_ok=True) - - # Apply colormap on depth image (image must be converted to 8-bit per pixel first) - depth_image = cv2.applyColorMap(cv2.convertScaleAbs(depth, alpha=0.03), cv2.COLORMAP_JET) - - if write_shape: - write_shape_on_image_inplace(depth_image) - cv2.imwrite(str(path), depth_image) - - -def convert_torch_image_to_cv2(tensor, rgb_to_bgr=True): - assert tensor.ndim == 3 - c, h, w = tensor.shape - assert c < h and c < w - color_image = einops.rearrange(tensor, "c h w -> h w c").numpy() - if rgb_to_bgr: - color_image = cv2.cvtColor(color_image, cv2.COLOR_RGB2BGR) - return color_image - - # Defines a camera type class Camera(Protocol): def connect(self): ... diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/robot_devices/motors/dynamixel.py index 0c3145028..815b4986a 100644 --- a/lerobot/common/robot_devices/motors/dynamixel.py +++ b/lerobot/common/robot_devices/motors/dynamixel.py @@ -159,30 +159,25 @@ def convert_to_bytes(value, bytes, mock=False): if mock: return value - from dynamixel_sdk import ( - DXL_HIBYTE, - DXL_HIWORD, - DXL_LOBYTE, - DXL_LOWORD, - ) + import dynamixel_sdk as dxl # Note: No need to convert back into unsigned int, since this byte preprocessing # already handles it for us. if bytes == 1: data = [ - DXL_LOBYTE(DXL_LOWORD(value)), + dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)), ] elif bytes == 2: data = [ - DXL_LOBYTE(DXL_LOWORD(value)), - DXL_HIBYTE(DXL_LOWORD(value)), + dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)), + dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)), ] elif bytes == 4: data = [ - DXL_LOBYTE(DXL_LOWORD(value)), - DXL_HIBYTE(DXL_LOWORD(value)), - DXL_LOBYTE(DXL_HIWORD(value)), - DXL_HIBYTE(DXL_HIWORD(value)), + dxl.DXL_LOBYTE(dxl.DXL_LOWORD(value)), + dxl.DXL_HIBYTE(dxl.DXL_LOWORD(value)), + dxl.DXL_LOBYTE(dxl.DXL_HIWORD(value)), + dxl.DXL_HIBYTE(dxl.DXL_HIWORD(value)), ] else: raise NotImplementedError( @@ -361,12 +356,12 @@ def connect(self): ) if self.mock: - from tests.mock_dynamixel_sdk import PacketHandler, PortHandler + import tests.mock_dynamixel_sdk as dxl else: - from dynamixel_sdk import PacketHandler, PortHandler + import dynamixel_sdk as dxl - self.port_handler = PortHandler(self.port) - self.packet_handler = PacketHandler(PROTOCOL_VERSION) + self.port_handler = dxl.PortHandler(self.port) + self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION) try: if not self.port_handler.openPort(): @@ -399,12 +394,12 @@ def connect(self): def reconnect(self): if self.mock: - from tests.mock_dynamixel_sdk import PacketHandler, PortHandler + import tests.mock_dynamixel_sdk as dxl else: - from dynamixel_sdk import PacketHandler, PortHandler + import dynamixel_sdk as dxl - self.port_handler = PortHandler(self.port) - self.packet_handler = PacketHandler(PROTOCOL_VERSION) + self.port_handler = dxl.PortHandler(self.port) + self.packet_handler = dxl.PacketHandler(PROTOCOL_VERSION) if not self.port_handler.openPort(): raise OSError(f"Failed to open port '{self.port}'.") @@ -795,9 +790,9 @@ def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | def _read_with_motor_ids(self, motor_models, motor_ids, data_name): if self.mock: - from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + import tests.mock_dynamixel_sdk as dxl else: - from dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + import dynamixel_sdk as dxl return_list = True if not isinstance(motor_ids, list): @@ -806,12 +801,12 @@ def _read_with_motor_ids(self, motor_models, motor_ids, data_name): assert_same_address(self.model_ctrl_table, self.motor_models, data_name) addr, bytes = self.model_ctrl_table[motor_models[0]][data_name] - group = GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes) + group = dxl.GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes) for idx in motor_ids: group.addParam(idx) comm = group.txRxPacket() - if comm != COMM_SUCCESS: + if comm != dxl.COMM_SUCCESS: raise ConnectionError( f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: " f"{self.packet_handler.getTxRxResult(comm)}" @@ -836,9 +831,9 @@ def read(self, data_name, motor_names: str | list[str] | None = None): start_time = time.perf_counter() if self.mock: - from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + import tests.mock_dynamixel_sdk as dxl else: - from dynamixel_sdk import COMM_SUCCESS, GroupSyncRead + import dynamixel_sdk as dxl if motor_names is None: motor_names = self.motor_names @@ -859,16 +854,18 @@ def read(self, data_name, motor_names: str | list[str] | None = None): if data_name not in self.group_readers: # create new group reader - self.group_readers[group_key] = GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes) + self.group_readers[group_key] = dxl.GroupSyncRead( + self.port_handler, self.packet_handler, addr, bytes + ) for idx in motor_ids: self.group_readers[group_key].addParam(idx) for _ in range(NUM_READ_RETRY): comm = self.group_readers[group_key].txRxPacket() - if comm == COMM_SUCCESS: + if comm == dxl.COMM_SUCCESS: break - if comm != COMM_SUCCESS: + if comm != dxl.COMM_SUCCESS: raise ConnectionError( f"Read failed due to communication error on port {self.port} for group_key {group_key}: " f"{self.packet_handler.getTxRxResult(comm)}" @@ -900,9 +897,9 @@ def read(self, data_name, motor_names: str | list[str] | None = None): def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values): if self.mock: - from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + import tests.mock_dynamixel_sdk as dxl else: - from dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + import dynamixel_sdk as dxl if not isinstance(motor_ids, list): motor_ids = [motor_ids] @@ -911,13 +908,13 @@ def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values): assert_same_address(self.model_ctrl_table, motor_models, data_name) addr, bytes = self.model_ctrl_table[motor_models[0]][data_name] - group = GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes) + group = dxl.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes) for idx, value in zip(motor_ids, values, strict=True): data = convert_to_bytes(value, bytes, self.mock) group.addParam(idx, data) comm = group.txPacket() - if comm != COMM_SUCCESS: + if comm != dxl.COMM_SUCCESS: raise ConnectionError( f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: " f"{self.packet_handler.getTxRxResult(comm)}" @@ -932,9 +929,9 @@ def write(self, data_name, values: int | float | np.ndarray, motor_names: str | start_time = time.perf_counter() if self.mock: - from tests.mock_dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + import tests.mock_dynamixel_sdk as dxl else: - from dynamixel_sdk import COMM_SUCCESS, GroupSyncWrite + import dynamixel_sdk as dxl if motor_names is None: motor_names = self.motor_names @@ -965,7 +962,7 @@ def write(self, data_name, values: int | float | np.ndarray, motor_names: str | init_group = data_name not in self.group_readers if init_group: - self.group_writers[group_key] = GroupSyncWrite( + self.group_writers[group_key] = dxl.GroupSyncWrite( self.port_handler, self.packet_handler, addr, bytes ) @@ -977,7 +974,7 @@ def write(self, data_name, values: int | float | np.ndarray, motor_names: str | self.group_writers[group_key].changeParam(idx, data) comm = self.group_writers[group_key].txPacket() - if comm != COMM_SUCCESS: + if comm != dxl.COMM_SUCCESS: raise ConnectionError( f"Write failed due to communication error on port {self.port} for group_key {group_key}: " f"{self.packet_handler.getTxRxResult(comm)}" diff --git a/lerobot/common/robot_devices/robots/factory.py b/lerobot/common/robot_devices/robots/factory.py index 2edcd2925..17e8e5e6a 100644 --- a/lerobot/common/robot_devices/robots/factory.py +++ b/lerobot/common/robot_devices/robots/factory.py @@ -1,7 +1,9 @@ import hydra from omegaconf import DictConfig +from lerobot.common.robot_devices.robots.utils import Robot -def make_robot(cfg: DictConfig): + +def make_robot(cfg: DictConfig) -> Robot: robot = hydra.utils.instantiate(cfg) return robot diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index 337519765..98ae691a0 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -681,6 +681,10 @@ def send_action(self, action: torch.Tensor) -> torch.Tensor: return torch.cat(action_sent) + def print_logs(self): + pass + # TODO(aliberts): move robot-specific logs logic here + def disconnect(self): if not self.is_connected: raise RobotDeviceNotConnectedError( diff --git a/lerobot/common/robot_devices/robots/stretch.py b/lerobot/common/robot_devices/robots/stretch.py new file mode 100644 index 000000000..ff86b6d80 --- /dev/null +++ b/lerobot/common/robot_devices/robots/stretch.py @@ -0,0 +1,216 @@ +#!/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. + +import time +from dataclasses import dataclass, field, replace + +import torch +from stretch_body.gamepad_teleop import GamePadTeleop +from stretch_body.robot import Robot as StretchAPI +from stretch_body.robot_params import RobotParams + +from lerobot.common.robot_devices.cameras.utils import Camera + + +@dataclass +class StretchRobotConfig: + robot_type: str | None = "stretch" + cameras: dict[str, Camera] = field(default_factory=lambda: {}) + # TODO(aliberts): add feature with max_relative target + # TODO(aliberts): add comment on max_relative target + max_relative_target: list[float] | float | None = None + + +class StretchRobot(StretchAPI): + """Wrapper of stretch_body.robot.Robot""" + + def __init__(self, config: StretchRobotConfig | None = None, **kwargs): + super().__init__() + if config is None: + config = StretchRobotConfig() + # Overwrite config arguments using kwargs + self.config = replace(config, **kwargs) + + self.robot_type = self.config.robot_type + self.cameras = self.config.cameras + self.is_connected = False + self.teleop = None + self.logs = {} + + # TODO(aliberts): test this + RobotParams.set_logging_level("WARNING") + RobotParams.set_logging_formatter("brief_console_formatter") + + self.state_keys = None + self.action_keys = None + + def connect(self) -> None: + self.is_connected = self.startup() + if not self.is_connected: + print("Another process is already using Stretch. Try running 'stretch_free_robot_process.py'") + raise ConnectionError() + + for name in self.cameras: + self.cameras[name].connect() + self.is_connected = self.is_connected and self.cameras[name].is_connected + + if not self.is_connected: + print("Could not connect to the cameras, check that all cameras are plugged-in.") + raise ConnectionError() + + self.run_calibration() + + def run_calibration(self) -> None: + if not self.is_homed(): + self.home() + + def teleop_step( + self, record_data=False + ) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]: + # TODO(aliberts): return ndarrays instead of torch.Tensors + if not self.is_connected: + raise ConnectionError() + + if self.teleop is None: + self.teleop = GamePadTeleop(robot_instance=False) + self.teleop.startup(robot=self) + + before_read_t = time.perf_counter() + state = self.get_state() + action = self.teleop.gamepad_controller.get_state() + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + before_write_t = time.perf_counter() + self.teleop.do_motion(robot=self) + self.push_command() + self.logs["write_pos_dt_s"] = time.perf_counter() - before_write_t + + if self.state_keys is None: + self.state_keys = list(state) + + if not record_data: + return + + state = torch.as_tensor(list(state.values())) + action = torch.as_tensor(list(action.values())) + + # Capture images from cameras + images = {} + for name in self.cameras: + before_camread_t = time.perf_counter() + images[name] = self.cameras[name].async_read() + images[name] = torch.from_numpy(images[name]) + 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 + obs_dict, action_dict = {}, {} + obs_dict["observation.state"] = state + action_dict["action"] = action + for name in self.cameras: + obs_dict[f"observation.images.{name}"] = images[name] + + return obs_dict, action_dict + + def get_state(self) -> dict: + status = self.get_status() + return { + "head_pan.pos": status["head"]["head_pan"]["pos"], + "head_tilt.pos": status["head"]["head_tilt"]["pos"], + "lift.pos": status["lift"]["pos"], + "arm.pos": status["arm"]["pos"], + "wrist_pitch.pos": status["end_of_arm"]["wrist_pitch"]["pos"], + "wrist_roll.pos": status["end_of_arm"]["wrist_roll"]["pos"], + "wrist_yaw.pos": status["end_of_arm"]["wrist_yaw"]["pos"], + "gripper.pos": status["end_of_arm"]["stretch_gripper"]["pos"], + "base_x.vel": status["base"]["x_vel"], + "base_y.vel": status["base"]["y_vel"], + "base_theta.vel": status["base"]["theta_vel"], + } + + def capture_observation(self) -> dict: + # TODO(aliberts): return ndarrays instead of torch.Tensors + before_read_t = time.perf_counter() + state = self.get_state() + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + if self.state_keys is None: + self.state_keys = list(state) + + state = torch.as_tensor(list(state.values())) + + # Capture images from cameras + images = {} + for name in self.cameras: + before_camread_t = time.perf_counter() + images[name] = self.cameras[name].async_read() + images[name] = torch.from_numpy(images[name]) + 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 + obs_dict = {} + obs_dict["observation.state"] = state + for name in self.cameras: + obs_dict[f"observation.images.{name}"] = images[name] + + return obs_dict + + def send_action(self, action: torch.Tensor) -> torch.Tensor: + # TODO(aliberts): return ndarrays instead of torch.Tensors + if not self.is_connected: + raise ConnectionError() + + if self.teleop is None: + self.teleop = GamePadTeleop(robot_instance=False) + self.teleop.startup(robot=self) + + if self.action_keys is None: + dummy_action = self.teleop.gamepad_controller.get_state() + self.action_keys = list(dummy_action.keys()) + + action_dict = dict(zip(self.action_keys, action.tolist(), strict=True)) + + before_write_t = time.perf_counter() + self.teleop.do_motion(state=action_dict, robot=self) + self.push_command() + self.logs["write_pos_dt_s"] = time.perf_counter() - before_write_t + + # TODO(aliberts): return action_sent when motion is limited + return action + + def print_logs(self) -> None: + pass + # TODO(aliberts): move robot-specific logs logic here + + def teleop_safety_stop(self) -> None: + if self.teleop is not None: + self.teleop._safety_stop(robot=self) + + def disconnect(self) -> None: + self.stop() + if self.teleop is not None: + self.teleop.gamepad_controller.stop() + self.teleop.stop() + + if len(self.cameras) > 0: + for cam in self.cameras.values(): + cam.disconnect() + + self.is_connected = False + + def __del__(self): + self.disconnect() diff --git a/lerobot/common/robot_devices/robots/utils.py b/lerobot/common/robot_devices/robots/utils.py index 122155f78..5cd5bd100 100644 --- a/lerobot/common/robot_devices/robots/utils.py +++ b/lerobot/common/robot_devices/robots/utils.py @@ -9,8 +9,12 @@ def get_arm_id(name, arm_type): class Robot(Protocol): - def init_teleop(self): ... + # TODO(rcadene, aliberts): Add unit test checking the protocol is implemented in the corresponding classes + robot_type: str + + def connect(self): ... def run_calibration(self): ... def teleop_step(self, record_data=False): ... def capture_observation(self): ... def send_action(self, action): ... + def disconnect(self): ... diff --git a/lerobot/common/robot_devices/utils.py b/lerobot/common/robot_devices/utils.py index bcbeb8e02..19bb637e5 100644 --- a/lerobot/common/robot_devices/utils.py +++ b/lerobot/common/robot_devices/utils.py @@ -16,6 +16,20 @@ def busy_wait(seconds): time.sleep(seconds) +def safe_disconnect(func): + # TODO(aliberts): Allow to pass custom exceptions + # (e.g. ThreadServiceExit, KeyboardInterrupt, SystemExit, UnpluggedError, DynamixelCommError) + def wrapper(robot, *args, **kwargs): + try: + return func(robot, *args, **kwargs) + except Exception as e: + if robot.is_connected: + robot.disconnect() + raise e + + return wrapper + + class RobotDeviceNotConnectedError(Exception): """Exception raised when the robot device is not connected.""" diff --git a/lerobot/configs/robot/aloha.yaml b/lerobot/configs/robot/aloha.yaml index 938fa2e3d..51cde6a69 100644 --- a/lerobot/configs/robot/aloha.yaml +++ b/lerobot/configs/robot/aloha.yaml @@ -91,25 +91,25 @@ follower_arms: cameras: cam_high: _target_: lerobot.common.robot_devices.cameras.intelrealsense.IntelRealSenseCamera - camera_index: 128422271347 + serial_number: 128422271347 fps: 30 width: 640 height: 480 cam_low: _target_: lerobot.common.robot_devices.cameras.intelrealsense.IntelRealSenseCamera - camera_index: 130322270656 + serial_number: 130322270656 fps: 30 width: 640 height: 480 cam_left_wrist: _target_: lerobot.common.robot_devices.cameras.intelrealsense.IntelRealSenseCamera - camera_index: 218622272670 + serial_number: 218622272670 fps: 30 width: 640 height: 480 cam_right_wrist: _target_: lerobot.common.robot_devices.cameras.intelrealsense.IntelRealSenseCamera - camera_index: 130322272300 + serial_number: 130322272300 fps: 30 width: 640 height: 480 diff --git a/lerobot/configs/robot/stretch.yaml b/lerobot/configs/robot/stretch.yaml new file mode 100644 index 000000000..6d9f0be85 --- /dev/null +++ b/lerobot/configs/robot/stretch.yaml @@ -0,0 +1,24 @@ +_target_: lerobot.common.robot_devices.robots.stretch.StretchRobot +robot_type: stretch3 + +cameras: + navigation: + _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera + camera_index: /dev/hello-nav-head-camera + fps: 10 + width: 1280 + height: 720 + rotation: -90 + head: + _target_: lerobot.common.robot_devices.cameras.intelrealsense.IntelRealSenseCamera.init_from_name + name: Intel RealSense D435I + fps: 30 + width: 640 + height: 480 + rotation: 90 + wrist: + _target_: lerobot.common.robot_devices.cameras.intelrealsense.IntelRealSenseCamera.init_from_name + name: Intel RealSense D405 + fps: 30 + width: 640 + height: 480 diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index ff9cf3dc3..742dd8bca 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -128,7 +128,7 @@ from lerobot.common.policies.factory import make_policy from lerobot.common.robot_devices.robots.factory import make_robot from lerobot.common.robot_devices.robots.utils import Robot, get_arm_id -from lerobot.common.robot_devices.utils import busy_wait +from lerobot.common.robot_devices.utils import busy_wait, safe_disconnect from lerobot.common.utils.utils import get_safe_torch_device, init_hydra_config, init_logging, set_global_seed from lerobot.scripts.eval import get_pretrained_policy_path from lerobot.scripts.push_dataset_to_hub import ( @@ -176,7 +176,7 @@ def none_or_int(value): return int(value) -def log_control_info(robot, dt_s, episode_index=None, frame_index=None, fps=None): +def log_control_info(robot: Robot, dt_s, episode_index=None, frame_index=None, fps=None): log_items = [] if episode_index is not None: log_items.append(f"ep:{episode_index}") @@ -195,24 +195,26 @@ def log_dt(shortname, dt_val_s): # total step time displayed in milliseconds and its frequency log_dt("dt", dt_s) - for name in robot.leader_arms: - key = f"read_leader_{name}_pos_dt_s" - if key in robot.logs: - log_dt("dtRlead", robot.logs[key]) + # TODO(aliberts): move robot-specific logs logic in robot.print_logs() + if not robot.robot_type.startswith("stretch"): + for name in robot.leader_arms: + key = f"read_leader_{name}_pos_dt_s" + if key in robot.logs: + log_dt("dtRlead", robot.logs[key]) - for name in robot.follower_arms: - key = f"write_follower_{name}_goal_pos_dt_s" - if key in robot.logs: - log_dt("dtWfoll", robot.logs[key]) + for name in robot.follower_arms: + key = f"write_follower_{name}_goal_pos_dt_s" + if key in robot.logs: + log_dt("dtWfoll", robot.logs[key]) - key = f"read_follower_{name}_pos_dt_s" - if key in robot.logs: - log_dt("dtRfoll", robot.logs[key]) + key = f"read_follower_{name}_pos_dt_s" + if key in robot.logs: + log_dt("dtRfoll", robot.logs[key]) - for name in robot.cameras: - key = f"read_camera_{name}_dt_s" - if key in robot.logs: - log_dt(f"dtR{name}", robot.logs[key]) + for name in robot.cameras: + key = f"read_camera_{name}_dt_s" + if key in robot.logs: + log_dt(f"dtR{name}", robot.logs[key]) info_str = " ".join(log_items) logging.info(info_str) @@ -237,9 +239,8 @@ def is_headless(): return True -######################################################################################## -# Control modes -######################################################################################## +def has_method(_object: object, method_name: str): + return hasattr(_object, method_name) and callable(getattr(_object, method_name)) def get_available_arms(robot): @@ -254,7 +255,21 @@ def get_available_arms(robot): return available_arms +######################################################################################## +# Control modes +######################################################################################## + + +@safe_disconnect def calibrate(robot: Robot, arms: list[str] | None): + # TODO(aliberts): move this code in robots' classes + if robot.robot_type.startswith("stretch"): + if not robot.is_connected: + robot.connect() + if not robot.is_homed(): + robot.home() + return + available_arms = get_available_arms(robot) unknown_arms = [arm_id for arm_id in arms if arm_id not in available_arms] available_arms_str = " ".join(available_arms) @@ -289,6 +304,7 @@ def calibrate(robot: Robot, arms: list[str] | None): print("Calibration is done! You can now teleoperate and record datasets!") +@safe_disconnect def teleoperate(robot: Robot, fps: int | None = None, teleop_time_s: float | None = None): # TODO(rcadene): Add option to record logs if not robot.is_connected: @@ -310,6 +326,7 @@ def teleoperate(robot: Robot, fps: int | None = None, teleop_time_s: float | Non break +@safe_disconnect def record( robot: Robot, policy: torch.nn.Module | None = None, @@ -443,6 +460,9 @@ def on_press(key): timestamp = time.perf_counter() - start_warmup_t + if has_method(robot, "teleop_safety_stop"): + robot.teleop_safety_stop() + # Save images using threads to reach high fps (30 and more) # Using `with` to exist smoothly if an execption is raised. futures = [] @@ -536,6 +556,10 @@ def on_press(key): exit_early = False break + # TODO(alibets): allow for teleop during reset + if has_method(robot, "teleop_safety_stop"): + robot.teleop_safety_stop() + if not stop_recording: # Start resetting env while the executor are finishing logging.info("Reset the environment") diff --git a/poetry.lock b/poetry.lock index a46d38b59..43089048d 100644 --- a/poetry.lock +++ b/poetry.lock @@ -11,101 +11,141 @@ files = [ {file = "absl_py-2.1.0-py3-none-any.whl", hash = "sha256:526a04eadab8b4ee719ce68f204172ead1027549089702d99b9059f129ff1308"}, ] +[[package]] +name = "aiohappyeyeballs" +version = "2.4.0" +description = "Happy Eyeballs for asyncio" +optional = false +python-versions = ">=3.8" +files = [ + {file = "aiohappyeyeballs-2.4.0-py3-none-any.whl", hash = "sha256:7ce92076e249169a13c2f49320d1967425eaf1f407522d707d59cac7628d62bd"}, + {file = "aiohappyeyeballs-2.4.0.tar.gz", hash = "sha256:55a1714f084e63d49639800f95716da97a1f173d46a16dfcfda0016abb93b6b2"}, +] + [[package]] name = "aiohttp" -version = "3.9.5" +version = "3.10.6" description = "Async http client/server framework (asyncio)" optional = false python-versions = ">=3.8" files = [ - {file = "aiohttp-3.9.5-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:fcde4c397f673fdec23e6b05ebf8d4751314fa7c24f93334bf1f1364c1c69ac7"}, - {file = "aiohttp-3.9.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:5d6b3f1fabe465e819aed2c421a6743d8debbde79b6a8600739300630a01bf2c"}, - {file = "aiohttp-3.9.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:6ae79c1bc12c34082d92bf9422764f799aee4746fd7a392db46b7fd357d4a17a"}, - {file = "aiohttp-3.9.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4d3ebb9e1316ec74277d19c5f482f98cc65a73ccd5430540d6d11682cd857430"}, - {file = "aiohttp-3.9.5-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:84dabd95154f43a2ea80deffec9cb44d2e301e38a0c9d331cc4aa0166fe28ae3"}, - {file = "aiohttp-3.9.5-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c8a02fbeca6f63cb1f0475c799679057fc9268b77075ab7cf3f1c600e81dd46b"}, - {file = "aiohttp-3.9.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c26959ca7b75ff768e2776d8055bf9582a6267e24556bb7f7bd29e677932be72"}, - {file = "aiohttp-3.9.5-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:714d4e5231fed4ba2762ed489b4aec07b2b9953cf4ee31e9871caac895a839c0"}, - {file = "aiohttp-3.9.5-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:e7a6a8354f1b62e15d48e04350f13e726fa08b62c3d7b8401c0a1314f02e3558"}, - {file = "aiohttp-3.9.5-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:c413016880e03e69d166efb5a1a95d40f83d5a3a648d16486592c49ffb76d0db"}, - {file = "aiohttp-3.9.5-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:ff84aeb864e0fac81f676be9f4685f0527b660f1efdc40dcede3c251ef1e867f"}, - {file = "aiohttp-3.9.5-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:ad7f2919d7dac062f24d6f5fe95d401597fbb015a25771f85e692d043c9d7832"}, - {file = "aiohttp-3.9.5-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:702e2c7c187c1a498a4e2b03155d52658fdd6fda882d3d7fbb891a5cf108bb10"}, - {file = "aiohttp-3.9.5-cp310-cp310-win32.whl", hash = "sha256:67c3119f5ddc7261d47163ed86d760ddf0e625cd6246b4ed852e82159617b5fb"}, - {file = "aiohttp-3.9.5-cp310-cp310-win_amd64.whl", hash = "sha256:471f0ef53ccedec9995287f02caf0c068732f026455f07db3f01a46e49d76bbb"}, - {file = "aiohttp-3.9.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:e0ae53e33ee7476dd3d1132f932eeb39bf6125083820049d06edcdca4381f342"}, - {file = "aiohttp-3.9.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c088c4d70d21f8ca5c0b8b5403fe84a7bc8e024161febdd4ef04575ef35d474d"}, - {file = "aiohttp-3.9.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:639d0042b7670222f33b0028de6b4e2fad6451462ce7df2af8aee37dcac55424"}, - {file = "aiohttp-3.9.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f26383adb94da5e7fb388d441bf09c61e5e35f455a3217bfd790c6b6bc64b2ee"}, - {file = "aiohttp-3.9.5-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:66331d00fb28dc90aa606d9a54304af76b335ae204d1836f65797d6fe27f1ca2"}, - {file = "aiohttp-3.9.5-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4ff550491f5492ab5ed3533e76b8567f4b37bd2995e780a1f46bca2024223233"}, - {file = "aiohttp-3.9.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f22eb3a6c1080d862befa0a89c380b4dafce29dc6cd56083f630073d102eb595"}, - {file = "aiohttp-3.9.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a81b1143d42b66ffc40a441379387076243ef7b51019204fd3ec36b9f69e77d6"}, - {file = "aiohttp-3.9.5-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:f64fd07515dad67f24b6ea4a66ae2876c01031de91c93075b8093f07c0a2d93d"}, - {file = "aiohttp-3.9.5-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:93e22add827447d2e26d67c9ac0161756007f152fdc5210277d00a85f6c92323"}, - {file = "aiohttp-3.9.5-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:55b39c8684a46e56ef8c8d24faf02de4a2b2ac60d26cee93bc595651ff545de9"}, - {file = "aiohttp-3.9.5-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:4715a9b778f4293b9f8ae7a0a7cef9829f02ff8d6277a39d7f40565c737d3771"}, - {file = "aiohttp-3.9.5-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:afc52b8d969eff14e069a710057d15ab9ac17cd4b6753042c407dcea0e40bf75"}, - {file = "aiohttp-3.9.5-cp311-cp311-win32.whl", hash = "sha256:b3df71da99c98534be076196791adca8819761f0bf6e08e07fd7da25127150d6"}, - {file = "aiohttp-3.9.5-cp311-cp311-win_amd64.whl", hash = "sha256:88e311d98cc0bf45b62fc46c66753a83445f5ab20038bcc1b8a1cc05666f428a"}, - {file = "aiohttp-3.9.5-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:c7a4b7a6cf5b6eb11e109a9755fd4fda7d57395f8c575e166d363b9fc3ec4678"}, - {file = "aiohttp-3.9.5-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:0a158704edf0abcac8ac371fbb54044f3270bdbc93e254a82b6c82be1ef08f3c"}, - {file = "aiohttp-3.9.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d153f652a687a8e95ad367a86a61e8d53d528b0530ef382ec5aaf533140ed00f"}, - {file = "aiohttp-3.9.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:82a6a97d9771cb48ae16979c3a3a9a18b600a8505b1115cfe354dfb2054468b4"}, - {file = "aiohttp-3.9.5-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:60cdbd56f4cad9f69c35eaac0fbbdf1f77b0ff9456cebd4902f3dd1cf096464c"}, - {file = "aiohttp-3.9.5-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8676e8fd73141ded15ea586de0b7cda1542960a7b9ad89b2b06428e97125d4fa"}, - {file = "aiohttp-3.9.5-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:da00da442a0e31f1c69d26d224e1efd3a1ca5bcbf210978a2ca7426dfcae9f58"}, - {file = "aiohttp-3.9.5-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:18f634d540dd099c262e9f887c8bbacc959847cfe5da7a0e2e1cf3f14dbf2daf"}, - {file = "aiohttp-3.9.5-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:320e8618eda64e19d11bdb3bd04ccc0a816c17eaecb7e4945d01deee2a22f95f"}, - {file = "aiohttp-3.9.5-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:2faa61a904b83142747fc6a6d7ad8fccff898c849123030f8e75d5d967fd4a81"}, - {file = "aiohttp-3.9.5-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:8c64a6dc3fe5db7b1b4d2b5cb84c4f677768bdc340611eca673afb7cf416ef5a"}, - {file = "aiohttp-3.9.5-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:393c7aba2b55559ef7ab791c94b44f7482a07bf7640d17b341b79081f5e5cd1a"}, - {file = "aiohttp-3.9.5-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:c671dc117c2c21a1ca10c116cfcd6e3e44da7fcde37bf83b2be485ab377b25da"}, - {file = "aiohttp-3.9.5-cp312-cp312-win32.whl", hash = "sha256:5a7ee16aab26e76add4afc45e8f8206c95d1d75540f1039b84a03c3b3800dd59"}, - {file = "aiohttp-3.9.5-cp312-cp312-win_amd64.whl", hash = "sha256:5ca51eadbd67045396bc92a4345d1790b7301c14d1848feaac1d6a6c9289e888"}, - {file = "aiohttp-3.9.5-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:694d828b5c41255e54bc2dddb51a9f5150b4eefa9886e38b52605a05d96566e8"}, - {file = "aiohttp-3.9.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:0605cc2c0088fcaae79f01c913a38611ad09ba68ff482402d3410bf59039bfb8"}, - {file = "aiohttp-3.9.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:4558e5012ee03d2638c681e156461d37b7a113fe13970d438d95d10173d25f78"}, - {file = "aiohttp-3.9.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9dbc053ac75ccc63dc3a3cc547b98c7258ec35a215a92bd9f983e0aac95d3d5b"}, - {file = "aiohttp-3.9.5-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4109adee842b90671f1b689901b948f347325045c15f46b39797ae1bf17019de"}, - {file = "aiohttp-3.9.5-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a6ea1a5b409a85477fd8e5ee6ad8f0e40bf2844c270955e09360418cfd09abac"}, - {file = "aiohttp-3.9.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f3c2890ca8c59ee683fd09adf32321a40fe1cf164e3387799efb2acebf090c11"}, - {file = "aiohttp-3.9.5-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3916c8692dbd9d55c523374a3b8213e628424d19116ac4308e434dbf6d95bbdd"}, - {file = "aiohttp-3.9.5-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:8d1964eb7617907c792ca00b341b5ec3e01ae8c280825deadbbd678447b127e1"}, - {file = "aiohttp-3.9.5-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:d5ab8e1f6bee051a4bf6195e38a5c13e5e161cb7bad83d8854524798bd9fcd6e"}, - {file = "aiohttp-3.9.5-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:52c27110f3862a1afbcb2af4281fc9fdc40327fa286c4625dfee247c3ba90156"}, - {file = "aiohttp-3.9.5-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:7f64cbd44443e80094309875d4f9c71d0401e966d191c3d469cde4642bc2e031"}, - {file = "aiohttp-3.9.5-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:8b4f72fbb66279624bfe83fd5eb6aea0022dad8eec62b71e7bf63ee1caadeafe"}, - {file = "aiohttp-3.9.5-cp38-cp38-win32.whl", hash = "sha256:6380c039ec52866c06d69b5c7aad5478b24ed11696f0e72f6b807cfb261453da"}, - {file = "aiohttp-3.9.5-cp38-cp38-win_amd64.whl", hash = "sha256:da22dab31d7180f8c3ac7c7635f3bcd53808f374f6aa333fe0b0b9e14b01f91a"}, - {file = "aiohttp-3.9.5-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:1732102949ff6087589408d76cd6dea656b93c896b011ecafff418c9661dc4ed"}, - {file = "aiohttp-3.9.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:c6021d296318cb6f9414b48e6a439a7f5d1f665464da507e8ff640848ee2a58a"}, - {file = "aiohttp-3.9.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:239f975589a944eeb1bad26b8b140a59a3a320067fb3cd10b75c3092405a1372"}, - {file = "aiohttp-3.9.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3b7b30258348082826d274504fbc7c849959f1989d86c29bc355107accec6cfb"}, - {file = "aiohttp-3.9.5-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:cd2adf5c87ff6d8b277814a28a535b59e20bfea40a101db6b3bdca7e9926bc24"}, - {file = "aiohttp-3.9.5-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e9a3d838441bebcf5cf442700e3963f58b5c33f015341f9ea86dcd7d503c07e2"}, - {file = "aiohttp-3.9.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9e3a1ae66e3d0c17cf65c08968a5ee3180c5a95920ec2731f53343fac9bad106"}, - {file = "aiohttp-3.9.5-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9c69e77370cce2d6df5d12b4e12bdcca60c47ba13d1cbbc8645dd005a20b738b"}, - {file = "aiohttp-3.9.5-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:0cbf56238f4bbf49dab8c2dc2e6b1b68502b1e88d335bea59b3f5b9f4c001475"}, - {file = "aiohttp-3.9.5-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:d1469f228cd9ffddd396d9948b8c9cd8022b6d1bf1e40c6f25b0fb90b4f893ed"}, - {file = "aiohttp-3.9.5-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:45731330e754f5811c314901cebdf19dd776a44b31927fa4b4dbecab9e457b0c"}, - {file = "aiohttp-3.9.5-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:3fcb4046d2904378e3aeea1df51f697b0467f2aac55d232c87ba162709478c46"}, - {file = "aiohttp-3.9.5-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:8cf142aa6c1a751fcb364158fd710b8a9be874b81889c2bd13aa8893197455e2"}, - {file = "aiohttp-3.9.5-cp39-cp39-win32.whl", hash = "sha256:7b179eea70833c8dee51ec42f3b4097bd6370892fa93f510f76762105568cf09"}, - {file = "aiohttp-3.9.5-cp39-cp39-win_amd64.whl", hash = "sha256:38d80498e2e169bc61418ff36170e0aad0cd268da8b38a17c4cf29d254a8b3f1"}, - {file = "aiohttp-3.9.5.tar.gz", hash = "sha256:edea7d15772ceeb29db4aff55e482d4bcfb6ae160ce144f2682de02f6d693551"}, + {file = "aiohttp-3.10.6-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:682836fc672972cc3101cc9e30d49c5f7e8f1d010478d46119fe725a4545acfd"}, + {file = "aiohttp-3.10.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:289fa8a20018d0d5aa9e4b35d899bd51bcb80f0d5f365d9a23e30dac3b79159b"}, + {file = "aiohttp-3.10.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8617c96a20dd57e7e9d398ff9d04f3d11c4d28b1767273a5b1a018ada5a654d3"}, + {file = "aiohttp-3.10.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bdbeff1b062751c2a2a55b171f7050fb7073633c699299d042e962aacdbe1a07"}, + {file = "aiohttp-3.10.6-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7ea35d849cdd4a9268f910bff4497baebbc1aa3f2f625fd8ccd9ac99c860c621"}, + {file = "aiohttp-3.10.6-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:473961b3252f3b949bb84873d6e268fb6d8aa0ccc6eb7404fa58c76a326bb8e1"}, + {file = "aiohttp-3.10.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3d2665c5df629eb2f981dab244c01bfa6cdc185f4ffa026639286c4d56fafb54"}, + {file = "aiohttp-3.10.6-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:25d92f794f1332f656e3765841fc2b7ad5c26c3f3d01e8949eeb3495691cf9f4"}, + {file = "aiohttp-3.10.6-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:9bd6b2033993d5ae80883bb29b83fb2b432270bbe067c2f53cc73bb57c46065f"}, + {file = "aiohttp-3.10.6-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:d7f408c43f5e75ea1edc152fb375e8f46ef916f545fb66d4aebcbcfad05e2796"}, + {file = "aiohttp-3.10.6-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:cf8b8560aa965f87bf9c13bf9fed7025993a155ca0ce8422da74bf46d18c2f5f"}, + {file = "aiohttp-3.10.6-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:14477c4e52e2f17437b99893fd220ffe7d7ee41df5ebf931a92b8ca82e6fd094"}, + {file = "aiohttp-3.10.6-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:fb138fbf9f53928e779650f5ed26d0ea1ed8b2cab67f0ea5d63afa09fdc07593"}, + {file = "aiohttp-3.10.6-cp310-cp310-win32.whl", hash = "sha256:9843d683b8756971797be171ead21511d2215a2d6e3c899c6e3107fbbe826791"}, + {file = "aiohttp-3.10.6-cp310-cp310-win_amd64.whl", hash = "sha256:f8b8e49fe02f744d38352daca1dbef462c3874900bd8166516f6ea8e82b5aacf"}, + {file = "aiohttp-3.10.6-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f52e54fd776ad0da1006708762213b079b154644db54bcfc62f06eaa5b896402"}, + {file = "aiohttp-3.10.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:995ab1a238fd0d19dc65f2d222e5eb064e409665c6426a3e51d5101c1979ee84"}, + {file = "aiohttp-3.10.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:0749c4d5a08a802dd66ecdf59b2df4d76b900004017468a7bb736c3b5a3dd902"}, + {file = "aiohttp-3.10.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e05b39158f2af0e2438cc2075cfc271f4ace0c3cc4a81ec95b27a0432e161951"}, + {file = "aiohttp-3.10.6-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a9f196c970db2dcde4f24317e06615363349dc357cf4d7a3b0716c20ac6d7bcd"}, + {file = "aiohttp-3.10.6-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:47647c8af04a70e07a2462931b0eba63146a13affa697afb4ecbab9d03a480ce"}, + {file = "aiohttp-3.10.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:669c0efe7e99f6d94d63274c06344bd0e9c8daf184ce5602a29bc39e00a18720"}, + {file = "aiohttp-3.10.6-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c9721cdd83a994225352ca84cd537760d41a9da3c0eacb3ff534747ab8fba6d0"}, + {file = "aiohttp-3.10.6-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0b82c8ebed66ce182893e7c0b6b60ba2ace45b1df104feb52380edae266a4850"}, + {file = "aiohttp-3.10.6-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:b169f8e755e541b72e714b89a831b315bbe70db44e33fead28516c9e13d5f931"}, + {file = "aiohttp-3.10.6-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:0be3115753baf8b4153e64f9aa7bf6c0c64af57979aa900c31f496301b374570"}, + {file = "aiohttp-3.10.6-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:e1f80cd17d81a404b6e70ef22bfe1870bafc511728397634ad5f5efc8698df56"}, + {file = "aiohttp-3.10.6-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6419728b08fb6380c66a470d2319cafcec554c81780e2114b7e150329b9a9a7f"}, + {file = "aiohttp-3.10.6-cp311-cp311-win32.whl", hash = "sha256:bd294dcdc1afdc510bb51d35444003f14e327572877d016d576ac3b9a5888a27"}, + {file = "aiohttp-3.10.6-cp311-cp311-win_amd64.whl", hash = "sha256:bf861da9a43d282d6dd9dcd64c23a0fccf2c5aa5cd7c32024513c8c79fb69de3"}, + {file = "aiohttp-3.10.6-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:2708baccdc62f4b1251e59c2aac725936a900081f079b88843dabcab0feeeb27"}, + {file = "aiohttp-3.10.6-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:7475da7a5e2ccf1a1c86c8fee241e277f4874c96564d06f726d8df8e77683ef7"}, + {file = "aiohttp-3.10.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:02108326574ff60267b7b35b17ac5c0bbd0008ccb942ce4c48b657bb90f0b8aa"}, + {file = "aiohttp-3.10.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:029a019627b37fa9eac5c75cc54a6bb722c4ebbf5a54d8c8c0fb4dd8facf2702"}, + {file = "aiohttp-3.10.6-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8a637d387db6fdad95e293fab5433b775fd104ae6348d2388beaaa60d08b38c4"}, + {file = "aiohttp-3.10.6-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:dc1a16f3fc1944c61290d33c88dc3f09ba62d159b284c38c5331868425aca426"}, + {file = "aiohttp-3.10.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:81b292f37969f9cc54f4643f0be7dacabf3612b3b4a65413661cf6c350226787"}, + {file = "aiohttp-3.10.6-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0754690a3a26e819173a34093798c155bafb21c3c640bff13be1afa1e9d421f9"}, + {file = "aiohttp-3.10.6-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:164ecd32e65467d86843dbb121a6666c3deb23b460e3f8aefdcaacae79eb718a"}, + {file = "aiohttp-3.10.6-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:438c5863feb761f7ca3270d48c292c334814459f61cc12bab5ba5b702d7c9e56"}, + {file = "aiohttp-3.10.6-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:ba18573bb1de1063d222f41de64a0d3741223982dcea863b3f74646faf618ec7"}, + {file = "aiohttp-3.10.6-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:c82a94ddec996413a905f622f3da02c4359952aab8d817c01cf9915419525e95"}, + {file = "aiohttp-3.10.6-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:92351aa5363fc3c1f872ca763f86730ced32b01607f0c9662b1fa711087968d0"}, + {file = "aiohttp-3.10.6-cp312-cp312-win32.whl", hash = "sha256:3e15e33bfc73fa97c228f72e05e8795e163a693fd5323549f49367c76a6e5883"}, + {file = "aiohttp-3.10.6-cp312-cp312-win_amd64.whl", hash = "sha256:fe517113fe4d35d9072b826c3e147d63c5f808ca8167d450b4f96c520c8a1d8d"}, + {file = "aiohttp-3.10.6-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:482f74057ea13d387a7549d7a7ecb60e45146d15f3e58a2d93a0ad2d5a8457cd"}, + {file = "aiohttp-3.10.6-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:03fa40d1450ee5196e843315ddf74a51afc7e83d489dbfc380eecefea74158b1"}, + {file = "aiohttp-3.10.6-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:1e52e59ed5f4cc3a3acfe2a610f8891f216f486de54d95d6600a2c9ba1581f4d"}, + {file = "aiohttp-3.10.6-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d2b3935a22c9e41a8000d90588bed96cf395ef572dbb409be44c6219c61d900d"}, + {file = "aiohttp-3.10.6-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4bef1480ee50f75abcfcb4b11c12de1005968ca9d0172aec4a5057ba9f2b644f"}, + {file = "aiohttp-3.10.6-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:671745ea7db19693ce867359d503772177f0b20fa8f6ee1e74e00449f4c4151d"}, + {file = "aiohttp-3.10.6-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6b50b367308ca8c12e0b50cba5773bc9abe64c428d3fd2bbf5cd25aab37c77bf"}, + {file = "aiohttp-3.10.6-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6a504d7cdb431a777d05a124fd0b21efb94498efa743103ea01b1e3136d2e4fb"}, + {file = "aiohttp-3.10.6-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:66bc81361131763660b969132a22edce2c4d184978ba39614e8f8f95db5c95f8"}, + {file = "aiohttp-3.10.6-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:27cf19a38506e2e9f12fc17e55f118f04897b0a78537055d93a9de4bf3022e3d"}, + {file = "aiohttp-3.10.6-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:3468b39f977a11271517c6925b226720e148311039a380cc9117b1e2258a721f"}, + {file = "aiohttp-3.10.6-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:9d26da22a793dfd424be1050712a70c0afd96345245c29aced1e35dbace03413"}, + {file = "aiohttp-3.10.6-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:844d48ff9173d0b941abed8b2ea6a412f82b56d9ab1edb918c74000c15839362"}, + {file = "aiohttp-3.10.6-cp313-cp313-win32.whl", hash = "sha256:2dd56e3c43660ed3bea67fd4c5025f1ac1f9ecf6f0b991a6e5efe2e678c490c5"}, + {file = "aiohttp-3.10.6-cp313-cp313-win_amd64.whl", hash = "sha256:c91781d969fbced1993537f45efe1213bd6fccb4b37bfae2a026e20d6fbed206"}, + {file = "aiohttp-3.10.6-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:4407a80bca3e694f2d2a523058e20e1f9f98a416619e04f6dc09dc910352ac8b"}, + {file = "aiohttp-3.10.6-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:1cb045ec5961f51af3e2c08cd6fe523f07cc6e345033adee711c49b7b91bb954"}, + {file = "aiohttp-3.10.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:4fabdcdc781a36b8fd7b2ca9dea8172f29a99e11d00ca0f83ffeb50958da84a1"}, + {file = "aiohttp-3.10.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:79a9f42efcc2681790595ab3d03c0e52d01edc23a0973ea09f0dc8d295e12b8e"}, + {file = "aiohttp-3.10.6-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:cca776a440795db437d82c07455761c85bbcf3956221c3c23b8c93176c278ce7"}, + {file = "aiohttp-3.10.6-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5582de171f0898139cf51dd9fcdc79b848e28d9abd68e837f0803fc9f30807b1"}, + {file = "aiohttp-3.10.6-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:370e2d47575c53c817ee42a18acc34aad8da4dbdaac0a6c836d58878955f1477"}, + {file = "aiohttp-3.10.6-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:444d1704e2af6b30766debed9be8a795958029e552fe77551355badb1944012c"}, + {file = "aiohttp-3.10.6-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:40271a2a375812967401c9ca8077de9368e09a43a964f4dce0ff603301ec9358"}, + {file = "aiohttp-3.10.6-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:f3af26f86863fad12e25395805bb0babbd49d512806af91ec9708a272b696248"}, + {file = "aiohttp-3.10.6-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:4752df44df48fd42b80f51d6a97553b482cda1274d9dc5df214a3a1aa5d8f018"}, + {file = "aiohttp-3.10.6-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:2cd5290ab66cfca2f90045db2cc6434c1f4f9fbf97c9f1c316e785033782e7d2"}, + {file = "aiohttp-3.10.6-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:3427031064b0d5c95647e6369c4aa3c556402f324a3e18107cb09517abe5f962"}, + {file = "aiohttp-3.10.6-cp38-cp38-win32.whl", hash = "sha256:614fc21e86adc28e4165a6391f851a6da6e9cbd7bb232d0df7718b453a89ee98"}, + {file = "aiohttp-3.10.6-cp38-cp38-win_amd64.whl", hash = "sha256:58c5d7318a136a3874c78717dd6de57519bc64f6363c5827c2b1cb775bea71dd"}, + {file = "aiohttp-3.10.6-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:5db26bbca8e7968c4c977a0c640e0b9ce7224e1f4dcafa57870dc6ee28e27de6"}, + {file = "aiohttp-3.10.6-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:3fb4216e3ec0dbc01db5ba802f02ed78ad8f07121be54eb9e918448cc3f61b7c"}, + {file = "aiohttp-3.10.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:a976ef488f26e224079deb3d424f29144c6d5ba4ded313198169a8af8f47fb82"}, + {file = "aiohttp-3.10.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6a86610174de8a85a920e956e2d4f9945e7da89f29a00e95ac62a4a414c4ef4e"}, + {file = "aiohttp-3.10.6-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:217791c6a399cc4f2e6577bb44344cba1f5714a2aebf6a0bea04cfa956658284"}, + {file = "aiohttp-3.10.6-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ba3662d41abe2eab0eeec7ee56f33ef4e0b34858f38abf24377687f9e1fb00a5"}, + {file = "aiohttp-3.10.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d4dfa5ad4bce9ca30a76117fbaa1c1decf41ebb6c18a4e098df44298941566f9"}, + {file = "aiohttp-3.10.6-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e0009258e97502936d3bd5bf2ced15769629097d0abb81e6495fba1047824fe0"}, + {file = "aiohttp-3.10.6-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:0a75d5c9fb4f06c41d029ae70ad943c3a844c40c0a769d12be4b99b04f473d3d"}, + {file = "aiohttp-3.10.6-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:8198b7c002aae2b40b2d16bfe724b9a90bcbc9b78b2566fc96131ef4e382574d"}, + {file = "aiohttp-3.10.6-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:4611db8c907f90fe86be112efdc2398cd7b4c8eeded5a4f0314b70fdea8feab0"}, + {file = "aiohttp-3.10.6-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:ff99ae06eef85c7a565854826114ced72765832ee16c7e3e766c5e4c5b98d20e"}, + {file = "aiohttp-3.10.6-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:7641920bdcc7cd2d3ddfb8bb9133a6c9536b09dbd49490b79e125180b2d25b93"}, + {file = "aiohttp-3.10.6-cp39-cp39-win32.whl", hash = "sha256:e2e7d5591ea868d5ec82b90bbeb366a198715672841d46281b623e23079593db"}, + {file = "aiohttp-3.10.6-cp39-cp39-win_amd64.whl", hash = "sha256:b504c08c45623bf5c7ca41be380156d925f00199b3970efd758aef4a77645feb"}, + {file = "aiohttp-3.10.6.tar.gz", hash = "sha256:d2578ef941be0c2ba58f6f421a703527d08427237ed45ecb091fed6f83305336"}, ] [package.dependencies] +aiohappyeyeballs = ">=2.3.0" aiosignal = ">=1.1.2" async-timeout = {version = ">=4.0,<5.0", markers = "python_version < \"3.11\""} attrs = ">=17.3.0" frozenlist = ">=1.1.1" multidict = ">=4.5,<7.0" -yarl = ">=1.0,<2.0" +yarl = ">=1.12.0,<2.0" [package.extras] -speedups = ["Brotli", "aiodns", "brotlicffi"] +speedups = ["Brotli", "aiodns (>=3.2.0)", "brotlicffi"] + +[[package]] +name = "aioserial" +version = "1.3.1" +description = "An asynchronous serial port library of Python" +optional = true +python-versions = ">=3.6,<4.0" +files = [ + {file = "aioserial-1.3.1.tar.gz", hash = "sha256:702bf03b0eb84b8ef2d8dac5cb925e1e685dce98f77b125569bc6fd2b3b58228"}, +] + +[package.dependencies] +pyserial = "*" [[package]] name = "aiosignal" @@ -131,6 +171,115 @@ files = [ {file = "antlr4-python3-runtime-4.9.3.tar.gz", hash = "sha256:f224469b4168294902bb1efa80a8bf7855f24c99aef99cbefc1bcd3cce77881b"}, ] +[[package]] +name = "anyio" +version = "4.6.0" +description = "High level compatibility layer for multiple asynchronous event loop implementations" +optional = true +python-versions = ">=3.9" +files = [ + {file = "anyio-4.6.0-py3-none-any.whl", hash = "sha256:c7d2e9d63e31599eeb636c8c5c03a7e108d73b345f064f1c19fdc87b79036a9a"}, + {file = "anyio-4.6.0.tar.gz", hash = "sha256:137b4559cbb034c477165047febb6ff83f390fc3b20bf181c1fc0a728cb8beeb"}, +] + +[package.dependencies] +exceptiongroup = {version = ">=1.0.2", markers = "python_version < \"3.11\""} +idna = ">=2.8" +sniffio = ">=1.1" +typing-extensions = {version = ">=4.1", markers = "python_version < \"3.11\""} + +[package.extras] +doc = ["Sphinx (>=7.4,<8.0)", "packaging", "sphinx-autodoc-typehints (>=1.2.0)", "sphinx-rtd-theme"] +test = ["anyio[trio]", "coverage[toml] (>=7)", "exceptiongroup (>=1.2.0)", "hypothesis (>=4.0)", "psutil (>=5.9)", "pytest (>=7.0)", "pytest-mock (>=3.6.1)", "trustme", "uvloop (>=0.21.0b1)"] +trio = ["trio (>=0.26.1)"] + +[[package]] +name = "appnope" +version = "0.1.4" +description = "Disable App Nap on macOS >= 10.9" +optional = true +python-versions = ">=3.6" +files = [ + {file = "appnope-0.1.4-py2.py3-none-any.whl", hash = "sha256:502575ee11cd7a28c0205f379b525beefebab9d161b7c964670864014ed7213c"}, + {file = "appnope-0.1.4.tar.gz", hash = "sha256:1de3860566df9caf38f01f86f65e0e13e379af54f9e4bee1e66b48f2efffd1ee"}, +] + +[[package]] +name = "argon2-cffi" +version = "23.1.0" +description = "Argon2 for Python" +optional = true +python-versions = ">=3.7" +files = [ + {file = "argon2_cffi-23.1.0-py3-none-any.whl", hash = "sha256:c670642b78ba29641818ab2e68bd4e6a78ba53b7eff7b4c3815ae16abf91c7ea"}, + {file = "argon2_cffi-23.1.0.tar.gz", hash = "sha256:879c3e79a2729ce768ebb7d36d4609e3a78a4ca2ec3a9f12286ca057e3d0db08"}, +] + +[package.dependencies] +argon2-cffi-bindings = "*" + +[package.extras] +dev = ["argon2-cffi[tests,typing]", "tox (>4)"] +docs = ["furo", "myst-parser", "sphinx", "sphinx-copybutton", "sphinx-notfound-page"] +tests = ["hypothesis", "pytest"] +typing = ["mypy"] + +[[package]] +name = "argon2-cffi-bindings" +version = "21.2.0" +description = "Low-level CFFI bindings for Argon2" +optional = true +python-versions = ">=3.6" +files = [ + {file = "argon2-cffi-bindings-21.2.0.tar.gz", hash = "sha256:bb89ceffa6c791807d1305ceb77dbfacc5aa499891d2c55661c6459651fc39e3"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-macosx_10_9_x86_64.whl", hash = "sha256:ccb949252cb2ab3a08c02024acb77cfb179492d5701c7cbdbfd776124d4d2367"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9524464572e12979364b7d600abf96181d3541da11e23ddf565a32e70bd4dc0d"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b746dba803a79238e925d9046a63aa26bf86ab2a2fe74ce6b009a1c3f5c8f2ae"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:58ed19212051f49a523abb1dbe954337dc82d947fb6e5a0da60f7c8471a8476c"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-musllinux_1_1_aarch64.whl", hash = "sha256:bd46088725ef7f58b5a1ef7ca06647ebaf0eb4baff7d1d0d177c6cc8744abd86"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-musllinux_1_1_i686.whl", hash = "sha256:8cd69c07dd875537a824deec19f978e0f2078fdda07fd5c42ac29668dda5f40f"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-musllinux_1_1_x86_64.whl", hash = "sha256:f1152ac548bd5b8bcecfb0b0371f082037e47128653df2e8ba6e914d384f3c3e"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-win32.whl", hash = "sha256:603ca0aba86b1349b147cab91ae970c63118a0f30444d4bc80355937c950c082"}, + {file = "argon2_cffi_bindings-21.2.0-cp36-abi3-win_amd64.whl", hash = "sha256:b2ef1c30440dbbcba7a5dc3e319408b59676e2e039e2ae11a8775ecf482b192f"}, + {file = "argon2_cffi_bindings-21.2.0-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:e415e3f62c8d124ee16018e491a009937f8cf7ebf5eb430ffc5de21b900dad93"}, + {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:3e385d1c39c520c08b53d63300c3ecc28622f076f4c2b0e6d7e796e9f6502194"}, + {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c3e3cc67fdb7d82c4718f19b4e7a87123caf8a93fde7e23cf66ac0337d3cb3f"}, + {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6a22ad9800121b71099d0fb0a65323810a15f2e292f2ba450810a7316e128ee5"}, + {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f9f8b450ed0547e3d473fdc8612083fd08dd2120d6ac8f73828df9b7d45bb351"}, + {file = "argon2_cffi_bindings-21.2.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:93f9bf70084f97245ba10ee36575f0c3f1e7d7724d67d8e5b08e61787c320ed7"}, + {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:3b9ef65804859d335dc6b31582cad2c5166f0c3e7975f324d9ffaa34ee7e6583"}, + {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d4966ef5848d820776f5f562a7d45fdd70c2f330c961d0d745b784034bd9f48d"}, + {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:20ef543a89dee4db46a1a6e206cd015360e5a75822f76df533845c3cbaf72670"}, + {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ed2937d286e2ad0cc79a7087d3c272832865f779430e0cc2b4f3718d3159b0cb"}, + {file = "argon2_cffi_bindings-21.2.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:5e00316dabdaea0b2dd82d141cc66889ced0cdcbfa599e8b471cf22c620c329a"}, +] + +[package.dependencies] +cffi = ">=1.0.1" + +[package.extras] +dev = ["cogapp", "pre-commit", "pytest", "wheel"] +tests = ["pytest"] + +[[package]] +name = "arrow" +version = "1.3.0" +description = "Better dates & times for Python" +optional = true +python-versions = ">=3.8" +files = [ + {file = "arrow-1.3.0-py3-none-any.whl", hash = "sha256:c728b120ebc00eb84e01882a6f5e7927a53960aa990ce7dd2b10f39005a67f80"}, + {file = "arrow-1.3.0.tar.gz", hash = "sha256:d4540617648cb5f895730f1ad8c82a65f2dad0166f57b75f3ca54759c4d67a85"}, +] + +[package.dependencies] +python-dateutil = ">=2.7.0" +types-python-dateutil = ">=2.8.10" + +[package.extras] +doc = ["doc8", "sphinx (>=7.0.0)", "sphinx-autobuild", "sphinx-autodoc-typehints", "sphinx_rtd_theme (>=1.3.0)"] +test = ["dateparser (==1.*)", "pre-commit", "pytest", "pytest-cov", "pytest-mock", "pytz (==2021.1)", "simplejson (==3.*)"] + [[package]] name = "asciitree" version = "0.3.3" @@ -141,6 +290,38 @@ files = [ {file = "asciitree-0.3.3.tar.gz", hash = "sha256:4aa4b9b649f85e3fcb343363d97564aa1fb62e249677f2e18a96765145cc0f6e"}, ] +[[package]] +name = "asttokens" +version = "2.4.1" +description = "Annotate AST trees with source code positions" +optional = true +python-versions = "*" +files = [ + {file = "asttokens-2.4.1-py2.py3-none-any.whl", hash = "sha256:051ed49c3dcae8913ea7cd08e46a606dba30b79993209636c4875bc1d637bc24"}, + {file = "asttokens-2.4.1.tar.gz", hash = "sha256:b03869718ba9a6eb027e134bfdf69f38a236d681c83c160d510768af11254ba0"}, +] + +[package.dependencies] +six = ">=1.12.0" + +[package.extras] +astroid = ["astroid (>=1,<2)", "astroid (>=2,<4)"] +test = ["astroid (>=1,<2)", "astroid (>=2,<4)", "pytest"] + +[[package]] +name = "async-lru" +version = "2.0.4" +description = "Simple LRU cache for asyncio" +optional = true +python-versions = ">=3.8" +files = [ + {file = "async-lru-2.0.4.tar.gz", hash = "sha256:b8a59a5df60805ff63220b2a0c5b5393da5521b113cd5465a44eb037d81a5627"}, + {file = "async_lru-2.0.4-py3-none-any.whl", hash = "sha256:ff02944ce3c288c5be660c42dbcca0742b32c3b279d6dceda655190240b99224"}, +] + +[package.dependencies] +typing-extensions = {version = ">=4.0.0", markers = "python_version < \"3.11\""} + [[package]] name = "async-timeout" version = "4.0.3" @@ -154,22 +335,36 @@ files = [ [[package]] name = "attrs" -version = "23.2.0" +version = "24.2.0" description = "Classes Without Boilerplate" optional = false python-versions = ">=3.7" files = [ - {file = "attrs-23.2.0-py3-none-any.whl", hash = "sha256:99b87a485a5820b23b879f04c2305b44b951b502fd64be915879d77a7e8fc6f1"}, - {file = "attrs-23.2.0.tar.gz", hash = "sha256:935dc3b529c262f6cf76e50877d35a4bd3c1de194fd41f47a2b7ae8f19971f30"}, + {file = "attrs-24.2.0-py3-none-any.whl", hash = "sha256:81921eb96de3191c8258c199618104dd27ac608d9366f5e35d011eae1867ede2"}, + {file = "attrs-24.2.0.tar.gz", hash = "sha256:5cfb1b9148b5b086569baec03f20d7b6bf3bcacc9a42bebf87ffaaca362f6346"}, +] + +[package.extras] +benchmark = ["cloudpickle", "hypothesis", "mypy (>=1.11.1)", "pympler", "pytest (>=4.3.0)", "pytest-codspeed", "pytest-mypy-plugins", "pytest-xdist[psutil]"] +cov = ["cloudpickle", "coverage[toml] (>=5.3)", "hypothesis", "mypy (>=1.11.1)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "pytest-xdist[psutil]"] +dev = ["cloudpickle", "hypothesis", "mypy (>=1.11.1)", "pre-commit", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "pytest-xdist[psutil]"] +docs = ["cogapp", "furo", "myst-parser", "sphinx", "sphinx-notfound-page", "sphinxcontrib-towncrier", "towncrier (<24.7)"] +tests = ["cloudpickle", "hypothesis", "mypy (>=1.11.1)", "pympler", "pytest (>=4.3.0)", "pytest-mypy-plugins", "pytest-xdist[psutil]"] +tests-mypy = ["mypy (>=1.11.1)", "pytest-mypy-plugins"] + +[[package]] +name = "babel" +version = "2.16.0" +description = "Internationalization utilities" +optional = true +python-versions = ">=3.8" +files = [ + {file = "babel-2.16.0-py3-none-any.whl", hash = "sha256:368b5b98b37c06b7daf6696391c3240c938b37767d4584413e8438c5c435fa8b"}, + {file = "babel-2.16.0.tar.gz", hash = "sha256:d1f3554ca26605fe173f3de0c65f750f5a42f924499bf134de6423582298e316"}, ] [package.extras] -cov = ["attrs[tests]", "coverage[toml] (>=5.3)"] -dev = ["attrs[tests]", "pre-commit"] -docs = ["furo", "myst-parser", "sphinx", "sphinx-notfound-page", "sphinxcontrib-towncrier", "towncrier", "zope-interface"] -tests = ["attrs[tests-no-zope]", "zope-interface"] -tests-mypy = ["mypy (>=1.6)", "pytest-mypy-plugins"] -tests-no-zope = ["attrs[tests-mypy]", "cloudpickle", "hypothesis", "pympler", "pytest (>=4.3.0)", "pytest-xdist[psutil]"] +dev = ["freezegun (>=1.0,<2.0)", "pytest (>=6.0)", "pytest-cov"] [[package]] name = "beautifulsoup4" @@ -192,6 +387,24 @@ charset-normalizer = ["charset-normalizer"] html5lib = ["html5lib"] lxml = ["lxml"] +[[package]] +name = "bleach" +version = "6.1.0" +description = "An easy safelist-based HTML-sanitizing tool." +optional = true +python-versions = ">=3.8" +files = [ + {file = "bleach-6.1.0-py3-none-any.whl", hash = "sha256:3225f354cfc436b9789c66c4ee030194bee0568fbf9cbdad3bc8b5c26c5f12b6"}, + {file = "bleach-6.1.0.tar.gz", hash = "sha256:0a31f1837963c41d46bbf1331b8778e1308ea0791db03cc4e7357b97cf42a8fe"}, +] + +[package.dependencies] +six = ">=1.9.0" +webencodings = "*" + +[package.extras] +css = ["tinycss2 (>=1.1.0,<1.3)"] + [[package]] name = "blinker" version = "1.8.2" @@ -205,74 +418,89 @@ files = [ [[package]] name = "certifi" -version = "2024.7.4" +version = "2024.8.30" description = "Python package for providing Mozilla's CA Bundle." optional = false python-versions = ">=3.6" files = [ - {file = "certifi-2024.7.4-py3-none-any.whl", hash = "sha256:c198e21b1289c2ab85ee4e67bb4b4ef3ead0892059901a8d5b622f24a1101e90"}, - {file = "certifi-2024.7.4.tar.gz", hash = "sha256:5a1e7645bc0ec61a09e26c36f6106dd4cf40c6db3a1fb6352b0244e7fb057c7b"}, + {file = "certifi-2024.8.30-py3-none-any.whl", hash = "sha256:922820b53db7a7257ffbda3f597266d435245903d80737e34f8a45ff3e3230d8"}, + {file = "certifi-2024.8.30.tar.gz", hash = "sha256:bec941d2aa8195e248a60b31ff9f0558284cf01a52591ceda73ea9afffd69fd9"}, ] [[package]] name = "cffi" -version = "1.16.0" +version = "1.17.1" description = "Foreign Function Interface for Python calling C code." optional = false python-versions = ">=3.8" files = [ - {file = "cffi-1.16.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:6b3d6606d369fc1da4fd8c357d026317fbb9c9b75d36dc16e90e84c26854b088"}, - {file = "cffi-1.16.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ac0f5edd2360eea2f1daa9e26a41db02dd4b0451b48f7c318e217ee092a213e9"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7e61e3e4fa664a8588aa25c883eab612a188c725755afff6289454d6362b9673"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a72e8961a86d19bdb45851d8f1f08b041ea37d2bd8d4fd19903bc3083d80c896"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5b50bf3f55561dac5438f8e70bfcdfd74543fd60df5fa5f62d94e5867deca684"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7651c50c8c5ef7bdb41108b7b8c5a83013bfaa8a935590c5d74627c047a583c7"}, - {file = "cffi-1.16.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e4108df7fe9b707191e55f33efbcb2d81928e10cea45527879a4749cbe472614"}, - {file = "cffi-1.16.0-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:32c68ef735dbe5857c810328cb2481e24722a59a2003018885514d4c09af9743"}, - {file = "cffi-1.16.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:673739cb539f8cdaa07d92d02efa93c9ccf87e345b9a0b556e3ecc666718468d"}, - {file = "cffi-1.16.0-cp310-cp310-win32.whl", hash = "sha256:9f90389693731ff1f659e55c7d1640e2ec43ff725cc61b04b2f9c6d8d017df6a"}, - {file = "cffi-1.16.0-cp310-cp310-win_amd64.whl", hash = "sha256:e6024675e67af929088fda399b2094574609396b1decb609c55fa58b028a32a1"}, - {file = "cffi-1.16.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b84834d0cf97e7d27dd5b7f3aca7b6e9263c56308ab9dc8aae9784abb774d404"}, - {file = "cffi-1.16.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1b8ebc27c014c59692bb2664c7d13ce7a6e9a629be20e54e7271fa696ff2b417"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ee07e47c12890ef248766a6e55bd38ebfb2bb8edd4142d56db91b21ea68b7627"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8a9d3ebe49f084ad71f9269834ceccbf398253c9fac910c4fd7053ff1386936"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e70f54f1796669ef691ca07d046cd81a29cb4deb1e5f942003f401c0c4a2695d"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5bf44d66cdf9e893637896c7faa22298baebcd18d1ddb6d2626a6e39793a1d56"}, - {file = "cffi-1.16.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7b78010e7b97fef4bee1e896df8a4bbb6712b7f05b7ef630f9d1da00f6444d2e"}, - {file = "cffi-1.16.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:c6a164aa47843fb1b01e941d385aab7215563bb8816d80ff3a363a9f8448a8dc"}, - {file = "cffi-1.16.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e09f3ff613345df5e8c3667da1d918f9149bd623cd9070c983c013792a9a62eb"}, - {file = "cffi-1.16.0-cp311-cp311-win32.whl", hash = "sha256:2c56b361916f390cd758a57f2e16233eb4f64bcbeee88a4881ea90fca14dc6ab"}, - {file = "cffi-1.16.0-cp311-cp311-win_amd64.whl", hash = "sha256:db8e577c19c0fda0beb7e0d4e09e0ba74b1e4c092e0e40bfa12fe05b6f6d75ba"}, - {file = "cffi-1.16.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:fa3a0128b152627161ce47201262d3140edb5a5c3da88d73a1b790a959126956"}, - {file = "cffi-1.16.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:68e7c44931cc171c54ccb702482e9fc723192e88d25a0e133edd7aff8fcd1f6e"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:abd808f9c129ba2beda4cfc53bde801e5bcf9d6e0f22f095e45327c038bfe68e"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88e2b3c14bdb32e440be531ade29d3c50a1a59cd4e51b1dd8b0865c54ea5d2e2"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fcc8eb6d5902bb1cf6dc4f187ee3ea80a1eba0a89aba40a5cb20a5087d961357"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b7be2d771cdba2942e13215c4e340bfd76398e9227ad10402a8767ab1865d2e6"}, - {file = "cffi-1.16.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e715596e683d2ce000574bae5d07bd522c781a822866c20495e52520564f0969"}, - {file = "cffi-1.16.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:2d92b25dbf6cae33f65005baf472d2c245c050b1ce709cc4588cdcdd5495b520"}, - {file = "cffi-1.16.0-cp312-cp312-win32.whl", hash = "sha256:b2ca4e77f9f47c55c194982e10f058db063937845bb2b7a86c84a6cfe0aefa8b"}, - {file = "cffi-1.16.0-cp312-cp312-win_amd64.whl", hash = "sha256:68678abf380b42ce21a5f2abde8efee05c114c2fdb2e9eef2efdb0257fba1235"}, - {file = "cffi-1.16.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:0c9ef6ff37e974b73c25eecc13952c55bceed9112be2d9d938ded8e856138bcc"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a09582f178759ee8128d9270cd1344154fd473bb77d94ce0aeb2a93ebf0feaf0"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e760191dd42581e023a68b758769e2da259b5d52e3103c6060ddc02c9edb8d7b"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:80876338e19c951fdfed6198e70bc88f1c9758b94578d5a7c4c91a87af3cf31c"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a6a14b17d7e17fa0d207ac08642c8820f84f25ce17a442fd15e27ea18d67c59b"}, - {file = "cffi-1.16.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6602bc8dc6f3a9e02b6c22c4fc1e47aa50f8f8e6d3f78a5e16ac33ef5fefa324"}, - {file = "cffi-1.16.0-cp38-cp38-win32.whl", hash = "sha256:131fd094d1065b19540c3d72594260f118b231090295d8c34e19a7bbcf2e860a"}, - {file = "cffi-1.16.0-cp38-cp38-win_amd64.whl", hash = "sha256:31d13b0f99e0836b7ff893d37af07366ebc90b678b6664c955b54561fc36ef36"}, - {file = "cffi-1.16.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:582215a0e9adbe0e379761260553ba11c58943e4bbe9c36430c4ca6ac74b15ed"}, - {file = "cffi-1.16.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:b29ebffcf550f9da55bec9e02ad430c992a87e5f512cd63388abb76f1036d8d2"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dc9b18bf40cc75f66f40a7379f6a9513244fe33c0e8aa72e2d56b0196a7ef872"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9cb4a35b3642fc5c005a6755a5d17c6c8b6bcb6981baf81cea8bfbc8903e8ba8"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b86851a328eedc692acf81fb05444bdf1891747c25af7529e39ddafaf68a4f3f"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c0f31130ebc2d37cdd8e44605fb5fa7ad59049298b3f745c74fa74c62fbfcfc4"}, - {file = "cffi-1.16.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f8e709127c6c77446a8c0a8c8bf3c8ee706a06cd44b1e827c3e6a2ee6b8c098"}, - {file = "cffi-1.16.0-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:748dcd1e3d3d7cd5443ef03ce8685043294ad6bd7c02a38d1bd367cfd968e000"}, - {file = "cffi-1.16.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:8895613bcc094d4a1b2dbe179d88d7fb4a15cee43c052e8885783fac397d91fe"}, - {file = "cffi-1.16.0-cp39-cp39-win32.whl", hash = "sha256:ed86a35631f7bfbb28e108dd96773b9d5a6ce4811cf6ea468bb6a359b256b1e4"}, - {file = "cffi-1.16.0-cp39-cp39-win_amd64.whl", hash = "sha256:3686dffb02459559c74dd3d81748269ffb0eb027c39a6fc99502de37d501faa8"}, - {file = "cffi-1.16.0.tar.gz", hash = "sha256:bcb3ef43e58665bbda2fb198698fcae6776483e0c4a631aa5647806c25e02cc0"}, + {file = "cffi-1.17.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:df8b1c11f177bc2313ec4b2d46baec87a5f3e71fc8b45dab2ee7cae86d9aba14"}, + {file = "cffi-1.17.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:8f2cdc858323644ab277e9bb925ad72ae0e67f69e804f4898c070998d50b1a67"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:edae79245293e15384b51f88b00613ba9f7198016a5948b5dddf4917d4d26382"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:45398b671ac6d70e67da8e4224a065cec6a93541bb7aebe1b198a61b58c7b702"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ad9413ccdeda48c5afdae7e4fa2192157e991ff761e7ab8fdd8926f40b160cc3"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5da5719280082ac6bd9aa7becb3938dc9f9cbd57fac7d2871717b1feb0902ab6"}, + {file = "cffi-1.17.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2bb1a08b8008b281856e5971307cc386a8e9c5b625ac297e853d36da6efe9c17"}, + {file = "cffi-1.17.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:045d61c734659cc045141be4bae381a41d89b741f795af1dd018bfb532fd0df8"}, + {file = "cffi-1.17.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:6883e737d7d9e4899a8a695e00ec36bd4e5e4f18fabe0aca0efe0a4b44cdb13e"}, + {file = "cffi-1.17.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:6b8b4a92e1c65048ff98cfe1f735ef8f1ceb72e3d5f0c25fdb12087a23da22be"}, + {file = "cffi-1.17.1-cp310-cp310-win32.whl", hash = "sha256:c9c3d058ebabb74db66e431095118094d06abf53284d9c81f27300d0e0d8bc7c"}, + {file = "cffi-1.17.1-cp310-cp310-win_amd64.whl", hash = "sha256:0f048dcf80db46f0098ccac01132761580d28e28bc0f78ae0d58048063317e15"}, + {file = "cffi-1.17.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a45e3c6913c5b87b3ff120dcdc03f6131fa0065027d0ed7ee6190736a74cd401"}, + {file = "cffi-1.17.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:30c5e0cb5ae493c04c8b42916e52ca38079f1b235c2f8ae5f4527b963c401caf"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f75c7ab1f9e4aca5414ed4d8e5c0e303a34f4421f8a0d47a4d019ceff0ab6af4"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a1ed2dd2972641495a3ec98445e09766f077aee98a1c896dcb4ad0d303628e41"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:46bf43160c1a35f7ec506d254e5c890f3c03648a4dbac12d624e4490a7046cd1"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a24ed04c8ffd54b0729c07cee15a81d964e6fee0e3d4d342a27b020d22959dc6"}, + {file = "cffi-1.17.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:610faea79c43e44c71e1ec53a554553fa22321b65fae24889706c0a84d4ad86d"}, + {file = "cffi-1.17.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:a9b15d491f3ad5d692e11f6b71f7857e7835eb677955c00cc0aefcd0669adaf6"}, + {file = "cffi-1.17.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:de2ea4b5833625383e464549fec1bc395c1bdeeb5f25c4a3a82b5a8c756ec22f"}, + {file = "cffi-1.17.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:fc48c783f9c87e60831201f2cce7f3b2e4846bf4d8728eabe54d60700b318a0b"}, + {file = "cffi-1.17.1-cp311-cp311-win32.whl", hash = "sha256:85a950a4ac9c359340d5963966e3e0a94a676bd6245a4b55bc43949eee26a655"}, + {file = "cffi-1.17.1-cp311-cp311-win_amd64.whl", hash = "sha256:caaf0640ef5f5517f49bc275eca1406b0ffa6aa184892812030f04c2abf589a0"}, + {file = "cffi-1.17.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:805b4371bf7197c329fcb3ead37e710d1bca9da5d583f5073b799d5c5bd1eee4"}, + {file = "cffi-1.17.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:733e99bc2df47476e3848417c5a4540522f234dfd4ef3ab7fafdf555b082ec0c"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1257bdabf294dceb59f5e70c64a3e2f462c30c7ad68092d01bbbfb1c16b1ba36"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:da95af8214998d77a98cc14e3a3bd00aa191526343078b530ceb0bd710fb48a5"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d63afe322132c194cf832bfec0dc69a99fb9bb6bbd550f161a49e9e855cc78ff"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f79fc4fc25f1c8698ff97788206bb3c2598949bfe0fef03d299eb1b5356ada99"}, + {file = "cffi-1.17.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b62ce867176a75d03a665bad002af8e6d54644fad99a3c70905c543130e39d93"}, + {file = "cffi-1.17.1-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:386c8bf53c502fff58903061338ce4f4950cbdcb23e2902d86c0f722b786bbe3"}, + {file = "cffi-1.17.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:4ceb10419a9adf4460ea14cfd6bc43d08701f0835e979bf821052f1805850fe8"}, + {file = "cffi-1.17.1-cp312-cp312-win32.whl", hash = "sha256:a08d7e755f8ed21095a310a693525137cfe756ce62d066e53f502a83dc550f65"}, + {file = "cffi-1.17.1-cp312-cp312-win_amd64.whl", hash = "sha256:51392eae71afec0d0c8fb1a53b204dbb3bcabcb3c9b807eedf3e1e6ccf2de903"}, + {file = "cffi-1.17.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:f3a2b4222ce6b60e2e8b337bb9596923045681d71e5a082783484d845390938e"}, + {file = "cffi-1.17.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:0984a4925a435b1da406122d4d7968dd861c1385afe3b45ba82b750f229811e2"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d01b12eeeb4427d3110de311e1774046ad344f5b1a7403101878976ecd7a10f3"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:706510fe141c86a69c8ddc029c7910003a17353970cff3b904ff0686a5927683"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:de55b766c7aa2e2a3092c51e0483d700341182f08e67c63630d5b6f200bb28e5"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c59d6e989d07460165cc5ad3c61f9fd8f1b4796eacbd81cee78957842b834af4"}, + {file = "cffi-1.17.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd398dbc6773384a17fe0d3e7eeb8d1a21c2200473ee6806bb5e6a8e62bb73dd"}, + {file = "cffi-1.17.1-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:3edc8d958eb099c634dace3c7e16560ae474aa3803a5df240542b305d14e14ed"}, + {file = "cffi-1.17.1-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:72e72408cad3d5419375fc87d289076ee319835bdfa2caad331e377589aebba9"}, + {file = "cffi-1.17.1-cp313-cp313-win32.whl", hash = "sha256:e03eab0a8677fa80d646b5ddece1cbeaf556c313dcfac435ba11f107ba117b5d"}, + {file = "cffi-1.17.1-cp313-cp313-win_amd64.whl", hash = "sha256:f6a16c31041f09ead72d69f583767292f750d24913dadacf5756b966aacb3f1a"}, + {file = "cffi-1.17.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:636062ea65bd0195bc012fea9321aca499c0504409f413dc88af450b57ffd03b"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c7eac2ef9b63c79431bc4b25f1cd649d7f061a28808cbc6c47b534bd789ef964"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e221cf152cff04059d011ee126477f0d9588303eb57e88923578ace7baad17f9"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:31000ec67d4221a71bd3f67df918b1f88f676f1c3b535a7eb473255fdc0b83fc"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:6f17be4345073b0a7b8ea599688f692ac3ef23ce28e5df79c04de519dbc4912c"}, + {file = "cffi-1.17.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0e2b1fac190ae3ebfe37b979cc1ce69c81f4e4fe5746bb401dca63a9062cdaf1"}, + {file = "cffi-1.17.1-cp38-cp38-win32.whl", hash = "sha256:7596d6620d3fa590f677e9ee430df2958d2d6d6de2feeae5b20e82c00b76fbf8"}, + {file = "cffi-1.17.1-cp38-cp38-win_amd64.whl", hash = "sha256:78122be759c3f8a014ce010908ae03364d00a1f81ab5c7f4a7a5120607ea56e1"}, + {file = "cffi-1.17.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:b2ab587605f4ba0bf81dc0cb08a41bd1c0a5906bd59243d56bad7668a6fc6c16"}, + {file = "cffi-1.17.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:28b16024becceed8c6dfbc75629e27788d8a3f9030691a1dbf9821a128b22c36"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1d599671f396c4723d016dbddb72fe8e0397082b0a77a4fab8028923bec050e8"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ca74b8dbe6e8e8263c0ffd60277de77dcee6c837a3d0881d8c1ead7268c9e576"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f7f5baafcc48261359e14bcd6d9bff6d4b28d9103847c9e136694cb0501aef87"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:98e3969bcff97cae1b2def8ba499ea3d6f31ddfdb7635374834cf89a1a08ecf0"}, + {file = "cffi-1.17.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cdf5ce3acdfd1661132f2a9c19cac174758dc2352bfe37d98aa7512c6b7178b3"}, + {file = "cffi-1.17.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:9755e4345d1ec879e3849e62222a18c7174d65a6a92d5b346b1863912168b595"}, + {file = "cffi-1.17.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:f1e22e8c4419538cb197e4dd60acc919d7696e5ef98ee4da4e01d3f8cfa4cc5a"}, + {file = "cffi-1.17.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:c03e868a0b3bc35839ba98e74211ed2b05d2119be4e8a0f224fba9384f1fe02e"}, + {file = "cffi-1.17.1-cp39-cp39-win32.whl", hash = "sha256:e31ae45bc2e29f6b2abd0de1cc3b9d5205aa847cafaecb8af1476a609a2f6eb7"}, + {file = "cffi-1.17.1-cp39-cp39-win_amd64.whl", hash = "sha256:d016c76bdd850f3c626af19b0542c9677ba156e4ee4fccfdd7848803533ef662"}, + {file = "cffi-1.17.1.tar.gz", hash = "sha256:1c39c6016c32bc48dd54561950ebd6836e1670f2ae46128f67cf49e789c52824"}, ] [package.dependencies] @@ -388,6 +616,17 @@ files = [ {file = "charset_normalizer-3.3.2-py3-none-any.whl", hash = "sha256:3e4d1f6587322d2788836a99c69062fbb091331ec940e02d12d179c1d53e25fc"}, ] +[[package]] +name = "chime" +version = "0.7.0" +description = "Python sound notifications made easy." +optional = true +python-versions = ">=3.6,<4.0" +files = [ + {file = "chime-0.7.0-py3-none-any.whl", hash = "sha256:9626f8151cb008b1e0ffb7de6d1834b7013ba5fc4c4e3c9ba6e29dc9bf5feac6"}, + {file = "chime-0.7.0.tar.gz", hash = "sha256:ba4af8934ec8bd9a89a340b4433b2e500097b979823386432be7128e0b201f0d"}, +] + [[package]] name = "click" version = "8.1.7" @@ -413,30 +652,48 @@ files = [ {file = "cloudpickle-3.0.0.tar.gz", hash = "sha256:996d9a482c6fb4f33c1a35335cf8afd065d2a56e973270364840712d9131a882"}, ] +[[package]] +name = "cma" +version = "4.0.0" +description = "CMA-ES, Covariance Matrix Adaptation Evolution Strategy for non-linear numerical optimization in Python" +optional = true +python-versions = "*" +files = [ + {file = "cma-4.0.0-py3-none-any.whl", hash = "sha256:97b86ba1ac9f1cbb189a06c4d4a78f591f0878e5dd3e55c95e88e622e78c1a10"}, + {file = "cma-4.0.0.tar.gz", hash = "sha256:fd28ce56983bf2fca0e614189d60134ebb80bf604f070d1ea095ea4e856f13a5"}, +] + +[package.dependencies] +numpy = "*" + +[package.extras] +constrained-solution-tracking = ["moarchiving"] +plotting = ["matplotlib"] + [[package]] name = "cmake" -version = "3.30.0" +version = "3.30.3" description = "CMake is an open-source, cross-platform family of tools designed to build, test and package software" optional = false python-versions = ">=3.7" files = [ - {file = "cmake-3.30.0-py3-none-macosx_10_10_x86_64.macosx_11_0_universal2.macosx_11_0_arm64.whl", hash = "sha256:9caf5839d041f3276596abf564267f7bbaf4b36731ad1f574f3d4c04d7f8c26b"}, - {file = "cmake-3.30.0-py3-none-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:2c19c50ee12fb1fddb636401b60f301e873b1f0bc726968509556450496c26fb"}, - {file = "cmake-3.30.0-py3-none-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:cc343a5fd4b3013e313083fd3226f4599210560e4d72743faa98057e9f41ccea"}, - {file = "cmake-3.30.0-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cbe32916158e6ca2f45f6e1dc4578a99f5c9ab6cfc7e4f812fae284d54c4749d"}, - {file = "cmake-3.30.0-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4a981336efd0d97a02bab4aba90f989077516a42c2510a1ba216f1a5cc00656f"}, - {file = "cmake-3.30.0-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:59b8491d54064bf734e709001b1f79b1356a4c6c016f78445d5c0516785d096b"}, - {file = "cmake-3.30.0-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:968e00571f6c07f36b2226a8dbd63eeba4888bcc2f9f30b1dbd2673f75b98564"}, - {file = "cmake-3.30.0-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e123afb34f08e38e76cd3303d1cea166f15ec7acd48353b6fe9d1175b10b4553"}, - {file = "cmake-3.30.0-py3-none-musllinux_1_1_aarch64.whl", hash = "sha256:d7c6265b3d066b25eaf07fc69b8672c28f531b59403cbabb864219f84098b378"}, - {file = "cmake-3.30.0-py3-none-musllinux_1_1_i686.whl", hash = "sha256:a6960b4b9e91bbcd68fc1a0395306a0eab68981752e667d4dc1721d9ad895358"}, - {file = "cmake-3.30.0-py3-none-musllinux_1_1_ppc64le.whl", hash = "sha256:100da4b77c2133a426ec6bffc01efcbdd9c212665c0b9acaa20bcaf98dc75097"}, - {file = "cmake-3.30.0-py3-none-musllinux_1_1_s390x.whl", hash = "sha256:e6e3ab9d48d5bf5564840e8152bcfe41a9318b1fe95b1410f8cc1f15800ff2bf"}, - {file = "cmake-3.30.0-py3-none-musllinux_1_1_x86_64.whl", hash = "sha256:bfb761c3dc275034d251494503e643dc8f23d15e8e6284eca1b2bfbde4634851"}, - {file = "cmake-3.30.0-py3-none-win32.whl", hash = "sha256:23253f76f44f0f69cf18c8343e56184ea3ab51e837198db691fbdef1bf986455"}, - {file = "cmake-3.30.0-py3-none-win_amd64.whl", hash = "sha256:aa9b483ff53804566909ec7ef8c25eaf4226c224756d731cb3dd28d9be2dea46"}, - {file = "cmake-3.30.0-py3-none-win_arm64.whl", hash = "sha256:fc9aba5cc8a631cbbe7a6b4b6b1f981346e70af35900459b4ac6a1b18f489568"}, - {file = "cmake-3.30.0.tar.gz", hash = "sha256:b6b9b584ce226dfde4d419578a2ae542e72409655c0ea2c989d5f9bb688cf024"}, + {file = "cmake-3.30.3-py3-none-macosx_11_0_universal2.macosx_11_0_arm64.macosx_10_10_x86_64.whl", hash = "sha256:8cc4c67432cca5e7a24a74eb102bc0472581a71231e58c224e544373dcb147a7"}, + {file = "cmake-3.30.3-py3-none-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:1ca7e29f5952634274d33ec1cb0cd9ddb79cb0b09cc3887b55d24c9852eed9d0"}, + {file = "cmake-3.30.3-py3-none-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:30c2cdf8a863573a5fd7bf39159fbb96e75ac1955e481d35e5295ac601ea23af"}, + {file = "cmake-3.30.3-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:81e5dc3103a4c6594d3efdf652e21e21d610e264f0c489ebefa3db04b1cdd2bc"}, + {file = "cmake-3.30.3-py3-none-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fc5fba153bd0255adb246f27358d98db597a62264b61970d32038f9c7f355a70"}, + {file = "cmake-3.30.3-py3-none-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a5ac1157eaa1e95bd67f11bd6ebc6f85b42ce6f2aac7b93d28dd84a5230be55b"}, + {file = "cmake-3.30.3-py3-none-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ba26cb3c19f5b4cb83787394647a5dafbd2922a6de4af39409d7d287536a617f"}, + {file = "cmake-3.30.3-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6e294e3f424175b085809f713dd7ee36edd36b6b8a579911ef90359d8f884658"}, + {file = "cmake-3.30.3-py3-none-musllinux_1_1_aarch64.whl", hash = "sha256:1616e2806c4c85e21fd0b6e92a61d41cb47479b5305bfa6f0c00baacfd029d7d"}, + {file = "cmake-3.30.3-py3-none-musllinux_1_1_i686.whl", hash = "sha256:c98cf8980ed75dd15be9948da559a51ce4cd0f017fc44969a72dcd37f507fa61"}, + {file = "cmake-3.30.3-py3-none-musllinux_1_1_ppc64le.whl", hash = "sha256:870ebf590fb2f7cc58c8aa5b4dc32b50d4ca9c2fb9f1e46cd0426a995a2ef71e"}, + {file = "cmake-3.30.3-py3-none-musllinux_1_1_s390x.whl", hash = "sha256:592cfcf280570713b8743bf8a8dec3753e0b82a7791d7d79f5ddb4f2be8b48b8"}, + {file = "cmake-3.30.3-py3-none-musllinux_1_1_x86_64.whl", hash = "sha256:e0fd7746f8895ec54e20c5d5dcc76a42256483e1f4736050264a180a13f9f8ef"}, + {file = "cmake-3.30.3-py3-none-win32.whl", hash = "sha256:ca990748d1a1d778a1a31cc1e33dcb01f2ed6fb0a752e945ff9e2d5435cff191"}, + {file = "cmake-3.30.3-py3-none-win_amd64.whl", hash = "sha256:3b41b0fbf3b449dd387c71444c9eb7f23e9a8061554bbf8fd8157ee355427220"}, + {file = "cmake-3.30.3-py3-none-win_arm64.whl", hash = "sha256:a9e14118824992313bd0e2b3b86d9c85d7883c39b784199ea755fc32aeeb9e81"}, + {file = "cmake-3.30.3.tar.gz", hash = "sha256:c015d02e5f25973b66b66a060d3ad8c1c382cf38ba7b09712770d9de50b67b80"}, ] [package.extras] @@ -453,65 +710,201 @@ files = [ {file = "colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44"}, ] +[[package]] +name = "comm" +version = "0.2.2" +description = "Jupyter Python Comm implementation, for usage in ipykernel, xeus-python etc." +optional = true +python-versions = ">=3.8" +files = [ + {file = "comm-0.2.2-py3-none-any.whl", hash = "sha256:e6fb86cb70ff661ee8c9c14e7d36d6de3b4066f1441be4063df9c5009f0a64d3"}, + {file = "comm-0.2.2.tar.gz", hash = "sha256:3fd7a84065306e07bea1773df6eb8282de51ba82f77c72f9c85716ab11fe980e"}, +] + +[package.dependencies] +traitlets = ">=4" + +[package.extras] +test = ["pytest"] + +[[package]] +name = "configargparse" +version = "1.7" +description = "A drop-in replacement for argparse that allows options to also be set via config files and/or environment variables." +optional = true +python-versions = ">=3.5" +files = [ + {file = "ConfigArgParse-1.7-py3-none-any.whl", hash = "sha256:d249da6591465c6c26df64a9f73d2536e743be2f244eb3ebe61114af2f94f86b"}, + {file = "ConfigArgParse-1.7.tar.gz", hash = "sha256:e7067471884de5478c58a511e529f0f9bd1c66bfef1dea90935438d6c23306d1"}, +] + +[package.extras] +test = ["PyYAML", "mock", "pytest"] +yaml = ["PyYAML"] + +[[package]] +name = "contourpy" +version = "1.3.0" +description = "Python library for calculating contours of 2D quadrilateral grids" +optional = true +python-versions = ">=3.9" +files = [ + {file = "contourpy-1.3.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:880ea32e5c774634f9fcd46504bf9f080a41ad855f4fef54f5380f5133d343c7"}, + {file = "contourpy-1.3.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:76c905ef940a4474a6289c71d53122a4f77766eef23c03cd57016ce19d0f7b42"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:92f8557cbb07415a4d6fa191f20fd9d2d9eb9c0b61d1b2f52a8926e43c6e9af7"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:36f965570cff02b874773c49bfe85562b47030805d7d8360748f3eca570f4cab"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:cacd81e2d4b6f89c9f8a5b69b86490152ff39afc58a95af002a398273e5ce589"}, + {file = "contourpy-1.3.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:69375194457ad0fad3a839b9e29aa0b0ed53bb54db1bfb6c3ae43d111c31ce41"}, + {file = "contourpy-1.3.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:7a52040312b1a858b5e31ef28c2e865376a386c60c0e248370bbea2d3f3b760d"}, + {file = "contourpy-1.3.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3faeb2998e4fcb256542e8a926d08da08977f7f5e62cf733f3c211c2a5586223"}, + {file = "contourpy-1.3.0-cp310-cp310-win32.whl", hash = "sha256:36e0cff201bcb17a0a8ecc7f454fe078437fa6bda730e695a92f2d9932bd507f"}, + {file = "contourpy-1.3.0-cp310-cp310-win_amd64.whl", hash = "sha256:87ddffef1dbe5e669b5c2440b643d3fdd8622a348fe1983fad7a0f0ccb1cd67b"}, + {file = "contourpy-1.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:0fa4c02abe6c446ba70d96ece336e621efa4aecae43eaa9b030ae5fb92b309ad"}, + {file = "contourpy-1.3.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:834e0cfe17ba12f79963861e0f908556b2cedd52e1f75e6578801febcc6a9f49"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dbc4c3217eee163fa3984fd1567632b48d6dfd29216da3ded3d7b844a8014a66"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4865cd1d419e0c7a7bf6de1777b185eebdc51470800a9f42b9e9decf17762081"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:303c252947ab4b14c08afeb52375b26781ccd6a5ccd81abcdfc1fafd14cf93c1"}, + {file = "contourpy-1.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:637f674226be46f6ba372fd29d9523dd977a291f66ab2a74fbeb5530bb3f445d"}, + {file = "contourpy-1.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:76a896b2f195b57db25d6b44e7e03f221d32fe318d03ede41f8b4d9ba1bff53c"}, + {file = "contourpy-1.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:e1fd23e9d01591bab45546c089ae89d926917a66dceb3abcf01f6105d927e2cb"}, + {file = "contourpy-1.3.0-cp311-cp311-win32.whl", hash = "sha256:d402880b84df3bec6eab53cd0cf802cae6a2ef9537e70cf75e91618a3801c20c"}, + {file = "contourpy-1.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:6cb6cc968059db9c62cb35fbf70248f40994dfcd7aa10444bbf8b3faeb7c2d67"}, + {file = "contourpy-1.3.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:570ef7cf892f0afbe5b2ee410c507ce12e15a5fa91017a0009f79f7d93a1268f"}, + {file = "contourpy-1.3.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:da84c537cb8b97d153e9fb208c221c45605f73147bd4cadd23bdae915042aad6"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0be4d8425bfa755e0fd76ee1e019636ccc7c29f77a7c86b4328a9eb6a26d0639"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9c0da700bf58f6e0b65312d0a5e695179a71d0163957fa381bb3c1f72972537c"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:eb8b141bb00fa977d9122636b16aa67d37fd40a3d8b52dd837e536d64b9a4d06"}, + {file = "contourpy-1.3.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3634b5385c6716c258d0419c46d05c8aa7dc8cb70326c9a4fb66b69ad2b52e09"}, + {file = "contourpy-1.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:0dce35502151b6bd35027ac39ba6e5a44be13a68f55735c3612c568cac3805fd"}, + {file = "contourpy-1.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:aea348f053c645100612b333adc5983d87be69acdc6d77d3169c090d3b01dc35"}, + {file = "contourpy-1.3.0-cp312-cp312-win32.whl", hash = "sha256:90f73a5116ad1ba7174341ef3ea5c3150ddf20b024b98fb0c3b29034752c8aeb"}, + {file = "contourpy-1.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:b11b39aea6be6764f84360fce6c82211a9db32a7c7de8fa6dd5397cf1d079c3b"}, + {file = "contourpy-1.3.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:3e1c7fa44aaae40a2247e2e8e0627f4bea3dd257014764aa644f319a5f8600e3"}, + {file = "contourpy-1.3.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:364174c2a76057feef647c802652f00953b575723062560498dc7930fc9b1cb7"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:32b238b3b3b649e09ce9aaf51f0c261d38644bdfa35cbaf7b263457850957a84"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d51fca85f9f7ad0b65b4b9fe800406d0d77017d7270d31ec3fb1cc07358fdea0"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:732896af21716b29ab3e988d4ce14bc5133733b85956316fb0c56355f398099b"}, + {file = "contourpy-1.3.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d73f659398a0904e125280836ae6f88ba9b178b2fed6884f3b1f95b989d2c8da"}, + {file = "contourpy-1.3.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:c6c7c2408b7048082932cf4e641fa3b8ca848259212f51c8c59c45aa7ac18f14"}, + {file = "contourpy-1.3.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:f317576606de89da6b7e0861cf6061f6146ead3528acabff9236458a6ba467f8"}, + {file = "contourpy-1.3.0-cp313-cp313-win32.whl", hash = "sha256:31cd3a85dbdf1fc002280c65caa7e2b5f65e4a973fcdf70dd2fdcb9868069294"}, + {file = "contourpy-1.3.0-cp313-cp313-win_amd64.whl", hash = "sha256:4553c421929ec95fb07b3aaca0fae668b2eb5a5203d1217ca7c34c063c53d087"}, + {file = "contourpy-1.3.0-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:345af746d7766821d05d72cb8f3845dfd08dd137101a2cb9b24de277d716def8"}, + {file = "contourpy-1.3.0-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:3bb3808858a9dc68f6f03d319acd5f1b8a337e6cdda197f02f4b8ff67ad2057b"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:420d39daa61aab1221567b42eecb01112908b2cab7f1b4106a52caaec8d36973"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4d63ee447261e963af02642ffcb864e5a2ee4cbfd78080657a9880b8b1868e18"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:167d6c890815e1dac9536dca00828b445d5d0df4d6a8c6adb4a7ec3166812fa8"}, + {file = "contourpy-1.3.0-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:710a26b3dc80c0e4febf04555de66f5fd17e9cf7170a7b08000601a10570bda6"}, + {file = "contourpy-1.3.0-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:75ee7cb1a14c617f34a51d11fa7524173e56551646828353c4af859c56b766e2"}, + {file = "contourpy-1.3.0-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:33c92cdae89ec5135d036e7218e69b0bb2851206077251f04a6c4e0e21f03927"}, + {file = "contourpy-1.3.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:a11077e395f67ffc2c44ec2418cfebed032cd6da3022a94fc227b6faf8e2acb8"}, + {file = "contourpy-1.3.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e8134301d7e204c88ed7ab50028ba06c683000040ede1d617298611f9dc6240c"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e12968fdfd5bb45ffdf6192a590bd8ddd3ba9e58360b29683c6bb71a7b41edca"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fd2a0fc506eccaaa7595b7e1418951f213cf8255be2600f1ea1b61e46a60c55f"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4cfb5c62ce023dfc410d6059c936dcf96442ba40814aefbfa575425a3a7f19dc"}, + {file = "contourpy-1.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:68a32389b06b82c2fdd68276148d7b9275b5f5cf13e5417e4252f6d1a34f72a2"}, + {file = "contourpy-1.3.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:94e848a6b83da10898cbf1311a815f770acc9b6a3f2d646f330d57eb4e87592e"}, + {file = "contourpy-1.3.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:d78ab28a03c854a873787a0a42254a0ccb3cb133c672f645c9f9c8f3ae9d0800"}, + {file = "contourpy-1.3.0-cp39-cp39-win32.whl", hash = "sha256:81cb5ed4952aae6014bc9d0421dec7c5835c9c8c31cdf51910b708f548cf58e5"}, + {file = "contourpy-1.3.0-cp39-cp39-win_amd64.whl", hash = "sha256:14e262f67bd7e6eb6880bc564dcda30b15e351a594657e55b7eec94b6ef72843"}, + {file = "contourpy-1.3.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:fe41b41505a5a33aeaed2a613dccaeaa74e0e3ead6dd6fd3a118fb471644fd6c"}, + {file = "contourpy-1.3.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eca7e17a65f72a5133bdbec9ecf22401c62bcf4821361ef7811faee695799779"}, + {file = "contourpy-1.3.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:1ec4dc6bf570f5b22ed0d7efba0dfa9c5b9e0431aeea7581aa217542d9e809a4"}, + {file = "contourpy-1.3.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:00ccd0dbaad6d804ab259820fa7cb0b8036bda0686ef844d24125d8287178ce0"}, + {file = "contourpy-1.3.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8ca947601224119117f7c19c9cdf6b3ab54c5726ef1d906aa4a69dfb6dd58102"}, + {file = "contourpy-1.3.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:c6ec93afeb848a0845a18989da3beca3eec2c0f852322efe21af1931147d12cb"}, + {file = "contourpy-1.3.0.tar.gz", hash = "sha256:7ffa0db17717a8ffb127efd0c95a4362d996b892c2904db72428d5b52e1938a4"}, +] + +[package.dependencies] +numpy = ">=1.23" + +[package.extras] +bokeh = ["bokeh", "selenium"] +docs = ["furo", "sphinx (>=7.2)", "sphinx-copybutton"] +mypy = ["contourpy[bokeh,docs]", "docutils-stubs", "mypy (==1.11.1)", "types-Pillow"] +test = ["Pillow", "contourpy[test-no-images]", "matplotlib"] +test-no-images = ["pytest", "pytest-cov", "pytest-rerunfailures", "pytest-xdist", "wurlitzer"] + [[package]] name = "coverage" -version = "7.6.0" +version = "7.6.1" description = "Code coverage measurement for Python" optional = true python-versions = ">=3.8" files = [ - {file = "coverage-7.6.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:dff044f661f59dace805eedb4a7404c573b6ff0cdba4a524141bc63d7be5c7fd"}, - {file = "coverage-7.6.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:a8659fd33ee9e6ca03950cfdcdf271d645cf681609153f218826dd9805ab585c"}, - {file = "coverage-7.6.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7792f0ab20df8071d669d929c75c97fecfa6bcab82c10ee4adb91c7a54055463"}, - {file = "coverage-7.6.0-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d4b3cd1ca7cd73d229487fa5caca9e4bc1f0bca96526b922d61053ea751fe791"}, - {file = "coverage-7.6.0-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e7e128f85c0b419907d1f38e616c4f1e9f1d1b37a7949f44df9a73d5da5cd53c"}, - {file = "coverage-7.6.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:a94925102c89247530ae1dab7dc02c690942566f22e189cbd53579b0693c0783"}, - {file = "coverage-7.6.0-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:dcd070b5b585b50e6617e8972f3fbbee786afca71b1936ac06257f7e178f00f6"}, - {file = "coverage-7.6.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:d50a252b23b9b4dfeefc1f663c568a221092cbaded20a05a11665d0dbec9b8fb"}, - {file = "coverage-7.6.0-cp310-cp310-win32.whl", hash = "sha256:0e7b27d04131c46e6894f23a4ae186a6a2207209a05df5b6ad4caee6d54a222c"}, - {file = "coverage-7.6.0-cp310-cp310-win_amd64.whl", hash = "sha256:54dece71673b3187c86226c3ca793c5f891f9fc3d8aa183f2e3653da18566169"}, - {file = "coverage-7.6.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c7b525ab52ce18c57ae232ba6f7010297a87ced82a2383b1afd238849c1ff933"}, - {file = "coverage-7.6.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:4bea27c4269234e06f621f3fac3925f56ff34bc14521484b8f66a580aacc2e7d"}, - {file = "coverage-7.6.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ed8d1d1821ba5fc88d4a4f45387b65de52382fa3ef1f0115a4f7a20cdfab0e94"}, - {file = "coverage-7.6.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:01c322ef2bbe15057bc4bf132b525b7e3f7206f071799eb8aa6ad1940bcf5fb1"}, - {file = "coverage-7.6.0-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:03cafe82c1b32b770a29fd6de923625ccac3185a54a5e66606da26d105f37dac"}, - {file = "coverage-7.6.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0d1b923fc4a40c5832be4f35a5dab0e5ff89cddf83bb4174499e02ea089daf57"}, - {file = "coverage-7.6.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:4b03741e70fb811d1a9a1d75355cf391f274ed85847f4b78e35459899f57af4d"}, - {file = "coverage-7.6.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:a73d18625f6a8a1cbb11eadc1d03929f9510f4131879288e3f7922097a429f63"}, - {file = "coverage-7.6.0-cp311-cp311-win32.whl", hash = "sha256:65fa405b837060db569a61ec368b74688f429b32fa47a8929a7a2f9b47183713"}, - {file = "coverage-7.6.0-cp311-cp311-win_amd64.whl", hash = "sha256:6379688fb4cfa921ae349c76eb1a9ab26b65f32b03d46bb0eed841fd4cb6afb1"}, - {file = "coverage-7.6.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:f7db0b6ae1f96ae41afe626095149ecd1b212b424626175a6633c2999eaad45b"}, - {file = "coverage-7.6.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:bbdf9a72403110a3bdae77948b8011f644571311c2fb35ee15f0f10a8fc082e8"}, - {file = "coverage-7.6.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9cc44bf0315268e253bf563f3560e6c004efe38f76db03a1558274a6e04bf5d5"}, - {file = "coverage-7.6.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:da8549d17489cd52f85a9829d0e1d91059359b3c54a26f28bec2c5d369524807"}, - {file = "coverage-7.6.0-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0086cd4fc71b7d485ac93ca4239c8f75732c2ae3ba83f6be1c9be59d9e2c6382"}, - {file = "coverage-7.6.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1fad32ee9b27350687035cb5fdf9145bc9cf0a094a9577d43e909948ebcfa27b"}, - {file = "coverage-7.6.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:044a0985a4f25b335882b0966625270a8d9db3d3409ddc49a4eb00b0ef5e8cee"}, - {file = "coverage-7.6.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:76d5f82213aa78098b9b964ea89de4617e70e0d43e97900c2778a50856dac605"}, - {file = "coverage-7.6.0-cp312-cp312-win32.whl", hash = "sha256:3c59105f8d58ce500f348c5b56163a4113a440dad6daa2294b5052a10db866da"}, - {file = "coverage-7.6.0-cp312-cp312-win_amd64.whl", hash = "sha256:ca5d79cfdae420a1d52bf177de4bc2289c321d6c961ae321503b2ca59c17ae67"}, - {file = "coverage-7.6.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:d39bd10f0ae453554798b125d2f39884290c480f56e8a02ba7a6ed552005243b"}, - {file = "coverage-7.6.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:beb08e8508e53a568811016e59f3234d29c2583f6b6e28572f0954a6b4f7e03d"}, - {file = "coverage-7.6.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b2e16f4cd2bc4d88ba30ca2d3bbf2f21f00f382cf4e1ce3b1ddc96c634bc48ca"}, - {file = "coverage-7.6.0-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6616d1c9bf1e3faea78711ee42a8b972367d82ceae233ec0ac61cc7fec09fa6b"}, - {file = "coverage-7.6.0-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ad4567d6c334c46046d1c4c20024de2a1c3abc626817ae21ae3da600f5779b44"}, - {file = "coverage-7.6.0-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:d17c6a415d68cfe1091d3296ba5749d3d8696e42c37fca5d4860c5bf7b729f03"}, - {file = "coverage-7.6.0-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:9146579352d7b5f6412735d0f203bbd8d00113a680b66565e205bc605ef81bc6"}, - {file = "coverage-7.6.0-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:cdab02a0a941af190df8782aafc591ef3ad08824f97850b015c8c6a8b3877b0b"}, - {file = "coverage-7.6.0-cp38-cp38-win32.whl", hash = "sha256:df423f351b162a702c053d5dddc0fc0ef9a9e27ea3f449781ace5f906b664428"}, - {file = "coverage-7.6.0-cp38-cp38-win_amd64.whl", hash = "sha256:f2501d60d7497fd55e391f423f965bbe9e650e9ffc3c627d5f0ac516026000b8"}, - {file = "coverage-7.6.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:7221f9ac9dad9492cecab6f676b3eaf9185141539d5c9689d13fd6b0d7de840c"}, - {file = "coverage-7.6.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:ddaaa91bfc4477d2871442bbf30a125e8fe6b05da8a0015507bfbf4718228ab2"}, - {file = "coverage-7.6.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c4cbe651f3904e28f3a55d6f371203049034b4ddbce65a54527a3f189ca3b390"}, - {file = "coverage-7.6.0-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:831b476d79408ab6ccfadaaf199906c833f02fdb32c9ab907b1d4aa0713cfa3b"}, - {file = "coverage-7.6.0-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:46c3d091059ad0b9c59d1034de74a7f36dcfa7f6d3bde782c49deb42438f2450"}, - {file = "coverage-7.6.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:4d5fae0a22dc86259dee66f2cc6c1d3e490c4a1214d7daa2a93d07491c5c04b6"}, - {file = "coverage-7.6.0-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:07ed352205574aad067482e53dd606926afebcb5590653121063fbf4e2175166"}, - {file = "coverage-7.6.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:49c76cdfa13015c4560702574bad67f0e15ca5a2872c6a125f6327ead2b731dd"}, - {file = "coverage-7.6.0-cp39-cp39-win32.whl", hash = "sha256:482855914928c8175735a2a59c8dc5806cf7d8f032e4820d52e845d1f731dca2"}, - {file = "coverage-7.6.0-cp39-cp39-win_amd64.whl", hash = "sha256:543ef9179bc55edfd895154a51792b01c017c87af0ebaae092720152e19e42ca"}, - {file = "coverage-7.6.0-pp38.pp39.pp310-none-any.whl", hash = "sha256:6fe885135c8a479d3e37a7aae61cbd3a0fb2deccb4dda3c25f92a49189f766d6"}, - {file = "coverage-7.6.0.tar.gz", hash = "sha256:289cc803fa1dc901f84701ac10c9ee873619320f2f9aff38794db4a4a0268d51"}, + {file = "coverage-7.6.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:b06079abebbc0e89e6163b8e8f0e16270124c154dc6e4a47b413dd538859af16"}, + {file = "coverage-7.6.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:cf4b19715bccd7ee27b6b120e7e9dd56037b9c0681dcc1adc9ba9db3d417fa36"}, + {file = "coverage-7.6.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e61c0abb4c85b095a784ef23fdd4aede7a2628478e7baba7c5e3deba61070a02"}, + {file = "coverage-7.6.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:fd21f6ae3f08b41004dfb433fa895d858f3f5979e7762d052b12aef444e29afc"}, + {file = "coverage-7.6.1-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f59d57baca39b32db42b83b2a7ba6f47ad9c394ec2076b084c3f029b7afca23"}, + {file = "coverage-7.6.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:a1ac0ae2b8bd743b88ed0502544847c3053d7171a3cff9228af618a068ed9c34"}, + {file = "coverage-7.6.1-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:e6a08c0be454c3b3beb105c0596ebdc2371fab6bb90c0c0297f4e58fd7e1012c"}, + {file = "coverage-7.6.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:f5796e664fe802da4f57a168c85359a8fbf3eab5e55cd4e4569fbacecc903959"}, + {file = "coverage-7.6.1-cp310-cp310-win32.whl", hash = "sha256:7bb65125fcbef8d989fa1dd0e8a060999497629ca5b0efbca209588a73356232"}, + {file = "coverage-7.6.1-cp310-cp310-win_amd64.whl", hash = "sha256:3115a95daa9bdba70aea750db7b96b37259a81a709223c8448fa97727d546fe0"}, + {file = "coverage-7.6.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:7dea0889685db8550f839fa202744652e87c60015029ce3f60e006f8c4462c93"}, + {file = "coverage-7.6.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:ed37bd3c3b063412f7620464a9ac1314d33100329f39799255fb8d3027da50d3"}, + {file = "coverage-7.6.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d85f5e9a5f8b73e2350097c3756ef7e785f55bd71205defa0bfdaf96c31616ff"}, + {file = "coverage-7.6.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9bc572be474cafb617672c43fe989d6e48d3c83af02ce8de73fff1c6bb3c198d"}, + {file = "coverage-7.6.1-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0c0420b573964c760df9e9e86d1a9a622d0d27f417e1a949a8a66dd7bcee7bc6"}, + {file = "coverage-7.6.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:1f4aa8219db826ce6be7099d559f8ec311549bfc4046f7f9fe9b5cea5c581c56"}, + {file = "coverage-7.6.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:fc5a77d0c516700ebad189b587de289a20a78324bc54baee03dd486f0855d234"}, + {file = "coverage-7.6.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b48f312cca9621272ae49008c7f613337c53fadca647d6384cc129d2996d1133"}, + {file = "coverage-7.6.1-cp311-cp311-win32.whl", hash = "sha256:1125ca0e5fd475cbbba3bb67ae20bd2c23a98fac4e32412883f9bcbaa81c314c"}, + {file = "coverage-7.6.1-cp311-cp311-win_amd64.whl", hash = "sha256:8ae539519c4c040c5ffd0632784e21b2f03fc1340752af711f33e5be83a9d6c6"}, + {file = "coverage-7.6.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:95cae0efeb032af8458fc27d191f85d1717b1d4e49f7cb226cf526ff28179778"}, + {file = "coverage-7.6.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5621a9175cf9d0b0c84c2ef2b12e9f5f5071357c4d2ea6ca1cf01814f45d2391"}, + {file = "coverage-7.6.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:260933720fdcd75340e7dbe9060655aff3af1f0c5d20f46b57f262ab6c86a5e8"}, + {file = "coverage-7.6.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:07e2ca0ad381b91350c0ed49d52699b625aab2b44b65e1b4e02fa9df0e92ad2d"}, + {file = "coverage-7.6.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c44fee9975f04b33331cb8eb272827111efc8930cfd582e0320613263ca849ca"}, + {file = "coverage-7.6.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:877abb17e6339d96bf08e7a622d05095e72b71f8afd8a9fefc82cf30ed944163"}, + {file = "coverage-7.6.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:3e0cadcf6733c09154b461f1ca72d5416635e5e4ec4e536192180d34ec160f8a"}, + {file = "coverage-7.6.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c3c02d12f837d9683e5ab2f3d9844dc57655b92c74e286c262e0fc54213c216d"}, + {file = "coverage-7.6.1-cp312-cp312-win32.whl", hash = "sha256:e05882b70b87a18d937ca6768ff33cc3f72847cbc4de4491c8e73880766718e5"}, + {file = "coverage-7.6.1-cp312-cp312-win_amd64.whl", hash = "sha256:b5d7b556859dd85f3a541db6a4e0167b86e7273e1cdc973e5b175166bb634fdb"}, + {file = "coverage-7.6.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:a4acd025ecc06185ba2b801f2de85546e0b8ac787cf9d3b06e7e2a69f925b106"}, + {file = "coverage-7.6.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:a6d3adcf24b624a7b778533480e32434a39ad8fa30c315208f6d3e5542aeb6e9"}, + {file = "coverage-7.6.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d0c212c49b6c10e6951362f7c6df3329f04c2b1c28499563d4035d964ab8e08c"}, + {file = "coverage-7.6.1-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6e81d7a3e58882450ec4186ca59a3f20a5d4440f25b1cff6f0902ad890e6748a"}, + {file = "coverage-7.6.1-cp313-cp313-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:78b260de9790fd81e69401c2dc8b17da47c8038176a79092a89cb2b7d945d060"}, + {file = "coverage-7.6.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:a78d169acd38300060b28d600344a803628c3fd585c912cacc9ea8790fe96862"}, + {file = "coverage-7.6.1-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:2c09f4ce52cb99dd7505cd0fc8e0e37c77b87f46bc9c1eb03fe3bc9991085388"}, + {file = "coverage-7.6.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:6878ef48d4227aace338d88c48738a4258213cd7b74fd9a3d4d7582bb1d8a155"}, + {file = "coverage-7.6.1-cp313-cp313-win32.whl", hash = "sha256:44df346d5215a8c0e360307d46ffaabe0f5d3502c8a1cefd700b34baf31d411a"}, + {file = "coverage-7.6.1-cp313-cp313-win_amd64.whl", hash = "sha256:8284cf8c0dd272a247bc154eb6c95548722dce90d098c17a883ed36e67cdb129"}, + {file = "coverage-7.6.1-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:d3296782ca4eab572a1a4eca686d8bfb00226300dcefdf43faa25b5242ab8a3e"}, + {file = "coverage-7.6.1-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:502753043567491d3ff6d08629270127e0c31d4184c4c8d98f92c26f65019962"}, + {file = "coverage-7.6.1-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6a89ecca80709d4076b95f89f308544ec8f7b4727e8a547913a35f16717856cb"}, + {file = "coverage-7.6.1-cp313-cp313t-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:a318d68e92e80af8b00fa99609796fdbcdfef3629c77c6283566c6f02c6d6704"}, + {file = "coverage-7.6.1-cp313-cp313t-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:13b0a73a0896988f053e4fbb7de6d93388e6dd292b0d87ee51d106f2c11b465b"}, + {file = "coverage-7.6.1-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:4421712dbfc5562150f7554f13dde997a2e932a6b5f352edcce948a815efee6f"}, + {file = "coverage-7.6.1-cp313-cp313t-musllinux_1_2_i686.whl", hash = "sha256:166811d20dfea725e2e4baa71fffd6c968a958577848d2131f39b60043400223"}, + {file = "coverage-7.6.1-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:225667980479a17db1048cb2bf8bfb39b8e5be8f164b8f6628b64f78a72cf9d3"}, + {file = "coverage-7.6.1-cp313-cp313t-win32.whl", hash = "sha256:170d444ab405852903b7d04ea9ae9b98f98ab6d7e63e1115e82620807519797f"}, + {file = "coverage-7.6.1-cp313-cp313t-win_amd64.whl", hash = "sha256:b9f222de8cded79c49bf184bdbc06630d4c58eec9459b939b4a690c82ed05657"}, + {file = "coverage-7.6.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:6db04803b6c7291985a761004e9060b2bca08da6d04f26a7f2294b8623a0c1a0"}, + {file = "coverage-7.6.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:f1adfc8ac319e1a348af294106bc6a8458a0f1633cc62a1446aebc30c5fa186a"}, + {file = "coverage-7.6.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a95324a9de9650a729239daea117df21f4b9868ce32e63f8b650ebe6cef5595b"}, + {file = "coverage-7.6.1-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b43c03669dc4618ec25270b06ecd3ee4fa94c7f9b3c14bae6571ca00ef98b0d3"}, + {file = "coverage-7.6.1-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8929543a7192c13d177b770008bc4e8119f2e1f881d563fc6b6305d2d0ebe9de"}, + {file = "coverage-7.6.1-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:a09ece4a69cf399510c8ab25e0950d9cf2b42f7b3cb0374f95d2e2ff594478a6"}, + {file = "coverage-7.6.1-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:9054a0754de38d9dbd01a46621636689124d666bad1936d76c0341f7d71bf569"}, + {file = "coverage-7.6.1-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:0dbde0f4aa9a16fa4d754356a8f2e36296ff4d83994b2c9d8398aa32f222f989"}, + {file = "coverage-7.6.1-cp38-cp38-win32.whl", hash = "sha256:da511e6ad4f7323ee5702e6633085fb76c2f893aaf8ce4c51a0ba4fc07580ea7"}, + {file = "coverage-7.6.1-cp38-cp38-win_amd64.whl", hash = "sha256:3f1156e3e8f2872197af3840d8ad307a9dd18e615dc64d9ee41696f287c57ad8"}, + {file = "coverage-7.6.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:abd5fd0db5f4dc9289408aaf34908072f805ff7792632250dcb36dc591d24255"}, + {file = "coverage-7.6.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:547f45fa1a93154bd82050a7f3cddbc1a7a4dd2a9bf5cb7d06f4ae29fe94eaf8"}, + {file = "coverage-7.6.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:645786266c8f18a931b65bfcefdbf6952dd0dea98feee39bd188607a9d307ed2"}, + {file = "coverage-7.6.1-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9e0b2df163b8ed01d515807af24f63de04bebcecbd6c3bfeff88385789fdf75a"}, + {file = "coverage-7.6.1-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:609b06f178fe8e9f89ef676532760ec0b4deea15e9969bf754b37f7c40326dbc"}, + {file = "coverage-7.6.1-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:702855feff378050ae4f741045e19a32d57d19f3e0676d589df0575008ea5004"}, + {file = "coverage-7.6.1-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:2bdb062ea438f22d99cba0d7829c2ef0af1d768d1e4a4f528087224c90b132cb"}, + {file = "coverage-7.6.1-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:9c56863d44bd1c4fe2abb8a4d6f5371d197f1ac0ebdee542f07f35895fc07f36"}, + {file = "coverage-7.6.1-cp39-cp39-win32.whl", hash = "sha256:6e2cd258d7d927d09493c8df1ce9174ad01b381d4729a9d8d4e38670ca24774c"}, + {file = "coverage-7.6.1-cp39-cp39-win_amd64.whl", hash = "sha256:06a737c882bd26d0d6ee7269b20b12f14a8704807a01056c80bb881a4b2ce6ca"}, + {file = "coverage-7.6.1-pp38.pp39.pp310-none-any.whl", hash = "sha256:e9a6e0eb86070e8ccaedfbd9d38fec54864f3125ab95419970575b42af7541df"}, + {file = "coverage-7.6.1.tar.gz", hash = "sha256:953510dfb7b12ab69d20135a0662397f077c59b1e6379a768e97c59d852ee51d"}, ] [package.dependencies] @@ -520,108 +913,209 @@ tomli = {version = "*", optional = true, markers = "python_full_version <= \"3.1 [package.extras] toml = ["tomli"] +[[package]] +name = "cycler" +version = "0.12.1" +description = "Composable style cycles" +optional = true +python-versions = ">=3.8" +files = [ + {file = "cycler-0.12.1-py3-none-any.whl", hash = "sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30"}, + {file = "cycler-0.12.1.tar.gz", hash = "sha256:88bb128f02ba341da8ef447245a9e138fae777f6a23943da4540077d3601eb1c"}, +] + +[package.extras] +docs = ["ipython", "matplotlib", "numpydoc", "sphinx"] +tests = ["pytest", "pytest-cov", "pytest-xdist"] + +[[package]] +name = "dash" +version = "2.18.1" +description = "A Python framework for building reactive web-apps. Developed by Plotly." +optional = true +python-versions = ">=3.8" +files = [ + {file = "dash-2.18.1-py3-none-any.whl", hash = "sha256:07c4513bb5f79a4b936847a0b49afc21dbd4b001ff77ea78d4d836043e211a07"}, + {file = "dash-2.18.1.tar.gz", hash = "sha256:ffdf89690d734f6851ef1cb344222826ffb11ad2214ab9172668bf8aadd75d12"}, +] + +[package.dependencies] +dash-core-components = "2.0.0" +dash-html-components = "2.0.0" +dash-table = "5.0.0" +Flask = ">=1.0.4,<3.1" +importlib-metadata = "*" +nest-asyncio = "*" +plotly = ">=5.0.0" +requests = "*" +retrying = "*" +setuptools = "*" +typing-extensions = ">=4.1.1" +Werkzeug = "<3.1" + +[package.extras] +celery = ["celery[redis] (>=5.1.2)", "redis (>=3.5.3)"] +ci = ["black (==22.3.0)", "dash-dangerously-set-inner-html", "dash-flow-example (==0.0.5)", "flake8 (==7.0.0)", "flaky (==3.8.1)", "flask-talisman (==1.0.0)", "jupyterlab (<4.0.0)", "mimesis (<=11.1.0)", "mock (==4.0.3)", "numpy (<=1.26.3)", "openpyxl", "orjson (==3.10.3)", "pandas (>=1.4.0)", "pyarrow", "pylint (==3.0.3)", "pytest-mock", "pytest-rerunfailures", "pytest-sugar (==0.9.6)", "pyzmq (==25.1.2)", "xlrd (>=2.0.1)"] +compress = ["flask-compress"] +dev = ["PyYAML (>=5.4.1)", "coloredlogs (>=15.0.1)", "fire (>=0.4.0)"] +diskcache = ["diskcache (>=5.2.1)", "multiprocess (>=0.70.12)", "psutil (>=5.8.0)"] +testing = ["beautifulsoup4 (>=4.8.2)", "cryptography", "dash-testing-stub (>=0.0.2)", "lxml (>=4.6.2)", "multiprocess (>=0.70.12)", "percy (>=2.0.2)", "psutil (>=5.8.0)", "pytest (>=6.0.2)", "requests[security] (>=2.21.0)", "selenium (>=3.141.0,<=4.2.0)", "waitress (>=1.4.4)"] + +[[package]] +name = "dash-core-components" +version = "2.0.0" +description = "Core component suite for Dash" +optional = true +python-versions = "*" +files = [ + {file = "dash_core_components-2.0.0-py3-none-any.whl", hash = "sha256:52b8e8cce13b18d0802ee3acbc5e888cb1248a04968f962d63d070400af2e346"}, + {file = "dash_core_components-2.0.0.tar.gz", hash = "sha256:c6733874af975e552f95a1398a16c2ee7df14ce43fa60bb3718a3c6e0b63ffee"}, +] + +[[package]] +name = "dash-html-components" +version = "2.0.0" +description = "Vanilla HTML components for Dash" +optional = true +python-versions = "*" +files = [ + {file = "dash_html_components-2.0.0-py3-none-any.whl", hash = "sha256:b42cc903713c9706af03b3f2548bda4be7307a7cf89b7d6eae3da872717d1b63"}, + {file = "dash_html_components-2.0.0.tar.gz", hash = "sha256:8703a601080f02619a6390998e0b3da4a5daabe97a1fd7a9cebc09d015f26e50"}, +] + +[[package]] +name = "dash-table" +version = "5.0.0" +description = "Dash table" +optional = true +python-versions = "*" +files = [ + {file = "dash_table-5.0.0-py3-none-any.whl", hash = "sha256:19036fa352bb1c11baf38068ec62d172f0515f73ca3276c79dee49b95ddc16c9"}, + {file = "dash_table-5.0.0.tar.gz", hash = "sha256:18624d693d4c8ef2ddec99a6f167593437a7ea0bf153aa20f318c170c5bc7308"}, +] + [[package]] name = "datasets" -version = "2.20.0" +version = "3.0.0" description = "HuggingFace community-driven open-source library of datasets" optional = false python-versions = ">=3.8.0" files = [ - {file = "datasets-2.20.0-py3-none-any.whl", hash = "sha256:76ac02e3bdfff824492e20678f0b6b1b6d080515957fe834b00c2ba8d6b18e5e"}, - {file = "datasets-2.20.0.tar.gz", hash = "sha256:3c4dbcd27e0f642b9d41d20ff2efa721a5e04b32b2ca4009e0fc9139e324553f"}, + {file = "datasets-3.0.0-py3-none-any.whl", hash = "sha256:c23fefb6c953dcb1cd5f6deb6c502729c733ef98791e0c3f2d80c7ca2d9a01dd"}, + {file = "datasets-3.0.0.tar.gz", hash = "sha256:592317eb137f0fc5aac068ff283ba13c3c66d10c9c034d44bc8aa584126cf3e2"}, ] [package.dependencies] aiohttp = "*" dill = ">=0.3.0,<0.3.9" filelock = "*" -fsspec = {version = ">=2023.1.0,<=2024.5.0", extras = ["http"]} -huggingface-hub = ">=0.21.2" +fsspec = {version = ">=2023.1.0,<=2024.6.1", extras = ["http"]} +huggingface-hub = ">=0.22.0" multiprocess = "*" numpy = ">=1.17" packaging = "*" pandas = "*" pyarrow = ">=15.0.0" -pyarrow-hotfix = "*" pyyaml = ">=5.1" requests = ">=2.32.2" tqdm = ">=4.66.3" xxhash = "*" [package.extras] -apache-beam = ["apache-beam (>=2.26.0)"] -audio = ["librosa", "soundfile (>=0.12.1)"] +audio = ["librosa", "soundfile (>=0.12.1)", "soxr (>=0.4.0)"] benchmarks = ["tensorflow (==2.12.0)", "torch (==2.0.1)", "transformers (==4.30.1)"] -dev = ["Pillow (>=9.4.0)", "absl-py", "elasticsearch (<8.0.0)", "faiss-cpu (>=1.6.4)", "jax (>=0.3.14)", "jaxlib (>=0.3.14)", "joblib (<1.3.0)", "joblibspark", "librosa", "lz4", "polars[timezone] (>=0.20.0)", "protobuf (<4.0.0)", "py7zr", "pyspark (>=3.4)", "pytest", "pytest-datadir", "pytest-xdist", "rarfile (>=4.0)", "ruff (>=0.3.0)", "s3fs", "s3fs (>=2021.11.1)", "soundfile (>=0.12.1)", "sqlalchemy", "tensorflow (>=2.6.0)", "tiktoken", "torch", "torch (>=2.0.0)", "transformers", "typing-extensions (>=4.6.1)", "zstandard"] +dev = ["Pillow (>=9.4.0)", "absl-py", "decorator", "elasticsearch (<8.0.0)", "faiss-cpu (>=1.8.0.post1)", "jax (>=0.3.14)", "jaxlib (>=0.3.14)", "joblib (<1.3.0)", "joblibspark", "librosa", "lz4", "moto[server]", "polars[timezone] (>=0.20.0)", "protobuf (<4.0.0)", "py7zr", "pyspark (>=3.4)", "pytest", "pytest-datadir", "pytest-xdist", "rarfile (>=4.0)", "ruff (>=0.3.0)", "s3fs", "s3fs (>=2021.11.1)", "soundfile (>=0.12.1)", "soxr (>=0.4.0)", "sqlalchemy", "tensorflow (>=2.16.0)", "tensorflow (>=2.6.0)", "tensorflow (>=2.6.0)", "tiktoken", "torch", "torch (>=2.0.0)", "transformers", "transformers (>=4.42.0)", "zstandard"] docs = ["s3fs", "tensorflow (>=2.6.0)", "torch", "transformers"] jax = ["jax (>=0.3.14)", "jaxlib (>=0.3.14)"] -metrics-tests = ["Werkzeug (>=1.0.1)", "accelerate", "bert-score (>=0.3.6)", "jiwer", "langdetect", "mauve-text", "nltk", "requests-file (>=1.5.1)", "rouge-score", "sacrebleu", "sacremoses", "scikit-learn", "scipy", "sentencepiece", "seqeval", "six (>=1.15.0,<1.16.0)", "spacy (>=3.0.0)", "texttable (>=1.6.3)", "tldextract", "tldextract (>=3.1.0)", "toml (>=0.10.1)", "typer (<0.5.0)"] quality = ["ruff (>=0.3.0)"] s3 = ["s3fs"] tensorflow = ["tensorflow (>=2.6.0)"] tensorflow-gpu = ["tensorflow (>=2.6.0)"] -tests = ["Pillow (>=9.4.0)", "absl-py", "elasticsearch (<8.0.0)", "faiss-cpu (>=1.6.4)", "jax (>=0.3.14)", "jaxlib (>=0.3.14)", "joblib (<1.3.0)", "joblibspark", "librosa", "lz4", "polars[timezone] (>=0.20.0)", "protobuf (<4.0.0)", "py7zr", "pyspark (>=3.4)", "pytest", "pytest-datadir", "pytest-xdist", "rarfile (>=4.0)", "s3fs (>=2021.11.1)", "soundfile (>=0.12.1)", "sqlalchemy", "tensorflow (>=2.6.0)", "tiktoken", "torch (>=2.0.0)", "transformers", "typing-extensions (>=4.6.1)", "zstandard"] +tests = ["Pillow (>=9.4.0)", "absl-py", "decorator", "elasticsearch (<8.0.0)", "faiss-cpu (>=1.8.0.post1)", "jax (>=0.3.14)", "jaxlib (>=0.3.14)", "joblib (<1.3.0)", "joblibspark", "librosa", "lz4", "moto[server]", "polars[timezone] (>=0.20.0)", "protobuf (<4.0.0)", "py7zr", "pyspark (>=3.4)", "pytest", "pytest-datadir", "pytest-xdist", "rarfile (>=4.0)", "s3fs (>=2021.11.1)", "soundfile (>=0.12.1)", "soxr (>=0.4.0)", "sqlalchemy", "tensorflow (>=2.16.0)", "tensorflow (>=2.6.0)", "tiktoken", "torch (>=2.0.0)", "transformers (>=4.42.0)", "zstandard"] +tests-numpy2 = ["Pillow (>=9.4.0)", "absl-py", "decorator", "elasticsearch (<8.0.0)", "jax (>=0.3.14)", "jaxlib (>=0.3.14)", "joblib (<1.3.0)", "joblibspark", "lz4", "moto[server]", "polars[timezone] (>=0.20.0)", "protobuf (<4.0.0)", "py7zr", "pyspark (>=3.4)", "pytest", "pytest-datadir", "pytest-xdist", "rarfile (>=4.0)", "s3fs (>=2021.11.1)", "soundfile (>=0.12.1)", "soxr (>=0.4.0)", "sqlalchemy", "tiktoken", "torch (>=2.0.0)", "transformers (>=4.42.0)", "zstandard"] torch = ["torch"] vision = ["Pillow (>=9.4.0)"] [[package]] name = "debugpy" -version = "1.8.2" +version = "1.8.6" description = "An implementation of the Debug Adapter Protocol for Python" optional = true python-versions = ">=3.8" files = [ - {file = "debugpy-1.8.2-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:7ee2e1afbf44b138c005e4380097d92532e1001580853a7cb40ed84e0ef1c3d2"}, - {file = "debugpy-1.8.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3f8c3f7c53130a070f0fc845a0f2cee8ed88d220d6b04595897b66605df1edd6"}, - {file = "debugpy-1.8.2-cp310-cp310-win32.whl", hash = "sha256:f179af1e1bd4c88b0b9f0fa153569b24f6b6f3de33f94703336363ae62f4bf47"}, - {file = "debugpy-1.8.2-cp310-cp310-win_amd64.whl", hash = "sha256:0600faef1d0b8d0e85c816b8bb0cb90ed94fc611f308d5fde28cb8b3d2ff0fe3"}, - {file = "debugpy-1.8.2-cp311-cp311-macosx_11_0_universal2.whl", hash = "sha256:8a13417ccd5978a642e91fb79b871baded925d4fadd4dfafec1928196292aa0a"}, - {file = "debugpy-1.8.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:acdf39855f65c48ac9667b2801234fc64d46778021efac2de7e50907ab90c634"}, - {file = "debugpy-1.8.2-cp311-cp311-win32.whl", hash = "sha256:2cbd4d9a2fc5e7f583ff9bf11f3b7d78dfda8401e8bb6856ad1ed190be4281ad"}, - {file = "debugpy-1.8.2-cp311-cp311-win_amd64.whl", hash = "sha256:d3408fddd76414034c02880e891ea434e9a9cf3a69842098ef92f6e809d09afa"}, - {file = "debugpy-1.8.2-cp312-cp312-macosx_11_0_universal2.whl", hash = "sha256:5d3ccd39e4021f2eb86b8d748a96c766058b39443c1f18b2dc52c10ac2757835"}, - {file = "debugpy-1.8.2-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:62658aefe289598680193ff655ff3940e2a601765259b123dc7f89c0239b8cd3"}, - {file = "debugpy-1.8.2-cp312-cp312-win32.whl", hash = "sha256:bd11fe35d6fd3431f1546d94121322c0ac572e1bfb1f6be0e9b8655fb4ea941e"}, - {file = "debugpy-1.8.2-cp312-cp312-win_amd64.whl", hash = "sha256:15bc2f4b0f5e99bf86c162c91a74c0631dbd9cef3c6a1d1329c946586255e859"}, - {file = "debugpy-1.8.2-cp38-cp38-macosx_11_0_x86_64.whl", hash = "sha256:5a019d4574afedc6ead1daa22736c530712465c0c4cd44f820d803d937531b2d"}, - {file = "debugpy-1.8.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40f062d6877d2e45b112c0bbade9a17aac507445fd638922b1a5434df34aed02"}, - {file = "debugpy-1.8.2-cp38-cp38-win32.whl", hash = "sha256:c78ba1680f1015c0ca7115671fe347b28b446081dada3fedf54138f44e4ba031"}, - {file = "debugpy-1.8.2-cp38-cp38-win_amd64.whl", hash = "sha256:cf327316ae0c0e7dd81eb92d24ba8b5e88bb4d1b585b5c0d32929274a66a5210"}, - {file = "debugpy-1.8.2-cp39-cp39-macosx_11_0_x86_64.whl", hash = "sha256:1523bc551e28e15147815d1397afc150ac99dbd3a8e64641d53425dba57b0ff9"}, - {file = "debugpy-1.8.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e24ccb0cd6f8bfaec68d577cb49e9c680621c336f347479b3fce060ba7c09ec1"}, - {file = "debugpy-1.8.2-cp39-cp39-win32.whl", hash = "sha256:7f8d57a98c5a486c5c7824bc0b9f2f11189d08d73635c326abef268f83950326"}, - {file = "debugpy-1.8.2-cp39-cp39-win_amd64.whl", hash = "sha256:16c8dcab02617b75697a0a925a62943e26a0330da076e2a10437edd9f0bf3755"}, - {file = "debugpy-1.8.2-py2.py3-none-any.whl", hash = "sha256:16e16df3a98a35c63c3ab1e4d19be4cbc7fdda92d9ddc059294f18910928e0ca"}, - {file = "debugpy-1.8.2.zip", hash = "sha256:95378ed08ed2089221896b9b3a8d021e642c24edc8fef20e5d4342ca8be65c00"}, + {file = "debugpy-1.8.6-cp310-cp310-macosx_14_0_x86_64.whl", hash = "sha256:30f467c5345d9dfdcc0afdb10e018e47f092e383447500f125b4e013236bf14b"}, + {file = "debugpy-1.8.6-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5d73d8c52614432f4215d0fe79a7e595d0dd162b5c15233762565be2f014803b"}, + {file = "debugpy-1.8.6-cp310-cp310-win32.whl", hash = "sha256:e3e182cd98eac20ee23a00653503315085b29ab44ed66269482349d307b08df9"}, + {file = "debugpy-1.8.6-cp310-cp310-win_amd64.whl", hash = "sha256:e3a82da039cfe717b6fb1886cbbe5c4a3f15d7df4765af857f4307585121c2dd"}, + {file = "debugpy-1.8.6-cp311-cp311-macosx_14_0_universal2.whl", hash = "sha256:67479a94cf5fd2c2d88f9615e087fcb4fec169ec780464a3f2ba4a9a2bb79955"}, + {file = "debugpy-1.8.6-cp311-cp311-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9fb8653f6cbf1dd0a305ac1aa66ec246002145074ea57933978346ea5afdf70b"}, + {file = "debugpy-1.8.6-cp311-cp311-win32.whl", hash = "sha256:cdaf0b9691879da2d13fa39b61c01887c34558d1ff6e5c30e2eb698f5384cd43"}, + {file = "debugpy-1.8.6-cp311-cp311-win_amd64.whl", hash = "sha256:43996632bee7435583952155c06881074b9a742a86cee74e701d87ca532fe833"}, + {file = "debugpy-1.8.6-cp312-cp312-macosx_14_0_universal2.whl", hash = "sha256:db891b141fc6ee4b5fc6d1cc8035ec329cabc64bdd2ae672b4550c87d4ecb128"}, + {file = "debugpy-1.8.6-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:567419081ff67da766c898ccf21e79f1adad0e321381b0dfc7a9c8f7a9347972"}, + {file = "debugpy-1.8.6-cp312-cp312-win32.whl", hash = "sha256:c9834dfd701a1f6bf0f7f0b8b1573970ae99ebbeee68314116e0ccc5c78eea3c"}, + {file = "debugpy-1.8.6-cp312-cp312-win_amd64.whl", hash = "sha256:e4ce0570aa4aca87137890d23b86faeadf184924ad892d20c54237bcaab75d8f"}, + {file = "debugpy-1.8.6-cp38-cp38-macosx_14_0_x86_64.whl", hash = "sha256:df5dc9eb4ca050273b8e374a4cd967c43be1327eeb42bfe2f58b3cdfe7c68dcb"}, + {file = "debugpy-1.8.6-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0a85707c6a84b0c5b3db92a2df685b5230dd8fb8c108298ba4f11dba157a615a"}, + {file = "debugpy-1.8.6-cp38-cp38-win32.whl", hash = "sha256:538c6cdcdcdad310bbefd96d7850be1cd46e703079cc9e67d42a9ca776cdc8a8"}, + {file = "debugpy-1.8.6-cp38-cp38-win_amd64.whl", hash = "sha256:22140bc02c66cda6053b6eb56dfe01bbe22a4447846581ba1dd6df2c9f97982d"}, + {file = "debugpy-1.8.6-cp39-cp39-macosx_14_0_x86_64.whl", hash = "sha256:c1cef65cffbc96e7b392d9178dbfd524ab0750da6c0023c027ddcac968fd1caa"}, + {file = "debugpy-1.8.6-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f1e60bd06bb3cc5c0e957df748d1fab501e01416c43a7bdc756d2a992ea1b881"}, + {file = "debugpy-1.8.6-cp39-cp39-win32.whl", hash = "sha256:f7158252803d0752ed5398d291dee4c553bb12d14547c0e1843ab74ee9c31123"}, + {file = "debugpy-1.8.6-cp39-cp39-win_amd64.whl", hash = "sha256:3358aa619a073b620cd0d51d8a6176590af24abcc3fe2e479929a154bf591b51"}, + {file = "debugpy-1.8.6-py2.py3-none-any.whl", hash = "sha256:b48892df4d810eff21d3ef37274f4c60d32cdcafc462ad5647239036b0f0649f"}, + {file = "debugpy-1.8.6.zip", hash = "sha256:c931a9371a86784cee25dec8d65bc2dc7a21f3f1552e3833d9ef8f919d22280a"}, +] + +[[package]] +name = "decorator" +version = "5.1.1" +description = "Decorators for Humans" +optional = true +python-versions = ">=3.5" +files = [ + {file = "decorator-5.1.1-py3-none-any.whl", hash = "sha256:b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186"}, + {file = "decorator-5.1.1.tar.gz", hash = "sha256:637996211036b6385ef91435e4fae22989472f9d571faba8927ba8253acbc330"}, ] [[package]] name = "deepdiff" -version = "7.0.1" +version = "8.0.1" description = "Deep Difference and Search of any Python object/data. Recreate objects by adding adding deltas to each other." optional = false python-versions = ">=3.8" files = [ - {file = "deepdiff-7.0.1-py3-none-any.whl", hash = "sha256:447760081918216aa4fd4ca78a4b6a848b81307b2ea94c810255334b759e1dc3"}, - {file = "deepdiff-7.0.1.tar.gz", hash = "sha256:260c16f052d4badbf60351b4f77e8390bee03a0b516246f6839bc813fb429ddf"}, + {file = "deepdiff-8.0.1-py3-none-any.whl", hash = "sha256:42e99004ce603f9a53934c634a57b04ad5900e0d8ed0abb15e635767489cbc05"}, + {file = "deepdiff-8.0.1.tar.gz", hash = "sha256:245599a4586ab59bb599ca3517a9c42f3318ff600ded5e80a3432693c8ec3c4b"}, ] [package.dependencies] -ordered-set = ">=4.1.0,<4.2.0" +orderly-set = "5.2.2" [package.extras] cli = ["click (==8.1.7)", "pyyaml (==6.0.1)"] optimize = ["orjson"] +[[package]] +name = "defusedxml" +version = "0.7.1" +description = "XML bomb protection for Python stdlib modules" +optional = true +python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" +files = [ + {file = "defusedxml-0.7.1-py2.py3-none-any.whl", hash = "sha256:a352e7e428770286cc899e2542b6cdaedb2b4953ff269a210103ec58f6198a61"}, + {file = "defusedxml-0.7.1.tar.gz", hash = "sha256:1bb3032db185915b62d7c6209c5a8792be6a32ab2fedacc84e01b52c51aa3e69"}, +] + [[package]] name = "diffusers" -version = "0.29.2" +version = "0.30.3" description = "State-of-the-art diffusion in PyTorch and JAX." optional = false python-versions = ">=3.8.0" files = [ - {file = "diffusers-0.29.2-py3-none-any.whl", hash = "sha256:d5e9bb13c8097b4eed10df23d1294d2e5a418f53e3f89c7ef228b5b982970428"}, - {file = "diffusers-0.29.2.tar.gz", hash = "sha256:b85f277668e22089cf68b40dd9b76940db7d24ba9cdac107533ed10ab8e4e9db"}, + {file = "diffusers-0.30.3-py3-none-any.whl", hash = "sha256:1b70209e4d2c61223b96a7e13bc4d70869c8b0b68f54a35ce3a67fcf813edeee"}, + {file = "diffusers-0.30.3.tar.gz", hash = "sha256:67c5eb25d5b50bf0742624ef43fe0f6d1e1604f64aad3e8558469cbe89ecf72f"}, ] [package.dependencies] @@ -635,13 +1129,13 @@ requests = "*" safetensors = ">=0.3.1" [package.extras] -dev = ["GitPython (<3.1.19)", "Jinja2", "accelerate (>=0.29.3)", "compel (==0.1.8)", "datasets", "flax (>=0.4.1)", "hf-doc-builder (>=0.3.0)", "invisible-watermark (>=0.2.0)", "isort (>=5.5.4)", "jax (>=0.4.1)", "jaxlib (>=0.4.1)", "k-diffusion (>=0.0.12)", "librosa", "parameterized", "peft (>=0.6.0)", "protobuf (>=3.20.3,<4)", "pytest", "pytest-timeout", "pytest-xdist", "requests-mock (==1.10.0)", "ruff (==0.1.5)", "safetensors (>=0.3.1)", "scipy", "sentencepiece (>=0.1.91,!=0.1.92)", "tensorboard", "torch (>=1.4)", "torchvision", "transformers (>=4.25.1)", "urllib3 (<=2.0.0)"] +dev = ["GitPython (<3.1.19)", "Jinja2", "accelerate (>=0.31.0)", "compel (==0.1.8)", "datasets", "flax (>=0.4.1)", "hf-doc-builder (>=0.3.0)", "invisible-watermark (>=0.2.0)", "isort (>=5.5.4)", "jax (>=0.4.1)", "jaxlib (>=0.4.1)", "k-diffusion (>=0.0.12)", "librosa", "parameterized", "peft (>=0.6.0)", "protobuf (>=3.20.3,<4)", "pytest", "pytest-timeout", "pytest-xdist", "requests-mock (==1.10.0)", "ruff (==0.1.5)", "safetensors (>=0.3.1)", "scipy", "sentencepiece (>=0.1.91,!=0.1.92)", "tensorboard", "torch (>=1.4)", "torchvision", "transformers (>=4.41.2)", "urllib3 (<=2.0.0)"] docs = ["hf-doc-builder (>=0.3.0)"] flax = ["flax (>=0.4.1)", "jax (>=0.4.1)", "jaxlib (>=0.4.1)"] quality = ["hf-doc-builder (>=0.3.0)", "isort (>=5.5.4)", "ruff (==0.1.5)", "urllib3 (<=2.0.0)"] -test = ["GitPython (<3.1.19)", "Jinja2", "compel (==0.1.8)", "datasets", "invisible-watermark (>=0.2.0)", "k-diffusion (>=0.0.12)", "librosa", "parameterized", "pytest", "pytest-timeout", "pytest-xdist", "requests-mock (==1.10.0)", "safetensors (>=0.3.1)", "scipy", "sentencepiece (>=0.1.91,!=0.1.92)", "torchvision", "transformers (>=4.25.1)"] -torch = ["accelerate (>=0.29.3)", "torch (>=1.4)"] -training = ["Jinja2", "accelerate (>=0.29.3)", "datasets", "peft (>=0.6.0)", "protobuf (>=3.20.3,<4)", "tensorboard"] +test = ["GitPython (<3.1.19)", "Jinja2", "compel (==0.1.8)", "datasets", "invisible-watermark (>=0.2.0)", "k-diffusion (>=0.0.12)", "librosa", "parameterized", "pytest", "pytest-timeout", "pytest-xdist", "requests-mock (==1.10.0)", "safetensors (>=0.3.1)", "scipy", "sentencepiece (>=0.1.91,!=0.1.92)", "torchvision", "transformers (>=4.41.2)"] +torch = ["accelerate (>=0.31.0)", "torch (>=1.4)"] +training = ["Jinja2", "accelerate (>=0.31.0)", "datasets", "peft (>=0.6.0)", "protobuf (>=3.20.3,<4)", "tensorboard"] [[package]] name = "dill" @@ -787,26 +1281,40 @@ six = ">=1.4.0" [[package]] name = "dora-rs" -version = "0.3.5" +version = "0.3.6" description = "`dora` goal is to be a low latency, composable, and distributed data flow." optional = true python-versions = "*" files = [ - {file = "dora_rs-0.3.5-cp37-abi3-macosx_10_12_x86_64.whl", hash = "sha256:01f811d0c6722f74743c153a7be0144686daeafa968c473e60f6b6c5dc8f5bff"}, - {file = "dora_rs-0.3.5-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:a36e97d31eeb66e6d5913130695d188ceee1248029961012a8b4f59fd3f58670"}, - {file = "dora_rs-0.3.5-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:25d620123a733661dc740ef2b456601ddbaa69ae2b50d8141daa3c684bda385c"}, - {file = "dora_rs-0.3.5-cp37-abi3-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:a9fdc4e73578bebb1c8d0f8bea2243a5a9e179f08c74d98576123b59b75e5cac"}, - {file = "dora_rs-0.3.5-cp37-abi3-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e65830634c58158557f0ab90e5d1f492bcbc6b74587b05825ba4c20b634dc1bd"}, - {file = "dora_rs-0.3.5-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c01f9ab8f93295341aeab2d606d484d9cff9d05f57581e2180433ec8e0d38307"}, - {file = "dora_rs-0.3.5-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:5d6d46a49a34cd7e4f74496a1089b9a1b78282c219a28d98fe031a763e92d530"}, - {file = "dora_rs-0.3.5-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:bb888db22f63a7cc6ed6a287827d03a94e80f3668297b9c80169d393b99b5e6d"}, - {file = "dora_rs-0.3.5-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:c51284263fc72c936bd735b0a9c46303c5bda8c2000cb1cb443c8cf54c1f7ff3"}, - {file = "dora_rs-0.3.5-cp37-abi3-win_amd64.whl", hash = "sha256:88b4fe5e5569562fcdb3817abb89532f4abca913e8bd02e4ec228833716cbd09"}, + {file = "dora_rs-0.3.6-cp37-abi3-macosx_10_12_x86_64.whl", hash = "sha256:c036d2d0792d8d6e0e9db1936ab5fd4c6d19e097f3fc259058733e526f94253a"}, + {file = "dora_rs-0.3.6-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:95036f6fcb5aeb7bba8a1f37d84c627eefe09af1db17e36bc19209e950652446"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6b5ef774dbafbdf8bda56939c6475916b7ec8f4b0c57c5b80f1d46eb642f5d07"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:78656d3ae1282a142a5fed410ec3a6f725fdf8d9f9192ed673e336ea3b083e12"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:681e22c8ecb3b48d11cb9019f8a32d4ae1e353e20d4ce3a0f0eedd0ccbd95e5f"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4598572bab6f726ec41fabb43bf0f7e3cf8082ea0f6f8f4e57845a6c919f31b3"}, + {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:297350f05f5f87a0bf647a1e5b4446728e5f800788c6bb28b462bcd167f1de7f"}, + {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:b1870a8e30f0ac298d17fd546224348d13a648bcfa0cbc51dba7e5136c1af928"}, + {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:182a189212d41be0c960fd3299bf6731af2e771f8858cfb1be7ebcc17d60a254"}, + {file = "dora_rs-0.3.6-cp37-abi3-win_amd64.whl", hash = "sha256:a8f9343073e3fbca6bff3f0a13e5d2feabbe841a985c49e4294f7c14eb747bb5"}, ] [package.dependencies] pyarrow = "*" +[[package]] +name = "drawnow" +version = "0.72.5" +description = "MATLAB-like drawnow" +optional = true +python-versions = "*" +files = [ + {file = "drawnow-0.72.5-py3-none-any.whl", hash = "sha256:4ff83a8b15f61a781edaaa2a3e6b71e2c8fd948960f188b870def701afcfa0d5"}, + {file = "drawnow-0.72.5.tar.gz", hash = "sha256:9d1855605b2ec6ebc4e8a95201a7a0068eb1e2a5d1695cb1b7c462d660f32593"}, +] + +[package.dependencies] +matplotlib = ">=1.5" + [[package]] name = "dynamixel-sdk" version = "3.7.31" @@ -855,6 +1363,20 @@ files = [ [package.extras] test = ["pytest (>=6)"] +[[package]] +name = "executing" +version = "2.1.0" +description = "Get the currently executing AST node of a frame, and other information" +optional = true +python-versions = ">=3.8" +files = [ + {file = "executing-2.1.0-py2.py3-none-any.whl", hash = "sha256:8d63781349375b5ebccc3142f4b30350c0cd9c79f921cde38be2be4637e98eaf"}, + {file = "executing-2.1.0.tar.gz", hash = "sha256:8ea27ddd260da8150fa5a708269c4a10e76161e2496ec3e587da9e3c0fe4b9ab"}, +] + +[package.extras] +tests = ["asttokens (>=2.1.0)", "coverage", "coverage-enable-subprocess", "ipython", "littleutils", "pytest", "rich"] + [[package]] name = "farama-notifications" version = "0.0.4" @@ -877,21 +1399,35 @@ files = [ {file = "fasteners-0.19.tar.gz", hash = "sha256:b4f37c3ac52d8a445af3a66bce57b33b5e90b97c696b7b984f530cf8f0ded09c"}, ] +[[package]] +name = "fastjsonschema" +version = "2.20.0" +description = "Fastest Python implementation of JSON schema" +optional = true +python-versions = "*" +files = [ + {file = "fastjsonschema-2.20.0-py3-none-any.whl", hash = "sha256:5875f0b0fa7a0043a91e93a9b8f793bcbbba9691e7fd83dca95c28ba26d21f0a"}, + {file = "fastjsonschema-2.20.0.tar.gz", hash = "sha256:3d48fc5300ee96f5d116f10fe6f28d938e6008f59a6a025c2649475b87f76a23"}, +] + +[package.extras] +devel = ["colorama", "json-spec", "jsonschema", "pylint", "pytest", "pytest-benchmark", "pytest-cache", "validictory"] + [[package]] name = "filelock" -version = "3.15.4" +version = "3.16.1" description = "A platform independent file lock." optional = false python-versions = ">=3.8" files = [ - {file = "filelock-3.15.4-py3-none-any.whl", hash = "sha256:6ca1fffae96225dab4c6eaf1c4f4f28cd2568d3ec2a44e15a08520504de468e7"}, - {file = "filelock-3.15.4.tar.gz", hash = "sha256:2207938cbc1844345cb01a5a95524dae30f0ce089eba5b00378295a17e3e90cb"}, + {file = "filelock-3.16.1-py3-none-any.whl", hash = "sha256:2082e5703d51fbf98ea75855d9d5527e33d8ff23099bec374a134febee6946b0"}, + {file = "filelock-3.16.1.tar.gz", hash = "sha256:c249fbfcd5db47e5e2d6d62198e565475ee65e4831e2561c8e313fa7eb961435"}, ] [package.extras] -docs = ["furo (>=2023.9.10)", "sphinx (>=7.2.6)", "sphinx-autodoc-typehints (>=1.25.2)"] -testing = ["covdefaults (>=2.3)", "coverage (>=7.3.2)", "diff-cover (>=8.0.1)", "pytest (>=7.4.3)", "pytest-asyncio (>=0.21)", "pytest-cov (>=4.1)", "pytest-mock (>=3.12)", "pytest-timeout (>=2.2)", "virtualenv (>=20.26.2)"] -typing = ["typing-extensions (>=4.8)"] +docs = ["furo (>=2024.8.6)", "sphinx (>=8.0.2)", "sphinx-autodoc-typehints (>=2.4.1)"] +testing = ["covdefaults (>=2.3)", "coverage (>=7.6.1)", "diff-cover (>=9.2)", "pytest (>=8.3.3)", "pytest-asyncio (>=0.24)", "pytest-cov (>=5)", "pytest-mock (>=3.14)", "pytest-timeout (>=2.3.1)", "virtualenv (>=20.26.4)"] +typing = ["typing-extensions (>=4.12.2)"] [[package]] name = "flask" @@ -915,6 +1451,104 @@ Werkzeug = ">=3.0.0" async = ["asgiref (>=3.2)"] dotenv = ["python-dotenv"] +[[package]] +name = "fonttools" +version = "4.54.1" +description = "Tools to manipulate font files" +optional = true +python-versions = ">=3.8" +files = [ + {file = "fonttools-4.54.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:7ed7ee041ff7b34cc62f07545e55e1468808691dddfd315d51dd82a6b37ddef2"}, + {file = "fonttools-4.54.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:41bb0b250c8132b2fcac148e2e9198e62ff06f3cc472065dff839327945c5882"}, + {file = "fonttools-4.54.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7965af9b67dd546e52afcf2e38641b5be956d68c425bef2158e95af11d229f10"}, + {file = "fonttools-4.54.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:278913a168f90d53378c20c23b80f4e599dca62fbffae4cc620c8eed476b723e"}, + {file = "fonttools-4.54.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:0e88e3018ac809b9662615072dcd6b84dca4c2d991c6d66e1970a112503bba7e"}, + {file = "fonttools-4.54.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:4aa4817f0031206e637d1e685251ac61be64d1adef111060df84fdcbc6ab6c44"}, + {file = "fonttools-4.54.1-cp310-cp310-win32.whl", hash = "sha256:7e3b7d44e18c085fd8c16dcc6f1ad6c61b71ff463636fcb13df7b1b818bd0c02"}, + {file = "fonttools-4.54.1-cp310-cp310-win_amd64.whl", hash = "sha256:dd9cc95b8d6e27d01e1e1f1fae8559ef3c02c76317da650a19047f249acd519d"}, + {file = "fonttools-4.54.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:5419771b64248484299fa77689d4f3aeed643ea6630b2ea750eeab219588ba20"}, + {file = "fonttools-4.54.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:301540e89cf4ce89d462eb23a89464fef50915255ece765d10eee8b2bf9d75b2"}, + {file = "fonttools-4.54.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:76ae5091547e74e7efecc3cbf8e75200bc92daaeb88e5433c5e3e95ea8ce5aa7"}, + {file = "fonttools-4.54.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:82834962b3d7c5ca98cb56001c33cf20eb110ecf442725dc5fdf36d16ed1ab07"}, + {file = "fonttools-4.54.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:d26732ae002cc3d2ecab04897bb02ae3f11f06dd7575d1df46acd2f7c012a8d8"}, + {file = "fonttools-4.54.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:58974b4987b2a71ee08ade1e7f47f410c367cdfc5a94fabd599c88165f56213a"}, + {file = "fonttools-4.54.1-cp311-cp311-win32.whl", hash = "sha256:ab774fa225238986218a463f3fe151e04d8c25d7de09df7f0f5fce27b1243dbc"}, + {file = "fonttools-4.54.1-cp311-cp311-win_amd64.whl", hash = "sha256:07e005dc454eee1cc60105d6a29593459a06321c21897f769a281ff2d08939f6"}, + {file = "fonttools-4.54.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:54471032f7cb5fca694b5f1a0aaeba4af6e10ae989df408e0216f7fd6cdc405d"}, + {file = "fonttools-4.54.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8fa92cb248e573daab8d032919623cc309c005086d743afb014c836636166f08"}, + {file = "fonttools-4.54.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0a911591200114969befa7f2cb74ac148bce5a91df5645443371aba6d222e263"}, + {file = "fonttools-4.54.1-cp312-cp312-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:93d458c8a6a354dc8b48fc78d66d2a8a90b941f7fec30e94c7ad9982b1fa6bab"}, + {file = "fonttools-4.54.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:5eb2474a7c5be8a5331146758debb2669bf5635c021aee00fd7c353558fc659d"}, + {file = "fonttools-4.54.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c9c563351ddc230725c4bdf7d9e1e92cbe6ae8553942bd1fb2b2ff0884e8b714"}, + {file = "fonttools-4.54.1-cp312-cp312-win32.whl", hash = "sha256:fdb062893fd6d47b527d39346e0c5578b7957dcea6d6a3b6794569370013d9ac"}, + {file = "fonttools-4.54.1-cp312-cp312-win_amd64.whl", hash = "sha256:e4564cf40cebcb53f3dc825e85910bf54835e8a8b6880d59e5159f0f325e637e"}, + {file = "fonttools-4.54.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:6e37561751b017cf5c40fce0d90fd9e8274716de327ec4ffb0df957160be3bff"}, + {file = "fonttools-4.54.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:357cacb988a18aace66e5e55fe1247f2ee706e01debc4b1a20d77400354cddeb"}, + {file = "fonttools-4.54.1-cp313-cp313-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f8e953cc0bddc2beaf3a3c3b5dd9ab7554677da72dfaf46951e193c9653e515a"}, + {file = "fonttools-4.54.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:58d29b9a294573d8319f16f2f79e42428ba9b6480442fa1836e4eb89c4d9d61c"}, + {file = "fonttools-4.54.1-cp313-cp313-win32.whl", hash = "sha256:9ef1b167e22709b46bf8168368b7b5d3efeaaa746c6d39661c1b4405b6352e58"}, + {file = "fonttools-4.54.1-cp313-cp313-win_amd64.whl", hash = "sha256:262705b1663f18c04250bd1242b0515d3bbae177bee7752be67c979b7d47f43d"}, + {file = "fonttools-4.54.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:ed2f80ca07025551636c555dec2b755dd005e2ea8fbeb99fc5cdff319b70b23b"}, + {file = "fonttools-4.54.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:9dc080e5a1c3b2656caff2ac2633d009b3a9ff7b5e93d0452f40cd76d3da3b3c"}, + {file = "fonttools-4.54.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1d152d1be65652fc65e695e5619e0aa0982295a95a9b29b52b85775243c06556"}, + {file = "fonttools-4.54.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8583e563df41fdecef31b793b4dd3af8a9caa03397be648945ad32717a92885b"}, + {file = "fonttools-4.54.1-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:0d1d353ef198c422515a3e974a1e8d5b304cd54a4c2eebcae708e37cd9eeffb1"}, + {file = "fonttools-4.54.1-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:fda582236fee135d4daeca056c8c88ec5f6f6d88a004a79b84a02547c8f57386"}, + {file = "fonttools-4.54.1-cp38-cp38-win32.whl", hash = "sha256:e7d82b9e56716ed32574ee106cabca80992e6bbdcf25a88d97d21f73a0aae664"}, + {file = "fonttools-4.54.1-cp38-cp38-win_amd64.whl", hash = "sha256:ada215fd079e23e060157aab12eba0d66704316547f334eee9ff26f8c0d7b8ab"}, + {file = "fonttools-4.54.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:f5b8a096e649768c2f4233f947cf9737f8dbf8728b90e2771e2497c6e3d21d13"}, + {file = "fonttools-4.54.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:4e10d2e0a12e18f4e2dd031e1bf7c3d7017be5c8dbe524d07706179f355c5dac"}, + {file = "fonttools-4.54.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:31c32d7d4b0958600eac75eaf524b7b7cb68d3a8c196635252b7a2c30d80e986"}, + {file = "fonttools-4.54.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c39287f5c8f4a0c5a55daf9eaf9ccd223ea59eed3f6d467133cc727d7b943a55"}, + {file = "fonttools-4.54.1-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:a7a310c6e0471602fe3bf8efaf193d396ea561486aeaa7adc1f132e02d30c4b9"}, + {file = "fonttools-4.54.1-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:d3b659d1029946f4ff9b6183984578041b520ce0f8fb7078bb37ec7445806b33"}, + {file = "fonttools-4.54.1-cp39-cp39-win32.whl", hash = "sha256:e96bc94c8cda58f577277d4a71f51c8e2129b8b36fd05adece6320dd3d57de8a"}, + {file = "fonttools-4.54.1-cp39-cp39-win_amd64.whl", hash = "sha256:e8a4b261c1ef91e7188a30571be6ad98d1c6d9fa2427244c545e2fa0a2494dd7"}, + {file = "fonttools-4.54.1-py3-none-any.whl", hash = "sha256:37cddd62d83dc4f72f7c3f3c2bcf2697e89a30efb152079896544a93907733bd"}, + {file = "fonttools-4.54.1.tar.gz", hash = "sha256:957f669d4922f92c171ba01bef7f29410668db09f6c02111e22b2bce446f3285"}, +] + +[package.extras] +all = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "fs (>=2.2.0,<3)", "lxml (>=4.0)", "lz4 (>=1.7.4.2)", "matplotlib", "munkres", "pycairo", "scipy", "skia-pathops (>=0.5.0)", "sympy", "uharfbuzz (>=0.23.0)", "unicodedata2 (>=15.1.0)", "xattr", "zopfli (>=0.1.4)"] +graphite = ["lz4 (>=1.7.4.2)"] +interpolatable = ["munkres", "pycairo", "scipy"] +lxml = ["lxml (>=4.0)"] +pathops = ["skia-pathops (>=0.5.0)"] +plot = ["matplotlib"] +repacker = ["uharfbuzz (>=0.23.0)"] +symfont = ["sympy"] +type1 = ["xattr"] +ufo = ["fs (>=2.2.0,<3)"] +unicode = ["unicodedata2 (>=15.1.0)"] +woff = ["brotli (>=1.0.1)", "brotlicffi (>=0.8.0)", "zopfli (>=0.1.4)"] + +[[package]] +name = "fqdn" +version = "1.5.1" +description = "Validates fully-qualified domain names against RFC 1123, so that they are acceptable to modern bowsers" +optional = true +python-versions = ">=2.7, !=3.0, !=3.1, !=3.2, !=3.3, !=3.4, <4" +files = [ + {file = "fqdn-1.5.1-py3-none-any.whl", hash = "sha256:3a179af3761e4df6eb2e026ff9e1a3033d3587bf980a0b1b2e1e5d08d7358014"}, + {file = "fqdn-1.5.1.tar.gz", hash = "sha256:105ed3677e767fb5ca086a0c1f4bb66ebc3c100be518f0e0d755d9eae164d89f"}, +] + +[[package]] +name = "freetype-py" +version = "2.5.1" +description = "Freetype python bindings" +optional = true +python-versions = ">=3.7" +files = [ + {file = "freetype-py-2.5.1.zip", hash = "sha256:cfe2686a174d0dd3d71a9d8ee9bf6a2c23f5872385cf8ce9f24af83d076e2fbd"}, + {file = "freetype_py-2.5.1-py3-none-macosx_10_9_universal2.whl", hash = "sha256:d01ded2557694f06aa0413f3400c0c0b2b5ebcaabeef7aaf3d756be44f51e90b"}, + {file = "freetype_py-2.5.1-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d2f6b3d68496797da23204b3b9c4e77e67559c80390fc0dc8b3f454ae1cd819"}, + {file = "freetype_py-2.5.1-py3-none-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:289b443547e03a4f85302e3ac91376838e0d11636050166662a4f75e3087ed0b"}, + {file = "freetype_py-2.5.1-py3-none-musllinux_1_1_aarch64.whl", hash = "sha256:cd3bfdbb7e1a84818cfbc8025fca3096f4f2afcd5d4641184bf0a3a2e6f97bbf"}, + {file = "freetype_py-2.5.1-py3-none-musllinux_1_1_x86_64.whl", hash = "sha256:3c1aefc4f0d5b7425f014daccc5fdc7c6f914fb7d6a695cc684f1c09cd8c1660"}, + {file = "freetype_py-2.5.1-py3-none-win_amd64.whl", hash = "sha256:0b7f8e0342779f65ca13ef8bc103938366fecade23e6bb37cb671c2b8ad7f124"}, +] + [[package]] name = "frozenlist" version = "1.4.1" @@ -1003,13 +1637,13 @@ files = [ [[package]] name = "fsspec" -version = "2024.5.0" +version = "2024.6.1" description = "File-system specification" optional = false python-versions = ">=3.8" files = [ - {file = "fsspec-2024.5.0-py3-none-any.whl", hash = "sha256:e0fdbc446d67e182f49a70b82cf7889028a63588fde6b222521f10937b2b670c"}, - {file = "fsspec-2024.5.0.tar.gz", hash = "sha256:1d021b0b0f933e3b3029ed808eb400c08ba101ca2de4b3483fbc9ca23fcee94a"}, + {file = "fsspec-2024.6.1-py3-none-any.whl", hash = "sha256:3cb443f8bcd2efb31295a5b9fdb02aee81d8452c80d28f97a6d0959e6cee101e"}, + {file = "fsspec-2024.6.1.tar.gz", hash = "sha256:fad7d7e209dd4c1208e3bbfda706620e0da5142bebbd9c384afb95b07e798e49"}, ] [package.dependencies] @@ -1021,6 +1655,7 @@ adl = ["adlfs"] arrow = ["pyarrow (>=1)"] dask = ["dask", "distributed"] dev = ["pre-commit", "ruff"] +doc = ["numpydoc", "sphinx", "sphinx-design", "sphinx-rtd-theme", "yarl"] dropbox = ["dropbox", "dropboxdrivefs", "requests"] full = ["adlfs", "aiohttp (!=4.0.0a0,!=4.0.0a1)", "dask", "distributed", "dropbox", "dropboxdrivefs", "fusepy", "gcsfs", "libarchive-c", "ocifs", "panel", "paramiko", "pyarrow (>=1)", "pygit2", "requests", "s3fs", "smbprotocol", "tqdm"] fuse = ["fusepy"] @@ -1042,6 +1677,17 @@ test-downstream = ["aiobotocore (>=2.5.4,<3.0.0)", "dask-expr", "dask[dataframe, test-full = ["adlfs", "aiohttp (!=4.0.0a0,!=4.0.0a1)", "cloudpickle", "dask", "distributed", "dropbox", "dropboxdrivefs", "fastparquet", "fusepy", "gcsfs", "jinja2", "kerchunk", "libarchive-c", "lz4", "notebook", "numpy", "ocifs", "pandas", "panel", "paramiko", "pyarrow", "pyarrow (>=1)", "pyftpdlib", "pygit2", "pytest", "pytest-asyncio (!=0.22.0)", "pytest-benchmark", "pytest-cov", "pytest-mock", "pytest-recording", "pytest-rerunfailures", "python-snappy", "requests", "smbprotocol", "tqdm", "urllib3", "zarr", "zstandard"] tqdm = ["tqdm"] +[[package]] +name = "future" +version = "1.0.0" +description = "Clean single-source support for Python 3 and 2" +optional = true +python-versions = ">=2.6, !=3.0.*, !=3.1.*, !=3.2.*" +files = [ + {file = "future-1.0.0-py3-none-any.whl", hash = "sha256:929292d34f5872e70396626ef385ec22355a1fae8ad29e1a734c3e43f9fbc216"}, + {file = "future-1.0.0.tar.gz", hash = "sha256:bd2968309307861edae1458a4f8a4f3598c03be43b97521076aebf5d94c07b05"}, +] + [[package]] name = "gdown" version = "5.2.0" @@ -1154,7 +1800,7 @@ pyarrow = ">=12.0.0" type = "git" url = "https://github.com/dora-rs/dora-lerobot.git" reference = "HEAD" -resolved_reference = "fda22deba84c46695369736edd34dc740aef45eb" +resolved_reference = "3a5dbc4d36d9973439470128f309ef7511d23465" subdirectory = "gym_dora" [[package]] @@ -1253,6 +1899,17 @@ PettingZoo = ">=1.23.0" mujoco-py = ["cython (<3)", "mujoco-py (>=2.1,<2.2)"] testing = ["Jinja2 (>=3.0.3)", "PettingZoo (>=1.23.0)", "cython (<3)", "mujoco-py (>=2.1,<2.2)", "pytest (==7.0.1)"] +[[package]] +name = "h11" +version = "0.14.0" +description = "A pure-Python, bring-your-own-I/O implementation of HTTP/1.1" +optional = true +python-versions = ">=3.7" +files = [ + {file = "h11-0.14.0-py3-none-any.whl", hash = "sha256:e3fe4ac4b851c468cc8363d500db52c2ead036020723024a109d37346efaa761"}, + {file = "h11-0.14.0.tar.gz", hash = "sha256:8f19fbbe99e72420ff35c00b27a34cb9937e902a8b810e2c88300c6f0a3b699d"}, +] + [[package]] name = "h5py" version = "3.11.0" @@ -1287,86 +1944,267 @@ files = [ numpy = ">=1.17.3" [[package]] -name = "hf-transfer" -version = "0.1.6" -description = "" +name = "hello-robot-stretch-body" +version = "0.7.27" +description = "Stretch Body low level Python API" +optional = true +python-versions = "*" +files = [ + {file = "hello_robot_stretch_body-0.7.27-py3-none-any.whl", hash = "sha256:740e6abae4a0ba43b23ce7831129e3ef9356acd706ea73b5512873b04ba3c5f0"}, + {file = "hello_robot_stretch_body-0.7.27.tar.gz", hash = "sha256:dd289ea95f9df7be1306cbc26ac75037946db04f4f22503fc6e2741a57c68732"}, +] + +[package.dependencies] +aioserial = "*" +chime = "*" +click = "*" +cma = "*" +colorama = "*" +drawnow = "*" +dynamixel-sdk = "*" +filelock = "*" +gitpython = "*" +hello-robot-stretch-body-tools = ">=0.4.2" +hello-robot-stretch-factory = ">=0.3.5" +hello-robot-stretch-tool-share = ">=0.3.3" +hello-robot-stretch-urdf = ">=0.0.19" +inputs = "*" +ipython = "*" +jupyter = "*" +matplotlib = "*" +meshio = "*" +nose = "*" +numba = "*" +numpy = ">=1.24" +numpy-stl = "*" +open3d = "*" +opencv-contrib-python = "*" +pandas = "*" +pathlib = "*" +pixel-ring = "*" +psutil = "*" +pyrealsense2 = "*" +pyrender = "*" +pyusb = "*" +pyyaml = ">=5.1" +renamed-opencv-python-inference-engine = {version = "*", markers = "python_version >= \"3.0.0\""} +rplidar-roboticia = "*" +scikit-image = "*" +scipy = "*" +snakeviz = "*" +SpeechRecognition = "*" +sympy = "*" +transforms3d = ">=0.4.2" +urchin = "*" +urdf-parser-py = "*" + +[[package]] +name = "hello-robot-stretch-body-tools" +version = "0.7.13" +description = "Stretch Body Tools" +optional = true +python-versions = "*" +files = [ + {file = "hello_robot_stretch_body_tools-0.7.13-py3-none-any.whl", hash = "sha256:f12bd4ee40e48c11e68392e7fd91c3a752e87d44d864d1adb3998b30c0166e75"}, + {file = "hello_robot_stretch_body_tools-0.7.13.tar.gz", hash = "sha256:9ce65bfc9a53444b7622c3479ab45c6aa9369618eb3bf102ef1172474d1873b7"}, +] + +[package.dependencies] +click = "*" +cma = "*" +colorama = "*" +drawnow = "*" +filelock = "*" +gitpython = "*" +inputs = "*" +ipython = "*" +matplotlib = "*" +nose = "*" +numpy = ">=1.24" +open3d = "*" +opencv-contrib-python = "*" +packaging = "*" +pandas = "*" +pixel-ring = "*" +pyaudio = "*" +pyrealsense2 = "*" +pyusb = "*" +pyyaml = ">=5.1" +rplidar-roboticia = "*" +scikit-image = "*" +scipy = "*" +sh = "*" +snakeviz = "*" +SpeechRecognition = "*" +sympy = "*" +trimesh = "4.4.7" +urchin = "*" +xmltodict = "*" + +[[package]] +name = "hello-robot-stretch-factory" +version = "0.5.6" +description = "Stretch Factory Tools" +optional = true +python-versions = "*" +files = [ + {file = "hello-robot-stretch-factory-0.5.6.tar.gz", hash = "sha256:e2b060daf5eda699781cde96faf608b7ed3c234ac5b22317f028a69f889846de"}, + {file = "hello_robot_stretch_factory-0.5.6-py3-none-any.whl", hash = "sha256:09bb97bf1fc146855843af042684d1820d6b1775945dbc3e1cd44eff75be702f"}, +] + +[package.dependencies] +future = "*" +gitpython = "*" +hello-robot-stretch-body = ">=0.4.26" +pyserial = "*" +python-xlib = "*" +pyusb = "*" +tabulate = "*" + +[[package]] +name = "hello-robot-stretch-tool-share" +version = "0.3.4" +description = "Stretch end of arm tool interfaces" +optional = true +python-versions = "*" +files = [ + {file = "hello_robot_stretch_tool_share-0.3.4-py3-none-any.whl", hash = "sha256:230d24f88a84cc983c019078911c579882d9c2c9e24129e5acbe1c756189a1d1"}, + {file = "hello_robot_stretch_tool_share-0.3.4.tar.gz", hash = "sha256:8e0a2cea088dcb50e41257aade5c6190964a0f1407f1f54f24d114ff31ecb2c6"}, +] + +[[package]] +name = "hello-robot-stretch-urdf" +version = "0.0.29" +description = "Stretch URDF" +optional = true +python-versions = "*" +files = [ + {file = "hello-robot-stretch-urdf-0.0.29.tar.gz", hash = "sha256:6ae05263c0ca4b817f57ff41feaf149c8284ebd1aa511b65bd230e6ab6d39bdc"}, + {file = "hello_robot_stretch_urdf-0.0.29-py3-none-any.whl", hash = "sha256:d33fb4cdea14b508ee56d177084cbd157f7fbc25c4048cfd00b465e94a72a2e5"}, +] + +[package.dependencies] +urchin = "*" + +[[package]] +name = "hf-transfer" +version = "0.1.8" +description = "Speed up file transfers with the Hugging Face Hub." optional = false python-versions = ">=3.7" files = [ - {file = "hf_transfer-0.1.6-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:6fd3d61f9229d27def007e53540412507b74ac2fdb1a29985ae0b6a5137749a2"}, - {file = "hf_transfer-0.1.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:b043bb78df1225de043eb041de9d97783fcca14a0bdc1b1d560fc172fc21b648"}, - {file = "hf_transfer-0.1.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7db60dd18eae4fa6ea157235fb82196cde5313995b396d1b591aad3b790a7f8f"}, - {file = "hf_transfer-0.1.6-cp310-cp310-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:30d31dbab9b5a558cce407b8728e39d87d7af1ef8745ddb90187e9ae0b9e1e90"}, - {file = "hf_transfer-0.1.6-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f6b368bddd757efc7af3126ba81f9ac8f9435e2cc00902cb3d64f2be28d8f719"}, - {file = "hf_transfer-0.1.6-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:aa2086d8aefaaa3e144e167324574882004c0cec49bf2d0638ec4b74732d8da0"}, - {file = "hf_transfer-0.1.6-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:45d8985a0940bfe1535cb4ca781f5c11e47c83798ef3373ee1f5d57bbe527a9c"}, - {file = "hf_transfer-0.1.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2f42b89735f1cde22f2a795d1f0915741023235666be7de45879e533c7d6010c"}, - {file = "hf_transfer-0.1.6-cp310-none-win32.whl", hash = "sha256:2d2c4c4613f3ad45b6ce6291e347b2d3ba1b86816635681436567e461cb3c961"}, - {file = "hf_transfer-0.1.6-cp310-none-win_amd64.whl", hash = "sha256:78b0eed8d8dce60168a46e584b9742b816af127d7e410a713e12c31249195342"}, - {file = "hf_transfer-0.1.6-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:f1d8c172153f9a6cdaecf137612c42796076f61f6bea1072c90ac2e17c1ab6fa"}, - {file = "hf_transfer-0.1.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:2c601996351f90c514a75a0eeb02bf700b1ad1db2d946cbfe4b60b79e29f0b2f"}, - {file = "hf_transfer-0.1.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8e585c808405557d3f5488f385706abb696997bbae262ea04520757e30836d9d"}, - {file = "hf_transfer-0.1.6-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:ec51af1e8cf4268c268bd88932ade3d7ca895a3c661b42493503f02610ae906b"}, - {file = "hf_transfer-0.1.6-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d106fdf996332f6df3ed3fab6d6332df82e8c1fb4b20fd81a491ca4d2ab5616a"}, - {file = "hf_transfer-0.1.6-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e9c2ee9e9fde5a0319cc0e8ddfea10897482bc06d5709b10a238f1bc2ebcbc0b"}, - {file = "hf_transfer-0.1.6-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f394ea32bc7802b061e549d3133efc523b4ae4fd19bf4b74b183ca6066eef94e"}, - {file = "hf_transfer-0.1.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4282f09902114cd67fca98a1a1bad569a44521a8395fedf327e966714f68b977"}, - {file = "hf_transfer-0.1.6-cp311-none-win32.whl", hash = "sha256:276dbf307d5ab6f1bcbf57b5918bfcf9c59d6848ccb28242349e1bb5985f983b"}, - {file = "hf_transfer-0.1.6-cp311-none-win_amd64.whl", hash = "sha256:fa475175c51451186bea804471995fa8e7b2a48a61dcca55534911dc25955527"}, - {file = "hf_transfer-0.1.6-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:23d157a67acfa00007799323a1c441b2bbacc7dee625b016b7946fe0e25e6c89"}, - {file = "hf_transfer-0.1.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:6067342a2864b988f861cd2d31bd78eb1e84d153a3f6df38485b6696d9ad3013"}, - {file = "hf_transfer-0.1.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:91cfcb3070e205b58fa8dc8bcb6a62ccc40913fcdb9cd1ff7c364c8e3aa85345"}, - {file = "hf_transfer-0.1.6-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:eb76064ac5165d5eeaaf8d0903e8bf55477221ecc2a4a4d69f0baca065ab905b"}, - {file = "hf_transfer-0.1.6-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9dabd3a177d83028f164984cf4dd859f77ec1e20c97a6f307ff8fcada0785ef1"}, - {file = "hf_transfer-0.1.6-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d0bf4254e44f64a26e0a5b73b5d7e8d91bb36870718fb4f8e126ec943ff4c805"}, - {file = "hf_transfer-0.1.6-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5d32c1b106f38f336ceb21531f4db9b57d777b9a33017dafdb6a5316388ebe50"}, - {file = "hf_transfer-0.1.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ff05aba3c83921e5c7635ba9f07c693cc893350c447644824043aeac27b285f5"}, - {file = "hf_transfer-0.1.6-cp312-none-win32.whl", hash = "sha256:051ef0c55607652cb5974f59638da035773254b9a07d7ee5b574fe062de4c9d1"}, - {file = "hf_transfer-0.1.6-cp312-none-win_amd64.whl", hash = "sha256:716fb5c574fcbdd8092ce73f9b6c66f42e3544337490f77c60ec07df02bd081b"}, - {file = "hf_transfer-0.1.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6c0c981134a55965e279cb7be778c1ccaf93f902fc9ebe31da4f30caf824cc4d"}, - {file = "hf_transfer-0.1.6-cp37-cp37m-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:1ef1f145f04c5b573915bcb1eb5db4039c74f6b46fce73fc473c4287e613b623"}, - {file = "hf_transfer-0.1.6-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d0a7609b004db3347dbb7796df45403eceb171238210d054d93897d6d84c63a4"}, - {file = "hf_transfer-0.1.6-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:60f0864bf5996773dbd5f8ae4d1649041f773fe9d5769f4c0eeb5553100acef3"}, - {file = "hf_transfer-0.1.6-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5d01e55d630ffe70a4f5d0ed576a04c6a48d7c65ca9a7d18f2fca385f20685a9"}, - {file = "hf_transfer-0.1.6-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d855946c5062b665190de15b2bdbd4c8eddfee35350bfb7564592e23d36fbbd3"}, - {file = "hf_transfer-0.1.6-cp37-none-win32.whl", hash = "sha256:fd40b2409cfaf3e8aba20169ee09552f69140e029adeec261b988903ff0c8f6f"}, - {file = "hf_transfer-0.1.6-cp37-none-win_amd64.whl", hash = "sha256:0e0eba49d46d3b5481919aea0794aec625fbc6ecdf13fe7e0e9f3fc5d5ad5971"}, - {file = "hf_transfer-0.1.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7e669fecb29fc454449739f9f53ed9253197e7c19e6a6eaa0f08334207af4287"}, - {file = "hf_transfer-0.1.6-cp38-cp38-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:89f701802892e5eb84f89f402686861f87dc227d6082b05f4e9d9b4e8015a3c3"}, - {file = "hf_transfer-0.1.6-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b6f2b0c8b95b01409275d789a9b74d5f2e146346f985d384bf50ec727caf1ccc"}, - {file = "hf_transfer-0.1.6-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:aa855a2fa262792a230f9efcdb5da6d431b747d1861d2a69fe7834b19aea077e"}, - {file = "hf_transfer-0.1.6-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4aa8ca349afb2f0713475426946261eb2035e4efb50ebd2c1d5ad04f395f4217"}, - {file = "hf_transfer-0.1.6-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:01255f043996bc7d1bae62d8afc5033a90c7e36ce308b988eeb84afe0a69562f"}, - {file = "hf_transfer-0.1.6-cp38-none-win32.whl", hash = "sha256:60b1db183e8a7540cd4f8b2160ff4de55f77cb0c3fc6a10be1e7c30eb1b2bdeb"}, - {file = "hf_transfer-0.1.6-cp38-none-win_amd64.whl", hash = "sha256:fb8be3cba6aaa50ab2e9dffbd25c8eb2046785eeff642cf0cdd0dd9ae6be3539"}, - {file = "hf_transfer-0.1.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d09af35e3e3f09b664e6429e9a0dc200f29c5bdfd88bdd9666de51183b1fe202"}, - {file = "hf_transfer-0.1.6-cp39-cp39-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:a4505bd707cc14d85c800f961fad8ca76f804a8ad22fbb7b1a217d8d0c15e6a5"}, - {file = "hf_transfer-0.1.6-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2c453fd8b0be9740faa23cecd1f28ee9ead7d900cefa64ff836960c503a744c9"}, - {file = "hf_transfer-0.1.6-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:13cb8884e718a78c3b81a8cdec9c7ac196dd42961fce55c3ccff3dd783e5ad7a"}, - {file = "hf_transfer-0.1.6-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:39cd39df171a2b5404de69c4e6cd14eee47f6fe91c1692f939bfb9e59a0110d8"}, - {file = "hf_transfer-0.1.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8ff0629ee9f98df57a783599602eb498f9ec3619dc69348b12e4d9d754abf0e9"}, - {file = "hf_transfer-0.1.6-cp39-none-win32.whl", hash = "sha256:164a6ce445eb0cc7c645f5b6e1042c003d33292520c90052b6325f30c98e4c5f"}, - {file = "hf_transfer-0.1.6-cp39-none-win_amd64.whl", hash = "sha256:11b8b4b73bf455f13218c5f827698a30ae10998ca31b8264b51052868c7a9f11"}, - {file = "hf_transfer-0.1.6-pp310-pypy310_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:16957ba057376a99ea361074ce1094f61b58e769defa6be2422ae59c0b6a6530"}, - {file = "hf_transfer-0.1.6-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7db952112e3b8ee1a5cbf500d2443e9ce4fb893281c5310a3e31469898628005"}, - {file = "hf_transfer-0.1.6-pp37-pypy37_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d39d826a7344f5e39f438d62632acd00467aa54a083b66496f61ef67a9885a56"}, - {file = "hf_transfer-0.1.6-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a4e2653fbfa92e7651db73d99b697c8684e7345c479bd6857da80bed6138abb2"}, - {file = "hf_transfer-0.1.6-pp38-pypy38_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:144277e6a86add10b90ec3b583253aec777130312256bfc8d5ade5377e253807"}, - {file = "hf_transfer-0.1.6-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3bb53bcd16365313b2aa0dbdc28206f577d70770f31249cdabc387ac5841edcc"}, - {file = "hf_transfer-0.1.6-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:990d73a5a68d8261980f146c51f4c5f9995314011cb225222021ad7c39f3af2d"}, - {file = "hf_transfer-0.1.6-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:652406037029ab9b4097b4c5f29321bad5f64c2b46fbff142509d918aec87c29"}, - {file = "hf_transfer-0.1.6.tar.gz", hash = "sha256:deb505a7d417d7055fd7b3549eadb91dfe782941261f3344025c486c16d1d2f9"}, + {file = "hf_transfer-0.1.8-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:70858f9e94286738ed300484a45beb5cfee6a7ddac4c5886f9c6fce7823ac5ab"}, + {file = "hf_transfer-0.1.8-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:38adc73f0a8526319d90f7cc5dc2d5e4bb66f487a513d94b98aa6725be732e4a"}, + {file = "hf_transfer-0.1.8-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:44d2f0c08198d8d899fe9d66e86aee2dd844bd7ce33888f261373fcec81d2a54"}, + {file = "hf_transfer-0.1.8-cp310-cp310-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:1de2a4ef36f9e60b3d3bec00193c0aafd75771709f2ca51b9b162373f5af3d32"}, + {file = "hf_transfer-0.1.8-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e319269e3606a5ff2979296841766649ac73598a4a8eee2a968f86c8071fea5a"}, + {file = "hf_transfer-0.1.8-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:0f6026cf3be6a53ea42f92172f60c1c0675baaa9073f865e671b661dde5fd157"}, + {file = "hf_transfer-0.1.8-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f865c33ada5bd3650c2b46e59979f2d7755c3f517f8d0facc78576a0c7d26406"}, + {file = "hf_transfer-0.1.8-cp310-none-win32.whl", hash = "sha256:2054730e8d8ed21917c64be7199e06424b2bd08df1c43a72766afaed7992f2d3"}, + {file = "hf_transfer-0.1.8-cp310-none-win_amd64.whl", hash = "sha256:2b4f1a9446ba31170b5b1eca4e916504d18378a6b5fe959896bdac8a736a5ecb"}, + {file = "hf_transfer-0.1.8-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:e27c15fcc5869ad7e52bbc0bdec6106b288d1c463f8d2da92f28615a3b181361"}, + {file = "hf_transfer-0.1.8-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:871a0032d011ebc6409a73a8406b98b84ff2cd3ed7d9e1af8cdf4d660b9fab9b"}, + {file = "hf_transfer-0.1.8-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:686fa756e1e0214bb6327d33c66732c52274d94a8460beb50604ad988b391cf6"}, + {file = "hf_transfer-0.1.8-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:36a03b1b2911b0cf15b1b9d971a34b32dadcc4f2fd979aaff5979d6ce4017c34"}, + {file = "hf_transfer-0.1.8-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:079db90c81f41f4cf3227dfaaa855a9b8e9aef45bc7c2be29ce7232cd83ff881"}, + {file = "hf_transfer-0.1.8-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ac08a4524127fdd14c234d4bcbe49d1c498acf5335c781714823179bcc8dc039"}, + {file = "hf_transfer-0.1.8-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:837432e73cb17274a6782b6216e8ce058aa325a475dc44a5a6a753d48b86d18a"}, + {file = "hf_transfer-0.1.8-cp311-none-win32.whl", hash = "sha256:b180f9823dde35aba9bc0f1d0c04ac8a873baebd3732a7ffe4f11940abc7df0d"}, + {file = "hf_transfer-0.1.8-cp311-none-win_amd64.whl", hash = "sha256:37907d2135cebcf8b6d419bb575148d89c224f16b69357f027bd29d0e85c6529"}, + {file = "hf_transfer-0.1.8-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:baf948f4f493949309cbe60529620b9b0aef854a22b6e526753364acc57c09b6"}, + {file = "hf_transfer-0.1.8-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:0bce5c8bdefa478c5d5eaa646cc4ce1df5cfe764d98572ad0c6b8773e98d49f6"}, + {file = "hf_transfer-0.1.8-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:54d6f8a1a86128d651a3799e1267c343d60f81f2c565d7c5416eb8e674e4cf0e"}, + {file = "hf_transfer-0.1.8-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:f79fd1b0c2ed93efb4c5f684118d7a762ecdd218e170df8208c4e13d3dcd4959"}, + {file = "hf_transfer-0.1.8-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:414df35692670683bf5623498ef9d88a8df5d77e9516515da6e2b34d1054c11f"}, + {file = "hf_transfer-0.1.8-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3c9798d5f951f66b96d40a7a53910260cb5874fda56cf5944dddb7c571f37ec3"}, + {file = "hf_transfer-0.1.8-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:060c661691f85a61392e57579c80eb64b5ee277434e81fb582f605c1c8ff05d5"}, + {file = "hf_transfer-0.1.8-cp312-none-win32.whl", hash = "sha256:f7840e32379820c3e1571a480238e05ea043e970c99d2e999578004a2eb17788"}, + {file = "hf_transfer-0.1.8-cp312-none-win_amd64.whl", hash = "sha256:9a3204ec423cc5e659872e8179f8704ad9ce2abb1e6a991f8838aedf1dc07830"}, + {file = "hf_transfer-0.1.8-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:09949e86ad63ee139e463fd0dfaf401515ae70445854199f61d545514c65f744"}, + {file = "hf_transfer-0.1.8-cp37-cp37m-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:bf1a74552845b93ea972e6e7131ef54e56056aa54137e93a40faf3fbcb2442ff"}, + {file = "hf_transfer-0.1.8-cp37-cp37m-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:959bcb3afb4ee6f2a07031a947dba98ec0b64c001bc914fbd8fc32e13a287162"}, + {file = "hf_transfer-0.1.8-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e01eecdb8162bd61dab9090fbd9f8034dd8b5755ef727a21ca8a057f80cb91ee"}, + {file = "hf_transfer-0.1.8-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:50650a38e9d31f5ad8f010e4598bf304ecd99c17162e7d93f67e031571b864ee"}, + {file = "hf_transfer-0.1.8-cp37-none-win32.whl", hash = "sha256:e29b9d1d378138f2f4eae0e93ca94af3b5d45f4532eef69f1ab97fe06f9c9d9e"}, + {file = "hf_transfer-0.1.8-cp37-none-win_amd64.whl", hash = "sha256:cfd6cef43ae883103117a371f8ebae4e7f9637bc6fb480f1be5568e2fe22a8a7"}, + {file = "hf_transfer-0.1.8-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:92a68f7a0043cca8a0de4decc760dca177530944cbab502afac503bd1b2fa01a"}, + {file = "hf_transfer-0.1.8-cp38-cp38-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:e3138e408179f80a5480598e32f8e1abb564915cbde4d3bc8da52811c75dc3ea"}, + {file = "hf_transfer-0.1.8-cp38-cp38-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4544d148930ad34442d43b8fa911c8479c04a95b858b1d1f91e0b7da77082fad"}, + {file = "hf_transfer-0.1.8-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a851794b9f029965664f8c3002c957fccf21685e9397ceb4f9f19c986dee8ad3"}, + {file = "hf_transfer-0.1.8-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:791aaf87c5319ac83edb6ab2994b3db19924c49d6ff667dd3d8a610b455ff70a"}, + {file = "hf_transfer-0.1.8-cp38-none-win32.whl", hash = "sha256:8f71e5d35d3a3160dcca12fdcc8119033aeacaa6a32838a7ad9f9cb1008bbe58"}, + {file = "hf_transfer-0.1.8-cp38-none-win_amd64.whl", hash = "sha256:543287b4ceb1e25501580b99690f7f0df9d3631d29306f37cbd97e918c732944"}, + {file = "hf_transfer-0.1.8-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:7ce02a18bd0bb2343e707ac85b68c946bc37623ee24150c69158f6b2b2c7a98f"}, + {file = "hf_transfer-0.1.8-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:64d7f8dbd64ba183ed1df75d47c84e075ff666ceaa335bff1de16b09eaac5b80"}, + {file = "hf_transfer-0.1.8-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1e7858694e11419ae27e542fb8fc0d0e54d46ff7768fe73bc359d70b8f5aa578"}, + {file = "hf_transfer-0.1.8-cp39-cp39-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:bed116cd9d1edfa32c0136d7cb8e5f1afd2b32df43c49085d428f108fc8e1c8f"}, + {file = "hf_transfer-0.1.8-cp39-cp39-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6e385d0da9c6b3472ab29285d2d46c9f9903205b8d108f88a82f3f85aafae0ab"}, + {file = "hf_transfer-0.1.8-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:98f75fa4b86ef15433cd907807ac77d1fb39d7e7b790bfd39c7ae9c385bf0200"}, + {file = "hf_transfer-0.1.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d1a63ad947d2901425ac0a3ed70c3696dfde27fadb0482ed763bdd5cc946b278"}, + {file = "hf_transfer-0.1.8-cp39-none-win32.whl", hash = "sha256:3e74096915813ae842ea6a5bdf10c0fef960aa51a35a560955b3e61cdfe3db57"}, + {file = "hf_transfer-0.1.8-cp39-none-win_amd64.whl", hash = "sha256:05ea16307bf4a5eb097cbc6e5057e4eb5e080a138af23ef639fd38857723c288"}, + {file = "hf_transfer-0.1.8-pp310-pypy310_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:928ff036c3e98e10dcfbdb4fcdfc4592d37a5cc8e365a7ba8dfd4337e849d675"}, + {file = "hf_transfer-0.1.8-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d49ba3ce67035f460ae1924fe2feafec155cb535eec7f31ed5109c19064cd294"}, + {file = "hf_transfer-0.1.8-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b01f5872c62cfee3ec9ca5c738818296f69f8adf84b4d8d15f2a5601d9dda339"}, + {file = "hf_transfer-0.1.8-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:659d4212d50847a5165666bf43d67727679b4f694ef9c413613cc27093136527"}, + {file = "hf_transfer-0.1.8.tar.gz", hash = "sha256:26d229468152e7a3ec12664cac86b8c2800695fd85f9c9a96677a775cc04f0b3"}, +] + +[[package]] +name = "httpcore" +version = "1.0.5" +description = "A minimal low-level HTTP client." +optional = true +python-versions = ">=3.8" +files = [ + {file = "httpcore-1.0.5-py3-none-any.whl", hash = "sha256:421f18bac248b25d310f3cacd198d55b8e6125c107797b609ff9b7a6ba7991b5"}, + {file = "httpcore-1.0.5.tar.gz", hash = "sha256:34a38e2f9291467ee3b44e89dd52615370e152954ba21721378a87b2960f7a61"}, ] +[package.dependencies] +certifi = "*" +h11 = ">=0.13,<0.15" + +[package.extras] +asyncio = ["anyio (>=4.0,<5.0)"] +http2 = ["h2 (>=3,<5)"] +socks = ["socksio (==1.*)"] +trio = ["trio (>=0.22.0,<0.26.0)"] + +[[package]] +name = "httpx" +version = "0.27.2" +description = "The next generation HTTP client." +optional = true +python-versions = ">=3.8" +files = [ + {file = "httpx-0.27.2-py3-none-any.whl", hash = "sha256:7bb2708e112d8fdd7829cd4243970f0c223274051cb35ee80c03301ee29a3df0"}, + {file = "httpx-0.27.2.tar.gz", hash = "sha256:f7c2be1d2f3c3c3160d441802406b206c2b76f5947b11115e6df10c6c65e66c2"}, +] + +[package.dependencies] +anyio = "*" +certifi = "*" +httpcore = "==1.*" +idna = "*" +sniffio = "*" + +[package.extras] +brotli = ["brotli", "brotlicffi"] +cli = ["click (==8.*)", "pygments (==2.*)", "rich (>=10,<14)"] +http2 = ["h2 (>=3,<5)"] +socks = ["socksio (==1.*)"] +zstd = ["zstandard (>=0.18.0)"] + [[package]] name = "huggingface-hub" -version = "0.25.0" +version = "0.25.1" description = "Client library to download and publish models, datasets and other repos on the huggingface.co hub" optional = false python-versions = ">=3.8.0" files = [ - {file = "huggingface_hub-0.25.0-py3-none-any.whl", hash = "sha256:e2f357b35d72d5012cfd127108c4e14abcd61ba4ebc90a5a374dc2456cb34e12"}, - {file = "huggingface_hub-0.25.0.tar.gz", hash = "sha256:fb5fbe6c12fcd99d187ec7db95db9110fb1a20505f23040a5449a717c1a0db4d"}, + {file = "huggingface_hub-0.25.1-py3-none-any.whl", hash = "sha256:a5158ded931b3188f54ea9028097312cb0acd50bffaaa2612014c3c526b44972"}, + {file = "huggingface_hub-0.25.1.tar.gz", hash = "sha256:9ff7cb327343211fbd06e2b149b8f362fd1e389454f3f14c6db75a4999ee20ff"}, ] [package.dependencies] @@ -1412,13 +2250,13 @@ packaging = "*" [[package]] name = "identify" -version = "2.6.0" +version = "2.6.1" description = "File identification library for Python" optional = true python-versions = ">=3.8" files = [ - {file = "identify-2.6.0-py2.py3-none-any.whl", hash = "sha256:e79ae4406387a9d300332b5fd366d8994f1525e8414984e1a59e058b2eda2dd0"}, - {file = "identify-2.6.0.tar.gz", hash = "sha256:cb171c685bdc31bcc4c1734698736a7d5b6c8bf2e0c15117f4d469c8640ae5cf"}, + {file = "identify-2.6.1-py2.py3-none-any.whl", hash = "sha256:53863bcac7caf8d2ed85bd20312ea5dcfc22226800f6d6881f232d861db5a8f0"}, + {file = "identify-2.6.1.tar.gz", hash = "sha256:91478c5fb7c3aac5ff7bf9b4344f803843dc586832d5f110d672b19aa1984c98"}, ] [package.extras] @@ -1426,50 +2264,60 @@ license = ["ukkonen"] [[package]] name = "idna" -version = "3.7" +version = "3.10" description = "Internationalized Domain Names in Applications (IDNA)" optional = false -python-versions = ">=3.5" +python-versions = ">=3.6" files = [ - {file = "idna-3.7-py3-none-any.whl", hash = "sha256:82fee1fc78add43492d3a1898bfa6d8a904cc97d8427f683ed8e798d07761aa0"}, - {file = "idna-3.7.tar.gz", hash = "sha256:028ff3aadf0609c1fd278d8ea3089299412a7a8b9bd005dd08b9f8285bcb5cfc"}, + {file = "idna-3.10-py3-none-any.whl", hash = "sha256:946d195a0d259cbba61165e88e65941f16e9b36ea6ddb97f00452bae8b1287d3"}, + {file = "idna-3.10.tar.gz", hash = "sha256:12f65c9b470abda6dc35cf8e63cc574b1c52b11df2c86030af0ac09b01b13ea9"}, ] +[package.extras] +all = ["flake8 (>=7.1.1)", "mypy (>=1.11.2)", "pytest (>=8.3.2)", "ruff (>=0.6.2)"] + [[package]] name = "imagecodecs" -version = "2024.6.1" +version = "2024.9.22" description = "Image transformation, compression, and decompression codecs" optional = true python-versions = ">=3.9" files = [ - {file = "imagecodecs-2024.6.1-cp310-cp310-macosx_10_14_x86_64.whl", hash = "sha256:369816eaddfe6e9d8d1faa6794341c89f3494fef846c9b5d834f77dc7583bfdf"}, - {file = "imagecodecs-2024.6.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:9300198b5e4ec09f94f5d6bdd6f727d02bbccba5ed0c974e9931d3f9d5d7fa35"}, - {file = "imagecodecs-2024.6.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:42eafc88b3dd44cfb7a8b076ff64ff794874e88d45c3691b32e9e93fbc42e86e"}, - {file = "imagecodecs-2024.6.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f428f141ed102cecf98ffbe61ed02b1f3f7d65db0bf1459cf2e7b1a53fb279b2"}, - {file = "imagecodecs-2024.6.1-cp310-cp310-win32.whl", hash = "sha256:5526a7e41939613a5c68403911f7cc738f6fe1a8ac0456535720f53253497b76"}, - {file = "imagecodecs-2024.6.1-cp310-cp310-win_amd64.whl", hash = "sha256:8d3d82ebe83a3e31ab7f09a8b72155c5436a3f87145052ca57dc5caf3a2dc9c0"}, - {file = "imagecodecs-2024.6.1-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:328ea133e0f292cf54c5feb13e247fbf45a6055c8dc6822e841c208d2dc5c96a"}, - {file = "imagecodecs-2024.6.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:8045ea3a9c9de78ea00e2a387f47d784434bfad05967decbe0c1b3bee5aadf25"}, - {file = "imagecodecs-2024.6.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:42bd9ec14e4d38f15e2fa387c90b726dba42c16da0a9b6ff2c23e01478b8cd93"}, - {file = "imagecodecs-2024.6.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9eb5b2d755a64de9a7e0604d5dcc1151c96b43b4e5ac69bebc6d8d790b77ca58"}, - {file = "imagecodecs-2024.6.1-cp311-cp311-win32.whl", hash = "sha256:03ace438a843e024239cddbe7fe6940bd2a6cf3316b08c281b95842b5217c0f7"}, - {file = "imagecodecs-2024.6.1-cp311-cp311-win_amd64.whl", hash = "sha256:cd926589c6e3c564490b93258b1a2ca3b040da10c21e99b618b7be6dd76b2a25"}, - {file = "imagecodecs-2024.6.1-cp311-cp311-win_arm64.whl", hash = "sha256:101fcef57aedb8730d1d2d1779dfbaa23daf7e50cd4130e88945a4fe34d0212f"}, - {file = "imagecodecs-2024.6.1-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:3c5e0ebdf7e1f8ec23a6d3c4b06fc7a64f41ec47ba23516458c5a763685f29e3"}, - {file = "imagecodecs-2024.6.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:407d2859d62ed5834e69e74d9ebcbc2d30be71e4f1ee14fae37f1179110fec8c"}, - {file = "imagecodecs-2024.6.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f066aab64446a1d87271c8036a3d9f03dfac8678993e4e1e97923acd0d10f355"}, - {file = "imagecodecs-2024.6.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e3467f4929fe0159c91e59a1f186a656e3aa3ad330079ab3af3d7edff7603b82"}, - {file = "imagecodecs-2024.6.1-cp312-cp312-win32.whl", hash = "sha256:a9b4939934bde291f5b107fcc01dbd6d4b4307eb36915c880600592839cab682"}, - {file = "imagecodecs-2024.6.1-cp312-cp312-win_amd64.whl", hash = "sha256:35ddab6947bcf4c04bc0e5d171769c40ffdea07eb908e62de53d2dde3985d59d"}, - {file = "imagecodecs-2024.6.1-cp312-cp312-win_arm64.whl", hash = "sha256:0bd70e34ff9b14ea299c1cdc51db4a80c2c406ae2f422e5e400716e8df791bdc"}, - {file = "imagecodecs-2024.6.1-cp39-cp39-macosx_10_14_x86_64.whl", hash = "sha256:3d39699ddf13d8ce67b6a1a04e92a9c318613c0eecc245861590fed78f09e2a1"}, - {file = "imagecodecs-2024.6.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:421be324c4d0578ae1be6b75ebddf1cbe4e8092a83d31d2a8fa8021bc75e12d2"}, - {file = "imagecodecs-2024.6.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ababc300ec18c28e8fd515ad92252679742c243e88cdb7c5e217c72eaed8fa3a"}, - {file = "imagecodecs-2024.6.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fc50b613738a3b62aa77c00d457a9e9a6337e9fb7a2b8163d99a368d4a346f8d"}, - {file = "imagecodecs-2024.6.1-cp39-cp39-win32.whl", hash = "sha256:38c6a929ca5356ab9ffdd4aa6dcae5156a7265f886b662bd8cfb0bca1e3d6bee"}, - {file = "imagecodecs-2024.6.1-cp39-cp39-win_amd64.whl", hash = "sha256:01e41f59ebb7b09dc965cafd264cab0ee303d3cef981ecceb85bb556b933a8f3"}, - {file = "imagecodecs-2024.6.1-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:20d66ea962e9e6ea690a89f56ff9da7831378990d705c1fb133cddac2f2c507a"}, - {file = "imagecodecs-2024.6.1.tar.gz", hash = "sha256:0f3e94b7f51e2f78287b7ffae82cd850b1007639148894538274fa50bd179886"}, + {file = "imagecodecs-2024.9.22-cp310-cp310-macosx_10_14_x86_64.whl", hash = "sha256:4cc21a59c6eb409bc3930dc642039eb1ff67a36b3f8d9e8c229eaede6b26557e"}, + {file = "imagecodecs-2024.9.22-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:321ff2e6907820bdbf8350d20733f5068bf53513476d522028117aefab55fc03"}, + {file = "imagecodecs-2024.9.22-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e1608015c1e182e103d8b2ecda4a0e54595c3f846ca76fa484302283f24f3e7f"}, + {file = "imagecodecs-2024.9.22-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:432e518d74ee5b9ac7d5b1022ed29a9fdabd0eab18201220e742fde631962cf8"}, + {file = "imagecodecs-2024.9.22-cp310-cp310-win32.whl", hash = "sha256:50d14caef565ccb4bdeb60e045b61f5d899d3caaf18e980923cdb50a181e4db2"}, + {file = "imagecodecs-2024.9.22-cp310-cp310-win_amd64.whl", hash = "sha256:d7220e9134c3abda5e9f720dcd810031b01b8ba1a71faa8055ab6b43b5056109"}, + {file = "imagecodecs-2024.9.22-cp311-cp311-macosx_10_14_x86_64.whl", hash = "sha256:47259f811aea089d7cdf369e6617cb336b67359835102a45ee2a49f2a8e20624"}, + {file = "imagecodecs-2024.9.22-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:52007be4bc809104e5660805725196255cc091c248e465f588f9b4506544b886"}, + {file = "imagecodecs-2024.9.22-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:db9bcb5abd23522b119f619810cfa0217bf4756d1b8c1146a6a81635d7fb98d1"}, + {file = "imagecodecs-2024.9.22-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:606f3c31387aa9019007cdf7e5e3fcfc4d04fc158f56a8e94340018988f5af69"}, + {file = "imagecodecs-2024.9.22-cp311-cp311-win32.whl", hash = "sha256:180295983edbdd1220099ebe33718876d6cea6c68d9442a3771bba91de0be8c7"}, + {file = "imagecodecs-2024.9.22-cp311-cp311-win_amd64.whl", hash = "sha256:915397c69f986da92608ec4af331b9682ad933f3d645a4e9f7b106530e57683c"}, + {file = "imagecodecs-2024.9.22-cp311-cp311-win_arm64.whl", hash = "sha256:15e7b21488d50f95980b1f865983a6963dad1c752d51cef5bfa76bdd1a325935"}, + {file = "imagecodecs-2024.9.22-cp312-cp312-macosx_10_14_x86_64.whl", hash = "sha256:ba7e98ad714100ae892aeadea5dd636e31eb95663f7e71fb3654fc3399f8a312"}, + {file = "imagecodecs-2024.9.22-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:d1b59ffeaf1fdc06c5da1b8faf34a5f74f914c55a7148060b1746f7684552b6f"}, + {file = "imagecodecs-2024.9.22-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a9646cd9e8933c9a181387b159392d57832fb4f4b444f2d475a6ef7ba0ea8ef8"}, + {file = "imagecodecs-2024.9.22-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:cd9c62286c5aa9cdd73551c7e55c7db04424968304e53ec9240915edb9f30e23"}, + {file = "imagecodecs-2024.9.22-cp312-cp312-win32.whl", hash = "sha256:15959cf31ea8070741318fd0d5748b734e9001b83afd8bab6fe15236c27acba0"}, + {file = "imagecodecs-2024.9.22-cp312-cp312-win_amd64.whl", hash = "sha256:44d51f5aae669fe1eba1474144c042fbb56f4286c072f37aa86941fed865270a"}, + {file = "imagecodecs-2024.9.22-cp312-cp312-win_arm64.whl", hash = "sha256:aa5f47ebef13f4c55b1ac24fafef5e7b340963a6a73af9d2cef2f9bfdf58bf97"}, + {file = "imagecodecs-2024.9.22-cp313-cp313-macosx_10_14_x86_64.whl", hash = "sha256:d4bd89bc86c74439a7a828ce62e28d575db125f25cadc31bd877e2616ace2f0d"}, + {file = "imagecodecs-2024.9.22-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:c8c37f8cdeedd0e01f55b9588e82b2c7059bc1a0167ed8dd05166cad674bfbde"}, + {file = "imagecodecs-2024.9.22-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9752c9af72ba372bbb0afca8a94f76b3096c1c54dcdb5cf18156fdc6b73403d2"}, + {file = "imagecodecs-2024.9.22-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d9ddd053c7f262ca1333fc23f45ece7b375ddca31a0761c46e1197691e895bc3"}, + {file = "imagecodecs-2024.9.22-cp313-cp313-win32.whl", hash = "sha256:a5dc99af846febbaaf328f03518c2e2b0d0dfbe0a1a7b781361550605c7d4c58"}, + {file = "imagecodecs-2024.9.22-cp313-cp313-win_amd64.whl", hash = "sha256:c8951d3449f81aaf0664a8f575d431906134973f9bec93073dfc8d8247db0a1a"}, + {file = "imagecodecs-2024.9.22-cp313-cp313-win_arm64.whl", hash = "sha256:ead06b23300b9f1958026d103aafe8eba272ff40abcb8c5db02d7711a5992cc9"}, + {file = "imagecodecs-2024.9.22-cp39-cp39-macosx_10_14_x86_64.whl", hash = "sha256:fa72958dee65ce40e25f9536408b04f72a95004fe4630faa7042cf6c6c29a1d1"}, + {file = "imagecodecs-2024.9.22-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:4518e0edb5b369415bb7016097ff9cd1b2aed7a9960e21d2e616cf7e066af3fe"}, + {file = "imagecodecs-2024.9.22-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fbbe6f5929838adc954acdd51820602d1dfd8235f8b3eb3764be58e76c6626b7"}, + {file = "imagecodecs-2024.9.22-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:58dbee11a50f2bc2e8c81f3bc1887f1b1328d61f09d9d8caa2e4050ae635fbe9"}, + {file = "imagecodecs-2024.9.22-cp39-cp39-win32.whl", hash = "sha256:fcbbba54d0d61b6ca188d28695b244c4c5a9caaf848173015d81c91d3c0d47cb"}, + {file = "imagecodecs-2024.9.22-cp39-cp39-win_amd64.whl", hash = "sha256:3e55abc2934442fe3055b4f8943ebe8ff6c7eb57f9f895c80ca1732f38632d9f"}, + {file = "imagecodecs-2024.9.22-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:ec3ce35e6131853beb8a39e47e59b183d034c6e9476fafda38c7ab4d8d17e1f4"}, + {file = "imagecodecs-2024.9.22.tar.gz", hash = "sha256:fea0801b4008d25e971918d991397a351bbe76276cfa98eed2de54cb87e894a3"}, ] [package.dependencies] @@ -1477,16 +2325,17 @@ numpy = "*" [package.extras] all = ["matplotlib", "numcodecs", "tifffile"] +test = ["bitshuffle", "blosc", "blosc2", "czifile", "lz4", "numcodecs", "pyliblzfse", "pytest", "python-lzf", "python-snappy", "tifffile", "zarr (<3)", "zopflipy", "zstd"] [[package]] name = "imageio" -version = "2.34.2" +version = "2.35.1" description = "Library for reading and writing a wide range of image, video, scientific, and volumetric data formats." optional = false python-versions = ">=3.8" files = [ - {file = "imageio-2.34.2-py3-none-any.whl", hash = "sha256:a0bb27ec9d5bab36a9f4835e51b21d2cb099e1f78451441f94687ff3404b79f8"}, - {file = "imageio-2.34.2.tar.gz", hash = "sha256:5c0c0ee8faa018a1c42f649b90395dd4d3bb6187c09053a0cd6f1fdd51bbff5e"}, + {file = "imageio-2.35.1-py3-none-any.whl", hash = "sha256:6eb2e5244e7a16b85c10b5c2fe0f7bf961b40fcb9f1a9fd1bd1d2c2f8fb3cd65"}, + {file = "imageio-2.35.1.tar.gz", hash = "sha256:4952dfeef3c3947957f6d5dedb1f4ca31c6e509a476891062396834048aeed2a"}, ] [package.dependencies] @@ -1496,19 +2345,20 @@ pillow = ">=8.3.2" psutil = {version = "*", optional = true, markers = "extra == \"ffmpeg\""} [package.extras] -all-plugins = ["astropy", "av", "imageio-ffmpeg", "pillow-heif", "psutil", "tifffile"] -all-plugins-pypy = ["av", "imageio-ffmpeg", "pillow-heif", "psutil", "tifffile"] +all-plugins = ["astropy", "av", "imageio-ffmpeg", "psutil", "tifffile"] +all-plugins-pypy = ["av", "imageio-ffmpeg", "psutil", "tifffile"] build = ["wheel"] dev = ["black", "flake8", "fsspec[github]", "pytest", "pytest-cov"] docs = ["numpydoc", "pydata-sphinx-theme", "sphinx (<6)"] ffmpeg = ["imageio-ffmpeg", "psutil"] fits = ["astropy"] -full = ["astropy", "av", "black", "flake8", "fsspec[github]", "gdal", "imageio-ffmpeg", "itk", "numpydoc", "pillow-heif", "psutil", "pydata-sphinx-theme", "pytest", "pytest-cov", "sphinx (<6)", "tifffile", "wheel"] +full = ["astropy", "av", "black", "flake8", "fsspec[github]", "gdal", "imageio-ffmpeg", "itk", "numpy (>2)", "numpydoc", "pillow-heif", "psutil", "pydata-sphinx-theme", "pytest", "pytest-cov", "rawpy", "sphinx (<6)", "tifffile", "wheel"] gdal = ["gdal"] itk = ["itk"] linting = ["black", "flake8"] pillow-heif = ["pillow-heif"] pyav = ["av"] +rawpy = ["numpy (>2)", "rawpy"] test = ["fsspec[github]", "pytest", "pytest-cov"] tifffile = ["tifffile"] @@ -1532,22 +2382,26 @@ setuptools = "*" [[package]] name = "importlib-metadata" -version = "8.0.0" +version = "8.5.0" description = "Read metadata from Python packages" optional = false python-versions = ">=3.8" files = [ - {file = "importlib_metadata-8.0.0-py3-none-any.whl", hash = "sha256:15584cf2b1bf449d98ff8a6ff1abef57bf20f3ac6454f431736cd3e660921b2f"}, - {file = "importlib_metadata-8.0.0.tar.gz", hash = "sha256:188bd24e4c346d3f0a933f275c2fec67050326a856b9a359881d7c2a697e8812"}, + {file = "importlib_metadata-8.5.0-py3-none-any.whl", hash = "sha256:45e54197d28b7a7f1559e60b95e7c567032b602131fbd588f1497f47880aa68b"}, + {file = "importlib_metadata-8.5.0.tar.gz", hash = "sha256:71522656f0abace1d072b9e5481a48f07c138e00f079c38c8f883823f9c26bd7"}, ] [package.dependencies] -zipp = ">=0.5" +zipp = ">=3.20" [package.extras] +check = ["pytest-checkdocs (>=2.4)", "pytest-ruff (>=0.2.1)"] +cover = ["pytest-cov"] doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] +enabler = ["pytest-enabler (>=2.2)"] perf = ["ipython"] -test = ["flufl.flake8", "importlib-resources (>=1.3)", "jaraco.test (>=5.4)", "packaging", "pyfakefs", "pytest (>=6,!=8.1.*)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-mypy", "pytest-perf (>=0.9.2)", "pytest-ruff (>=0.2.1)"] +test = ["flufl.flake8", "importlib-resources (>=1.3)", "jaraco.test (>=5.4)", "packaging", "pyfakefs", "pytest (>=6,!=8.1.*)", "pytest-perf (>=0.9.2)"] +type = ["pytest-mypy"] [[package]] name = "iniconfig" @@ -1560,6 +2414,17 @@ files = [ {file = "iniconfig-2.0.0.tar.gz", hash = "sha256:2d91e135bf72d31a410b17c16da610a82cb55f6b0477d1a902134b24a455b8b3"}, ] +[[package]] +name = "inputs" +version = "0.5" +description = "Cross-platform Python support for keyboards, mice and gamepads." +optional = true +python-versions = "*" +files = [ + {file = "inputs-0.5-py2.py3-none-any.whl", hash = "sha256:13f894564e52134cf1e3862b1811da034875eb1f2b62e6021e3776e9669a96ec"}, + {file = "inputs-0.5.tar.gz", hash = "sha256:a31d5b96a3525f1232f326be9e7ce8ccaf873c6b1fb84d9f3c9bc3d79b23eae4"}, +] + [[package]] name = "inquirerpy" version = "0.3.4" @@ -1579,19 +2444,110 @@ prompt-toolkit = ">=3.0.1,<4.0.0" docs = ["Sphinx (>=4.1.2,<5.0.0)", "furo (>=2021.8.17-beta.43,<2022.0.0)", "myst-parser (>=0.15.1,<0.16.0)", "sphinx-autobuild (>=2021.3.14,<2022.0.0)", "sphinx-copybutton (>=0.4.0,<0.5.0)"] [[package]] -name = "intel-openmp" -version = "2021.4.0" -description = "Intel OpenMP* Runtime Library" -optional = false -python-versions = "*" +name = "ipykernel" +version = "6.29.5" +description = "IPython Kernel for Jupyter" +optional = true +python-versions = ">=3.8" +files = [ + {file = "ipykernel-6.29.5-py3-none-any.whl", hash = "sha256:afdb66ba5aa354b09b91379bac28ae4afebbb30e8b39510c9690afb7a10421b5"}, + {file = "ipykernel-6.29.5.tar.gz", hash = "sha256:f093a22c4a40f8828f8e330a9c297cb93dcab13bd9678ded6de8e5cf81c56215"}, +] + +[package.dependencies] +appnope = {version = "*", markers = "platform_system == \"Darwin\""} +comm = ">=0.1.1" +debugpy = ">=1.6.5" +ipython = ">=7.23.1" +jupyter-client = ">=6.1.12" +jupyter-core = ">=4.12,<5.0.dev0 || >=5.1.dev0" +matplotlib-inline = ">=0.1" +nest-asyncio = "*" +packaging = "*" +psutil = "*" +pyzmq = ">=24" +tornado = ">=6.1" +traitlets = ">=5.4.0" + +[package.extras] +cov = ["coverage[toml]", "curio", "matplotlib", "pytest-cov", "trio"] +docs = ["myst-parser", "pydata-sphinx-theme", "sphinx", "sphinx-autodoc-typehints", "sphinxcontrib-github-alt", "sphinxcontrib-spelling", "trio"] +pyqt5 = ["pyqt5"] +pyside6 = ["pyside6"] +test = ["flaky", "ipyparallel", "pre-commit", "pytest (>=7.0)", "pytest-asyncio (>=0.23.5)", "pytest-cov", "pytest-timeout"] + +[[package]] +name = "ipython" +version = "8.27.0" +description = "IPython: Productive Interactive Computing" +optional = true +python-versions = ">=3.10" +files = [ + {file = "ipython-8.27.0-py3-none-any.whl", hash = "sha256:f68b3cb8bde357a5d7adc9598d57e22a45dfbea19eb6b98286fa3b288c9cd55c"}, + {file = "ipython-8.27.0.tar.gz", hash = "sha256:0b99a2dc9f15fd68692e898e5568725c6d49c527d36a9fb5960ffbdeaa82ff7e"}, +] + +[package.dependencies] +decorator = "*" +exceptiongroup = {version = "*", markers = "python_version < \"3.11\""} +jedi = ">=0.16" +matplotlib-inline = "*" +pexpect = {version = ">4.3", markers = "sys_platform != \"win32\" and sys_platform != \"emscripten\""} +prompt-toolkit = ">=3.0.41,<3.1.0" +pygments = ">=2.4.0" +stack-data = "*" +traitlets = ">=5.13.0" +typing-extensions = {version = ">=4.6", markers = "python_version < \"3.12\""} + +[package.extras] +all = ["ipython[black,doc,kernel,matplotlib,nbconvert,nbformat,notebook,parallel,qtconsole]", "ipython[test,test-extra]"] +black = ["black"] +doc = ["docrepr", "exceptiongroup", "intersphinx-registry", "ipykernel", "ipython[test]", "matplotlib", "setuptools (>=18.5)", "sphinx (>=1.3)", "sphinx-rtd-theme", "sphinxcontrib-jquery", "tomli", "typing-extensions"] +kernel = ["ipykernel"] +matplotlib = ["matplotlib"] +nbconvert = ["nbconvert"] +nbformat = ["nbformat"] +notebook = ["ipywidgets", "notebook"] +parallel = ["ipyparallel"] +qtconsole = ["qtconsole"] +test = ["packaging", "pickleshare", "pytest", "pytest-asyncio (<0.22)", "testpath"] +test-extra = ["curio", "ipython[test]", "matplotlib (!=3.2.0)", "nbformat", "numpy (>=1.23)", "pandas", "trio"] + +[[package]] +name = "ipywidgets" +version = "8.1.5" +description = "Jupyter interactive widgets" +optional = true +python-versions = ">=3.7" +files = [ + {file = "ipywidgets-8.1.5-py3-none-any.whl", hash = "sha256:3290f526f87ae6e77655555baba4f36681c555b8bdbbff430b70e52c34c86245"}, + {file = "ipywidgets-8.1.5.tar.gz", hash = "sha256:870e43b1a35656a80c18c9503bbf2d16802db1cb487eec6fab27d683381dde17"}, +] + +[package.dependencies] +comm = ">=0.1.3" +ipython = ">=6.1.0" +jupyterlab-widgets = ">=3.0.12,<3.1.0" +traitlets = ">=4.3.1" +widgetsnbextension = ">=4.0.12,<4.1.0" + +[package.extras] +test = ["ipykernel", "jsonschema", "pytest (>=3.6.0)", "pytest-cov", "pytz"] + +[[package]] +name = "isoduration" +version = "20.11.0" +description = "Operations with ISO 8601 durations" +optional = true +python-versions = ">=3.7" files = [ - {file = "intel_openmp-2021.4.0-py2.py3-none-macosx_10_15_x86_64.macosx_11_0_x86_64.whl", hash = "sha256:41c01e266a7fdb631a7609191709322da2bbf24b252ba763f125dd651bcc7675"}, - {file = "intel_openmp-2021.4.0-py2.py3-none-manylinux1_i686.whl", hash = "sha256:3b921236a38384e2016f0f3d65af6732cf2c12918087128a9163225451e776f2"}, - {file = "intel_openmp-2021.4.0-py2.py3-none-manylinux1_x86_64.whl", hash = "sha256:e2240ab8d01472fed04f3544a878cda5da16c26232b7ea1b59132dbfb48b186e"}, - {file = "intel_openmp-2021.4.0-py2.py3-none-win32.whl", hash = "sha256:6e863d8fd3d7e8ef389d52cf97a50fe2afe1a19247e8c0d168ce021546f96fc9"}, - {file = "intel_openmp-2021.4.0-py2.py3-none-win_amd64.whl", hash = "sha256:eef4c8bcc8acefd7f5cd3b9384dbf73d59e2c99fc56545712ded913f43c4a94f"}, + {file = "isoduration-20.11.0-py3-none-any.whl", hash = "sha256:b2904c2a4228c3d44f409c8ae8e2370eb21a26f7ac2ec5446df141dde3452042"}, + {file = "isoduration-20.11.0.tar.gz", hash = "sha256:ac2f9015137935279eac671f94f89eb00584f940f5dc49462a0c4ee692ba1bd9"}, ] +[package.dependencies] +arrow = ">=0.15.0" + [[package]] name = "itsdangerous" version = "2.2.0" @@ -1603,6 +2559,25 @@ files = [ {file = "itsdangerous-2.2.0.tar.gz", hash = "sha256:e0050c0b7da1eea53ffaf149c0cfbb5c6e2e2b69c4bef22c81fa6eb73e5f6173"}, ] +[[package]] +name = "jedi" +version = "0.19.1" +description = "An autocompletion tool for Python that can be used for text editors." +optional = true +python-versions = ">=3.6" +files = [ + {file = "jedi-0.19.1-py2.py3-none-any.whl", hash = "sha256:e983c654fe5c02867aef4cdfce5a2fbb4a50adc0af145f70504238f18ef5e7e0"}, + {file = "jedi-0.19.1.tar.gz", hash = "sha256:cf0496f3651bc65d7174ac1b7d043eff454892c708a87d1b683e57b569927ffd"}, +] + +[package.dependencies] +parso = ">=0.8.3,<0.9.0" + +[package.extras] +docs = ["Jinja2 (==2.11.3)", "MarkupSafe (==1.1.1)", "Pygments (==2.8.1)", "alabaster (==0.7.12)", "babel (==2.9.1)", "chardet (==4.0.0)", "commonmark (==0.8.1)", "docutils (==0.17.1)", "future (==0.18.2)", "idna (==2.10)", "imagesize (==1.2.0)", "mock (==1.0.1)", "packaging (==20.9)", "pyparsing (==2.4.7)", "pytz (==2021.1)", "readthedocs-sphinx-ext (==2.1.4)", "recommonmark (==0.5.0)", "requests (==2.25.1)", "six (==1.15.0)", "snowballstemmer (==2.1.0)", "sphinx (==1.8.5)", "sphinx-rtd-theme (==0.4.3)", "sphinxcontrib-serializinghtml (==1.1.4)", "sphinxcontrib-websupport (==1.2.4)", "urllib3 (==1.26.4)"] +qa = ["flake8 (==5.0.4)", "mypy (==0.971)", "types-setuptools (==67.2.0.1)"] +testing = ["Django", "attrs", "colorama", "docopt", "pytest (<7.0.0)"] + [[package]] name = "jinja2" version = "3.1.4" @@ -1620,6 +2595,453 @@ MarkupSafe = ">=2.0" [package.extras] i18n = ["Babel (>=2.7)"] +[[package]] +name = "json5" +version = "0.9.25" +description = "A Python implementation of the JSON5 data format." +optional = true +python-versions = ">=3.8" +files = [ + {file = "json5-0.9.25-py3-none-any.whl", hash = "sha256:34ed7d834b1341a86987ed52f3f76cd8ee184394906b6e22a1e0deb9ab294e8f"}, + {file = "json5-0.9.25.tar.gz", hash = "sha256:548e41b9be043f9426776f05df8635a00fe06104ea51ed24b67f908856e151ae"}, +] + +[[package]] +name = "jsonpointer" +version = "3.0.0" +description = "Identify specific nodes in a JSON document (RFC 6901)" +optional = true +python-versions = ">=3.7" +files = [ + {file = "jsonpointer-3.0.0-py2.py3-none-any.whl", hash = "sha256:13e088adc14fca8b6aa8177c044e12701e6ad4b28ff10e65f2267a90109c9942"}, + {file = "jsonpointer-3.0.0.tar.gz", hash = "sha256:2b2d729f2091522d61c3b31f82e11870f60b68f43fbc705cb76bf4b832af59ef"}, +] + +[[package]] +name = "jsonschema" +version = "4.23.0" +description = "An implementation of JSON Schema validation for Python" +optional = true +python-versions = ">=3.8" +files = [ + {file = "jsonschema-4.23.0-py3-none-any.whl", hash = "sha256:fbadb6f8b144a8f8cf9f0b89ba94501d143e50411a1278633f56a7acf7fd5566"}, + {file = "jsonschema-4.23.0.tar.gz", hash = "sha256:d71497fef26351a33265337fa77ffeb82423f3ea21283cd9467bb03999266bc4"}, +] + +[package.dependencies] +attrs = ">=22.2.0" +fqdn = {version = "*", optional = true, markers = "extra == \"format-nongpl\""} +idna = {version = "*", optional = true, markers = "extra == \"format-nongpl\""} +isoduration = {version = "*", optional = true, markers = "extra == \"format-nongpl\""} +jsonpointer = {version = ">1.13", optional = true, markers = "extra == \"format-nongpl\""} +jsonschema-specifications = ">=2023.03.6" +referencing = ">=0.28.4" +rfc3339-validator = {version = "*", optional = true, markers = "extra == \"format-nongpl\""} +rfc3986-validator = {version = ">0.1.0", optional = true, markers = "extra == \"format-nongpl\""} +rpds-py = ">=0.7.1" +uri-template = {version = "*", optional = true, markers = "extra == \"format-nongpl\""} +webcolors = {version = ">=24.6.0", optional = true, markers = "extra == \"format-nongpl\""} + +[package.extras] +format = ["fqdn", "idna", "isoduration", "jsonpointer (>1.13)", "rfc3339-validator", "rfc3987", "uri-template", "webcolors (>=1.11)"] +format-nongpl = ["fqdn", "idna", "isoduration", "jsonpointer (>1.13)", "rfc3339-validator", "rfc3986-validator (>0.1.0)", "uri-template", "webcolors (>=24.6.0)"] + +[[package]] +name = "jsonschema-specifications" +version = "2023.12.1" +description = "The JSON Schema meta-schemas and vocabularies, exposed as a Registry" +optional = true +python-versions = ">=3.8" +files = [ + {file = "jsonschema_specifications-2023.12.1-py3-none-any.whl", hash = "sha256:87e4fdf3a94858b8a2ba2778d9ba57d8a9cafca7c7489c46ba0d30a8bc6a9c3c"}, + {file = "jsonschema_specifications-2023.12.1.tar.gz", hash = "sha256:48a76787b3e70f5ed53f1160d2b81f586e4ca6d1548c5de7085d1682674764cc"}, +] + +[package.dependencies] +referencing = ">=0.31.0" + +[[package]] +name = "jupyter" +version = "1.1.1" +description = "Jupyter metapackage. Install all the Jupyter components in one go." +optional = true +python-versions = "*" +files = [ + {file = "jupyter-1.1.1-py2.py3-none-any.whl", hash = "sha256:7a59533c22af65439b24bbe60373a4e95af8f16ac65a6c00820ad378e3f7cc83"}, + {file = "jupyter-1.1.1.tar.gz", hash = "sha256:d55467bceabdea49d7e3624af7e33d59c37fff53ed3a350e1ac957bed731de7a"}, +] + +[package.dependencies] +ipykernel = "*" +ipywidgets = "*" +jupyter-console = "*" +jupyterlab = "*" +nbconvert = "*" +notebook = "*" + +[[package]] +name = "jupyter-client" +version = "8.6.3" +description = "Jupyter protocol implementation and client libraries" +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyter_client-8.6.3-py3-none-any.whl", hash = "sha256:e8a19cc986cc45905ac3362915f410f3af85424b4c0905e94fa5f2cb08e8f23f"}, + {file = "jupyter_client-8.6.3.tar.gz", hash = "sha256:35b3a0947c4a6e9d589eb97d7d4cd5e90f910ee73101611f01283732bd6d9419"}, +] + +[package.dependencies] +jupyter-core = ">=4.12,<5.0.dev0 || >=5.1.dev0" +python-dateutil = ">=2.8.2" +pyzmq = ">=23.0" +tornado = ">=6.2" +traitlets = ">=5.3" + +[package.extras] +docs = ["ipykernel", "myst-parser", "pydata-sphinx-theme", "sphinx (>=4)", "sphinx-autodoc-typehints", "sphinxcontrib-github-alt", "sphinxcontrib-spelling"] +test = ["coverage", "ipykernel (>=6.14)", "mypy", "paramiko", "pre-commit", "pytest (<8.2.0)", "pytest-cov", "pytest-jupyter[client] (>=0.4.1)", "pytest-timeout"] + +[[package]] +name = "jupyter-console" +version = "6.6.3" +description = "Jupyter terminal console" +optional = true +python-versions = ">=3.7" +files = [ + {file = "jupyter_console-6.6.3-py3-none-any.whl", hash = "sha256:309d33409fcc92ffdad25f0bcdf9a4a9daa61b6f341177570fdac03de5352485"}, + {file = "jupyter_console-6.6.3.tar.gz", hash = "sha256:566a4bf31c87adbfadf22cdf846e3069b59a71ed5da71d6ba4d8aaad14a53539"}, +] + +[package.dependencies] +ipykernel = ">=6.14" +ipython = "*" +jupyter-client = ">=7.0.0" +jupyter-core = ">=4.12,<5.0.dev0 || >=5.1.dev0" +prompt-toolkit = ">=3.0.30" +pygments = "*" +pyzmq = ">=17" +traitlets = ">=5.4" + +[package.extras] +test = ["flaky", "pexpect", "pytest"] + +[[package]] +name = "jupyter-core" +version = "5.7.2" +description = "Jupyter core package. A base package on which Jupyter projects rely." +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyter_core-5.7.2-py3-none-any.whl", hash = "sha256:4f7315d2f6b4bcf2e3e7cb6e46772eba760ae459cd1f59d29eb57b0a01bd7409"}, + {file = "jupyter_core-5.7.2.tar.gz", hash = "sha256:aa5f8d32bbf6b431ac830496da7392035d6f61b4f54872f15c4bd2a9c3f536d9"}, +] + +[package.dependencies] +platformdirs = ">=2.5" +traitlets = ">=5.3" + +[package.extras] +docs = ["myst-parser", "pydata-sphinx-theme", "sphinx-autodoc-typehints", "sphinxcontrib-github-alt", "sphinxcontrib-spelling", "traitlets"] +test = ["ipykernel", "pre-commit", "pytest (<8)", "pytest-cov", "pytest-timeout"] + +[[package]] +name = "jupyter-events" +version = "0.10.0" +description = "Jupyter Event System library" +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyter_events-0.10.0-py3-none-any.whl", hash = "sha256:4b72130875e59d57716d327ea70d3ebc3af1944d3717e5a498b8a06c6c159960"}, + {file = "jupyter_events-0.10.0.tar.gz", hash = "sha256:670b8229d3cc882ec782144ed22e0d29e1c2d639263f92ca8383e66682845e22"}, +] + +[package.dependencies] +jsonschema = {version = ">=4.18.0", extras = ["format-nongpl"]} +python-json-logger = ">=2.0.4" +pyyaml = ">=5.3" +referencing = "*" +rfc3339-validator = "*" +rfc3986-validator = ">=0.1.1" +traitlets = ">=5.3" + +[package.extras] +cli = ["click", "rich"] +docs = ["jupyterlite-sphinx", "myst-parser", "pydata-sphinx-theme", "sphinxcontrib-spelling"] +test = ["click", "pre-commit", "pytest (>=7.0)", "pytest-asyncio (>=0.19.0)", "pytest-console-scripts", "rich"] + +[[package]] +name = "jupyter-lsp" +version = "2.2.5" +description = "Multi-Language Server WebSocket proxy for Jupyter Notebook/Lab server" +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyter-lsp-2.2.5.tar.gz", hash = "sha256:793147a05ad446f809fd53ef1cd19a9f5256fd0a2d6b7ce943a982cb4f545001"}, + {file = "jupyter_lsp-2.2.5-py3-none-any.whl", hash = "sha256:45fbddbd505f3fbfb0b6cb2f1bc5e15e83ab7c79cd6e89416b248cb3c00c11da"}, +] + +[package.dependencies] +jupyter-server = ">=1.1.2" + +[[package]] +name = "jupyter-server" +version = "2.14.2" +description = "The backend—i.e. core services, APIs, and REST endpoints—to Jupyter web applications." +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyter_server-2.14.2-py3-none-any.whl", hash = "sha256:47ff506127c2f7851a17bf4713434208fc490955d0e8632e95014a9a9afbeefd"}, + {file = "jupyter_server-2.14.2.tar.gz", hash = "sha256:66095021aa9638ced276c248b1d81862e4c50f292d575920bbe960de1c56b12b"}, +] + +[package.dependencies] +anyio = ">=3.1.0" +argon2-cffi = ">=21.1" +jinja2 = ">=3.0.3" +jupyter-client = ">=7.4.4" +jupyter-core = ">=4.12,<5.0.dev0 || >=5.1.dev0" +jupyter-events = ">=0.9.0" +jupyter-server-terminals = ">=0.4.4" +nbconvert = ">=6.4.4" +nbformat = ">=5.3.0" +overrides = ">=5.0" +packaging = ">=22.0" +prometheus-client = ">=0.9" +pywinpty = {version = ">=2.0.1", markers = "os_name == \"nt\""} +pyzmq = ">=24" +send2trash = ">=1.8.2" +terminado = ">=0.8.3" +tornado = ">=6.2.0" +traitlets = ">=5.6.0" +websocket-client = ">=1.7" + +[package.extras] +docs = ["ipykernel", "jinja2", "jupyter-client", "myst-parser", "nbformat", "prometheus-client", "pydata-sphinx-theme", "send2trash", "sphinx-autodoc-typehints", "sphinxcontrib-github-alt", "sphinxcontrib-openapi (>=0.8.0)", "sphinxcontrib-spelling", "sphinxemoji", "tornado", "typing-extensions"] +test = ["flaky", "ipykernel", "pre-commit", "pytest (>=7.0,<9)", "pytest-console-scripts", "pytest-jupyter[server] (>=0.7)", "pytest-timeout", "requests"] + +[[package]] +name = "jupyter-server-terminals" +version = "0.5.3" +description = "A Jupyter Server Extension Providing Terminals." +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyter_server_terminals-0.5.3-py3-none-any.whl", hash = "sha256:41ee0d7dc0ebf2809c668e0fc726dfaf258fcd3e769568996ca731b6194ae9aa"}, + {file = "jupyter_server_terminals-0.5.3.tar.gz", hash = "sha256:5ae0295167220e9ace0edcfdb212afd2b01ee8d179fe6f23c899590e9b8a5269"}, +] + +[package.dependencies] +pywinpty = {version = ">=2.0.3", markers = "os_name == \"nt\""} +terminado = ">=0.8.3" + +[package.extras] +docs = ["jinja2", "jupyter-server", "mistune (<4.0)", "myst-parser", "nbformat", "packaging", "pydata-sphinx-theme", "sphinxcontrib-github-alt", "sphinxcontrib-openapi", "sphinxcontrib-spelling", "sphinxemoji", "tornado"] +test = ["jupyter-server (>=2.0.0)", "pytest (>=7.0)", "pytest-jupyter[server] (>=0.5.3)", "pytest-timeout"] + +[[package]] +name = "jupyterlab" +version = "4.2.5" +description = "JupyterLab computational environment" +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyterlab-4.2.5-py3-none-any.whl", hash = "sha256:73b6e0775d41a9fee7ee756c80f58a6bed4040869ccc21411dc559818874d321"}, + {file = "jupyterlab-4.2.5.tar.gz", hash = "sha256:ae7f3a1b8cb88b4f55009ce79fa7c06f99d70cd63601ee4aa91815d054f46f75"}, +] + +[package.dependencies] +async-lru = ">=1.0.0" +httpx = ">=0.25.0" +ipykernel = ">=6.5.0" +jinja2 = ">=3.0.3" +jupyter-core = "*" +jupyter-lsp = ">=2.0.0" +jupyter-server = ">=2.4.0,<3" +jupyterlab-server = ">=2.27.1,<3" +notebook-shim = ">=0.2" +packaging = "*" +setuptools = ">=40.1.0" +tomli = {version = ">=1.2.2", markers = "python_version < \"3.11\""} +tornado = ">=6.2.0" +traitlets = "*" + +[package.extras] +dev = ["build", "bump2version", "coverage", "hatch", "pre-commit", "pytest-cov", "ruff (==0.3.5)"] +docs = ["jsx-lexer", "myst-parser", "pydata-sphinx-theme (>=0.13.0)", "pytest", "pytest-check-links", "pytest-jupyter", "sphinx (>=1.8,<7.3.0)", "sphinx-copybutton"] +docs-screenshots = ["altair (==5.3.0)", "ipython (==8.16.1)", "ipywidgets (==8.1.2)", "jupyterlab-geojson (==3.4.0)", "jupyterlab-language-pack-zh-cn (==4.1.post2)", "matplotlib (==3.8.3)", "nbconvert (>=7.0.0)", "pandas (==2.2.1)", "scipy (==1.12.0)", "vega-datasets (==0.9.0)"] +test = ["coverage", "pytest (>=7.0)", "pytest-check-links (>=0.7)", "pytest-console-scripts", "pytest-cov", "pytest-jupyter (>=0.5.3)", "pytest-timeout", "pytest-tornasync", "requests", "requests-cache", "virtualenv"] +upgrade-extension = ["copier (>=9,<10)", "jinja2-time (<0.3)", "pydantic (<3.0)", "pyyaml-include (<3.0)", "tomli-w (<2.0)"] + +[[package]] +name = "jupyterlab-pygments" +version = "0.3.0" +description = "Pygments theme using JupyterLab CSS variables" +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyterlab_pygments-0.3.0-py3-none-any.whl", hash = "sha256:841a89020971da1d8693f1a99997aefc5dc424bb1b251fd6322462a1b8842780"}, + {file = "jupyterlab_pygments-0.3.0.tar.gz", hash = "sha256:721aca4d9029252b11cfa9d185e5b5af4d54772bb8072f9b7036f4170054d35d"}, +] + +[[package]] +name = "jupyterlab-server" +version = "2.27.3" +description = "A set of server components for JupyterLab and JupyterLab like applications." +optional = true +python-versions = ">=3.8" +files = [ + {file = "jupyterlab_server-2.27.3-py3-none-any.whl", hash = "sha256:e697488f66c3db49df675158a77b3b017520d772c6e1548c7d9bcc5df7944ee4"}, + {file = "jupyterlab_server-2.27.3.tar.gz", hash = "sha256:eb36caca59e74471988f0ae25c77945610b887f777255aa21f8065def9e51ed4"}, +] + +[package.dependencies] +babel = ">=2.10" +jinja2 = ">=3.0.3" +json5 = ">=0.9.0" +jsonschema = ">=4.18.0" +jupyter-server = ">=1.21,<3" +packaging = ">=21.3" +requests = ">=2.31" + +[package.extras] +docs = ["autodoc-traits", "jinja2 (<3.2.0)", "mistune (<4)", "myst-parser", "pydata-sphinx-theme", "sphinx", "sphinx-copybutton", "sphinxcontrib-openapi (>0.8)"] +openapi = ["openapi-core (>=0.18.0,<0.19.0)", "ruamel-yaml"] +test = ["hatch", "ipykernel", "openapi-core (>=0.18.0,<0.19.0)", "openapi-spec-validator (>=0.6.0,<0.8.0)", "pytest (>=7.0,<8)", "pytest-console-scripts", "pytest-cov", "pytest-jupyter[server] (>=0.6.2)", "pytest-timeout", "requests-mock", "ruamel-yaml", "sphinxcontrib-spelling", "strict-rfc3339", "werkzeug"] + +[[package]] +name = "jupyterlab-widgets" +version = "3.0.13" +description = "Jupyter interactive widgets for JupyterLab" +optional = true +python-versions = ">=3.7" +files = [ + {file = "jupyterlab_widgets-3.0.13-py3-none-any.whl", hash = "sha256:e3cda2c233ce144192f1e29914ad522b2f4c40e77214b0cc97377ca3d323db54"}, + {file = "jupyterlab_widgets-3.0.13.tar.gz", hash = "sha256:a2966d385328c1942b683a8cd96b89b8dd82c8b8f81dda902bb2bc06d46f5bed"}, +] + +[[package]] +name = "kiwisolver" +version = "1.4.7" +description = "A fast implementation of the Cassowary constraint solver" +optional = true +python-versions = ">=3.8" +files = [ + {file = "kiwisolver-1.4.7-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:8a9c83f75223d5e48b0bc9cb1bf2776cf01563e00ade8775ffe13b0b6e1af3a6"}, + {file = "kiwisolver-1.4.7-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:58370b1ffbd35407444d57057b57da5d6549d2d854fa30249771775c63b5fe17"}, + {file = "kiwisolver-1.4.7-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:aa0abdf853e09aff551db11fce173e2177d00786c688203f52c87ad7fcd91ef9"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:8d53103597a252fb3ab8b5845af04c7a26d5e7ea8122303dd7a021176a87e8b9"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:88f17c5ffa8e9462fb79f62746428dd57b46eb931698e42e990ad63103f35e6c"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:88a9ca9c710d598fd75ee5de59d5bda2684d9db36a9f50b6125eaea3969c2599"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f4d742cb7af1c28303a51b7a27aaee540e71bb8e24f68c736f6f2ffc82f2bf05"}, + {file = "kiwisolver-1.4.7-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e28c7fea2196bf4c2f8d46a0415c77a1c480cc0724722f23d7410ffe9842c407"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:e968b84db54f9d42046cf154e02911e39c0435c9801681e3fc9ce8a3c4130278"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:0c18ec74c0472de033e1bebb2911c3c310eef5649133dd0bedf2a169a1b269e5"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:8f0ea6da6d393d8b2e187e6a5e3fb81f5862010a40c3945e2c6d12ae45cfb2ad"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:f106407dda69ae456dd1227966bf445b157ccc80ba0dff3802bb63f30b74e895"}, + {file = "kiwisolver-1.4.7-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:84ec80df401cfee1457063732d90022f93951944b5b58975d34ab56bb150dfb3"}, + {file = "kiwisolver-1.4.7-cp310-cp310-win32.whl", hash = "sha256:71bb308552200fb2c195e35ef05de12f0c878c07fc91c270eb3d6e41698c3bcc"}, + {file = "kiwisolver-1.4.7-cp310-cp310-win_amd64.whl", hash = "sha256:44756f9fd339de0fb6ee4f8c1696cfd19b2422e0d70b4cefc1cc7f1f64045a8c"}, + {file = "kiwisolver-1.4.7-cp310-cp310-win_arm64.whl", hash = "sha256:78a42513018c41c2ffd262eb676442315cbfe3c44eed82385c2ed043bc63210a"}, + {file = "kiwisolver-1.4.7-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:d2b0e12a42fb4e72d509fc994713d099cbb15ebf1103545e8a45f14da2dfca54"}, + {file = "kiwisolver-1.4.7-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:2a8781ac3edc42ea4b90bc23e7d37b665d89423818e26eb6df90698aa2287c95"}, + {file = "kiwisolver-1.4.7-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:46707a10836894b559e04b0fd143e343945c97fd170d69a2d26d640b4e297935"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ef97b8df011141c9b0f6caf23b29379f87dd13183c978a30a3c546d2c47314cb"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3ab58c12a2cd0fc769089e6d38466c46d7f76aced0a1f54c77652446733d2d02"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:803b8e1459341c1bb56d1c5c010406d5edec8a0713a0945851290a7930679b51"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f9a9e8a507420fe35992ee9ecb302dab68550dedc0da9e2880dd88071c5fb052"}, + {file = "kiwisolver-1.4.7-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:18077b53dc3bb490e330669a99920c5e6a496889ae8c63b58fbc57c3d7f33a18"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6af936f79086a89b3680a280c47ea90b4df7047b5bdf3aa5c524bbedddb9e545"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:3abc5b19d24af4b77d1598a585b8a719beb8569a71568b66f4ebe1fb0449460b"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:933d4de052939d90afbe6e9d5273ae05fb836cc86c15b686edd4b3560cc0ee36"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:65e720d2ab2b53f1f72fb5da5fb477455905ce2c88aaa671ff0a447c2c80e8e3"}, + {file = "kiwisolver-1.4.7-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:3bf1ed55088f214ba6427484c59553123fdd9b218a42bbc8c6496d6754b1e523"}, + {file = "kiwisolver-1.4.7-cp311-cp311-win32.whl", hash = "sha256:4c00336b9dd5ad96d0a558fd18a8b6f711b7449acce4c157e7343ba92dd0cf3d"}, + {file = "kiwisolver-1.4.7-cp311-cp311-win_amd64.whl", hash = "sha256:929e294c1ac1e9f615c62a4e4313ca1823ba37326c164ec720a803287c4c499b"}, + {file = "kiwisolver-1.4.7-cp311-cp311-win_arm64.whl", hash = "sha256:e33e8fbd440c917106b237ef1a2f1449dfbb9b6f6e1ce17c94cd6a1e0d438376"}, + {file = "kiwisolver-1.4.7-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:5360cc32706dab3931f738d3079652d20982511f7c0ac5711483e6eab08efff2"}, + {file = "kiwisolver-1.4.7-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:942216596dc64ddb25adb215c3c783215b23626f8d84e8eff8d6d45c3f29f75a"}, + {file = "kiwisolver-1.4.7-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:48b571ecd8bae15702e4f22d3ff6a0f13e54d3d00cd25216d5e7f658242065ee"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ad42ba922c67c5f219097b28fae965e10045ddf145d2928bfac2eb2e17673640"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:612a10bdae23404a72941a0fc8fa2660c6ea1217c4ce0dbcab8a8f6543ea9e7f"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9e838bba3a3bac0fe06d849d29772eb1afb9745a59710762e4ba3f4cb8424483"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:22f499f6157236c19f4bbbd472fa55b063db77a16cd74d49afe28992dff8c258"}, + {file = "kiwisolver-1.4.7-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:693902d433cf585133699972b6d7c42a8b9f8f826ebcaf0132ff55200afc599e"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:4e77f2126c3e0b0d055f44513ed349038ac180371ed9b52fe96a32aa071a5107"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:657a05857bda581c3656bfc3b20e353c232e9193eb167766ad2dc58b56504948"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:4bfa75a048c056a411f9705856abfc872558e33c055d80af6a380e3658766038"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:34ea1de54beef1c104422d210c47c7d2a4999bdecf42c7b5718fbe59a4cac383"}, + {file = "kiwisolver-1.4.7-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:90da3b5f694b85231cf93586dad5e90e2d71b9428f9aad96952c99055582f520"}, + {file = "kiwisolver-1.4.7-cp312-cp312-win32.whl", hash = "sha256:18e0cca3e008e17fe9b164b55735a325140a5a35faad8de92dd80265cd5eb80b"}, + {file = "kiwisolver-1.4.7-cp312-cp312-win_amd64.whl", hash = "sha256:58cb20602b18f86f83a5c87d3ee1c766a79c0d452f8def86d925e6c60fbf7bfb"}, + {file = "kiwisolver-1.4.7-cp312-cp312-win_arm64.whl", hash = "sha256:f5a8b53bdc0b3961f8b6125e198617c40aeed638b387913bf1ce78afb1b0be2a"}, + {file = "kiwisolver-1.4.7-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:2e6039dcbe79a8e0f044f1c39db1986a1b8071051efba3ee4d74f5b365f5226e"}, + {file = "kiwisolver-1.4.7-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:a1ecf0ac1c518487d9d23b1cd7139a6a65bc460cd101ab01f1be82ecf09794b6"}, + {file = "kiwisolver-1.4.7-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:7ab9ccab2b5bd5702ab0803676a580fffa2aa178c2badc5557a84cc943fcf750"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f816dd2277f8d63d79f9c8473a79fe54047bc0467754962840782c575522224d"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf8bcc23ceb5a1b624572a1623b9f79d2c3b337c8c455405ef231933a10da379"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:dea0bf229319828467d7fca8c7c189780aa9ff679c94539eed7532ebe33ed37c"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c06a4c7cf15ec739ce0e5971b26c93638730090add60e183530d70848ebdd34"}, + {file = "kiwisolver-1.4.7-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:913983ad2deb14e66d83c28b632fd35ba2b825031f2fa4ca29675e665dfecbe1"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:5337ec7809bcd0f424c6b705ecf97941c46279cf5ed92311782c7c9c2026f07f"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:4c26ed10c4f6fa6ddb329a5120ba3b6db349ca192ae211e882970bfc9d91420b"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:c619b101e6de2222c1fcb0531e1b17bbffbe54294bfba43ea0d411d428618c27"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:073a36c8273647592ea332e816e75ef8da5c303236ec0167196793eb1e34657a"}, + {file = "kiwisolver-1.4.7-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:3ce6b2b0231bda412463e152fc18335ba32faf4e8c23a754ad50ffa70e4091ee"}, + {file = "kiwisolver-1.4.7-cp313-cp313-win32.whl", hash = "sha256:f4c9aee212bc89d4e13f58be11a56cc8036cabad119259d12ace14b34476fd07"}, + {file = "kiwisolver-1.4.7-cp313-cp313-win_amd64.whl", hash = "sha256:8a3ec5aa8e38fc4c8af308917ce12c536f1c88452ce554027e55b22cbbfbff76"}, + {file = "kiwisolver-1.4.7-cp313-cp313-win_arm64.whl", hash = "sha256:76c8094ac20ec259471ac53e774623eb62e6e1f56cd8690c67ce6ce4fcb05650"}, + {file = "kiwisolver-1.4.7-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:5d5abf8f8ec1f4e22882273c423e16cae834c36856cac348cfbfa68e01c40f3a"}, + {file = "kiwisolver-1.4.7-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:aeb3531b196ef6f11776c21674dba836aeea9d5bd1cf630f869e3d90b16cfade"}, + {file = "kiwisolver-1.4.7-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:b7d755065e4e866a8086c9bdada157133ff466476a2ad7861828e17b6026e22c"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:08471d4d86cbaec61f86b217dd938a83d85e03785f51121e791a6e6689a3be95"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7bbfcb7165ce3d54a3dfbe731e470f65739c4c1f85bb1018ee912bae139e263b"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5d34eb8494bea691a1a450141ebb5385e4b69d38bb8403b5146ad279f4b30fa3"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:9242795d174daa40105c1d86aba618e8eab7bf96ba8c3ee614da8302a9f95503"}, + {file = "kiwisolver-1.4.7-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:a0f64a48bb81af7450e641e3fe0b0394d7381e342805479178b3d335d60ca7cf"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:8e045731a5416357638d1700927529e2b8ab304811671f665b225f8bf8d8f933"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:4322872d5772cae7369f8351da1edf255a604ea7087fe295411397d0cfd9655e"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:e1631290ee9271dffe3062d2634c3ecac02c83890ada077d225e081aca8aab89"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:edcfc407e4eb17e037bca59be0e85a2031a2ac87e4fed26d3e9df88b4165f92d"}, + {file = "kiwisolver-1.4.7-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:4d05d81ecb47d11e7f8932bd8b61b720bf0b41199358f3f5e36d38e28f0532c5"}, + {file = "kiwisolver-1.4.7-cp38-cp38-win32.whl", hash = "sha256:b38ac83d5f04b15e515fd86f312479d950d05ce2368d5413d46c088dda7de90a"}, + {file = "kiwisolver-1.4.7-cp38-cp38-win_amd64.whl", hash = "sha256:d83db7cde68459fc803052a55ace60bea2bae361fc3b7a6d5da07e11954e4b09"}, + {file = "kiwisolver-1.4.7-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:3f9362ecfca44c863569d3d3c033dbe8ba452ff8eed6f6b5806382741a1334bd"}, + {file = "kiwisolver-1.4.7-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:e8df2eb9b2bac43ef8b082e06f750350fbbaf2887534a5be97f6cf07b19d9583"}, + {file = "kiwisolver-1.4.7-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:f32d6edbc638cde7652bd690c3e728b25332acbadd7cad670cc4a02558d9c417"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:e2e6c39bd7b9372b0be21456caab138e8e69cc0fc1190a9dfa92bd45a1e6e904"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:dda56c24d869b1193fcc763f1284b9126550eaf84b88bbc7256e15028f19188a"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:79849239c39b5e1fd906556c474d9b0439ea6792b637511f3fe3a41158d89ca8"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5e3bc157fed2a4c02ec468de4ecd12a6e22818d4f09cde2c31ee3226ffbefab2"}, + {file = "kiwisolver-1.4.7-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3da53da805b71e41053dc670f9a820d1157aae77b6b944e08024d17bcd51ef88"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:8705f17dfeb43139a692298cb6637ee2e59c0194538153e83e9ee0c75c2eddde"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:82a5c2f4b87c26bb1a0ef3d16b5c4753434633b83d365cc0ddf2770c93829e3c"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:ce8be0466f4c0d585cdb6c1e2ed07232221df101a4c6f28821d2aa754ca2d9e2"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:409afdfe1e2e90e6ee7fc896f3df9a7fec8e793e58bfa0d052c8a82f99c37abb"}, + {file = "kiwisolver-1.4.7-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:5b9c3f4ee0b9a439d2415012bd1b1cc2df59e4d6a9939f4d669241d30b414327"}, + {file = "kiwisolver-1.4.7-cp39-cp39-win32.whl", hash = "sha256:a79ae34384df2b615eefca647a2873842ac3b596418032bef9a7283675962644"}, + {file = "kiwisolver-1.4.7-cp39-cp39-win_amd64.whl", hash = "sha256:cf0438b42121a66a3a667de17e779330fc0f20b0d97d59d2f2121e182b0505e4"}, + {file = "kiwisolver-1.4.7-cp39-cp39-win_arm64.whl", hash = "sha256:764202cc7e70f767dab49e8df52c7455e8de0df5d858fa801a11aa0d882ccf3f"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:94252291e3fe68001b1dd747b4c0b3be12582839b95ad4d1b641924d68fd4643"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:5b7dfa3b546da08a9f622bb6becdb14b3e24aaa30adba66749d38f3cc7ea9706"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bd3de6481f4ed8b734da5df134cd5a6a64fe32124fe83dde1e5b5f29fe30b1e6"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a91b5f9f1205845d488c928e8570dcb62b893372f63b8b6e98b863ebd2368ff2"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40fa14dbd66b8b8f470d5fc79c089a66185619d31645f9b0773b88b19f7223c4"}, + {file = "kiwisolver-1.4.7-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:eb542fe7933aa09d8d8f9d9097ef37532a7df6497819d16efe4359890a2f417a"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:bfa1acfa0c54932d5607e19a2c24646fb4c1ae2694437789129cf099789a3b00"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-macosx_11_0_arm64.whl", hash = "sha256:eee3ea935c3d227d49b4eb85660ff631556841f6e567f0f7bda972df6c2c9935"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:f3160309af4396e0ed04db259c3ccbfdc3621b5559b5453075e5de555e1f3a1b"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:a17f6a29cf8935e587cc8a4dbfc8368c55edc645283db0ce9801016f83526c2d"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:10849fb2c1ecbfae45a693c070e0320a91b35dd4bcf58172c023b994283a124d"}, + {file = "kiwisolver-1.4.7-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:ac542bf38a8a4be2dc6b15248d36315ccc65f0743f7b1a76688ffb6b5129a5c2"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:8b01aac285f91ca889c800042c35ad3b239e704b150cfd3382adfc9dcc780e39"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:48be928f59a1f5c8207154f935334d374e79f2b5d212826307d072595ad76a2e"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f37cfe618a117e50d8c240555331160d73d0411422b59b5ee217843d7b693608"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:599b5c873c63a1f6ed7eead644a8a380cfbdf5db91dcb6f85707aaab213b1674"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:801fa7802e5cfabe3ab0c81a34c323a319b097dfb5004be950482d882f3d7225"}, + {file = "kiwisolver-1.4.7-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:0c6c43471bc764fad4bc99c5c2d6d16a676b1abf844ca7c8702bdae92df01ee0"}, + {file = "kiwisolver-1.4.7.tar.gz", hash = "sha256:9893ff81bd7107f7b685d3017cc6583daadb4fc26e4a888350df530e41980a60"}, +] + [[package]] name = "labmaze" version = "1.0.6" @@ -1715,153 +3137,149 @@ files = [ [[package]] name = "lxml" -version = "5.2.2" +version = "5.3.0" description = "Powerful and Pythonic XML processing library combining libxml2/libxslt with the ElementTree API." optional = true python-versions = ">=3.6" files = [ - {file = "lxml-5.2.2-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:364d03207f3e603922d0d3932ef363d55bbf48e3647395765f9bfcbdf6d23632"}, - {file = "lxml-5.2.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:50127c186f191b8917ea2fb8b206fbebe87fd414a6084d15568c27d0a21d60db"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:74e4f025ef3db1c6da4460dd27c118d8cd136d0391da4e387a15e48e5c975147"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:981a06a3076997adf7c743dcd0d7a0415582661e2517c7d961493572e909aa1d"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:aef5474d913d3b05e613906ba4090433c515e13ea49c837aca18bde190853dff"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1e275ea572389e41e8b039ac076a46cb87ee6b8542df3fff26f5baab43713bca"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f5b65529bb2f21ac7861a0e94fdbf5dc0daab41497d18223b46ee8515e5ad297"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:bcc98f911f10278d1daf14b87d65325851a1d29153caaf146877ec37031d5f36"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_28_ppc64le.whl", hash = "sha256:b47633251727c8fe279f34025844b3b3a3e40cd1b198356d003aa146258d13a2"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_28_s390x.whl", hash = "sha256:fbc9d316552f9ef7bba39f4edfad4a734d3d6f93341232a9dddadec4f15d425f"}, - {file = "lxml-5.2.2-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:13e69be35391ce72712184f69000cda04fc89689429179bc4c0ae5f0b7a8c21b"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:3b6a30a9ab040b3f545b697cb3adbf3696c05a3a68aad172e3fd7ca73ab3c835"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:a233bb68625a85126ac9f1fc66d24337d6e8a0f9207b688eec2e7c880f012ec0"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:dfa7c241073d8f2b8e8dbc7803c434f57dbb83ae2a3d7892dd068d99e96efe2c"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:1a7aca7964ac4bb07680d5c9d63b9d7028cace3e2d43175cb50bba8c5ad33316"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:ae4073a60ab98529ab8a72ebf429f2a8cc612619a8c04e08bed27450d52103c0"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:ffb2be176fed4457e445fe540617f0252a72a8bc56208fd65a690fdb1f57660b"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:e290d79a4107d7d794634ce3e985b9ae4f920380a813717adf61804904dc4393"}, - {file = "lxml-5.2.2-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:96e85aa09274955bb6bd483eaf5b12abadade01010478154b0ec70284c1b1526"}, - {file = "lxml-5.2.2-cp310-cp310-win32.whl", hash = "sha256:f956196ef61369f1685d14dad80611488d8dc1ef00be57c0c5a03064005b0f30"}, - {file = "lxml-5.2.2-cp310-cp310-win_amd64.whl", hash = "sha256:875a3f90d7eb5c5d77e529080d95140eacb3c6d13ad5b616ee8095447b1d22e7"}, - {file = "lxml-5.2.2-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:45f9494613160d0405682f9eee781c7e6d1bf45f819654eb249f8f46a2c22545"}, - {file = "lxml-5.2.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:b0b3f2df149efb242cee2ffdeb6674b7f30d23c9a7af26595099afaf46ef4e88"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d28cb356f119a437cc58a13f8135ab8a4c8ece18159eb9194b0d269ec4e28083"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:657a972f46bbefdbba2d4f14413c0d079f9ae243bd68193cb5061b9732fa54c1"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b74b9ea10063efb77a965a8d5f4182806fbf59ed068b3c3fd6f30d2ac7bee734"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:07542787f86112d46d07d4f3c4e7c760282011b354d012dc4141cc12a68cef5f"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:303f540ad2dddd35b92415b74b900c749ec2010e703ab3bfd6660979d01fd4ed"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:2eb2227ce1ff998faf0cd7fe85bbf086aa41dfc5af3b1d80867ecfe75fb68df3"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_28_ppc64le.whl", hash = "sha256:1d8a701774dfc42a2f0b8ccdfe7dbc140500d1049e0632a611985d943fcf12df"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_28_s390x.whl", hash = "sha256:56793b7a1a091a7c286b5f4aa1fe4ae5d1446fe742d00cdf2ffb1077865db10d"}, - {file = "lxml-5.2.2-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:eb00b549b13bd6d884c863554566095bf6fa9c3cecb2e7b399c4bc7904cb33b5"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:1a2569a1f15ae6c8c64108a2cd2b4a858fc1e13d25846be0666fc144715e32ab"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:8cf85a6e40ff1f37fe0f25719aadf443686b1ac7652593dc53c7ef9b8492b115"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:d237ba6664b8e60fd90b8549a149a74fcc675272e0e95539a00522e4ca688b04"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:0b3f5016e00ae7630a4b83d0868fca1e3d494c78a75b1c7252606a3a1c5fc2ad"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:23441e2b5339bc54dc949e9e675fa35efe858108404ef9aa92f0456929ef6fe8"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:2fb0ba3e8566548d6c8e7dd82a8229ff47bd8fb8c2da237607ac8e5a1b8312e5"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:79d1fb9252e7e2cfe4de6e9a6610c7cbb99b9708e2c3e29057f487de5a9eaefa"}, - {file = "lxml-5.2.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:6dcc3d17eac1df7859ae01202e9bb11ffa8c98949dcbeb1069c8b9a75917e01b"}, - {file = "lxml-5.2.2-cp311-cp311-win32.whl", hash = "sha256:4c30a2f83677876465f44c018830f608fa3c6a8a466eb223535035fbc16f3438"}, - {file = "lxml-5.2.2-cp311-cp311-win_amd64.whl", hash = "sha256:49095a38eb333aaf44c06052fd2ec3b8f23e19747ca7ec6f6c954ffea6dbf7be"}, - {file = "lxml-5.2.2-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:7429e7faa1a60cad26ae4227f4dd0459efde239e494c7312624ce228e04f6391"}, - {file = "lxml-5.2.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:50ccb5d355961c0f12f6cf24b7187dbabd5433f29e15147a67995474f27d1776"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:dc911208b18842a3a57266d8e51fc3cfaccee90a5351b92079beed912a7914c2"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:33ce9e786753743159799fdf8e92a5da351158c4bfb6f2db0bf31e7892a1feb5"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ec87c44f619380878bd49ca109669c9f221d9ae6883a5bcb3616785fa8f94c97"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:08ea0f606808354eb8f2dfaac095963cb25d9d28e27edcc375d7b30ab01abbf6"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:75a9632f1d4f698b2e6e2e1ada40e71f369b15d69baddb8968dcc8e683839b18"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:74da9f97daec6928567b48c90ea2c82a106b2d500f397eeb8941e47d30b1ca85"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_28_ppc64le.whl", hash = "sha256:0969e92af09c5687d769731e3f39ed62427cc72176cebb54b7a9d52cc4fa3b73"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_28_s390x.whl", hash = "sha256:9164361769b6ca7769079f4d426a41df6164879f7f3568be9086e15baca61466"}, - {file = "lxml-5.2.2-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:d26a618ae1766279f2660aca0081b2220aca6bd1aa06b2cf73f07383faf48927"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:ab67ed772c584b7ef2379797bf14b82df9aa5f7438c5b9a09624dd834c1c1aaf"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:3d1e35572a56941b32c239774d7e9ad724074d37f90c7a7d499ab98761bd80cf"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:8268cbcd48c5375f46e000adb1390572c98879eb4f77910c6053d25cc3ac2c67"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:e282aedd63c639c07c3857097fc0e236f984ceb4089a8b284da1c526491e3f3d"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6dfdc2bfe69e9adf0df4915949c22a25b39d175d599bf98e7ddf620a13678585"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:4aefd911793b5d2d7a921233a54c90329bf3d4a6817dc465f12ffdfe4fc7b8fe"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:8b8df03a9e995b6211dafa63b32f9d405881518ff1ddd775db4e7b98fb545e1c"}, - {file = "lxml-5.2.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:f11ae142f3a322d44513de1018b50f474f8f736bc3cd91d969f464b5bfef8836"}, - {file = "lxml-5.2.2-cp312-cp312-win32.whl", hash = "sha256:16a8326e51fcdffc886294c1e70b11ddccec836516a343f9ed0f82aac043c24a"}, - {file = "lxml-5.2.2-cp312-cp312-win_amd64.whl", hash = "sha256:bbc4b80af581e18568ff07f6395c02114d05f4865c2812a1f02f2eaecf0bfd48"}, - {file = "lxml-5.2.2-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:e3d9d13603410b72787579769469af730c38f2f25505573a5888a94b62b920f8"}, - {file = "lxml-5.2.2-cp36-cp36m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:38b67afb0a06b8575948641c1d6d68e41b83a3abeae2ca9eed2ac59892b36706"}, - {file = "lxml-5.2.2-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c689d0d5381f56de7bd6966a4541bff6e08bf8d3871bbd89a0c6ab18aa699573"}, - {file = "lxml-5.2.2-cp36-cp36m-manylinux_2_28_x86_64.whl", hash = "sha256:cf2a978c795b54c539f47964ec05e35c05bd045db5ca1e8366988c7f2fe6b3ce"}, - {file = "lxml-5.2.2-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:739e36ef7412b2bd940f75b278749106e6d025e40027c0b94a17ef7968d55d56"}, - {file = "lxml-5.2.2-cp36-cp36m-musllinux_1_1_x86_64.whl", hash = "sha256:d8bbcd21769594dbba9c37d3c819e2d5847656ca99c747ddb31ac1701d0c0ed9"}, - {file = "lxml-5.2.2-cp36-cp36m-musllinux_1_2_x86_64.whl", hash = "sha256:2304d3c93f2258ccf2cf7a6ba8c761d76ef84948d87bf9664e14d203da2cd264"}, - {file = "lxml-5.2.2-cp36-cp36m-win32.whl", hash = "sha256:02437fb7308386867c8b7b0e5bc4cd4b04548b1c5d089ffb8e7b31009b961dc3"}, - {file = "lxml-5.2.2-cp36-cp36m-win_amd64.whl", hash = "sha256:edcfa83e03370032a489430215c1e7783128808fd3e2e0a3225deee278585196"}, - {file = "lxml-5.2.2-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:28bf95177400066596cdbcfc933312493799382879da504633d16cf60bba735b"}, - {file = "lxml-5.2.2-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3a745cc98d504d5bd2c19b10c79c61c7c3df9222629f1b6210c0368177589fb8"}, - {file = "lxml-5.2.2-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1b590b39ef90c6b22ec0be925b211298e810b4856909c8ca60d27ffbca6c12e6"}, - {file = "lxml-5.2.2-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b336b0416828022bfd5a2e3083e7f5ba54b96242159f83c7e3eebaec752f1716"}, - {file = "lxml-5.2.2-cp37-cp37m-manylinux_2_28_aarch64.whl", hash = "sha256:c2faf60c583af0d135e853c86ac2735ce178f0e338a3c7f9ae8f622fd2eb788c"}, - {file = "lxml-5.2.2-cp37-cp37m-manylinux_2_28_x86_64.whl", hash = "sha256:4bc6cb140a7a0ad1f7bc37e018d0ed690b7b6520ade518285dc3171f7a117905"}, - {file = "lxml-5.2.2-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:7ff762670cada8e05b32bf1e4dc50b140790909caa8303cfddc4d702b71ea184"}, - {file = "lxml-5.2.2-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:57f0a0bbc9868e10ebe874e9f129d2917750adf008fe7b9c1598c0fbbfdde6a6"}, - {file = "lxml-5.2.2-cp37-cp37m-musllinux_1_2_aarch64.whl", hash = "sha256:a6d2092797b388342c1bc932077ad232f914351932353e2e8706851c870bca1f"}, - {file = "lxml-5.2.2-cp37-cp37m-musllinux_1_2_x86_64.whl", hash = "sha256:60499fe961b21264e17a471ec296dcbf4365fbea611bf9e303ab69db7159ce61"}, - {file = "lxml-5.2.2-cp37-cp37m-win32.whl", hash = "sha256:d9b342c76003c6b9336a80efcc766748a333573abf9350f4094ee46b006ec18f"}, - {file = "lxml-5.2.2-cp37-cp37m-win_amd64.whl", hash = "sha256:b16db2770517b8799c79aa80f4053cd6f8b716f21f8aca962725a9565ce3ee40"}, - {file = "lxml-5.2.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:7ed07b3062b055d7a7f9d6557a251cc655eed0b3152b76de619516621c56f5d3"}, - {file = "lxml-5.2.2-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f60fdd125d85bf9c279ffb8e94c78c51b3b6a37711464e1f5f31078b45002421"}, - {file = "lxml-5.2.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8a7e24cb69ee5f32e003f50e016d5fde438010c1022c96738b04fc2423e61706"}, - {file = "lxml-5.2.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:23cfafd56887eaed93d07bc4547abd5e09d837a002b791e9767765492a75883f"}, - {file = "lxml-5.2.2-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:19b4e485cd07b7d83e3fe3b72132e7df70bfac22b14fe4bf7a23822c3a35bff5"}, - {file = "lxml-5.2.2-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:7ce7ad8abebe737ad6143d9d3bf94b88b93365ea30a5b81f6877ec9c0dee0a48"}, - {file = "lxml-5.2.2-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:e49b052b768bb74f58c7dda4e0bdf7b79d43a9204ca584ffe1fb48a6f3c84c66"}, - {file = "lxml-5.2.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:d14a0d029a4e176795cef99c056d58067c06195e0c7e2dbb293bf95c08f772a3"}, - {file = "lxml-5.2.2-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:be49ad33819d7dcc28a309b86d4ed98e1a65f3075c6acd3cd4fe32103235222b"}, - {file = "lxml-5.2.2-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:a6d17e0370d2516d5bb9062c7b4cb731cff921fc875644c3d751ad857ba9c5b1"}, - {file = "lxml-5.2.2-cp38-cp38-win32.whl", hash = "sha256:5b8c041b6265e08eac8a724b74b655404070b636a8dd6d7a13c3adc07882ef30"}, - {file = "lxml-5.2.2-cp38-cp38-win_amd64.whl", hash = "sha256:f61efaf4bed1cc0860e567d2ecb2363974d414f7f1f124b1df368bbf183453a6"}, - {file = "lxml-5.2.2-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:fb91819461b1b56d06fa4bcf86617fac795f6a99d12239fb0c68dbeba41a0a30"}, - {file = "lxml-5.2.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:d4ed0c7cbecde7194cd3228c044e86bf73e30a23505af852857c09c24e77ec5d"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:54401c77a63cc7d6dc4b4e173bb484f28a5607f3df71484709fe037c92d4f0ed"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:625e3ef310e7fa3a761d48ca7ea1f9d8718a32b1542e727d584d82f4453d5eeb"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:519895c99c815a1a24a926d5b60627ce5ea48e9f639a5cd328bda0515ea0f10c"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c7079d5eb1c1315a858bbf180000757db8ad904a89476653232db835c3114001"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:343ab62e9ca78094f2306aefed67dcfad61c4683f87eee48ff2fd74902447726"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:cd9e78285da6c9ba2d5c769628f43ef66d96ac3085e59b10ad4f3707980710d3"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_28_ppc64le.whl", hash = "sha256:546cf886f6242dff9ec206331209db9c8e1643ae642dea5fdbecae2453cb50fd"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_28_s390x.whl", hash = "sha256:02f6a8eb6512fdc2fd4ca10a49c341c4e109aa6e9448cc4859af5b949622715a"}, - {file = "lxml-5.2.2-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:339ee4a4704bc724757cd5dd9dc8cf4d00980f5d3e6e06d5847c1b594ace68ab"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:0a028b61a2e357ace98b1615fc03f76eb517cc028993964fe08ad514b1e8892d"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:f90e552ecbad426eab352e7b2933091f2be77115bb16f09f78404861c8322981"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:d83e2d94b69bf31ead2fa45f0acdef0757fa0458a129734f59f67f3d2eb7ef32"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:a02d3c48f9bb1e10c7788d92c0c7db6f2002d024ab6e74d6f45ae33e3d0288a3"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:6d68ce8e7b2075390e8ac1e1d3a99e8b6372c694bbe612632606d1d546794207"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:453d037e09a5176d92ec0fd282e934ed26d806331a8b70ab431a81e2fbabf56d"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:3b019d4ee84b683342af793b56bb35034bd749e4cbdd3d33f7d1107790f8c472"}, - {file = "lxml-5.2.2-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:cb3942960f0beb9f46e2a71a3aca220d1ca32feb5a398656be934320804c0df9"}, - {file = "lxml-5.2.2-cp39-cp39-win32.whl", hash = "sha256:ac6540c9fff6e3813d29d0403ee7a81897f1d8ecc09a8ff84d2eea70ede1cdbf"}, - {file = "lxml-5.2.2-cp39-cp39-win_amd64.whl", hash = "sha256:610b5c77428a50269f38a534057444c249976433f40f53e3b47e68349cca1425"}, - {file = "lxml-5.2.2-pp310-pypy310_pp73-macosx_10_9_x86_64.whl", hash = "sha256:b537bd04d7ccd7c6350cdaaaad911f6312cbd61e6e6045542f781c7f8b2e99d2"}, - {file = "lxml-5.2.2-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4820c02195d6dfb7b8508ff276752f6b2ff8b64ae5d13ebe02e7667e035000b9"}, - {file = "lxml-5.2.2-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f2a09f6184f17a80897172863a655467da2b11151ec98ba8d7af89f17bf63dae"}, - {file = "lxml-5.2.2-pp310-pypy310_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:76acba4c66c47d27c8365e7c10b3d8016a7da83d3191d053a58382311a8bf4e1"}, - {file = "lxml-5.2.2-pp310-pypy310_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:b128092c927eaf485928cec0c28f6b8bead277e28acf56800e972aa2c2abd7a2"}, - {file = "lxml-5.2.2-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:ae791f6bd43305aade8c0e22f816b34f3b72b6c820477aab4d18473a37e8090b"}, - {file = "lxml-5.2.2-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:a2f6a1bc2460e643785a2cde17293bd7a8f990884b822f7bca47bee0a82fc66b"}, - {file = "lxml-5.2.2-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8e8d351ff44c1638cb6e980623d517abd9f580d2e53bfcd18d8941c052a5a009"}, - {file = "lxml-5.2.2-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bec4bd9133420c5c52d562469c754f27c5c9e36ee06abc169612c959bd7dbb07"}, - {file = "lxml-5.2.2-pp37-pypy37_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:55ce6b6d803890bd3cc89975fca9de1dff39729b43b73cb15ddd933b8bc20484"}, - {file = "lxml-5.2.2-pp37-pypy37_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:8ab6a358d1286498d80fe67bd3d69fcbc7d1359b45b41e74c4a26964ca99c3f8"}, - {file = "lxml-5.2.2-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:06668e39e1f3c065349c51ac27ae430719d7806c026fec462e5693b08b95696b"}, - {file = "lxml-5.2.2-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:9cd5323344d8ebb9fb5e96da5de5ad4ebab993bbf51674259dbe9d7a18049525"}, - {file = "lxml-5.2.2-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:89feb82ca055af0fe797a2323ec9043b26bc371365847dbe83c7fd2e2f181c34"}, - {file = "lxml-5.2.2-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e481bba1e11ba585fb06db666bfc23dbe181dbafc7b25776156120bf12e0d5a6"}, - {file = "lxml-5.2.2-pp38-pypy38_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:9d6c6ea6a11ca0ff9cd0390b885984ed31157c168565702959c25e2191674a14"}, - {file = "lxml-5.2.2-pp38-pypy38_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:3d98de734abee23e61f6b8c2e08a88453ada7d6486dc7cdc82922a03968928db"}, - {file = "lxml-5.2.2-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:69ab77a1373f1e7563e0fb5a29a8440367dec051da6c7405333699d07444f511"}, - {file = "lxml-5.2.2-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:34e17913c431f5ae01d8658dbf792fdc457073dcdfbb31dc0cc6ab256e664a8d"}, - {file = "lxml-5.2.2-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:05f8757b03208c3f50097761be2dea0aba02e94f0dc7023ed73a7bb14ff11eb0"}, - {file = "lxml-5.2.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6a520b4f9974b0a0a6ed73c2154de57cdfd0c8800f4f15ab2b73238ffed0b36e"}, - {file = "lxml-5.2.2-pp39-pypy39_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:5e097646944b66207023bc3c634827de858aebc226d5d4d6d16f0b77566ea182"}, - {file = "lxml-5.2.2-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:b5e4ef22ff25bfd4ede5f8fb30f7b24446345f3e79d9b7455aef2836437bc38a"}, - {file = "lxml-5.2.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:ff69a9a0b4b17d78170c73abe2ab12084bdf1691550c5629ad1fe7849433f324"}, - {file = "lxml-5.2.2.tar.gz", hash = "sha256:bb2dc4898180bea79863d5487e5f9c7c34297414bad54bcd0f0852aee9cfdb87"}, + {file = "lxml-5.3.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:dd36439be765e2dde7660212b5275641edbc813e7b24668831a5c8ac91180656"}, + {file = "lxml-5.3.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:ae5fe5c4b525aa82b8076c1a59d642c17b6e8739ecf852522c6321852178119d"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:501d0d7e26b4d261fca8132854d845e4988097611ba2531408ec91cf3fd9d20a"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fb66442c2546446944437df74379e9cf9e9db353e61301d1a0e26482f43f0dd8"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9e41506fec7a7f9405b14aa2d5c8abbb4dbbd09d88f9496958b6d00cb4d45330"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f7d4a670107d75dfe5ad080bed6c341d18c4442f9378c9f58e5851e86eb79965"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:41ce1f1e2c7755abfc7e759dc34d7d05fd221723ff822947132dc934d122fe22"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:44264ecae91b30e5633013fb66f6ddd05c006d3e0e884f75ce0b4755b3e3847b"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_28_ppc64le.whl", hash = "sha256:3c174dc350d3ec52deb77f2faf05c439331d6ed5e702fc247ccb4e6b62d884b7"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_28_s390x.whl", hash = "sha256:2dfab5fa6a28a0b60a20638dc48e6343c02ea9933e3279ccb132f555a62323d8"}, + {file = "lxml-5.3.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:b1c8c20847b9f34e98080da785bb2336ea982e7f913eed5809e5a3c872900f32"}, + {file = "lxml-5.3.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:2c86bf781b12ba417f64f3422cfc302523ac9cd1d8ae8c0f92a1c66e56ef2e86"}, + {file = "lxml-5.3.0-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:c162b216070f280fa7da844531169be0baf9ccb17263cf5a8bf876fcd3117fa5"}, + {file = "lxml-5.3.0-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:36aef61a1678cb778097b4a6eeae96a69875d51d1e8f4d4b491ab3cfb54b5a03"}, + {file = "lxml-5.3.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:f65e5120863c2b266dbcc927b306c5b78e502c71edf3295dfcb9501ec96e5fc7"}, + {file = "lxml-5.3.0-cp310-cp310-win32.whl", hash = "sha256:ef0c1fe22171dd7c7c27147f2e9c3e86f8bdf473fed75f16b0c2e84a5030ce80"}, + {file = "lxml-5.3.0-cp310-cp310-win_amd64.whl", hash = "sha256:052d99051e77a4f3e8482c65014cf6372e61b0a6f4fe9edb98503bb5364cfee3"}, + {file = "lxml-5.3.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:74bcb423462233bc5d6066e4e98b0264e7c1bed7541fff2f4e34fe6b21563c8b"}, + {file = "lxml-5.3.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:a3d819eb6f9b8677f57f9664265d0a10dd6551d227afb4af2b9cd7bdc2ccbf18"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5b8f5db71b28b8c404956ddf79575ea77aa8b1538e8b2ef9ec877945b3f46442"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2c3406b63232fc7e9b8783ab0b765d7c59e7c59ff96759d8ef9632fca27c7ee4"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:2ecdd78ab768f844c7a1d4a03595038c166b609f6395e25af9b0f3f26ae1230f"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:168f2dfcfdedf611eb285efac1516c8454c8c99caf271dccda8943576b67552e"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:aa617107a410245b8660028a7483b68e7914304a6d4882b5ff3d2d3eb5948d8c"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_28_aarch64.whl", hash = "sha256:69959bd3167b993e6e710b99051265654133a98f20cec1d9b493b931942e9c16"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_28_ppc64le.whl", hash = "sha256:bd96517ef76c8654446fc3db9242d019a1bb5fe8b751ba414765d59f99210b79"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_28_s390x.whl", hash = "sha256:ab6dd83b970dc97c2d10bc71aa925b84788c7c05de30241b9e96f9b6d9ea3080"}, + {file = "lxml-5.3.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:eec1bb8cdbba2925bedc887bc0609a80e599c75b12d87ae42ac23fd199445654"}, + {file = "lxml-5.3.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:6a7095eeec6f89111d03dabfe5883a1fd54da319c94e0fb104ee8f23616b572d"}, + {file = "lxml-5.3.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:6f651ebd0b21ec65dfca93aa629610a0dbc13dbc13554f19b0113da2e61a4763"}, + {file = "lxml-5.3.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:f422a209d2455c56849442ae42f25dbaaba1c6c3f501d58761c619c7836642ec"}, + {file = "lxml-5.3.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:62f7fdb0d1ed2065451f086519865b4c90aa19aed51081979ecd05a21eb4d1be"}, + {file = "lxml-5.3.0-cp311-cp311-win32.whl", hash = "sha256:c6379f35350b655fd817cd0d6cbeef7f265f3ae5fedb1caae2eb442bbeae9ab9"}, + {file = "lxml-5.3.0-cp311-cp311-win_amd64.whl", hash = "sha256:9c52100e2c2dbb0649b90467935c4b0de5528833c76a35ea1a2691ec9f1ee7a1"}, + {file = "lxml-5.3.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:e99f5507401436fdcc85036a2e7dc2e28d962550afe1cbfc07c40e454256a859"}, + {file = "lxml-5.3.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:384aacddf2e5813a36495233b64cb96b1949da72bef933918ba5c84e06af8f0e"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:874a216bf6afaf97c263b56371434e47e2c652d215788396f60477540298218f"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:65ab5685d56914b9a2a34d67dd5488b83213d680b0c5d10b47f81da5a16b0b0e"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:aac0bbd3e8dd2d9c45ceb82249e8bdd3ac99131a32b4d35c8af3cc9db1657179"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b369d3db3c22ed14c75ccd5af429086f166a19627e84a8fdade3f8f31426e52a"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c24037349665434f375645fa9d1f5304800cec574d0310f618490c871fd902b3"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_28_aarch64.whl", hash = "sha256:62d172f358f33a26d6b41b28c170c63886742f5b6772a42b59b4f0fa10526cb1"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_28_ppc64le.whl", hash = "sha256:c1f794c02903c2824fccce5b20c339a1a14b114e83b306ff11b597c5f71a1c8d"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_28_s390x.whl", hash = "sha256:5d6a6972b93c426ace71e0be9a6f4b2cfae9b1baed2eed2006076a746692288c"}, + {file = "lxml-5.3.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:3879cc6ce938ff4eb4900d901ed63555c778731a96365e53fadb36437a131a99"}, + {file = "lxml-5.3.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:74068c601baff6ff021c70f0935b0c7bc528baa8ea210c202e03757c68c5a4ff"}, + {file = "lxml-5.3.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:ecd4ad8453ac17bc7ba3868371bffb46f628161ad0eefbd0a855d2c8c32dd81a"}, + {file = "lxml-5.3.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:7e2f58095acc211eb9d8b5771bf04df9ff37d6b87618d1cbf85f92399c98dae8"}, + {file = "lxml-5.3.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:e63601ad5cd8f860aa99d109889b5ac34de571c7ee902d6812d5d9ddcc77fa7d"}, + {file = "lxml-5.3.0-cp312-cp312-win32.whl", hash = "sha256:17e8d968d04a37c50ad9c456a286b525d78c4a1c15dd53aa46c1d8e06bf6fa30"}, + {file = "lxml-5.3.0-cp312-cp312-win_amd64.whl", hash = "sha256:c1a69e58a6bb2de65902051d57fde951febad631a20a64572677a1052690482f"}, + {file = "lxml-5.3.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:8c72e9563347c7395910de6a3100a4840a75a6f60e05af5e58566868d5eb2d6a"}, + {file = "lxml-5.3.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:e92ce66cd919d18d14b3856906a61d3f6b6a8500e0794142338da644260595cd"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1d04f064bebdfef9240478f7a779e8c5dc32b8b7b0b2fc6a62e39b928d428e51"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5c2fb570d7823c2bbaf8b419ba6e5662137f8166e364a8b2b91051a1fb40ab8b"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:0c120f43553ec759f8de1fee2f4794452b0946773299d44c36bfe18e83caf002"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:562e7494778a69086f0312ec9689f6b6ac1c6b65670ed7d0267e49f57ffa08c4"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:423b121f7e6fa514ba0c7918e56955a1d4470ed35faa03e3d9f0e3baa4c7e492"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_28_aarch64.whl", hash = "sha256:c00f323cc00576df6165cc9d21a4c21285fa6b9989c5c39830c3903dc4303ef3"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_28_ppc64le.whl", hash = "sha256:1fdc9fae8dd4c763e8a31e7630afef517eab9f5d5d31a278df087f307bf601f4"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_28_s390x.whl", hash = "sha256:658f2aa69d31e09699705949b5fc4719cbecbd4a97f9656a232e7d6c7be1a367"}, + {file = "lxml-5.3.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:1473427aff3d66a3fa2199004c3e601e6c4500ab86696edffdbc84954c72d832"}, + {file = "lxml-5.3.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:a87de7dd873bf9a792bf1e58b1c3887b9264036629a5bf2d2e6579fe8e73edff"}, + {file = "lxml-5.3.0-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:0d7b36afa46c97875303a94e8f3ad932bf78bace9e18e603f2085b652422edcd"}, + {file = "lxml-5.3.0-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:cf120cce539453ae086eacc0130a324e7026113510efa83ab42ef3fcfccac7fb"}, + {file = "lxml-5.3.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:df5c7333167b9674aa8ae1d4008fa4bc17a313cc490b2cca27838bbdcc6bb15b"}, + {file = "lxml-5.3.0-cp313-cp313-win32.whl", hash = "sha256:c802e1c2ed9f0c06a65bc4ed0189d000ada8049312cfeab6ca635e39c9608957"}, + {file = "lxml-5.3.0-cp313-cp313-win_amd64.whl", hash = "sha256:406246b96d552e0503e17a1006fd27edac678b3fcc9f1be71a2f94b4ff61528d"}, + {file = "lxml-5.3.0-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:8f0de2d390af441fe8b2c12626d103540b5d850d585b18fcada58d972b74a74e"}, + {file = "lxml-5.3.0-cp36-cp36m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:1afe0a8c353746e610bd9031a630a95bcfb1a720684c3f2b36c4710a0a96528f"}, + {file = "lxml-5.3.0-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:56b9861a71575f5795bde89256e7467ece3d339c9b43141dbdd54544566b3b94"}, + {file = "lxml-5.3.0-cp36-cp36m-manylinux_2_28_x86_64.whl", hash = "sha256:9fb81d2824dff4f2e297a276297e9031f46d2682cafc484f49de182aa5e5df99"}, + {file = "lxml-5.3.0-cp36-cp36m-manylinux_2_5_x86_64.manylinux1_x86_64.whl", hash = "sha256:2c226a06ecb8cdef28845ae976da407917542c5e6e75dcac7cc33eb04aaeb237"}, + {file = "lxml-5.3.0-cp36-cp36m-musllinux_1_2_x86_64.whl", hash = "sha256:7d3d1ca42870cdb6d0d29939630dbe48fa511c203724820fc0fd507b2fb46577"}, + {file = "lxml-5.3.0-cp36-cp36m-win32.whl", hash = "sha256:094cb601ba9f55296774c2d57ad68730daa0b13dc260e1f941b4d13678239e70"}, + {file = "lxml-5.3.0-cp36-cp36m-win_amd64.whl", hash = "sha256:eafa2c8658f4e560b098fe9fc54539f86528651f61849b22111a9b107d18910c"}, + {file = "lxml-5.3.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:cb83f8a875b3d9b458cada4f880fa498646874ba4011dc974e071a0a84a1b033"}, + {file = "lxml-5.3.0-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:25f1b69d41656b05885aa185f5fdf822cb01a586d1b32739633679699f220391"}, + {file = "lxml-5.3.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:23e0553b8055600b3bf4a00b255ec5c92e1e4aebf8c2c09334f8368e8bd174d6"}, + {file = "lxml-5.3.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9ada35dd21dc6c039259596b358caab6b13f4db4d4a7f8665764d616daf9cc1d"}, + {file = "lxml-5.3.0-cp37-cp37m-manylinux_2_28_aarch64.whl", hash = "sha256:81b4e48da4c69313192d8c8d4311e5d818b8be1afe68ee20f6385d0e96fc9512"}, + {file = "lxml-5.3.0-cp37-cp37m-manylinux_2_28_x86_64.whl", hash = "sha256:2bc9fd5ca4729af796f9f59cd8ff160fe06a474da40aca03fcc79655ddee1a8b"}, + {file = "lxml-5.3.0-cp37-cp37m-musllinux_1_2_aarch64.whl", hash = "sha256:07da23d7ee08577760f0a71d67a861019103e4812c87e2fab26b039054594cc5"}, + {file = "lxml-5.3.0-cp37-cp37m-musllinux_1_2_x86_64.whl", hash = "sha256:ea2e2f6f801696ad7de8aec061044d6c8c0dd4037608c7cab38a9a4d316bfb11"}, + {file = "lxml-5.3.0-cp37-cp37m-win32.whl", hash = "sha256:5c54afdcbb0182d06836cc3d1be921e540be3ebdf8b8a51ee3ef987537455f84"}, + {file = "lxml-5.3.0-cp37-cp37m-win_amd64.whl", hash = "sha256:f2901429da1e645ce548bf9171784c0f74f0718c3f6150ce166be39e4dd66c3e"}, + {file = "lxml-5.3.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:c56a1d43b2f9ee4786e4658c7903f05da35b923fb53c11025712562d5cc02753"}, + {file = "lxml-5.3.0-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6ee8c39582d2652dcd516d1b879451500f8db3fe3607ce45d7c5957ab2596040"}, + {file = "lxml-5.3.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0fdf3a3059611f7585a78ee10399a15566356116a4288380921a4b598d807a22"}, + {file = "lxml-5.3.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:146173654d79eb1fc97498b4280c1d3e1e5d58c398fa530905c9ea50ea849b22"}, + {file = "lxml-5.3.0-cp38-cp38-manylinux_2_28_aarch64.whl", hash = "sha256:0a7056921edbdd7560746f4221dca89bb7a3fe457d3d74267995253f46343f15"}, + {file = "lxml-5.3.0-cp38-cp38-manylinux_2_28_x86_64.whl", hash = "sha256:9e4b47ac0f5e749cfc618efdf4726269441014ae1d5583e047b452a32e221920"}, + {file = "lxml-5.3.0-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:f914c03e6a31deb632e2daa881fe198461f4d06e57ac3d0e05bbcab8eae01945"}, + {file = "lxml-5.3.0-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:213261f168c5e1d9b7535a67e68b1f59f92398dd17a56d934550837143f79c42"}, + {file = "lxml-5.3.0-cp38-cp38-win32.whl", hash = "sha256:218c1b2e17a710e363855594230f44060e2025b05c80d1f0661258142b2add2e"}, + {file = "lxml-5.3.0-cp38-cp38-win_amd64.whl", hash = "sha256:315f9542011b2c4e1d280e4a20ddcca1761993dda3afc7a73b01235f8641e903"}, + {file = "lxml-5.3.0-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:1ffc23010330c2ab67fac02781df60998ca8fe759e8efde6f8b756a20599c5de"}, + {file = "lxml-5.3.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:2b3778cb38212f52fac9fe913017deea2fdf4eb1a4f8e4cfc6b009a13a6d3fcc"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4b0c7a688944891086ba192e21c5229dea54382f4836a209ff8d0a660fac06be"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:747a3d3e98e24597981ca0be0fd922aebd471fa99d0043a3842d00cdcad7ad6a"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:86a6b24b19eaebc448dc56b87c4865527855145d851f9fc3891673ff97950540"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b11a5d918a6216e521c715b02749240fb07ae5a1fefd4b7bf12f833bc8b4fe70"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:68b87753c784d6acb8a25b05cb526c3406913c9d988d51f80adecc2b0775d6aa"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_28_aarch64.whl", hash = "sha256:109fa6fede314cc50eed29e6e56c540075e63d922455346f11e4d7a036d2b8cf"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_28_ppc64le.whl", hash = "sha256:02ced472497b8362c8e902ade23e3300479f4f43e45f4105c85ef43b8db85229"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_28_s390x.whl", hash = "sha256:6b038cc86b285e4f9fea2ba5ee76e89f21ed1ea898e287dc277a25884f3a7dfe"}, + {file = "lxml-5.3.0-cp39-cp39-manylinux_2_28_x86_64.whl", hash = "sha256:7437237c6a66b7ca341e868cda48be24b8701862757426852c9b3186de1da8a2"}, + {file = "lxml-5.3.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:7f41026c1d64043a36fda21d64c5026762d53a77043e73e94b71f0521939cc71"}, + {file = "lxml-5.3.0-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:482c2f67761868f0108b1743098640fbb2a28a8e15bf3f47ada9fa59d9fe08c3"}, + {file = "lxml-5.3.0-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:1483fd3358963cc5c1c9b122c80606a3a79ee0875bcac0204149fa09d6ff2727"}, + {file = "lxml-5.3.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:2dec2d1130a9cda5b904696cec33b2cfb451304ba9081eeda7f90f724097300a"}, + {file = "lxml-5.3.0-cp39-cp39-win32.whl", hash = "sha256:a0eabd0a81625049c5df745209dc7fcef6e2aea7793e5f003ba363610aa0a3ff"}, + {file = "lxml-5.3.0-cp39-cp39-win_amd64.whl", hash = "sha256:89e043f1d9d341c52bf2af6d02e6adde62e0a46e6755d5eb60dc6e4f0b8aeca2"}, + {file = "lxml-5.3.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:7b1cd427cb0d5f7393c31b7496419da594fe600e6fdc4b105a54f82405e6626c"}, + {file = "lxml-5.3.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:51806cfe0279e06ed8500ce19479d757db42a30fd509940b1701be9c86a5ff9a"}, + {file = "lxml-5.3.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ee70d08fd60c9565ba8190f41a46a54096afa0eeb8f76bd66f2c25d3b1b83005"}, + {file = "lxml-5.3.0-pp310-pypy310_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:8dc2c0395bea8254d8daebc76dcf8eb3a95ec2a46fa6fae5eaccee366bfe02ce"}, + {file = "lxml-5.3.0-pp310-pypy310_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:6ba0d3dcac281aad8a0e5b14c7ed6f9fa89c8612b47939fc94f80b16e2e9bc83"}, + {file = "lxml-5.3.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:6e91cf736959057f7aac7adfc83481e03615a8e8dd5758aa1d95ea69e8931dba"}, + {file = "lxml-5.3.0-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:94d6c3782907b5e40e21cadf94b13b0842ac421192f26b84c45f13f3c9d5dc27"}, + {file = "lxml-5.3.0-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c300306673aa0f3ed5ed9372b21867690a17dba38c68c44b287437c362ce486b"}, + {file = "lxml-5.3.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:78d9b952e07aed35fe2e1a7ad26e929595412db48535921c5013edc8aa4a35ce"}, + {file = "lxml-5.3.0-pp37-pypy37_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:01220dca0d066d1349bd6a1726856a78f7929f3878f7e2ee83c296c69495309e"}, + {file = "lxml-5.3.0-pp37-pypy37_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:2d9b8d9177afaef80c53c0a9e30fa252ff3036fb1c6494d427c066a4ce6a282f"}, + {file = "lxml-5.3.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:20094fc3f21ea0a8669dc4c61ed7fa8263bd37d97d93b90f28fc613371e7a875"}, + {file = "lxml-5.3.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:ace2c2326a319a0bb8a8b0e5b570c764962e95818de9f259ce814ee666603f19"}, + {file = "lxml-5.3.0-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:92e67a0be1639c251d21e35fe74df6bcc40cba445c2cda7c4a967656733249e2"}, + {file = "lxml-5.3.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd5350b55f9fecddc51385463a4f67a5da829bc741e38cf689f38ec9023f54ab"}, + {file = "lxml-5.3.0-pp38-pypy38_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:4c1fefd7e3d00921c44dc9ca80a775af49698bbfd92ea84498e56acffd4c5469"}, + {file = "lxml-5.3.0-pp38-pypy38_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:71a8dd38fbd2f2319136d4ae855a7078c69c9a38ae06e0c17c73fd70fc6caad8"}, + {file = "lxml-5.3.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:97acf1e1fd66ab53dacd2c35b319d7e548380c2e9e8c54525c6e76d21b1ae3b1"}, + {file = "lxml-5.3.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:68934b242c51eb02907c5b81d138cb977b2129a0a75a8f8b60b01cb8586c7b21"}, + {file = "lxml-5.3.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b710bc2b8292966b23a6a0121f7a6c51d45d2347edcc75f016ac123b8054d3f2"}, + {file = "lxml-5.3.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:18feb4b93302091b1541221196a2155aa296c363fd233814fa11e181adebc52f"}, + {file = "lxml-5.3.0-pp39-pypy39_pp73-manylinux_2_28_aarch64.whl", hash = "sha256:3eb44520c4724c2e1a57c0af33a379eee41792595023f367ba3952a2d96c2aab"}, + {file = "lxml-5.3.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:609251a0ca4770e5a8768ff902aa02bf636339c5a93f9349b48eb1f606f7f3e9"}, + {file = "lxml-5.3.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:516f491c834eb320d6c843156440fe7fc0d50b33e44387fcec5b02f0bc118a4c"}, + {file = "lxml-5.3.0.tar.gz", hash = "sha256:4e109ca30d1edec1ac60cdbe341905dc3b8f55b16855e03a54aaf59e51ec8c6f"}, ] [package.extras] @@ -1869,7 +3287,31 @@ cssselect = ["cssselect (>=0.7)"] html-clean = ["lxml-html-clean"] html5 = ["html5lib"] htmlsoup = ["BeautifulSoup4"] -source = ["Cython (>=3.0.10)"] +source = ["Cython (>=3.0.11)"] + +[[package]] +name = "markdown-it-py" +version = "3.0.0" +description = "Python port of markdown-it. Markdown parsing, done right!" +optional = true +python-versions = ">=3.8" +files = [ + {file = "markdown-it-py-3.0.0.tar.gz", hash = "sha256:e3f60a94fa066dc52ec76661e37c851cb232d92f9886b15cb560aaada2df8feb"}, + {file = "markdown_it_py-3.0.0-py3-none-any.whl", hash = "sha256:355216845c60bd96232cd8d8c40e8f9765cc86f46880e43a8fd22dc1a1a8cab1"}, +] + +[package.dependencies] +mdurl = ">=0.1,<1.0" + +[package.extras] +benchmarking = ["psutil", "pytest", "pytest-benchmark"] +code-style = ["pre-commit (>=3.0,<4.0)"] +compare = ["commonmark (>=0.9,<1.0)", "markdown (>=3.4,<4.0)", "mistletoe (>=1.0,<2.0)", "mistune (>=2.0,<3.0)", "panflute (>=2.3,<3.0)"] +linkify = ["linkify-it-py (>=1,<3)"] +plugins = ["mdit-py-plugins"] +profiling = ["gprof2dot"] +rtd = ["jupyter_sphinx", "mdit-py-plugins", "myst-parser", "pyyaml", "sphinx", "sphinx-copybutton", "sphinx-design", "sphinx_book_theme"] +testing = ["coverage", "pytest", "pytest-cov", "pytest-regressions"] [[package]] name = "markupsafe" @@ -1941,22 +3383,121 @@ files = [ ] [[package]] -name = "mkl" -version = "2021.4.0" -description = "Intel® oneAPI Math Kernel Library" -optional = false -python-versions = "*" +name = "matplotlib" +version = "3.9.2" +description = "Python plotting package" +optional = true +python-versions = ">=3.9" +files = [ + {file = "matplotlib-3.9.2-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:9d78bbc0cbc891ad55b4f39a48c22182e9bdaea7fc0e5dbd364f49f729ca1bbb"}, + {file = "matplotlib-3.9.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c375cc72229614632c87355366bdf2570c2dac01ac66b8ad048d2dabadf2d0d4"}, + {file = "matplotlib-3.9.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1d94ff717eb2bd0b58fe66380bd8b14ac35f48a98e7c6765117fe67fb7684e64"}, + {file = "matplotlib-3.9.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ab68d50c06938ef28681073327795c5db99bb4666214d2d5f880ed11aeaded66"}, + {file = "matplotlib-3.9.2-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:65aacf95b62272d568044531e41de26285d54aec8cb859031f511f84bd8b495a"}, + {file = "matplotlib-3.9.2-cp310-cp310-win_amd64.whl", hash = "sha256:3fd595f34aa8a55b7fc8bf9ebea8aa665a84c82d275190a61118d33fbc82ccae"}, + {file = "matplotlib-3.9.2-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:d8dd059447824eec055e829258ab092b56bb0579fc3164fa09c64f3acd478772"}, + {file = "matplotlib-3.9.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c797dac8bb9c7a3fd3382b16fe8f215b4cf0f22adccea36f1545a6d7be310b41"}, + {file = "matplotlib-3.9.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d719465db13267bcef19ea8954a971db03b9f48b4647e3860e4bc8e6ed86610f"}, + {file = "matplotlib-3.9.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8912ef7c2362f7193b5819d17dae8629b34a95c58603d781329712ada83f9447"}, + {file = "matplotlib-3.9.2-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:7741f26a58a240f43bee74965c4882b6c93df3e7eb3de160126d8c8f53a6ae6e"}, + {file = "matplotlib-3.9.2-cp311-cp311-win_amd64.whl", hash = "sha256:ae82a14dab96fbfad7965403c643cafe6515e386de723e498cf3eeb1e0b70cc7"}, + {file = "matplotlib-3.9.2-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:ac43031375a65c3196bee99f6001e7fa5bdfb00ddf43379d3c0609bdca042df9"}, + {file = "matplotlib-3.9.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:be0fc24a5e4531ae4d8e858a1a548c1fe33b176bb13eff7f9d0d38ce5112a27d"}, + {file = "matplotlib-3.9.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bf81de2926c2db243c9b2cbc3917619a0fc85796c6ba4e58f541df814bbf83c7"}, + {file = "matplotlib-3.9.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f6ee45bc4245533111ced13f1f2cace1e7f89d1c793390392a80c139d6cf0e6c"}, + {file = "matplotlib-3.9.2-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:306c8dfc73239f0e72ac50e5a9cf19cc4e8e331dd0c54f5e69ca8758550f1e1e"}, + {file = "matplotlib-3.9.2-cp312-cp312-win_amd64.whl", hash = "sha256:5413401594cfaff0052f9d8b1aafc6d305b4bd7c4331dccd18f561ff7e1d3bd3"}, + {file = "matplotlib-3.9.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:18128cc08f0d3cfff10b76baa2f296fc28c4607368a8402de61bb3f2eb33c7d9"}, + {file = "matplotlib-3.9.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:4876d7d40219e8ae8bb70f9263bcbe5714415acfdf781086601211335e24f8aa"}, + {file = "matplotlib-3.9.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6d9f07a80deab4bb0b82858a9e9ad53d1382fd122be8cde11080f4e7dfedb38b"}, + {file = "matplotlib-3.9.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f7c0410f181a531ec4e93bbc27692f2c71a15c2da16766f5ba9761e7ae518413"}, + {file = "matplotlib-3.9.2-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:909645cce2dc28b735674ce0931a4ac94e12f5b13f6bb0b5a5e65e7cea2c192b"}, + {file = "matplotlib-3.9.2-cp313-cp313-win_amd64.whl", hash = "sha256:f32c7410c7f246838a77d6d1eff0c0f87f3cb0e7c4247aebea71a6d5a68cab49"}, + {file = "matplotlib-3.9.2-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:37e51dd1c2db16ede9cfd7b5cabdfc818b2c6397c83f8b10e0e797501c963a03"}, + {file = "matplotlib-3.9.2-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:b82c5045cebcecd8496a4d694d43f9cc84aeeb49fe2133e036b207abe73f4d30"}, + {file = "matplotlib-3.9.2-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f053c40f94bc51bc03832a41b4f153d83f2062d88c72b5e79997072594e97e51"}, + {file = "matplotlib-3.9.2-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dbe196377a8248972f5cede786d4c5508ed5f5ca4a1e09b44bda889958b33f8c"}, + {file = "matplotlib-3.9.2-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:5816b1e1fe8c192cbc013f8f3e3368ac56fbecf02fb41b8f8559303f24c5015e"}, + {file = "matplotlib-3.9.2-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:cef2a73d06601437be399908cf13aee74e86932a5ccc6ccdf173408ebc5f6bb2"}, + {file = "matplotlib-3.9.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e0830e188029c14e891fadd99702fd90d317df294c3298aad682739c5533721a"}, + {file = "matplotlib-3.9.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:03ba9c1299c920964e8d3857ba27173b4dbb51ca4bab47ffc2c2ba0eb5e2cbc5"}, + {file = "matplotlib-3.9.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1cd93b91ab47a3616b4d3c42b52f8363b88ca021e340804c6ab2536344fad9ca"}, + {file = "matplotlib-3.9.2-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:6d1ce5ed2aefcdce11904fc5bbea7d9c21fff3d5f543841edf3dea84451a09ea"}, + {file = "matplotlib-3.9.2-cp39-cp39-win_amd64.whl", hash = "sha256:b2696efdc08648536efd4e1601b5fd491fd47f4db97a5fbfd175549a7365c1b2"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:d52a3b618cb1cbb769ce2ee1dcdb333c3ab6e823944e9a2d36e37253815f9556"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:039082812cacd6c6bec8e17a9c1e6baca230d4116d522e81e1f63a74d01d2e21"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6758baae2ed64f2331d4fd19be38b7b4eae3ecec210049a26b6a4f3ae1c85dcc"}, + {file = "matplotlib-3.9.2-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:050598c2b29e0b9832cde72bcf97627bf00262adbc4a54e2b856426bb2ef0697"}, + {file = "matplotlib-3.9.2.tar.gz", hash = "sha256:96ab43906269ca64a6366934106fa01534454a69e471b7bf3d79083981aaab92"}, +] + +[package.dependencies] +contourpy = ">=1.0.1" +cycler = ">=0.10" +fonttools = ">=4.22.0" +kiwisolver = ">=1.3.1" +numpy = ">=1.23" +packaging = ">=20.0" +pillow = ">=8" +pyparsing = ">=2.3.1" +python-dateutil = ">=2.7" + +[package.extras] +dev = ["meson-python (>=0.13.1)", "numpy (>=1.25)", "pybind11 (>=2.6)", "setuptools (>=64)", "setuptools_scm (>=7)"] + +[[package]] +name = "matplotlib-inline" +version = "0.1.7" +description = "Inline Matplotlib backend for Jupyter" +optional = true +python-versions = ">=3.8" +files = [ + {file = "matplotlib_inline-0.1.7-py3-none-any.whl", hash = "sha256:df192d39a4ff8f21b1895d72e6a13f5fcc5099f00fa84384e0ea28c2cc0653ca"}, + {file = "matplotlib_inline-0.1.7.tar.gz", hash = "sha256:8423b23ec666be3d16e16b60bdd8ac4e86e840ebd1dd11a30b9f117f2fa0ab90"}, +] + +[package.dependencies] +traitlets = "*" + +[[package]] +name = "mdurl" +version = "0.1.2" +description = "Markdown URL utilities" +optional = true +python-versions = ">=3.7" +files = [ + {file = "mdurl-0.1.2-py3-none-any.whl", hash = "sha256:84008a41e51615a49fc9966191ff91509e3c40b939176e643fd50a5c2196b8f8"}, + {file = "mdurl-0.1.2.tar.gz", hash = "sha256:bb413d29f5eea38f31dd4754dd7377d4465116fb207585f97bf925588687c1ba"}, +] + +[[package]] +name = "meshio" +version = "5.3.5" +description = "I/O for many mesh formats" +optional = true +python-versions = ">=3.8" files = [ - {file = "mkl-2021.4.0-py2.py3-none-macosx_10_15_x86_64.macosx_11_0_x86_64.whl", hash = "sha256:67460f5cd7e30e405b54d70d1ed3ca78118370b65f7327d495e9c8847705e2fb"}, - {file = "mkl-2021.4.0-py2.py3-none-manylinux1_i686.whl", hash = "sha256:636d07d90e68ccc9630c654d47ce9fdeb036bb46e2b193b3a9ac8cfea683cce5"}, - {file = "mkl-2021.4.0-py2.py3-none-manylinux1_x86_64.whl", hash = "sha256:398dbf2b0d12acaf54117a5210e8f191827f373d362d796091d161f610c1ebfb"}, - {file = "mkl-2021.4.0-py2.py3-none-win32.whl", hash = "sha256:439c640b269a5668134e3dcbcea4350459c4a8bc46469669b2d67e07e3d330e8"}, - {file = "mkl-2021.4.0-py2.py3-none-win_amd64.whl", hash = "sha256:ceef3cafce4c009dd25f65d7ad0d833a0fbadc3d8903991ec92351fe5de1e718"}, + {file = "meshio-5.3.5-py3-none-any.whl", hash = "sha256:0736c6e34ecc768f62f2cde5d8233a3529512a9399b25c68ea2ca0d5900cdc10"}, + {file = "meshio-5.3.5.tar.gz", hash = "sha256:f21f01abd9f29ba06ea119304b3d39e610421cfe93b9dd23362834919f87586d"}, ] [package.dependencies] -intel-openmp = "==2021.*" -tbb = "==2021.*" +numpy = ">=1.20.0" +rich = "*" + +[package.extras] +all = ["h5py", "netCDF4"] + +[[package]] +name = "mistune" +version = "3.0.2" +description = "A sane and fast Markdown parser with useful plugins and renderers" +optional = true +python-versions = ">=3.7" +files = [ + {file = "mistune-3.0.2-py3-none-any.whl", hash = "sha256:71481854c30fdbc938963d3605b72501f5c10a9320ecd412c121c163a1c7d205"}, + {file = "mistune-3.0.2.tar.gz", hash = "sha256:fc7f93ded930c92394ef2cb6f04a8aabab4117a91449e72dcc8dfa646a508be8"}, +] [[package]] name = "mpmath" @@ -2017,103 +3558,108 @@ pyopengl = "*" [[package]] name = "multidict" -version = "6.0.5" +version = "6.1.0" description = "multidict implementation" optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "multidict-6.0.5-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:228b644ae063c10e7f324ab1ab6b548bdf6f8b47f3ec234fef1093bc2735e5f9"}, - {file = "multidict-6.0.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:896ebdcf62683551312c30e20614305f53125750803b614e9e6ce74a96232604"}, - {file = "multidict-6.0.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:411bf8515f3be9813d06004cac41ccf7d1cd46dfe233705933dd163b60e37600"}, - {file = "multidict-6.0.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1d147090048129ce3c453f0292e7697d333db95e52616b3793922945804a433c"}, - {file = "multidict-6.0.5-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:215ed703caf15f578dca76ee6f6b21b7603791ae090fbf1ef9d865571039ade5"}, - {file = "multidict-6.0.5-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c6390cf87ff6234643428991b7359b5f59cc15155695deb4eda5c777d2b880f"}, - {file = "multidict-6.0.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:21fd81c4ebdb4f214161be351eb5bcf385426bf023041da2fd9e60681f3cebae"}, - {file = "multidict-6.0.5-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3cc2ad10255f903656017363cd59436f2111443a76f996584d1077e43ee51182"}, - {file = "multidict-6.0.5-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:6939c95381e003f54cd4c5516740faba40cf5ad3eeff460c3ad1d3e0ea2549bf"}, - {file = "multidict-6.0.5-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:220dd781e3f7af2c2c1053da9fa96d9cf3072ca58f057f4c5adaaa1cab8fc442"}, - {file = "multidict-6.0.5-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:766c8f7511df26d9f11cd3a8be623e59cca73d44643abab3f8c8c07620524e4a"}, - {file = "multidict-6.0.5-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:fe5d7785250541f7f5019ab9cba2c71169dc7d74d0f45253f8313f436458a4ef"}, - {file = "multidict-6.0.5-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:c1c1496e73051918fcd4f58ff2e0f2f3066d1c76a0c6aeffd9b45d53243702cc"}, - {file = "multidict-6.0.5-cp310-cp310-win32.whl", hash = "sha256:7afcdd1fc07befad18ec4523a782cde4e93e0a2bf71239894b8d61ee578c1319"}, - {file = "multidict-6.0.5-cp310-cp310-win_amd64.whl", hash = "sha256:99f60d34c048c5c2fabc766108c103612344c46e35d4ed9ae0673d33c8fb26e8"}, - {file = "multidict-6.0.5-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f285e862d2f153a70586579c15c44656f888806ed0e5b56b64489afe4a2dbfba"}, - {file = "multidict-6.0.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:53689bb4e102200a4fafa9de9c7c3c212ab40a7ab2c8e474491914d2305f187e"}, - {file = "multidict-6.0.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:612d1156111ae11d14afaf3a0669ebf6c170dbb735e510a7438ffe2369a847fd"}, - {file = "multidict-6.0.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7be7047bd08accdb7487737631d25735c9a04327911de89ff1b26b81745bd4e3"}, - {file = "multidict-6.0.5-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:de170c7b4fe6859beb8926e84f7d7d6c693dfe8e27372ce3b76f01c46e489fcf"}, - {file = "multidict-6.0.5-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:04bde7a7b3de05732a4eb39c94574db1ec99abb56162d6c520ad26f83267de29"}, - {file = "multidict-6.0.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:85f67aed7bb647f93e7520633d8f51d3cbc6ab96957c71272b286b2f30dc70ed"}, - {file = "multidict-6.0.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:425bf820055005bfc8aa9a0b99ccb52cc2f4070153e34b701acc98d201693733"}, - {file = "multidict-6.0.5-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:d3eb1ceec286eba8220c26f3b0096cf189aea7057b6e7b7a2e60ed36b373b77f"}, - {file = "multidict-6.0.5-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:7901c05ead4b3fb75113fb1dd33eb1253c6d3ee37ce93305acd9d38e0b5f21a4"}, - {file = "multidict-6.0.5-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:e0e79d91e71b9867c73323a3444724d496c037e578a0e1755ae159ba14f4f3d1"}, - {file = "multidict-6.0.5-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:29bfeb0dff5cb5fdab2023a7a9947b3b4af63e9c47cae2a10ad58394b517fddc"}, - {file = "multidict-6.0.5-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e030047e85cbcedbfc073f71836d62dd5dadfbe7531cae27789ff66bc551bd5e"}, - {file = "multidict-6.0.5-cp311-cp311-win32.whl", hash = "sha256:2f4848aa3baa109e6ab81fe2006c77ed4d3cd1e0ac2c1fbddb7b1277c168788c"}, - {file = "multidict-6.0.5-cp311-cp311-win_amd64.whl", hash = "sha256:2faa5ae9376faba05f630d7e5e6be05be22913782b927b19d12b8145968a85ea"}, - {file = "multidict-6.0.5-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:51d035609b86722963404f711db441cf7134f1889107fb171a970c9701f92e1e"}, - {file = "multidict-6.0.5-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:cbebcd5bcaf1eaf302617c114aa67569dd3f090dd0ce8ba9e35e9985b41ac35b"}, - {file = "multidict-6.0.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2ffc42c922dbfddb4a4c3b438eb056828719f07608af27d163191cb3e3aa6cc5"}, - {file = "multidict-6.0.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ceb3b7e6a0135e092de86110c5a74e46bda4bd4fbfeeb3a3bcec79c0f861e450"}, - {file = "multidict-6.0.5-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:79660376075cfd4b2c80f295528aa6beb2058fd289f4c9252f986751a4cd0496"}, - {file = "multidict-6.0.5-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e4428b29611e989719874670fd152b6625500ad6c686d464e99f5aaeeaca175a"}, - {file = "multidict-6.0.5-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d84a5c3a5f7ce6db1f999fb9438f686bc2e09d38143f2d93d8406ed2dd6b9226"}, - {file = "multidict-6.0.5-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:76c0de87358b192de7ea9649beb392f107dcad9ad27276324c24c91774ca5271"}, - {file = "multidict-6.0.5-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:79a6d2ba910adb2cbafc95dad936f8b9386e77c84c35bc0add315b856d7c3abb"}, - {file = "multidict-6.0.5-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:92d16a3e275e38293623ebf639c471d3e03bb20b8ebb845237e0d3664914caef"}, - {file = "multidict-6.0.5-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:fb616be3538599e797a2017cccca78e354c767165e8858ab5116813146041a24"}, - {file = "multidict-6.0.5-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:14c2976aa9038c2629efa2c148022ed5eb4cb939e15ec7aace7ca932f48f9ba6"}, - {file = "multidict-6.0.5-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:435a0984199d81ca178b9ae2c26ec3d49692d20ee29bc4c11a2a8d4514c67eda"}, - {file = "multidict-6.0.5-cp312-cp312-win32.whl", hash = "sha256:9fe7b0653ba3d9d65cbe7698cca585bf0f8c83dbbcc710db9c90f478e175f2d5"}, - {file = "multidict-6.0.5-cp312-cp312-win_amd64.whl", hash = "sha256:01265f5e40f5a17f8241d52656ed27192be03bfa8764d88e8220141d1e4b3556"}, - {file = "multidict-6.0.5-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:19fe01cea168585ba0f678cad6f58133db2aa14eccaf22f88e4a6dccadfad8b3"}, - {file = "multidict-6.0.5-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6bf7a982604375a8d49b6cc1b781c1747f243d91b81035a9b43a2126c04766f5"}, - {file = "multidict-6.0.5-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:107c0cdefe028703fb5dafe640a409cb146d44a6ae201e55b35a4af8e95457dd"}, - {file = "multidict-6.0.5-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:403c0911cd5d5791605808b942c88a8155c2592e05332d2bf78f18697a5fa15e"}, - {file = "multidict-6.0.5-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:aeaf541ddbad8311a87dd695ed9642401131ea39ad7bc8cf3ef3967fd093b626"}, - {file = "multidict-6.0.5-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e4972624066095e52b569e02b5ca97dbd7a7ddd4294bf4e7247d52635630dd83"}, - {file = "multidict-6.0.5-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:d946b0a9eb8aaa590df1fe082cee553ceab173e6cb5b03239716338629c50c7a"}, - {file = "multidict-6.0.5-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:b55358304d7a73d7bdf5de62494aaf70bd33015831ffd98bc498b433dfe5b10c"}, - {file = "multidict-6.0.5-cp37-cp37m-musllinux_1_1_ppc64le.whl", hash = "sha256:a3145cb08d8625b2d3fee1b2d596a8766352979c9bffe5d7833e0503d0f0b5e5"}, - {file = "multidict-6.0.5-cp37-cp37m-musllinux_1_1_s390x.whl", hash = "sha256:d65f25da8e248202bd47445cec78e0025c0fe7582b23ec69c3b27a640dd7a8e3"}, - {file = "multidict-6.0.5-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:c9bf56195c6bbd293340ea82eafd0071cb3d450c703d2c93afb89f93b8386ccc"}, - {file = "multidict-6.0.5-cp37-cp37m-win32.whl", hash = "sha256:69db76c09796b313331bb7048229e3bee7928eb62bab5e071e9f7fcc4879caee"}, - {file = "multidict-6.0.5-cp37-cp37m-win_amd64.whl", hash = "sha256:fce28b3c8a81b6b36dfac9feb1de115bab619b3c13905b419ec71d03a3fc1423"}, - {file = "multidict-6.0.5-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:76f067f5121dcecf0d63a67f29080b26c43c71a98b10c701b0677e4a065fbd54"}, - {file = "multidict-6.0.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:b82cc8ace10ab5bd93235dfaab2021c70637005e1ac787031f4d1da63d493c1d"}, - {file = "multidict-6.0.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:5cb241881eefd96b46f89b1a056187ea8e9ba14ab88ba632e68d7a2ecb7aadf7"}, - {file = "multidict-6.0.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e8e94e6912639a02ce173341ff62cc1201232ab86b8a8fcc05572741a5dc7d93"}, - {file = "multidict-6.0.5-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:09a892e4a9fb47331da06948690ae38eaa2426de97b4ccbfafbdcbe5c8f37ff8"}, - {file = "multidict-6.0.5-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:55205d03e8a598cfc688c71ca8ea5f66447164efff8869517f175ea632c7cb7b"}, - {file = "multidict-6.0.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:37b15024f864916b4951adb95d3a80c9431299080341ab9544ed148091b53f50"}, - {file = "multidict-6.0.5-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f2a1dee728b52b33eebff5072817176c172050d44d67befd681609b4746e1c2e"}, - {file = "multidict-6.0.5-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:edd08e6f2f1a390bf137080507e44ccc086353c8e98c657e666c017718561b89"}, - {file = "multidict-6.0.5-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:60d698e8179a42ec85172d12f50b1668254628425a6bd611aba022257cac1386"}, - {file = "multidict-6.0.5-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:3d25f19500588cbc47dc19081d78131c32637c25804df8414463ec908631e453"}, - {file = "multidict-6.0.5-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:4cc0ef8b962ac7a5e62b9e826bd0cd5040e7d401bc45a6835910ed699037a461"}, - {file = "multidict-6.0.5-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:eca2e9d0cc5a889850e9bbd68e98314ada174ff6ccd1129500103df7a94a7a44"}, - {file = "multidict-6.0.5-cp38-cp38-win32.whl", hash = "sha256:4a6a4f196f08c58c59e0b8ef8ec441d12aee4125a7d4f4fef000ccb22f8d7241"}, - {file = "multidict-6.0.5-cp38-cp38-win_amd64.whl", hash = "sha256:0275e35209c27a3f7951e1ce7aaf93ce0d163b28948444bec61dd7badc6d3f8c"}, - {file = "multidict-6.0.5-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:e7be68734bd8c9a513f2b0cfd508802d6609da068f40dc57d4e3494cefc92929"}, - {file = "multidict-6.0.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:1d9ea7a7e779d7a3561aade7d596649fbecfa5c08a7674b11b423783217933f9"}, - {file = "multidict-6.0.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:ea1456df2a27c73ce51120fa2f519f1bea2f4a03a917f4a43c8707cf4cbbae1a"}, - {file = "multidict-6.0.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf590b134eb70629e350691ecca88eac3e3b8b3c86992042fb82e3cb1830d5e1"}, - {file = "multidict-6.0.5-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5c0631926c4f58e9a5ccce555ad7747d9a9f8b10619621f22f9635f069f6233e"}, - {file = "multidict-6.0.5-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:dce1c6912ab9ff5f179eaf6efe7365c1f425ed690b03341911bf4939ef2f3046"}, - {file = "multidict-6.0.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c0868d64af83169e4d4152ec612637a543f7a336e4a307b119e98042e852ad9c"}, - {file = "multidict-6.0.5-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:141b43360bfd3bdd75f15ed811850763555a251e38b2405967f8e25fb43f7d40"}, - {file = "multidict-6.0.5-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:7df704ca8cf4a073334e0427ae2345323613e4df18cc224f647f251e5e75a527"}, - {file = "multidict-6.0.5-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:6214c5a5571802c33f80e6c84713b2c79e024995b9c5897f794b43e714daeec9"}, - {file = "multidict-6.0.5-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:cd6c8fca38178e12c00418de737aef1261576bd1b6e8c6134d3e729a4e858b38"}, - {file = "multidict-6.0.5-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:e02021f87a5b6932fa6ce916ca004c4d441509d33bbdbeca70d05dff5e9d2479"}, - {file = "multidict-6.0.5-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:ebd8d160f91a764652d3e51ce0d2956b38efe37c9231cd82cfc0bed2e40b581c"}, - {file = "multidict-6.0.5-cp39-cp39-win32.whl", hash = "sha256:04da1bb8c8dbadf2a18a452639771951c662c5ad03aefe4884775454be322c9b"}, - {file = "multidict-6.0.5-cp39-cp39-win_amd64.whl", hash = "sha256:d6f6d4f185481c9669b9447bf9d9cf3b95a0e9df9d169bbc17e363b7d5487755"}, - {file = "multidict-6.0.5-py3-none-any.whl", hash = "sha256:0d63c74e3d7ab26de115c49bffc92cc77ed23395303d496eae515d4204a625e7"}, - {file = "multidict-6.0.5.tar.gz", hash = "sha256:f7e301075edaf50500f0b341543c41194d8df3ae5caf4702f2095f3ca73dd8da"}, + {file = "multidict-6.1.0-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:3380252550e372e8511d49481bd836264c009adb826b23fefcc5dd3c69692f60"}, + {file = "multidict-6.1.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:99f826cbf970077383d7de805c0681799491cb939c25450b9b5b3ced03ca99f1"}, + {file = "multidict-6.1.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:a114d03b938376557927ab23f1e950827c3b893ccb94b62fd95d430fd0e5cf53"}, + {file = "multidict-6.1.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b1c416351ee6271b2f49b56ad7f308072f6f44b37118d69c2cad94f3fa8a40d5"}, + {file = "multidict-6.1.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:6b5d83030255983181005e6cfbac1617ce9746b219bc2aad52201ad121226581"}, + {file = "multidict-6.1.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:3e97b5e938051226dc025ec80980c285b053ffb1e25a3db2a3aa3bc046bf7f56"}, + {file = "multidict-6.1.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d618649d4e70ac6efcbba75be98b26ef5078faad23592f9b51ca492953012429"}, + {file = "multidict-6.1.0-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:10524ebd769727ac77ef2278390fb0068d83f3acb7773792a5080f2b0abf7748"}, + {file = "multidict-6.1.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:ff3827aef427c89a25cc96ded1759271a93603aba9fb977a6d264648ebf989db"}, + {file = "multidict-6.1.0-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:06809f4f0f7ab7ea2cabf9caca7d79c22c0758b58a71f9d32943ae13c7ace056"}, + {file = "multidict-6.1.0-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:f179dee3b863ab1c59580ff60f9d99f632f34ccb38bf67a33ec6b3ecadd0fd76"}, + {file = "multidict-6.1.0-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:aaed8b0562be4a0876ee3b6946f6869b7bcdb571a5d1496683505944e268b160"}, + {file = "multidict-6.1.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:3c8b88a2ccf5493b6c8da9076fb151ba106960a2df90c2633f342f120751a9e7"}, + {file = "multidict-6.1.0-cp310-cp310-win32.whl", hash = "sha256:4a9cb68166a34117d6646c0023c7b759bf197bee5ad4272f420a0141d7eb03a0"}, + {file = "multidict-6.1.0-cp310-cp310-win_amd64.whl", hash = "sha256:20b9b5fbe0b88d0bdef2012ef7dee867f874b72528cf1d08f1d59b0e3850129d"}, + {file = "multidict-6.1.0-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:3efe2c2cb5763f2f1b275ad2bf7a287d3f7ebbef35648a9726e3b69284a4f3d6"}, + {file = "multidict-6.1.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c7053d3b0353a8b9de430a4f4b4268ac9a4fb3481af37dfe49825bf45ca24156"}, + {file = "multidict-6.1.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:27e5fc84ccef8dfaabb09d82b7d179c7cf1a3fbc8a966f8274fcb4ab2eb4cadb"}, + {file = "multidict-6.1.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0e2b90b43e696f25c62656389d32236e049568b39320e2735d51f08fd362761b"}, + {file = "multidict-6.1.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d83a047959d38a7ff552ff94be767b7fd79b831ad1cd9920662db05fec24fe72"}, + {file = "multidict-6.1.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d1a9dd711d0877a1ece3d2e4fea11a8e75741ca21954c919406b44e7cf971304"}, + {file = "multidict-6.1.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec2abea24d98246b94913b76a125e855eb5c434f7c46546046372fe60f666351"}, + {file = "multidict-6.1.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4867cafcbc6585e4b678876c489b9273b13e9fff9f6d6d66add5e15d11d926cb"}, + {file = "multidict-6.1.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:5b48204e8d955c47c55b72779802b219a39acc3ee3d0116d5080c388970b76e3"}, + {file = "multidict-6.1.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:d8fff389528cad1618fb4b26b95550327495462cd745d879a8c7c2115248e399"}, + {file = "multidict-6.1.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:a7a9541cd308eed5e30318430a9c74d2132e9a8cb46b901326272d780bf2d423"}, + {file = "multidict-6.1.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:da1758c76f50c39a2efd5e9859ce7d776317eb1dd34317c8152ac9251fc574a3"}, + {file = "multidict-6.1.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:c943a53e9186688b45b323602298ab727d8865d8c9ee0b17f8d62d14b56f0753"}, + {file = "multidict-6.1.0-cp311-cp311-win32.whl", hash = "sha256:90f8717cb649eea3504091e640a1b8568faad18bd4b9fcd692853a04475a4b80"}, + {file = "multidict-6.1.0-cp311-cp311-win_amd64.whl", hash = "sha256:82176036e65644a6cc5bd619f65f6f19781e8ec2e5330f51aa9ada7504cc1926"}, + {file = "multidict-6.1.0-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:b04772ed465fa3cc947db808fa306d79b43e896beb677a56fb2347ca1a49c1fa"}, + {file = "multidict-6.1.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:6180c0ae073bddeb5a97a38c03f30c233e0a4d39cd86166251617d1bbd0af436"}, + {file = "multidict-6.1.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:071120490b47aa997cca00666923a83f02c7fbb44f71cf7f136df753f7fa8761"}, + {file = "multidict-6.1.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:50b3a2710631848991d0bf7de077502e8994c804bb805aeb2925a981de58ec2e"}, + {file = "multidict-6.1.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b58c621844d55e71c1b7f7c498ce5aa6985d743a1a59034c57a905b3f153c1ef"}, + {file = "multidict-6.1.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:55b6d90641869892caa9ca42ff913f7ff1c5ece06474fbd32fb2cf6834726c95"}, + {file = "multidict-6.1.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4b820514bfc0b98a30e3d85462084779900347e4d49267f747ff54060cc33925"}, + {file = "multidict-6.1.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:10a9b09aba0c5b48c53761b7c720aaaf7cf236d5fe394cd399c7ba662d5f9966"}, + {file = "multidict-6.1.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:1e16bf3e5fc9f44632affb159d30a437bfe286ce9e02754759be5536b169b305"}, + {file = "multidict-6.1.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:76f364861c3bfc98cbbcbd402d83454ed9e01a5224bb3a28bf70002a230f73e2"}, + {file = "multidict-6.1.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:820c661588bd01a0aa62a1283f20d2be4281b086f80dad9e955e690c75fb54a2"}, + {file = "multidict-6.1.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:0e5f362e895bc5b9e67fe6e4ded2492d8124bdf817827f33c5b46c2fe3ffaca6"}, + {file = "multidict-6.1.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:3ec660d19bbc671e3a6443325f07263be452c453ac9e512f5eb935e7d4ac28b3"}, + {file = "multidict-6.1.0-cp312-cp312-win32.whl", hash = "sha256:58130ecf8f7b8112cdb841486404f1282b9c86ccb30d3519faf301b2e5659133"}, + {file = "multidict-6.1.0-cp312-cp312-win_amd64.whl", hash = "sha256:188215fc0aafb8e03341995e7c4797860181562380f81ed0a87ff455b70bf1f1"}, + {file = "multidict-6.1.0-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:d569388c381b24671589335a3be6e1d45546c2988c2ebe30fdcada8457a31008"}, + {file = "multidict-6.1.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:052e10d2d37810b99cc170b785945421141bf7bb7d2f8799d431e7db229c385f"}, + {file = "multidict-6.1.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:f90c822a402cb865e396a504f9fc8173ef34212a342d92e362ca498cad308e28"}, + {file = "multidict-6.1.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b225d95519a5bf73860323e633a664b0d85ad3d5bede6d30d95b35d4dfe8805b"}, + {file = "multidict-6.1.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:23bfd518810af7de1116313ebd9092cb9aa629beb12f6ed631ad53356ed6b86c"}, + {file = "multidict-6.1.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5c09fcfdccdd0b57867577b719c69e347a436b86cd83747f179dbf0cc0d4c1f3"}, + {file = "multidict-6.1.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bf6bea52ec97e95560af5ae576bdac3aa3aae0b6758c6efa115236d9e07dae44"}, + {file = "multidict-6.1.0-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:57feec87371dbb3520da6192213c7d6fc892d5589a93db548331954de8248fd2"}, + {file = "multidict-6.1.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:0c3f390dc53279cbc8ba976e5f8035eab997829066756d811616b652b00a23a3"}, + {file = "multidict-6.1.0-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:59bfeae4b25ec05b34f1956eaa1cb38032282cd4dfabc5056d0a1ec4d696d3aa"}, + {file = "multidict-6.1.0-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:b2f59caeaf7632cc633b5cf6fc449372b83bbdf0da4ae04d5be36118e46cc0aa"}, + {file = "multidict-6.1.0-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:37bb93b2178e02b7b618893990941900fd25b6b9ac0fa49931a40aecdf083fe4"}, + {file = "multidict-6.1.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:4e9f48f58c2c523d5a06faea47866cd35b32655c46b443f163d08c6d0ddb17d6"}, + {file = "multidict-6.1.0-cp313-cp313-win32.whl", hash = "sha256:3a37ffb35399029b45c6cc33640a92bef403c9fd388acce75cdc88f58bd19a81"}, + {file = "multidict-6.1.0-cp313-cp313-win_amd64.whl", hash = "sha256:e9aa71e15d9d9beaad2c6b9319edcdc0a49a43ef5c0a4c8265ca9ee7d6c67774"}, + {file = "multidict-6.1.0-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:db7457bac39421addd0c8449933ac32d8042aae84a14911a757ae6ca3eef1392"}, + {file = "multidict-6.1.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:d094ddec350a2fb899fec68d8353c78233debde9b7d8b4beeafa70825f1c281a"}, + {file = "multidict-6.1.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:5845c1fd4866bb5dd3125d89b90e57ed3138241540897de748cdf19de8a2fca2"}, + {file = "multidict-6.1.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9079dfc6a70abe341f521f78405b8949f96db48da98aeb43f9907f342f627cdc"}, + {file = "multidict-6.1.0-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3914f5aaa0f36d5d60e8ece6a308ee1c9784cd75ec8151062614657a114c4478"}, + {file = "multidict-6.1.0-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:c08be4f460903e5a9d0f76818db3250f12e9c344e79314d1d570fc69d7f4eae4"}, + {file = "multidict-6.1.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d093be959277cb7dee84b801eb1af388b6ad3ca6a6b6bf1ed7585895789d027d"}, + {file = "multidict-6.1.0-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3702ea6872c5a2a4eeefa6ffd36b042e9773f05b1f37ae3ef7264b1163c2dcf6"}, + {file = "multidict-6.1.0-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:2090f6a85cafc5b2db085124d752757c9d251548cedabe9bd31afe6363e0aff2"}, + {file = "multidict-6.1.0-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:f67f217af4b1ff66c68a87318012de788dd95fcfeb24cc889011f4e1c7454dfd"}, + {file = "multidict-6.1.0-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:189f652a87e876098bbc67b4da1049afb5f5dfbaa310dd67c594b01c10388db6"}, + {file = "multidict-6.1.0-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:6bb5992037f7a9eff7991ebe4273ea7f51f1c1c511e6a2ce511d0e7bdb754492"}, + {file = "multidict-6.1.0-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:ac10f4c2b9e770c4e393876e35a7046879d195cd123b4f116d299d442b335bcd"}, + {file = "multidict-6.1.0-cp38-cp38-win32.whl", hash = "sha256:e27bbb6d14416713a8bd7aaa1313c0fc8d44ee48d74497a0ff4c3a1b6ccb5167"}, + {file = "multidict-6.1.0-cp38-cp38-win_amd64.whl", hash = "sha256:22f3105d4fb15c8f57ff3959a58fcab6ce36814486500cd7485651230ad4d4ef"}, + {file = "multidict-6.1.0-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:4e18b656c5e844539d506a0a06432274d7bd52a7487e6828c63a63d69185626c"}, + {file = "multidict-6.1.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:a185f876e69897a6f3325c3f19f26a297fa058c5e456bfcff8015e9a27e83ae1"}, + {file = "multidict-6.1.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:ab7c4ceb38d91570a650dba194e1ca87c2b543488fe9309b4212694174fd539c"}, + {file = "multidict-6.1.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e617fb6b0b6953fffd762669610c1c4ffd05632c138d61ac7e14ad187870669c"}, + {file = "multidict-6.1.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:16e5f4bf4e603eb1fdd5d8180f1a25f30056f22e55ce51fb3d6ad4ab29f7d96f"}, + {file = "multidict-6.1.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f4c035da3f544b1882bac24115f3e2e8760f10a0107614fc9839fd232200b875"}, + {file = "multidict-6.1.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:957cf8e4b6e123a9eea554fa7ebc85674674b713551de587eb318a2df3e00255"}, + {file = "multidict-6.1.0-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:483a6aea59cb89904e1ceabd2b47368b5600fb7de78a6e4a2c2987b2d256cf30"}, + {file = "multidict-6.1.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:87701f25a2352e5bf7454caa64757642734da9f6b11384c1f9d1a8e699758057"}, + {file = "multidict-6.1.0-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:682b987361e5fd7a139ed565e30d81fd81e9629acc7d925a205366877d8c8657"}, + {file = "multidict-6.1.0-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:ce2186a7df133a9c895dea3331ddc5ddad42cdd0d1ea2f0a51e5d161e4762f28"}, + {file = "multidict-6.1.0-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:9f636b730f7e8cb19feb87094949ba54ee5357440b9658b2a32a5ce4bce53972"}, + {file = "multidict-6.1.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:73eae06aa53af2ea5270cc066dcaf02cc60d2994bbb2c4ef5764949257d10f43"}, + {file = "multidict-6.1.0-cp39-cp39-win32.whl", hash = "sha256:1ca0083e80e791cffc6efce7660ad24af66c8d4079d2a750b29001b53ff59ada"}, + {file = "multidict-6.1.0-cp39-cp39-win_amd64.whl", hash = "sha256:aa466da5b15ccea564bdab9c89175c762bc12825f4659c11227f515cee76fa4a"}, + {file = "multidict-6.1.0-py3-none-any.whl", hash = "sha256:48e171e52d1c4d33888e529b999e5900356b9ae588c2f09a52dcefb158b27506"}, + {file = "multidict-6.1.0.tar.gz", hash = "sha256:22ae2ebf9b0c69d206c003e2f6a914ea33f0a932d4aa16f236afc049d9958f4a"}, ] +[package.dependencies] +typing-extensions = {version = ">=4.1.0", markers = "python_version < \"3.11\""} + [[package]] name = "multiprocess" version = "0.70.16" @@ -2135,8 +3681,99 @@ files = [ {file = "multiprocess-0.70.16.tar.gz", hash = "sha256:161af703d4652a0e1410be6abccecde4a7ddffd19341be0a7011b94aeb171ac1"}, ] -[package.dependencies] -dill = ">=0.3.8" +[package.dependencies] +dill = ">=0.3.8" + +[[package]] +name = "nbclient" +version = "0.10.0" +description = "A client library for executing notebooks. Formerly nbconvert's ExecutePreprocessor." +optional = true +python-versions = ">=3.8.0" +files = [ + {file = "nbclient-0.10.0-py3-none-any.whl", hash = "sha256:f13e3529332a1f1f81d82a53210322476a168bb7090a0289c795fe9cc11c9d3f"}, + {file = "nbclient-0.10.0.tar.gz", hash = "sha256:4b3f1b7dba531e498449c4db4f53da339c91d449dc11e9af3a43b4eb5c5abb09"}, +] + +[package.dependencies] +jupyter-client = ">=6.1.12" +jupyter-core = ">=4.12,<5.0.dev0 || >=5.1.dev0" +nbformat = ">=5.1" +traitlets = ">=5.4" + +[package.extras] +dev = ["pre-commit"] +docs = ["autodoc-traits", "mock", "moto", "myst-parser", "nbclient[test]", "sphinx (>=1.7)", "sphinx-book-theme", "sphinxcontrib-spelling"] +test = ["flaky", "ipykernel (>=6.19.3)", "ipython", "ipywidgets", "nbconvert (>=7.0.0)", "pytest (>=7.0,<8)", "pytest-asyncio", "pytest-cov (>=4.0)", "testpath", "xmltodict"] + +[[package]] +name = "nbconvert" +version = "7.16.4" +description = "Converting Jupyter Notebooks (.ipynb files) to other formats. Output formats include asciidoc, html, latex, markdown, pdf, py, rst, script. nbconvert can be used both as a Python library (`import nbconvert`) or as a command line tool (invoked as `jupyter nbconvert ...`)." +optional = true +python-versions = ">=3.8" +files = [ + {file = "nbconvert-7.16.4-py3-none-any.whl", hash = "sha256:05873c620fe520b6322bf8a5ad562692343fe3452abda5765c7a34b7d1aa3eb3"}, + {file = "nbconvert-7.16.4.tar.gz", hash = "sha256:86ca91ba266b0a448dc96fa6c5b9d98affabde2867b363258703536807f9f7f4"}, +] + +[package.dependencies] +beautifulsoup4 = "*" +bleach = "!=5.0.0" +defusedxml = "*" +jinja2 = ">=3.0" +jupyter-core = ">=4.7" +jupyterlab-pygments = "*" +markupsafe = ">=2.0" +mistune = ">=2.0.3,<4" +nbclient = ">=0.5.0" +nbformat = ">=5.7" +packaging = "*" +pandocfilters = ">=1.4.1" +pygments = ">=2.4.1" +tinycss2 = "*" +traitlets = ">=5.1" + +[package.extras] +all = ["flaky", "ipykernel", "ipython", "ipywidgets (>=7.5)", "myst-parser", "nbsphinx (>=0.2.12)", "playwright", "pydata-sphinx-theme", "pyqtwebengine (>=5.15)", "pytest (>=7)", "sphinx (==5.0.2)", "sphinxcontrib-spelling", "tornado (>=6.1)"] +docs = ["ipykernel", "ipython", "myst-parser", "nbsphinx (>=0.2.12)", "pydata-sphinx-theme", "sphinx (==5.0.2)", "sphinxcontrib-spelling"] +qtpdf = ["pyqtwebengine (>=5.15)"] +qtpng = ["pyqtwebengine (>=5.15)"] +serve = ["tornado (>=6.1)"] +test = ["flaky", "ipykernel", "ipywidgets (>=7.5)", "pytest (>=7)"] +webpdf = ["playwright"] + +[[package]] +name = "nbformat" +version = "5.10.4" +description = "The Jupyter Notebook format" +optional = true +python-versions = ">=3.8" +files = [ + {file = "nbformat-5.10.4-py3-none-any.whl", hash = "sha256:3b48d6c8fbca4b299bf3982ea7db1af21580e4fec269ad087b9e81588891200b"}, + {file = "nbformat-5.10.4.tar.gz", hash = "sha256:322168b14f937a5d11362988ecac2a4952d3d8e3a2cbeb2319584631226d5b3a"}, +] + +[package.dependencies] +fastjsonschema = ">=2.15" +jsonschema = ">=2.6" +jupyter-core = ">=4.12,<5.0.dev0 || >=5.1.dev0" +traitlets = ">=5.1" + +[package.extras] +docs = ["myst-parser", "pydata-sphinx-theme", "sphinx", "sphinxcontrib-github-alt", "sphinxcontrib-spelling"] +test = ["pep440", "pre-commit", "pytest", "testpath"] + +[[package]] +name = "nest-asyncio" +version = "1.6.0" +description = "Patch asyncio to allow nested event loops" +optional = true +python-versions = ">=3.5" +files = [ + {file = "nest_asyncio-1.6.0-py3-none-any.whl", hash = "sha256:87af6efd6b5e897c81050477ef65c62e2b2f35d51703cae01aff2905b1852e1c"}, + {file = "nest_asyncio-1.6.0.tar.gz", hash = "sha256:6f172d5449aca15afd6c646851f4e31e02c598d553a667e38cafa997cfec55fe"}, +] [[package]] name = "networkx" @@ -2167,6 +3804,58 @@ files = [ {file = "nodeenv-1.9.1.tar.gz", hash = "sha256:6ec12890a2dab7946721edbfbcd91f3319c6ccc9aec47be7c7e6b7011ee6645f"}, ] +[[package]] +name = "nose" +version = "1.3.7" +description = "nose extends unittest to make testing easier" +optional = true +python-versions = "*" +files = [ + {file = "nose-1.3.7-py2-none-any.whl", hash = "sha256:dadcddc0aefbf99eea214e0f1232b94f2fa9bd98fa8353711dacb112bfcbbb2a"}, + {file = "nose-1.3.7-py3-none-any.whl", hash = "sha256:9ff7c6cc443f8c51994b34a667bbcf45afd6d945be7477b52e97516fd17c53ac"}, + {file = "nose-1.3.7.tar.gz", hash = "sha256:f1bffef9cbc82628f6e7d7b40d7e255aefaa1adb6a1b1d26c69a8b79e6208a98"}, +] + +[[package]] +name = "notebook" +version = "7.2.2" +description = "Jupyter Notebook - A web-based notebook environment for interactive computing" +optional = true +python-versions = ">=3.8" +files = [ + {file = "notebook-7.2.2-py3-none-any.whl", hash = "sha256:c89264081f671bc02eec0ed470a627ed791b9156cad9285226b31611d3e9fe1c"}, + {file = "notebook-7.2.2.tar.gz", hash = "sha256:2ef07d4220421623ad3fe88118d687bc0450055570cdd160814a59cf3a1c516e"}, +] + +[package.dependencies] +jupyter-server = ">=2.4.0,<3" +jupyterlab = ">=4.2.0,<4.3" +jupyterlab-server = ">=2.27.1,<3" +notebook-shim = ">=0.2,<0.3" +tornado = ">=6.2.0" + +[package.extras] +dev = ["hatch", "pre-commit"] +docs = ["myst-parser", "nbsphinx", "pydata-sphinx-theme", "sphinx (>=1.3.6)", "sphinxcontrib-github-alt", "sphinxcontrib-spelling"] +test = ["importlib-resources (>=5.0)", "ipykernel", "jupyter-server[test] (>=2.4.0,<3)", "jupyterlab-server[test] (>=2.27.1,<3)", "nbval", "pytest (>=7.0)", "pytest-console-scripts", "pytest-timeout", "pytest-tornasync", "requests"] + +[[package]] +name = "notebook-shim" +version = "0.2.4" +description = "A shim layer for notebook traits and config" +optional = true +python-versions = ">=3.7" +files = [ + {file = "notebook_shim-0.2.4-py3-none-any.whl", hash = "sha256:411a5be4e9dc882a074ccbcae671eda64cceb068767e9a3419096986560e1cef"}, + {file = "notebook_shim-0.2.4.tar.gz", hash = "sha256:b4b2cfa1b65d98307ca24361f5b30fe785b53c3fd07b7a47e89acb5e6ac638cb"}, +] + +[package.dependencies] +jupyter-server = ">=1.8,<3" + +[package.extras] +test = ["pytest", "pytest-console-scripts", "pytest-jupyter", "pytest-tornasync"] + [[package]] name = "numba" version = "0.60.0" @@ -2279,6 +3968,21 @@ files = [ {file = "numpy-1.26.4.tar.gz", hash = "sha256:2a02aba9ed12e4ac4eb3ea9421c420301a0c6460d9830d74a9df87efa4912010"}, ] +[[package]] +name = "numpy-stl" +version = "3.1.2" +description = "Library to make reading, writing and modifying both binary and ascii STL files easy." +optional = true +python-versions = ">3.6.0" +files = [ + {file = "numpy_stl-3.1.2-py3-none-any.whl", hash = "sha256:a55288340c837378bf44753a1c595c6823312995acda97f27ed04db4ff1d25f3"}, + {file = "numpy_stl-3.1.2.tar.gz", hash = "sha256:72b46950dfa3642df1c7b873cfa78a548533724b907478c567db42fdf57ee3d2"}, +] + +[package.dependencies] +numpy = "*" +python-utils = ">=3.4.5" + [[package]] name = "nvidia-cublas-cu12" version = "12.1.3.1" @@ -2325,12 +4029,13 @@ files = [ [[package]] name = "nvidia-cudnn-cu12" -version = "8.9.2.26" +version = "9.1.0.70" description = "cuDNN runtime libraries" optional = false python-versions = ">=3" files = [ - {file = "nvidia_cudnn_cu12-8.9.2.26-py3-none-manylinux1_x86_64.whl", hash = "sha256:5ccb288774fdfb07a7e7025ffec286971c06d8d7b4fb162525334616d7629ff9"}, + {file = "nvidia_cudnn_cu12-9.1.0.70-py3-none-manylinux2014_x86_64.whl", hash = "sha256:165764f44ef8c61fcdfdfdbe769d687e06374059fbb388b6c89ecb0e28793a6f"}, + {file = "nvidia_cudnn_cu12-9.1.0.70-py3-none-win_amd64.whl", hash = "sha256:6278562929433d68365a07a4a1546c237ba2849852c0d4b2262a486e805b977a"}, ] [package.dependencies] @@ -2401,13 +4106,14 @@ files = [ [[package]] name = "nvidia-nvjitlink-cu12" -version = "12.5.82" +version = "12.6.68" description = "Nvidia JIT LTO Library" optional = false python-versions = ">=3" files = [ - {file = "nvidia_nvjitlink_cu12-12.5.82-py3-none-manylinux2014_x86_64.whl", hash = "sha256:f9b37bc5c8cf7509665cb6ada5aaa0ce65618f2332b7d3e78e9790511f111212"}, - {file = "nvidia_nvjitlink_cu12-12.5.82-py3-none-win_amd64.whl", hash = "sha256:e782564d705ff0bf61ac3e1bf730166da66dd2fe9012f111ede5fc49b64ae697"}, + {file = "nvidia_nvjitlink_cu12-12.6.68-py3-none-manylinux2014_aarch64.whl", hash = "sha256:b3fd0779845f68b92063ab1393abab1ed0a23412fc520df79a8190d098b5cd6b"}, + {file = "nvidia_nvjitlink_cu12-12.6.68-py3-none-manylinux2014_x86_64.whl", hash = "sha256:125a6c2a44e96386dda634e13d944e60b07a0402d391a070e8fb4104b34ea1ab"}, + {file = "nvidia_nvjitlink_cu12-12.6.68-py3-none-win_amd64.whl", hash = "sha256:a55744c98d70317c5e23db14866a8cc2b733f7324509e941fc96276f9f37801d"}, ] [[package]] @@ -2436,6 +4142,66 @@ files = [ antlr4-python3-runtime = "==4.9.*" PyYAML = ">=5.1.0" +[[package]] +name = "open3d" +version = "0.18.0" +description = "Open3D: A Modern Library for 3D Data Processing." +optional = true +python-versions = ">=3.8" +files = [ + {file = "open3d-0.18.0-cp310-cp310-macosx_11_0_x86_64.whl", hash = "sha256:48ee627a142a5453c4a2869b529310acb6f6b2507989cb9199c56e75796c575e"}, + {file = "open3d-0.18.0-cp310-cp310-macosx_13_0_arm64.whl", hash = "sha256:9f3df5e8e8fe514b8285d05e43a4a3d57243d42d5c1dc9212adf8f18b6ab59b4"}, + {file = "open3d-0.18.0-cp310-cp310-manylinux_2_27_aarch64.whl", hash = "sha256:b9c8c8059cb92cd8b73c287385eeddf46195f2609ac7052302d6ac844a373dbf"}, + {file = "open3d-0.18.0-cp310-cp310-manylinux_2_27_x86_64.whl", hash = "sha256:f649d5d58090f73a337895fb0022c7b05c00f47f704b5722b103cceba04cc870"}, + {file = "open3d-0.18.0-cp310-cp310-win_amd64.whl", hash = "sha256:48cdf2af3051320140d198f5d3ea3a85eeb3355e7a989a835b611b16589b9646"}, + {file = "open3d-0.18.0-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:b35a68b9fef3e963266db3bb15fbfef20e05787bc61192f61725fde5215f3560"}, + {file = "open3d-0.18.0-cp311-cp311-macosx_13_0_arm64.whl", hash = "sha256:2182b818dcd3290dd2ddb0021ad0453bfda99098c931d5b2fc636a341cb3ca70"}, + {file = "open3d-0.18.0-cp311-cp311-manylinux_2_27_aarch64.whl", hash = "sha256:882f1e5039a3c1c5ec05183eb650537fd7431238b7ccb2b742ca5479f02f705b"}, + {file = "open3d-0.18.0-cp311-cp311-manylinux_2_27_x86_64.whl", hash = "sha256:8e3d1d1900a8f4d956f6819c246c78081725b9b0888f8549d2a7a49c8daa1303"}, + {file = "open3d-0.18.0-cp311-cp311-win_amd64.whl", hash = "sha256:2da5da6c9eb9227baee6fe98baa992233aca36b83ec9e7d4093c77e762db60e6"}, + {file = "open3d-0.18.0-cp38-cp38-macosx_11_0_x86_64.whl", hash = "sha256:877e67237f2a97f8219870108eecf1ff447a81b0fcf1d2eacea246c9619fc55c"}, + {file = "open3d-0.18.0-cp38-cp38-macosx_13_0_arm64.whl", hash = "sha256:0ec03fcd48a939ec105896e0d02a9d006e8328c60491a0647b9a4fe5d9e4117d"}, + {file = "open3d-0.18.0-cp38-cp38-manylinux_2_27_aarch64.whl", hash = "sha256:477ed692bafd0ed591676d78bcb898bb2b684dcaa2886befe29e1b19d38a7c6d"}, + {file = "open3d-0.18.0-cp38-cp38-manylinux_2_27_x86_64.whl", hash = "sha256:46b9c1b900716771827b78006cfd18489b5327eabda8cd3d01e028b8173f4301"}, + {file = "open3d-0.18.0-cp38-cp38-win_amd64.whl", hash = "sha256:d745affd0c7c765ed30ae9010abc4cfa80980b2c9f39a4f8678e8a9ef41ce089"}, + {file = "open3d-0.18.0-cp39-cp39-macosx_11_0_x86_64.whl", hash = "sha256:cce30304dfde3b9c0fbfca21687cf0e5280bcbabe2920d2c804ab352bfe610a5"}, + {file = "open3d-0.18.0-cp39-cp39-macosx_13_0_universal2.whl", hash = "sha256:ba5e07ca9a3ec6c70393bd2c5c707455a2e9c54209ccccca15ecf03834efd353"}, + {file = "open3d-0.18.0-cp39-cp39-manylinux_2_27_aarch64.whl", hash = "sha256:23a3bf135c7e69d4116f54b1ff78f58846245b5e70640b291981cee9e49a53d7"}, + {file = "open3d-0.18.0-cp39-cp39-manylinux_2_27_x86_64.whl", hash = "sha256:7d05fd6eedf75136cfbed24983da30bdfd08a6c4b1f968bf80ab84efc1fac861"}, + {file = "open3d-0.18.0-cp39-cp39-win_amd64.whl", hash = "sha256:41be2d652f1b9feed9efb8775b29368ece0b4328ba6e90278486ff7643c6d480"}, +] + +[package.dependencies] +configargparse = "*" +dash = ">=2.6.0" +nbformat = ">=5.7.0" +numpy = ">=1.18.0" +werkzeug = ">=2.2.3" + +[[package]] +name = "opencv-contrib-python" +version = "4.10.0.84" +description = "Wrapper package for OpenCV python bindings." +optional = true +python-versions = ">=3.6" +files = [ + {file = "opencv-contrib-python-4.10.0.84.tar.gz", hash = "sha256:4a3eae0ed9cadf1abe9293a6938a25a540e2fd6d7fc308595caa5896c8b36a0c"}, + {file = "opencv_contrib_python-4.10.0.84-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:ee4b0919026d8c533aeb69b16c6ec4a891a2f6844efaa14121bf68838753209c"}, + {file = "opencv_contrib_python-4.10.0.84-cp37-abi3-macosx_12_0_x86_64.whl", hash = "sha256:dea80d4db73b8acccf9e16b5744bf3654f47b22745074263f0a6c10de26c5ef5"}, + {file = "opencv_contrib_python-4.10.0.84-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:040575b69e4f3aa761676bace4e3d1b8485fbfaf77ef77b266ab6bda5a3b5e9b"}, + {file = "opencv_contrib_python-4.10.0.84-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a261223db41f6e512d76deaf21c8fcfb4fbbcbc2de62ca7f74a05f2c9ee489ef"}, + {file = "opencv_contrib_python-4.10.0.84-cp37-abi3-win32.whl", hash = "sha256:2a36257ec1375d1bec2a62177ea39828ff9804de6831ee39646bdc875c343cec"}, + {file = "opencv_contrib_python-4.10.0.84-cp37-abi3-win_amd64.whl", hash = "sha256:47ec3160dae75f70e099b286d1a2e086d20dac8b06e759f60eaf867e6bdecba7"}, +] + +[package.dependencies] +numpy = [ + {version = ">=1.21.4", markers = "python_version >= \"3.10\" and platform_system == \"Darwin\" and python_version < \"3.11\""}, + {version = ">=1.21.2", markers = "platform_system != \"Darwin\" and python_version >= \"3.10\" and python_version < \"3.11\""}, + {version = ">=1.23.5", markers = "python_version >= \"3.11\" and python_version < \"3.12\""}, + {version = ">=1.26.0", markers = "python_version >= \"3.12\""}, +] + [[package]] name = "opencv-python" version = "4.10.0.84" @@ -2461,18 +4227,26 @@ numpy = [ ] [[package]] -name = "ordered-set" -version = "4.1.0" -description = "An OrderedSet is a custom MutableSet that remembers its order, so that every" +name = "orderly-set" +version = "5.2.2" +description = "Orderly set" optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "ordered-set-4.1.0.tar.gz", hash = "sha256:694a8e44c87657c59292ede72891eb91d34131f6531463aab3009191c77364a8"}, - {file = "ordered_set-4.1.0-py3-none-any.whl", hash = "sha256:046e1132c71fcf3330438a539928932caf51ddbc582496833e23de611de14562"}, + {file = "orderly_set-5.2.2-py3-none-any.whl", hash = "sha256:f7a37c95a38c01cdfe41c3ffb62925a318a2286ea0a41790c057fc802aec54da"}, + {file = "orderly_set-5.2.2.tar.gz", hash = "sha256:52a18b86aaf3f5d5a498bbdb27bf3253a4e5c57ab38e5b7a56fa00115cd28448"}, ] -[package.extras] -dev = ["black", "mypy", "pytest"] +[[package]] +name = "overrides" +version = "7.7.0" +description = "A decorator to automatically detect mismatch when overriding a method." +optional = true +python-versions = ">=3.6" +files = [ + {file = "overrides-7.7.0-py3-none-any.whl", hash = "sha256:c7ed9d062f78b8e4c1a7b70bd8796b35ead4d9f510227ef9c5dc7626c60d7e49"}, + {file = "overrides-7.7.0.tar.gz", hash = "sha256:55158fa3d93b98cc75299b1e67078ad9003ca27945c76162c1c0766d6f91820a"}, +] [[package]] name = "packaging" @@ -2487,40 +4261,53 @@ files = [ [[package]] name = "pandas" -version = "2.2.2" +version = "2.2.3" description = "Powerful data structures for data analysis, time series, and statistics" optional = false python-versions = ">=3.9" files = [ - {file = "pandas-2.2.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:90c6fca2acf139569e74e8781709dccb6fe25940488755716d1d354d6bc58bce"}, - {file = "pandas-2.2.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c7adfc142dac335d8c1e0dcbd37eb8617eac386596eb9e1a1b77791cf2498238"}, - {file = "pandas-2.2.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4abfe0be0d7221be4f12552995e58723c7422c80a659da13ca382697de830c08"}, - {file = "pandas-2.2.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8635c16bf3d99040fdf3ca3db669a7250ddf49c55dc4aa8fe0ae0fa8d6dcc1f0"}, - {file = "pandas-2.2.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:40ae1dffb3967a52203105a077415a86044a2bea011b5f321c6aa64b379a3f51"}, - {file = "pandas-2.2.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:8e5a0b00e1e56a842f922e7fae8ae4077aee4af0acb5ae3622bd4b4c30aedf99"}, - {file = "pandas-2.2.2-cp310-cp310-win_amd64.whl", hash = "sha256:ddf818e4e6c7c6f4f7c8a12709696d193976b591cc7dc50588d3d1a6b5dc8772"}, - {file = "pandas-2.2.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:696039430f7a562b74fa45f540aca068ea85fa34c244d0deee539cb6d70aa288"}, - {file = "pandas-2.2.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:8e90497254aacacbc4ea6ae5e7a8cd75629d6ad2b30025a4a8b09aa4faf55151"}, - {file = "pandas-2.2.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:58b84b91b0b9f4bafac2a0ac55002280c094dfc6402402332c0913a59654ab2b"}, - {file = "pandas-2.2.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6d2123dc9ad6a814bcdea0f099885276b31b24f7edf40f6cdbc0912672e22eee"}, - {file = "pandas-2.2.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:2925720037f06e89af896c70bca73459d7e6a4be96f9de79e2d440bd499fe0db"}, - {file = "pandas-2.2.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:0cace394b6ea70c01ca1595f839cf193df35d1575986e484ad35c4aeae7266c1"}, - {file = "pandas-2.2.2-cp311-cp311-win_amd64.whl", hash = "sha256:873d13d177501a28b2756375d59816c365e42ed8417b41665f346289adc68d24"}, - {file = "pandas-2.2.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:9dfde2a0ddef507a631dc9dc4af6a9489d5e2e740e226ad426a05cabfbd7c8ef"}, - {file = "pandas-2.2.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:e9b79011ff7a0f4b1d6da6a61aa1aa604fb312d6647de5bad20013682d1429ce"}, - {file = "pandas-2.2.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1cb51fe389360f3b5a4d57dbd2848a5f033350336ca3b340d1c53a1fad33bcad"}, - {file = "pandas-2.2.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eee3a87076c0756de40b05c5e9a6069c035ba43e8dd71c379e68cab2c20f16ad"}, - {file = "pandas-2.2.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:3e374f59e440d4ab45ca2fffde54b81ac3834cf5ae2cdfa69c90bc03bde04d76"}, - {file = "pandas-2.2.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:43498c0bdb43d55cb162cdc8c06fac328ccb5d2eabe3cadeb3529ae6f0517c32"}, - {file = "pandas-2.2.2-cp312-cp312-win_amd64.whl", hash = "sha256:d187d355ecec3629624fccb01d104da7d7f391db0311145817525281e2804d23"}, - {file = "pandas-2.2.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:0ca6377b8fca51815f382bd0b697a0814c8bda55115678cbc94c30aacbb6eff2"}, - {file = "pandas-2.2.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:9057e6aa78a584bc93a13f0a9bf7e753a5e9770a30b4d758b8d5f2a62a9433cd"}, - {file = "pandas-2.2.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:001910ad31abc7bf06f49dcc903755d2f7f3a9186c0c040b827e522e9cef0863"}, - {file = "pandas-2.2.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:66b479b0bd07204e37583c191535505410daa8df638fd8e75ae1b383851fe921"}, - {file = "pandas-2.2.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:a77e9d1c386196879aa5eb712e77461aaee433e54c68cf253053a73b7e49c33a"}, - {file = "pandas-2.2.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:92fd6b027924a7e178ac202cfbe25e53368db90d56872d20ffae94b96c7acc57"}, - {file = "pandas-2.2.2-cp39-cp39-win_amd64.whl", hash = "sha256:640cef9aa381b60e296db324337a554aeeb883ead99dc8f6c18e81a93942f5f4"}, - {file = "pandas-2.2.2.tar.gz", hash = "sha256:9e79019aba43cb4fda9e4d983f8e88ca0373adbb697ae9c6c43093218de28b54"}, + {file = "pandas-2.2.3-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:1948ddde24197a0f7add2bdc4ca83bf2b1ef84a1bc8ccffd95eda17fd836ecb5"}, + {file = "pandas-2.2.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:381175499d3802cde0eabbaf6324cce0c4f5d52ca6f8c377c29ad442f50f6348"}, + {file = "pandas-2.2.3-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:d9c45366def9a3dd85a6454c0e7908f2b3b8e9c138f5dc38fed7ce720d8453ed"}, + {file = "pandas-2.2.3-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:86976a1c5b25ae3f8ccae3a5306e443569ee3c3faf444dfd0f41cda24667ad57"}, + {file = "pandas-2.2.3-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:b8661b0238a69d7aafe156b7fa86c44b881387509653fdf857bebc5e4008ad42"}, + {file = "pandas-2.2.3-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:37e0aced3e8f539eccf2e099f65cdb9c8aa85109b0be6e93e2baff94264bdc6f"}, + {file = "pandas-2.2.3-cp310-cp310-win_amd64.whl", hash = "sha256:56534ce0746a58afaf7942ba4863e0ef81c9c50d3f0ae93e9497d6a41a057645"}, + {file = "pandas-2.2.3-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:66108071e1b935240e74525006034333f98bcdb87ea116de573a6a0dccb6c039"}, + {file = "pandas-2.2.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7c2875855b0ff77b2a64a0365e24455d9990730d6431b9e0ee18ad8acee13dbd"}, + {file = "pandas-2.2.3-cp311-cp311-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:cd8d0c3be0515c12fed0bdbae072551c8b54b7192c7b1fda0ba56059a0179698"}, + {file = "pandas-2.2.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c124333816c3a9b03fbeef3a9f230ba9a737e9e5bb4060aa2107a86cc0a497fc"}, + {file = "pandas-2.2.3-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:63cc132e40a2e084cf01adf0775b15ac515ba905d7dcca47e9a251819c575ef3"}, + {file = "pandas-2.2.3-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:29401dbfa9ad77319367d36940cd8a0b3a11aba16063e39632d98b0e931ddf32"}, + {file = "pandas-2.2.3-cp311-cp311-win_amd64.whl", hash = "sha256:3fc6873a41186404dad67245896a6e440baacc92f5b716ccd1bc9ed2995ab2c5"}, + {file = "pandas-2.2.3-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:b1d432e8d08679a40e2a6d8b2f9770a5c21793a6f9f47fdd52c5ce1948a5a8a9"}, + {file = "pandas-2.2.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:a5a1595fe639f5988ba6a8e5bc9649af3baf26df3998a0abe56c02609392e0a4"}, + {file = "pandas-2.2.3-cp312-cp312-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:5de54125a92bb4d1c051c0659e6fcb75256bf799a732a87184e5ea503965bce3"}, + {file = "pandas-2.2.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fffb8ae78d8af97f849404f21411c95062db1496aeb3e56f146f0355c9989319"}, + {file = "pandas-2.2.3-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:6dfcb5ee8d4d50c06a51c2fffa6cff6272098ad6540aed1a76d15fb9318194d8"}, + {file = "pandas-2.2.3-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:062309c1b9ea12a50e8ce661145c6aab431b1e99530d3cd60640e255778bd43a"}, + {file = "pandas-2.2.3-cp312-cp312-win_amd64.whl", hash = "sha256:59ef3764d0fe818125a5097d2ae867ca3fa64df032331b7e0917cf5d7bf66b13"}, + {file = "pandas-2.2.3-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:f00d1345d84d8c86a63e476bb4955e46458b304b9575dcf71102b5c705320015"}, + {file = "pandas-2.2.3-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:3508d914817e153ad359d7e069d752cdd736a247c322d932eb89e6bc84217f28"}, + {file = "pandas-2.2.3-cp313-cp313-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:22a9d949bfc9a502d320aa04e5d02feab689d61da4e7764b62c30b991c42c5f0"}, + {file = "pandas-2.2.3-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f3a255b2c19987fbbe62a9dfd6cff7ff2aa9ccab3fc75218fd4b7530f01efa24"}, + {file = "pandas-2.2.3-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:800250ecdadb6d9c78eae4990da62743b857b470883fa27f652db8bdde7f6659"}, + {file = "pandas-2.2.3-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:6374c452ff3ec675a8f46fd9ab25c4ad0ba590b71cf0656f8b6daa5202bca3fb"}, + {file = "pandas-2.2.3-cp313-cp313-win_amd64.whl", hash = "sha256:61c5ad4043f791b61dd4752191d9f07f0ae412515d59ba8f005832a532f8736d"}, + {file = "pandas-2.2.3-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:3b71f27954685ee685317063bf13c7709a7ba74fc996b84fc6821c59b0f06468"}, + {file = "pandas-2.2.3-cp313-cp313t-macosx_11_0_arm64.whl", hash = "sha256:38cf8125c40dae9d5acc10fa66af8ea6fdf760b2714ee482ca691fc66e6fcb18"}, + {file = "pandas-2.2.3-cp313-cp313t-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:ba96630bc17c875161df3818780af30e43be9b166ce51c9a18c1feae342906c2"}, + {file = "pandas-2.2.3-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1db71525a1538b30142094edb9adc10be3f3e176748cd7acc2240c2f2e5aa3a4"}, + {file = "pandas-2.2.3-cp313-cp313t-musllinux_1_2_aarch64.whl", hash = "sha256:15c0e1e02e93116177d29ff83e8b1619c93ddc9c49083f237d4312337a61165d"}, + {file = "pandas-2.2.3-cp313-cp313t-musllinux_1_2_x86_64.whl", hash = "sha256:ad5b65698ab28ed8d7f18790a0dc58005c7629f227be9ecc1072aa74c0c1d43a"}, + {file = "pandas-2.2.3-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:bc6b93f9b966093cb0fd62ff1a7e4c09e6d546ad7c1de191767baffc57628f39"}, + {file = "pandas-2.2.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:5dbca4c1acd72e8eeef4753eeca07de9b1db4f398669d5994086f788a5d7cc30"}, + {file = "pandas-2.2.3-cp39-cp39-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:8cd6d7cc958a3910f934ea8dbdf17b2364827bb4dafc38ce6eef6bb3d65ff09c"}, + {file = "pandas-2.2.3-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:99df71520d25fade9db7c1076ac94eb994f4d2673ef2aa2e86ee039b6746d20c"}, + {file = "pandas-2.2.3-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:31d0ced62d4ea3e231a9f228366919a5ea0b07440d9d4dac345376fd8e1477ea"}, + {file = "pandas-2.2.3-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:7eee9e7cea6adf3e3d24e304ac6b8300646e2a5d1cd3a3c2abed9101b0846761"}, + {file = "pandas-2.2.3-cp39-cp39-win_amd64.whl", hash = "sha256:4850ba03528b6dd51d6c5d273c46f183f39a9baf3f0143e566b89450965b105e"}, + {file = "pandas-2.2.3.tar.gz", hash = "sha256:4f18ba62b61d7e192368b84517265a99b4d7ee8912f8708660fb4a366cc82667"}, ] [package.dependencies] @@ -2558,6 +4345,43 @@ sql-other = ["SQLAlchemy (>=2.0.0)", "adbc-driver-postgresql (>=0.8.0)", "adbc-d test = ["hypothesis (>=6.46.1)", "pytest (>=7.3.2)", "pytest-xdist (>=2.2.0)"] xml = ["lxml (>=4.9.2)"] +[[package]] +name = "pandocfilters" +version = "1.5.1" +description = "Utilities for writing pandoc filters in python" +optional = true +python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*" +files = [ + {file = "pandocfilters-1.5.1-py2.py3-none-any.whl", hash = "sha256:93be382804a9cdb0a7267585f157e5d1731bbe5545a85b268d6f5fe6232de2bc"}, + {file = "pandocfilters-1.5.1.tar.gz", hash = "sha256:002b4a555ee4ebc03f8b66307e287fa492e4a77b4ea14d3f934328297bb4939e"}, +] + +[[package]] +name = "parso" +version = "0.8.4" +description = "A Python Parser" +optional = true +python-versions = ">=3.6" +files = [ + {file = "parso-0.8.4-py2.py3-none-any.whl", hash = "sha256:a418670a20291dacd2dddc80c377c5c3791378ee1e8d12bffc35420643d43f18"}, + {file = "parso-0.8.4.tar.gz", hash = "sha256:eb3a7b58240fb99099a345571deecc0f9540ea5f4dd2fe14c2a99d6b281ab92d"}, +] + +[package.extras] +qa = ["flake8 (==5.0.4)", "mypy (==0.971)", "types-setuptools (==67.2.0.1)"] +testing = ["docopt", "pytest"] + +[[package]] +name = "pathlib" +version = "1.0.1" +description = "Object-oriented filesystem paths" +optional = true +python-versions = "*" +files = [ + {file = "pathlib-1.0.1-py3-none-any.whl", hash = "sha256:f35f95ab8b0f59e6d354090350b44a80a80635d22efdedfa84c7ad1cf0a74147"}, + {file = "pathlib-1.0.1.tar.gz", hash = "sha256:6940718dfc3eff4258203ad5021090933e5c04707d5ca8cc9e73c94a7894ea9f"}, +] + [[package]] name = "pettingzoo" version = "1.24.3" @@ -2583,6 +4407,20 @@ other = ["pillow (>=8.0.1)"] sisl = ["box2d-py (==2.3.5)", "pygame (==2.3.0)", "pymunk (==6.2.0)", "scipy (>=1.4.1)"] testing = ["AutoROM", "pre-commit", "pynput", "pytest", "pytest-cov", "pytest-markdown-docs", "pytest-xdist"] +[[package]] +name = "pexpect" +version = "4.9.0" +description = "Pexpect allows easy control of interactive console applications." +optional = true +python-versions = "*" +files = [ + {file = "pexpect-4.9.0-py2.py3-none-any.whl", hash = "sha256:7236d1e080e4936be2dc3e326cec0af72acf9212a7e1d060210e70a47e253523"}, + {file = "pexpect-4.9.0.tar.gz", hash = "sha256:ee7d41123f3c9911050ea2c2dac107568dc43b2d3b0c7557a33212c398ead30f"}, +] + +[package.dependencies] +ptyprocess = ">=0.5" + [[package]] name = "pfzy" version = "0.3.4" @@ -2694,21 +4532,51 @@ tests = ["check-manifest", "coverage", "defusedxml", "markdown2", "olefile", "pa typing = ["typing-extensions"] xmp = ["defusedxml"] +[[package]] +name = "pixel-ring" +version = "0.1.0" +description = "respeaker series pixel ring library" +optional = true +python-versions = "*" +files = [ + {file = "pixel-ring-0.1.0.tar.gz", hash = "sha256:9480f23b58ccb912321b989d00e9d31f087f7bbcd8d970fca0fb319853d03270"}, + {file = "pixel_ring-0.1.0-py2.py3-none-any.whl", hash = "sha256:c0fa51beb67be81b1f6ab058f651c489d69b47fb884d4361a0cf7594f093885b"}, +] + +[package.dependencies] +pyusb = "*" +spidev = "*" + [[package]] name = "platformdirs" -version = "4.2.2" +version = "4.3.6" description = "A small Python package for determining appropriate platform-specific dirs, e.g. a `user data dir`." optional = false python-versions = ">=3.8" files = [ - {file = "platformdirs-4.2.2-py3-none-any.whl", hash = "sha256:2d7a1657e36a80ea911db832a8a6ece5ee53d8de21edd5cc5879af6530b1bfee"}, - {file = "platformdirs-4.2.2.tar.gz", hash = "sha256:38b7b51f512eed9e84a22788b4bce1de17c0adb134d6becb09836e37d8654cd3"}, + {file = "platformdirs-4.3.6-py3-none-any.whl", hash = "sha256:73e575e1408ab8103900836b97580d5307456908a03e92031bab39e4554cc3fb"}, + {file = "platformdirs-4.3.6.tar.gz", hash = "sha256:357fb2acbc885b0419afd3ce3ed34564c13c9b95c89360cd9563f73aa5e2b907"}, ] [package.extras] -docs = ["furo (>=2023.9.10)", "proselint (>=0.13)", "sphinx (>=7.2.6)", "sphinx-autodoc-typehints (>=1.25.2)"] -test = ["appdirs (==1.4.4)", "covdefaults (>=2.3)", "pytest (>=7.4.3)", "pytest-cov (>=4.1)", "pytest-mock (>=3.12)"] -type = ["mypy (>=1.8)"] +docs = ["furo (>=2024.8.6)", "proselint (>=0.14)", "sphinx (>=8.0.2)", "sphinx-autodoc-typehints (>=2.4)"] +test = ["appdirs (==1.4.4)", "covdefaults (>=2.3)", "pytest (>=8.3.2)", "pytest-cov (>=5)", "pytest-mock (>=3.14)"] +type = ["mypy (>=1.11.2)"] + +[[package]] +name = "plotly" +version = "5.24.1" +description = "An open-source, interactive data visualization library for Python" +optional = true +python-versions = ">=3.8" +files = [ + {file = "plotly-5.24.1-py3-none-any.whl", hash = "sha256:f67073a1e637eb0dc3e46324d9d51e2fe76e9727c892dde64ddf1e1b51f29089"}, + {file = "plotly-5.24.1.tar.gz", hash = "sha256:dbc8ac8339d248a4bcc36e08a5659bacfe1b079390b8953533f4eb22169b4bae"}, +] + +[package.dependencies] +packaging = "*" +tenacity = ">=6.2.0" [[package]] name = "pluggy" @@ -2727,13 +4595,13 @@ testing = ["pytest", "pytest-benchmark"] [[package]] name = "pre-commit" -version = "3.7.1" +version = "3.8.0" description = "A framework for managing and maintaining multi-language pre-commit hooks." optional = true python-versions = ">=3.9" files = [ - {file = "pre_commit-3.7.1-py2.py3-none-any.whl", hash = "sha256:fae36fd1d7ad7d6a5a1c0b0d5adb2ed1a3bda5a21bf6c3e5372073d7a11cd4c5"}, - {file = "pre_commit-3.7.1.tar.gz", hash = "sha256:8ca3ad567bc78a4972a3f1a477e94a79d4597e8140a6e0b651c5e33899c3654a"}, + {file = "pre_commit-3.8.0-py2.py3-none-any.whl", hash = "sha256:9a90a53bf82fdd8778d58085faf8d83df56e40dfe18f45b19446e26bf1b3a63f"}, + {file = "pre_commit-3.8.0.tar.gz", hash = "sha256:8bb6494d4a20423842e198980c9ecf9f96607a07ea29549e180eef9ae80fe7af"}, ] [package.dependencies] @@ -2743,6 +4611,20 @@ nodeenv = ">=0.11.1" pyyaml = ">=5.1" virtualenv = ">=20.10.0" +[[package]] +name = "prometheus-client" +version = "0.21.0" +description = "Python client for the Prometheus monitoring system." +optional = true +python-versions = ">=3.8" +files = [ + {file = "prometheus_client-0.21.0-py3-none-any.whl", hash = "sha256:4fa6b4dd0ac16d58bb587c04b1caae65b8c5043e85f778f42f5f632f6af2e166"}, + {file = "prometheus_client-0.21.0.tar.gz", hash = "sha256:96c83c606b71ff2b0a433c98889d275f51ffec6c5e267de37c7a2b5c9aa9233e"}, +] + +[package.extras] +twisted = ["twisted"] + [[package]] name = "prompt-toolkit" version = "3.0.47" @@ -2759,22 +4641,22 @@ wcwidth = "*" [[package]] name = "protobuf" -version = "5.27.2" +version = "5.28.2" description = "" optional = false python-versions = ">=3.8" files = [ - {file = "protobuf-5.27.2-cp310-abi3-win32.whl", hash = "sha256:354d84fac2b0d76062e9b3221f4abbbacdfd2a4d8af36bab0474f3a0bb30ab38"}, - {file = "protobuf-5.27.2-cp310-abi3-win_amd64.whl", hash = "sha256:0e341109c609749d501986b835f667c6e1e24531096cff9d34ae411595e26505"}, - {file = "protobuf-5.27.2-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:a109916aaac42bff84702fb5187f3edadbc7c97fc2c99c5ff81dd15dcce0d1e5"}, - {file = "protobuf-5.27.2-cp38-abi3-manylinux2014_aarch64.whl", hash = "sha256:176c12b1f1c880bf7a76d9f7c75822b6a2bc3db2d28baa4d300e8ce4cde7409b"}, - {file = "protobuf-5.27.2-cp38-abi3-manylinux2014_x86_64.whl", hash = "sha256:b848dbe1d57ed7c191dfc4ea64b8b004a3f9ece4bf4d0d80a367b76df20bf36e"}, - {file = "protobuf-5.27.2-cp38-cp38-win32.whl", hash = "sha256:4fadd8d83e1992eed0248bc50a4a6361dc31bcccc84388c54c86e530b7f58863"}, - {file = "protobuf-5.27.2-cp38-cp38-win_amd64.whl", hash = "sha256:610e700f02469c4a997e58e328cac6f305f649826853813177e6290416e846c6"}, - {file = "protobuf-5.27.2-cp39-cp39-win32.whl", hash = "sha256:9e8f199bf7f97bd7ecebffcae45ebf9527603549b2b562df0fbc6d4d688f14ca"}, - {file = "protobuf-5.27.2-cp39-cp39-win_amd64.whl", hash = "sha256:7fc3add9e6003e026da5fc9e59b131b8f22b428b991ccd53e2af8071687b4fce"}, - {file = "protobuf-5.27.2-py3-none-any.whl", hash = "sha256:54330f07e4949d09614707c48b06d1a22f8ffb5763c159efd5c0928326a91470"}, - {file = "protobuf-5.27.2.tar.gz", hash = "sha256:f3ecdef226b9af856075f28227ff2c90ce3a594d092c39bee5513573f25e2714"}, + {file = "protobuf-5.28.2-cp310-abi3-win32.whl", hash = "sha256:eeea10f3dc0ac7e6b4933d32db20662902b4ab81bf28df12218aa389e9c2102d"}, + {file = "protobuf-5.28.2-cp310-abi3-win_amd64.whl", hash = "sha256:2c69461a7fcc8e24be697624c09a839976d82ae75062b11a0972e41fd2cd9132"}, + {file = "protobuf-5.28.2-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:a8b9403fc70764b08d2f593ce44f1d2920c5077bf7d311fefec999f8c40f78b7"}, + {file = "protobuf-5.28.2-cp38-abi3-manylinux2014_aarch64.whl", hash = "sha256:35cfcb15f213449af7ff6198d6eb5f739c37d7e4f1c09b5d0641babf2cc0c68f"}, + {file = "protobuf-5.28.2-cp38-abi3-manylinux2014_x86_64.whl", hash = "sha256:5e8a95246d581eef20471b5d5ba010d55f66740942b95ba9b872d918c459452f"}, + {file = "protobuf-5.28.2-cp38-cp38-win32.whl", hash = "sha256:87317e9bcda04a32f2ee82089a204d3a2f0d3c8aeed16568c7daf4756e4f1fe0"}, + {file = "protobuf-5.28.2-cp38-cp38-win_amd64.whl", hash = "sha256:c0ea0123dac3399a2eeb1a1443d82b7afc9ff40241433296769f7da42d142ec3"}, + {file = "protobuf-5.28.2-cp39-cp39-win32.whl", hash = "sha256:ca53faf29896c526863366a52a8f4d88e69cd04ec9571ed6082fa117fac3ab36"}, + {file = "protobuf-5.28.2-cp39-cp39-win_amd64.whl", hash = "sha256:8ddc60bf374785fb7cb12510b267f59067fa10087325b8e1855b898a0d81d276"}, + {file = "protobuf-5.28.2-py3-none-any.whl", hash = "sha256:52235802093bd8a2811abbe8bf0ab9c5f54cca0a751fdd3f6ac2a21438bffece"}, + {file = "protobuf-5.28.2.tar.gz", hash = "sha256:59379674ff119717404f7454647913787034f03fe7049cbef1d74a97bb4593f0"}, ] [[package]] @@ -2806,6 +4688,31 @@ files = [ [package.extras] test = ["enum34", "ipaddress", "mock", "pywin32", "wmi"] +[[package]] +name = "ptyprocess" +version = "0.7.0" +description = "Run a subprocess in a pseudo terminal" +optional = true +python-versions = "*" +files = [ + {file = "ptyprocess-0.7.0-py2.py3-none-any.whl", hash = "sha256:4b41f3967fce3af57cc7e94b888626c18bf37a083e3651ca8feeb66d492fef35"}, + {file = "ptyprocess-0.7.0.tar.gz", hash = "sha256:5c5d0a3b48ceee0b48485e0c26037c0acd7d29765ca3fbb5cb3831d347423220"}, +] + +[[package]] +name = "pure-eval" +version = "0.2.3" +description = "Safely evaluate AST nodes without side effects" +optional = true +python-versions = "*" +files = [ + {file = "pure_eval-0.2.3-py3-none-any.whl", hash = "sha256:1db8e35b67b3d218d818ae653e27f06c3aa420901fa7b081ca98cbedc874e0d0"}, + {file = "pure_eval-0.2.3.tar.gz", hash = "sha256:5f4e983f40564c576c7c8635ae88db5956bb2229d7e9237d03b3c0b0190eaf42"}, +] + +[package.extras] +tests = ["pytest"] + [[package]] name = "pyarrow" version = "17.0.0" @@ -2858,46 +4765,81 @@ numpy = ">=1.16.6" test = ["cffi", "hypothesis", "pandas", "pytest", "pytz"] [[package]] -name = "pyarrow-hotfix" -version = "0.6" -description = "" -optional = false -python-versions = ">=3.5" +name = "pyaudio" +version = "0.2.14" +description = "Cross-platform audio I/O with PortAudio" +optional = true +python-versions = "*" files = [ - {file = "pyarrow_hotfix-0.6-py3-none-any.whl", hash = "sha256:dcc9ae2d220dff0083be6a9aa8e0cdee5182ad358d4931fce825c545e5c89178"}, - {file = "pyarrow_hotfix-0.6.tar.gz", hash = "sha256:79d3e030f7ff890d408a100ac16d6f00b14d44a502d7897cd9fc3e3a534e9945"}, + {file = "PyAudio-0.2.14-cp310-cp310-win32.whl", hash = "sha256:126065b5e82a1c03ba16e7c0404d8f54e17368836e7d2d92427358ad44fefe61"}, + {file = "PyAudio-0.2.14-cp310-cp310-win_amd64.whl", hash = "sha256:2a166fc88d435a2779810dd2678354adc33499e9d4d7f937f28b20cc55893e83"}, + {file = "PyAudio-0.2.14-cp311-cp311-win32.whl", hash = "sha256:506b32a595f8693811682ab4b127602d404df7dfc453b499c91a80d0f7bad289"}, + {file = "PyAudio-0.2.14-cp311-cp311-win_amd64.whl", hash = "sha256:bbeb01d36a2f472ae5ee5e1451cacc42112986abe622f735bb870a5db77cf903"}, + {file = "PyAudio-0.2.14-cp312-cp312-win32.whl", hash = "sha256:5fce4bcdd2e0e8c063d835dbe2860dac46437506af509353c7f8114d4bacbd5b"}, + {file = "PyAudio-0.2.14-cp312-cp312-win_amd64.whl", hash = "sha256:12f2f1ba04e06ff95d80700a78967897a489c05e093e3bffa05a84ed9c0a7fa3"}, + {file = "PyAudio-0.2.14-cp38-cp38-win32.whl", hash = "sha256:858caf35b05c26d8fc62f1efa2e8f53d5fa1a01164842bd622f70ddc41f55000"}, + {file = "PyAudio-0.2.14-cp38-cp38-win_amd64.whl", hash = "sha256:2dac0d6d675fe7e181ba88f2de88d321059b69abd52e3f4934a8878e03a7a074"}, + {file = "PyAudio-0.2.14-cp39-cp39-win32.whl", hash = "sha256:f745109634a7c19fa4d6b8b7d6967c3123d988c9ade0cd35d4295ee1acdb53e9"}, + {file = "PyAudio-0.2.14-cp39-cp39-win_amd64.whl", hash = "sha256:009f357ee5aa6bc8eb19d69921cd30e98c42cddd34210615d592a71d09c4bd57"}, + {file = "PyAudio-0.2.14.tar.gz", hash = "sha256:78dfff3879b4994d1f4fc6485646a57755c6ee3c19647a491f790a0895bd2f87"}, ] +[package.extras] +test = ["numpy"] + [[package]] name = "pyav" -version = "12.2.0" +version = "13.0.0" description = "Pythonic bindings for FFmpeg's libraries." optional = false python-versions = ">=3.10" files = [ - {file = "pyav-12.2.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:2f00df6661b56271bc21b53397f7b5cdffe3450723cd358eb69c8f6428f17500"}, - {file = "pyav-12.2.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:bfbd521329be96f9e741ec25eccea19bb3a6c7ef5ee540f318fb1a38b5e690f0"}, - {file = "pyav-12.2.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:84ffc7b8f4bcb671a73cb4d98d6bde9f7b4a6dabc402d8004f633375fe75cd15"}, - {file = "pyav-12.2.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:acd6390b2834d6bc6cf39c72a8b461fe0d42993dac7c6739af7e41033e1a55d5"}, - {file = "pyav-12.2.0-cp310-cp310-win_amd64.whl", hash = "sha256:ace6a4de2f11e1dd8d0e5a5517ec2ccd3fe21ce7b1215aa9ec417e129897c84c"}, - {file = "pyav-12.2.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:d9806ec843ac216eddbd8127c2f0fc8a0f78f0edb6fb5ea06bdb8ec1226762e7"}, - {file = "pyav-12.2.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:c2889639e228abae0e7642768ceaefa30a87fe442b79e79a1709b531df7fded1"}, - {file = "pyav-12.2.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d50626b600abaa849b547600445538e3ec8a39e51ea20550d2ac5ef21281caa1"}, - {file = "pyav-12.2.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:57bf6e52b59099b25b16e3778c241c607c6b142dcceb17b9f04ddea1b53d9c37"}, - {file = "pyav-12.2.0-cp311-cp311-win_amd64.whl", hash = "sha256:d5463692bc9f92540f2d51d5851aae9b03a26a384d8ea62e02e942968c31bd6b"}, - {file = "pyav-12.2.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:796bc264e5a6cb4a3f052eda95c57891a8df60c9bbf6f9cd4fad6a1a6f3fb0a1"}, - {file = "pyav-12.2.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:3237e76fef91aa132cff3581c28188b18bad3da07bf228eda573a683acab7111"}, - {file = "pyav-12.2.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:52dc979a315e40081bb1816d1f265507ee62569282718d7d602e508c3daaf034"}, - {file = "pyav-12.2.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6175dc56d14b04b26dd36e5d12e7bc2961fa365b6e2669d2f900b2f860fdb243"}, - {file = "pyav-12.2.0-cp312-cp312-win_amd64.whl", hash = "sha256:5ce8e1219e84a71d776ef25f4fda1c7bbeed517339db7f9c7e1f99e6f96f0a2b"}, - {file = "pyav-12.2.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:f7a3f91ec889e44e4f246841c433f4a5e9c20a308015d1d6ff9d94ae182eabc3"}, - {file = "pyav-12.2.0-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:f1fd8e5a1d5ca3dc377400fec2b04c15ed7abf657cc9ed1522b2481bc4f31af2"}, - {file = "pyav-12.2.0-pp310-pypy310_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8561a399a7dfa30bc99b34a1a72790128593798d741423984389f31aa911d799"}, - {file = "pyav-12.2.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0938f1e26e3ad55b6ffe588255a8b4e306d9470fbf2cc6819644b75f10fcb7d4"}, - {file = "pyav-12.2.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:8b23bc2c36f84a924ad8407da5a287b2f1533af94bb42007331bc2ebab429a83"}, - {file = "pyav-12.2.0.tar.gz", hash = "sha256:6e77f8509c284e972fdac8221dc3f046f9dd69651f4218249d0910c71e041ae2"}, + {file = "pyav-13.0.0-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:9d423966eb46be1cc39d2e73bcdf6ddbf460e84ed397e2ed70a71f02e5a46459"}, + {file = "pyav-13.0.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:d06cf4871087460b103c425c9067906bbf42526dac1cf0d6c2f2fb8c287534d4"}, + {file = "pyav-13.0.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:284cae0c940a3b0f7ae27f965cdc19107bef9d8058dcb6119a028d5fc4f2a370"}, + {file = "pyav-13.0.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:09678c0c2e287d7d95b7a562d05893b49fbc2e25af2414de710c159475e5ffe9"}, + {file = "pyav-13.0.0-cp310-cp310-win_amd64.whl", hash = "sha256:4a499eb490ada91e5cdfd77daa2928b24124561e46ad731585ff11ecf9bac8b5"}, + {file = "pyav-13.0.0-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:24bfcc144ffdb895c88075fc518f52ead7cddfc9a3917ff09a2e20bf3db1107a"}, + {file = "pyav-13.0.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:99dbf1357db5c33596aeb8c06cb2fd55ad36fd8463bfd5697168ba546bc3d829"}, + {file = "pyav-13.0.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f95cb104d3e59d1304462d41f7e4ded29f680eed84b01a991b297f915f4363d1"}, + {file = "pyav-13.0.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0f18db877859a9243a8a128ae130180fd3fd98ed10e9ab6e047b77ac2d5e3155"}, + {file = "pyav-13.0.0-cp311-cp311-win_amd64.whl", hash = "sha256:80f848385f62faf80b08657f2b864be3b6bbb4dde9247dce38eb63f36bcc5961"}, + {file = "pyav-13.0.0-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:99e5b8d9391a94816156114ee657a1ceb7b6466f5ac75748bcb46f64a5053f48"}, + {file = "pyav-13.0.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:f860e37745695f35c48b4339fd439b783ebd7da31387bf09b610e12a18c5b60a"}, + {file = "pyav-13.0.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:618e434d6ac8595e4c8ae35ccf82d56a405b95a51fd153a430c4d89c50c2711d"}, + {file = "pyav-13.0.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:89d80bbbf1fea0ac05cf184543b33622fca535a7aa70b6a19657bc4c0a28609c"}, + {file = "pyav-13.0.0-cp312-cp312-win_amd64.whl", hash = "sha256:872c03ad737b86466d5fe38b3b320ccf2210b23a2311bb2b8fa1b7f88f39f0eb"}, + {file = "pyav-13.0.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:488dc9ac3cb79a8bb7e873a2eb0ba2570689feba352da80fa9e8fd71f6f72b61"}, + {file = "pyav-13.0.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:0ec841af409bd15fb84e7e849636ee770a7220b190796f5a9990e168f768f485"}, + {file = "pyav-13.0.0-cp313-cp313-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:361b6a148226c179035f34d922c8aa5ef9215c085eb3a4625f6f3ca022590250"}, + {file = "pyav-13.0.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d264bf6dd5f38bd05c28d37bcdb6569f166651155a4c3776b7d14a220e7deb8a"}, + {file = "pyav-13.0.0-cp313-cp313-win_amd64.whl", hash = "sha256:14bcafcc01df4e1925fd49afb97bcde25fd348c1ee84403fede3d614d7dcd635"}, + {file = "pyav-13.0.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:b549c980016460c0f08de18a13969fcdc8d69a36a9f0c86a238cb45503944308"}, + {file = "pyav-13.0.0-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:dd8638d438f4813ad45a4a1cc918ad2f035b4e69be396c61a12c4d4b8d1a5d42"}, + {file = "pyav-13.0.0-pp310-pypy310_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9f922af5d77d8fab6a8846dd56c95a5ffb7fd9cd4aba19a8c3b0bf84af7a6410"}, + {file = "pyav-13.0.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e53b5dff8dbfc50c494c82fe029498bdb1089417358713199c520d8e850dacf4"}, + {file = "pyav-13.0.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:84f0af351a1d51b001fea4fb457dc905e58e6f3bc6389baf8a64ac9a47ca99ee"}, + {file = "pyav-13.0.0.tar.gz", hash = "sha256:4ec8ab1eb8dcf5447e6bf5890be116849570d53372b74ab485457694e8b61762"}, +] + +[[package]] +name = "pycollada" +version = "0.8" +description = "python library for reading and writing collada documents" +optional = true +python-versions = "*" +files = [ + {file = "pycollada-0.8.tar.gz", hash = "sha256:f3a3759cc4cec1d59e932aad74399dbcf541d18862aad903c770040da42af20e"}, ] +[package.dependencies] +numpy = "*" +python-dateutil = ">=2.2" + +[package.extras] +prettyprint = ["lxml"] +validation = ["lxml"] + [[package]] name = "pycparser" version = "2.22" @@ -2975,6 +4917,31 @@ files = [ {file = "pygame-2.6.0.tar.gz", hash = "sha256:722d33ae676aa8533c1f955eded966411298831346b8d51a77dad22e46ba3e35"}, ] +[[package]] +name = "pyglet" +version = "2.0.17" +description = "pyglet is a cross-platform games and multimedia package." +optional = true +python-versions = ">=3.8" +files = [ + {file = "pyglet-2.0.17-py3-none-any.whl", hash = "sha256:c881615a5bf14455af36a0915fd9dad0069da904ab5e0ec19b4d6cdfcf1e84c2"}, + {file = "pyglet-2.0.17.tar.gz", hash = "sha256:50c533c1a7cafdccccf43041338ad921ae26866e9871b4f12bf608500632900a"}, +] + +[[package]] +name = "pygments" +version = "2.18.0" +description = "Pygments is a syntax highlighting package written in Python." +optional = true +python-versions = ">=3.8" +files = [ + {file = "pygments-2.18.0-py3-none-any.whl", hash = "sha256:b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a"}, + {file = "pygments-2.18.0.tar.gz", hash = "sha256:786ff802f32e91311bff3889f6e9a86e81505fe99f2735bb6d60ae0c5004f199"}, +] + +[package.extras] +windows-terminal = ["colorama (>=0.4.6)"] + [[package]] name = "pymunk" version = "6.8.1" @@ -3181,13 +5148,13 @@ files = [ [[package]] name = "pyparsing" -version = "3.1.2" +version = "3.1.4" description = "pyparsing module - Classes and methods to define and execute parsing grammars" optional = true python-versions = ">=3.6.8" files = [ - {file = "pyparsing-3.1.2-py3-none-any.whl", hash = "sha256:f9db75911801ed778fe61bb643079ff86601aca99fcae6345aa67292038fb742"}, - {file = "pyparsing-3.1.2.tar.gz", hash = "sha256:a1bac0ce561155ecc3ed78ca94d3c9378656ad4c94c1270de543f621420f94ad"}, + {file = "pyparsing-3.1.4-py3-none-any.whl", hash = "sha256:a6a7ee4235a3f944aa1fa2249307708f893fe5717dc603503c6c7969c070fb7c"}, + {file = "pyparsing-3.1.4.tar.gz", hash = "sha256:f86ec8d1a83f11977c9a6ea7598e8c27fc5cddfa5b07ea2241edbbde1d7bc032"}, ] [package.extras] @@ -3216,6 +5183,64 @@ files = [ {file = "pyrealsense2-2.55.1.6486-cp39-cp39-win_amd64.whl", hash = "sha256:5cbede3cd35946f3051ae6df42619ea01419c58379533c596bbad5dbf648c25b"}, ] +[[package]] +name = "pyrender" +version = "0.1.45" +description = "Easy-to-use Python renderer for 3D visualization" +optional = true +python-versions = "*" +files = [] +develop = false + +[package.dependencies] +freetype-py = "*" +imageio = "*" +networkx = "*" +numpy = "*" +Pillow = "*" +pyglet = ">=1.4.10" +PyOpenGL = ">=3.1.0,<3.2.0" +scipy = "*" +six = "*" +trimesh = "*" + +[package.extras] +dev = ["flake8", "pre-commit", "pytest", "pytest-cov", "tox"] +docs = ["sphinx", "sphinx-automodapi", "sphinx_rtd_theme"] + +[package.source] +type = "git" +url = "https://github.com/mmatl/pyrender.git" +reference = "HEAD" +resolved_reference = "a59963ef890891656fd17c90e12d663233dcaa99" + +[[package]] +name = "pyribbit" +version = "0.1.46" +description = "Easy-to-use Python renderer for 3D visualization" +optional = true +python-versions = "*" +files = [ + {file = "pyribbit-0.1.46-py3-none-any.whl", hash = "sha256:0d4943f7cc6903f20ef42787e9357d7bb25c95f2c04da9dfa1a8021bdf9e0ab6"}, + {file = "pyribbit-0.1.46.tar.gz", hash = "sha256:3bb7a31841549ed74c50e31415738d2494b720df825cf387501f17102299940b"}, +] + +[package.dependencies] +freetype-py = "*" +imageio = "*" +networkx = "*" +numpy = "*" +Pillow = "*" +pyglet = ">=1.4.10" +PyOpenGL = ">=3.1.0" +scipy = "*" +six = "*" +trimesh = "*" + +[package.extras] +dev = ["flake8", "pre-commit", "pytest", "pytest-cov", "tox"] +docs = ["sphinx", "sphinx-automodapi", "sphinx-rtd-theme"] + [[package]] name = "pyserial" version = "3.5" @@ -3244,13 +5269,13 @@ files = [ [[package]] name = "pytest" -version = "8.2.2" +version = "8.3.3" description = "pytest: simple powerful testing with Python" optional = true python-versions = ">=3.8" files = [ - {file = "pytest-8.2.2-py3-none-any.whl", hash = "sha256:c434598117762e2bd304e526244f67bf66bbd7b5d6cf22138be51ff661980343"}, - {file = "pytest-8.2.2.tar.gz", hash = "sha256:de4bb8104e201939ccdc688b27a89a7be2079b22e2bd2b07f806b6ba71117977"}, + {file = "pytest-8.3.3-py3-none-any.whl", hash = "sha256:a6853c7375b2663155079443d2e45de913a911a11d669df02a50814944db57b2"}, + {file = "pytest-8.3.3.tar.gz", hash = "sha256:70b98107bd648308a7952b06e6ca9a50bc660be218d53c257cc1fc94fda10181"}, ] [package.dependencies] @@ -3258,7 +5283,7 @@ colorama = {version = "*", markers = "sys_platform == \"win32\""} exceptiongroup = {version = ">=1.0.0rc8", markers = "python_version < \"3.11\""} iniconfig = "*" packaging = "*" -pluggy = ">=1.5,<2.0" +pluggy = ">=1.5,<2" tomli = {version = ">=1", markers = "python_version < \"3.11\""} [package.extras] @@ -3296,6 +5321,36 @@ files = [ [package.dependencies] six = ">=1.5" +[[package]] +name = "python-json-logger" +version = "2.0.7" +description = "A python library adding a json log formatter" +optional = true +python-versions = ">=3.6" +files = [ + {file = "python-json-logger-2.0.7.tar.gz", hash = "sha256:23e7ec02d34237c5aa1e29a070193a4ea87583bb4e7f8fd06d3de8264c4b2e1c"}, + {file = "python_json_logger-2.0.7-py3-none-any.whl", hash = "sha256:f380b826a991ebbe3de4d897aeec42760035ac760345e57b812938dc8b35e2bd"}, +] + +[[package]] +name = "python-utils" +version = "3.9.0" +description = "Python Utils is a module with some convenient utilities not included with the standard Python install" +optional = true +python-versions = ">3.9.0" +files = [ + {file = "python_utils-3.9.0-py2.py3-none-any.whl", hash = "sha256:a7719a5ef4bae7360d2a15c13b08c4e3c3e39b9df19bd16f119ff8d0cfeaafb7"}, + {file = "python_utils-3.9.0.tar.gz", hash = "sha256:3689556884e3ae53aec5a4c9f17b36e752a3e93a7ba2768c6553fc4dd6fa70ef"}, +] + +[package.dependencies] +typing-extensions = ">3.10.0.2" + +[package.extras] +docs = ["mock", "python-utils", "sphinx"] +loguru = ["loguru"] +tests = ["blessings", "loguru", "loguru-mypy", "mypy-ipython", "pyright", "pytest", "pytest-asyncio", "pytest-cov", "pytest-mypy", "ruff", "sphinx", "types-setuptools"] + [[package]] name = "python-xlib" version = "0.33" @@ -3312,163 +5367,355 @@ six = ">=1.10.0" [[package]] name = "pytz" -version = "2024.1" +version = "2024.2" description = "World timezone definitions, modern and historical" optional = false python-versions = "*" files = [ - {file = "pytz-2024.1-py2.py3-none-any.whl", hash = "sha256:328171f4e3623139da4983451950b28e95ac706e13f3f2630a879749e7a8b319"}, - {file = "pytz-2024.1.tar.gz", hash = "sha256:2a29735ea9c18baf14b448846bde5a48030ed267578472d8955cd0e7443a9812"}, + {file = "pytz-2024.2-py2.py3-none-any.whl", hash = "sha256:31c7c1817eb7fae7ca4b8c7ee50c72f93aa2dd863de768e1ef4245d426aa0725"}, + {file = "pytz-2024.2.tar.gz", hash = "sha256:2aa355083c50a0f93fa581709deac0c9ad65cca8a9e9beac660adcbd493c798a"}, +] + +[[package]] +name = "pyusb" +version = "1.2.1" +description = "Python USB access module" +optional = true +python-versions = ">=3.6.0" +files = [ + {file = "pyusb-1.2.1-py3-none-any.whl", hash = "sha256:2b4c7cb86dbadf044dfb9d3a4ff69fd217013dbe78a792177a3feb172449ea36"}, + {file = "pyusb-1.2.1.tar.gz", hash = "sha256:a4cc7404a203144754164b8b40994e2849fde1cfff06b08492f12fff9d9de7b9"}, +] + +[[package]] +name = "pywinpty" +version = "2.0.13" +description = "Pseudo terminal support for Windows from Python." +optional = true +python-versions = ">=3.8" +files = [ + {file = "pywinpty-2.0.13-cp310-none-win_amd64.whl", hash = "sha256:697bff211fb5a6508fee2dc6ff174ce03f34a9a233df9d8b5fe9c8ce4d5eaf56"}, + {file = "pywinpty-2.0.13-cp311-none-win_amd64.whl", hash = "sha256:b96fb14698db1284db84ca38c79f15b4cfdc3172065b5137383910567591fa99"}, + {file = "pywinpty-2.0.13-cp312-none-win_amd64.whl", hash = "sha256:2fd876b82ca750bb1333236ce98488c1be96b08f4f7647cfdf4129dfad83c2d4"}, + {file = "pywinpty-2.0.13-cp38-none-win_amd64.whl", hash = "sha256:61d420c2116c0212808d31625611b51caf621fe67f8a6377e2e8b617ea1c1f7d"}, + {file = "pywinpty-2.0.13-cp39-none-win_amd64.whl", hash = "sha256:71cb613a9ee24174730ac7ae439fd179ca34ccb8c5349e8d7b72ab5dea2c6f4b"}, + {file = "pywinpty-2.0.13.tar.gz", hash = "sha256:c34e32351a3313ddd0d7da23d27f835c860d32fe4ac814d372a3ea9594f41dde"}, ] [[package]] name = "pyyaml" -version = "6.0.1" +version = "6.0.2" description = "YAML parser and emitter for Python" optional = false -python-versions = ">=3.6" +python-versions = ">=3.8" files = [ - {file = "PyYAML-6.0.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:d858aa552c999bc8a8d57426ed01e40bef403cd8ccdd0fc5f6f04a00414cac2a"}, - {file = "PyYAML-6.0.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:fd66fc5d0da6d9815ba2cebeb4205f95818ff4b79c3ebe268e75d961704af52f"}, - {file = "PyYAML-6.0.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:69b023b2b4daa7548bcfbd4aa3da05b3a74b772db9e23b982788168117739938"}, - {file = "PyYAML-6.0.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:81e0b275a9ecc9c0c0c07b4b90ba548307583c125f54d5b6946cfee6360c733d"}, - {file = "PyYAML-6.0.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ba336e390cd8e4d1739f42dfe9bb83a3cc2e80f567d8805e11b46f4a943f5515"}, - {file = "PyYAML-6.0.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:326c013efe8048858a6d312ddd31d56e468118ad4cdeda36c719bf5bb6192290"}, - {file = "PyYAML-6.0.1-cp310-cp310-win32.whl", hash = "sha256:bd4af7373a854424dabd882decdc5579653d7868b8fb26dc7d0e99f823aa5924"}, - {file = "PyYAML-6.0.1-cp310-cp310-win_amd64.whl", hash = "sha256:fd1592b3fdf65fff2ad0004b5e363300ef59ced41c2e6b3a99d4089fa8c5435d"}, - {file = "PyYAML-6.0.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6965a7bc3cf88e5a1c3bd2e0b5c22f8d677dc88a455344035f03399034eb3007"}, - {file = "PyYAML-6.0.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:f003ed9ad21d6a4713f0a9b5a7a0a79e08dd0f221aff4525a2be4c346ee60aab"}, - {file = "PyYAML-6.0.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:42f8152b8dbc4fe7d96729ec2b99c7097d656dc1213a3229ca5383f973a5ed6d"}, - {file = "PyYAML-6.0.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:062582fca9fabdd2c8b54a3ef1c978d786e0f6b3a1510e0ac93ef59e0ddae2bc"}, - {file = "PyYAML-6.0.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d2b04aac4d386b172d5b9692e2d2da8de7bfb6c387fa4f801fbf6fb2e6ba4673"}, - {file = "PyYAML-6.0.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:e7d73685e87afe9f3b36c799222440d6cf362062f78be1013661b00c5c6f678b"}, - {file = "PyYAML-6.0.1-cp311-cp311-win32.whl", hash = "sha256:1635fd110e8d85d55237ab316b5b011de701ea0f29d07611174a1b42f1444741"}, - {file = "PyYAML-6.0.1-cp311-cp311-win_amd64.whl", hash = "sha256:bf07ee2fef7014951eeb99f56f39c9bb4af143d8aa3c21b1677805985307da34"}, - {file = "PyYAML-6.0.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:855fb52b0dc35af121542a76b9a84f8d1cd886ea97c84703eaa6d88e37a2ad28"}, - {file = "PyYAML-6.0.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:40df9b996c2b73138957fe23a16a4f0ba614f4c0efce1e9406a184b6d07fa3a9"}, - {file = "PyYAML-6.0.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a08c6f0fe150303c1c6b71ebcd7213c2858041a7e01975da3a99aed1e7a378ef"}, - {file = "PyYAML-6.0.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6c22bec3fbe2524cde73d7ada88f6566758a8f7227bfbf93a408a9d86bcc12a0"}, - {file = "PyYAML-6.0.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8d4e9c88387b0f5c7d5f281e55304de64cf7f9c0021a3525bd3b1c542da3b0e4"}, - {file = "PyYAML-6.0.1-cp312-cp312-win32.whl", hash = "sha256:d483d2cdf104e7c9fa60c544d92981f12ad66a457afae824d146093b8c294c54"}, - {file = "PyYAML-6.0.1-cp312-cp312-win_amd64.whl", hash = "sha256:0d3304d8c0adc42be59c5f8a4d9e3d7379e6955ad754aa9d6ab7a398b59dd1df"}, - {file = "PyYAML-6.0.1-cp36-cp36m-macosx_10_9_x86_64.whl", hash = "sha256:50550eb667afee136e9a77d6dc71ae76a44df8b3e51e41b77f6de2932bfe0f47"}, - {file = "PyYAML-6.0.1-cp36-cp36m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1fe35611261b29bd1de0070f0b2f47cb6ff71fa6595c077e42bd0c419fa27b98"}, - {file = "PyYAML-6.0.1-cp36-cp36m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:704219a11b772aea0d8ecd7058d0082713c3562b4e271b849ad7dc4a5c90c13c"}, - {file = "PyYAML-6.0.1-cp36-cp36m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:afd7e57eddb1a54f0f1a974bc4391af8bcce0b444685d936840f125cf046d5bd"}, - {file = "PyYAML-6.0.1-cp36-cp36m-win32.whl", hash = "sha256:fca0e3a251908a499833aa292323f32437106001d436eca0e6e7833256674585"}, - {file = "PyYAML-6.0.1-cp36-cp36m-win_amd64.whl", hash = "sha256:f22ac1c3cac4dbc50079e965eba2c1058622631e526bd9afd45fedd49ba781fa"}, - {file = "PyYAML-6.0.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:b1275ad35a5d18c62a7220633c913e1b42d44b46ee12554e5fd39c70a243d6a3"}, - {file = "PyYAML-6.0.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:18aeb1bf9a78867dc38b259769503436b7c72f7a1f1f4c93ff9a17de54319b27"}, - {file = "PyYAML-6.0.1-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:596106435fa6ad000c2991a98fa58eeb8656ef2325d7e158344fb33864ed87e3"}, - {file = "PyYAML-6.0.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:baa90d3f661d43131ca170712d903e6295d1f7a0f595074f151c0aed377c9b9c"}, - {file = "PyYAML-6.0.1-cp37-cp37m-win32.whl", hash = "sha256:9046c58c4395dff28dd494285c82ba00b546adfc7ef001486fbf0324bc174fba"}, - {file = "PyYAML-6.0.1-cp37-cp37m-win_amd64.whl", hash = "sha256:4fb147e7a67ef577a588a0e2c17b6db51dda102c71de36f8549b6816a96e1867"}, - {file = "PyYAML-6.0.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:1d4c7e777c441b20e32f52bd377e0c409713e8bb1386e1099c2415f26e479595"}, - {file = "PyYAML-6.0.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a0cd17c15d3bb3fa06978b4e8958dcdc6e0174ccea823003a106c7d4d7899ac5"}, - {file = "PyYAML-6.0.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:28c119d996beec18c05208a8bd78cbe4007878c6dd15091efb73a30e90539696"}, - {file = "PyYAML-6.0.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7e07cbde391ba96ab58e532ff4803f79c4129397514e1413a7dc761ccd755735"}, - {file = "PyYAML-6.0.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:49a183be227561de579b4a36efbb21b3eab9651dd81b1858589f796549873dd6"}, - {file = "PyYAML-6.0.1-cp38-cp38-win32.whl", hash = "sha256:184c5108a2aca3c5b3d3bf9395d50893a7ab82a38004c8f61c258d4428e80206"}, - {file = "PyYAML-6.0.1-cp38-cp38-win_amd64.whl", hash = "sha256:1e2722cc9fbb45d9b87631ac70924c11d3a401b2d7f410cc0e3bbf249f2dca62"}, - {file = "PyYAML-6.0.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:9eb6caa9a297fc2c2fb8862bc5370d0303ddba53ba97e71f08023b6cd73d16a8"}, - {file = "PyYAML-6.0.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:c8098ddcc2a85b61647b2590f825f3db38891662cfc2fc776415143f599bb859"}, - {file = "PyYAML-6.0.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5773183b6446b2c99bb77e77595dd486303b4faab2b086e7b17bc6bef28865f6"}, - {file = "PyYAML-6.0.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b786eecbdf8499b9ca1d697215862083bd6d2a99965554781d0d8d1ad31e13a0"}, - {file = "PyYAML-6.0.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bc1bf2925a1ecd43da378f4db9e4f799775d6367bdb94671027b73b393a7c42c"}, - {file = "PyYAML-6.0.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:04ac92ad1925b2cff1db0cfebffb6ffc43457495c9b3c39d3fcae417d7125dc5"}, - {file = "PyYAML-6.0.1-cp39-cp39-win32.whl", hash = "sha256:faca3bdcf85b2fc05d06ff3fbc1f83e1391b3e724afa3feba7d13eeab355484c"}, - {file = "PyYAML-6.0.1-cp39-cp39-win_amd64.whl", hash = "sha256:510c9deebc5c0225e8c96813043e62b680ba2f9c50a08d3724c7f28a747d1486"}, - {file = "PyYAML-6.0.1.tar.gz", hash = "sha256:bfdf460b1736c775f2ba9f6a92bca30bc2095067b8a9d77876d1fad6cc3b4a43"}, + {file = "PyYAML-6.0.2-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:0a9a2848a5b7feac301353437eb7d5957887edbf81d56e903999a75a3d743086"}, + {file = "PyYAML-6.0.2-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:29717114e51c84ddfba879543fb232a6ed60086602313ca38cce623c1d62cfbf"}, + {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8824b5a04a04a047e72eea5cec3bc266db09e35de6bdfe34c9436ac5ee27d237"}, + {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:7c36280e6fb8385e520936c3cb3b8042851904eba0e58d277dca80a5cfed590b"}, + {file = "PyYAML-6.0.2-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec031d5d2feb36d1d1a24380e4db6d43695f3748343d99434e6f5f9156aaa2ed"}, + {file = "PyYAML-6.0.2-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:936d68689298c36b53b29f23c6dbb74de12b4ac12ca6cfe0e047bedceea56180"}, + {file = "PyYAML-6.0.2-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:23502f431948090f597378482b4812b0caae32c22213aecf3b55325e049a6c68"}, + {file = "PyYAML-6.0.2-cp310-cp310-win32.whl", hash = "sha256:2e99c6826ffa974fe6e27cdb5ed0021786b03fc98e5ee3c5bfe1fd5015f42b99"}, + {file = "PyYAML-6.0.2-cp310-cp310-win_amd64.whl", hash = "sha256:a4d3091415f010369ae4ed1fc6b79def9416358877534caf6a0fdd2146c87a3e"}, + {file = "PyYAML-6.0.2-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:cc1c1159b3d456576af7a3e4d1ba7e6924cb39de8f67111c735f6fc832082774"}, + {file = "PyYAML-6.0.2-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:1e2120ef853f59c7419231f3bf4e7021f1b936f6ebd222406c3b60212205d2ee"}, + {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5d225db5a45f21e78dd9358e58a98702a0302f2659a3c6cd320564b75b86f47c"}, + {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5ac9328ec4831237bec75defaf839f7d4564be1e6b25ac710bd1a96321cc8317"}, + {file = "PyYAML-6.0.2-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3ad2a3decf9aaba3d29c8f537ac4b243e36bef957511b4766cb0057d32b0be85"}, + {file = "PyYAML-6.0.2-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:ff3824dc5261f50c9b0dfb3be22b4567a6f938ccce4587b38952d85fd9e9afe4"}, + {file = "PyYAML-6.0.2-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:797b4f722ffa07cc8d62053e4cff1486fa6dc094105d13fea7b1de7d8bf71c9e"}, + {file = "PyYAML-6.0.2-cp311-cp311-win32.whl", hash = "sha256:11d8f3dd2b9c1207dcaf2ee0bbbfd5991f571186ec9cc78427ba5bd32afae4b5"}, + {file = "PyYAML-6.0.2-cp311-cp311-win_amd64.whl", hash = "sha256:e10ce637b18caea04431ce14fabcf5c64a1c61ec9c56b071a4b7ca131ca52d44"}, + {file = "PyYAML-6.0.2-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c70c95198c015b85feafc136515252a261a84561b7b1d51e3384e0655ddf25ab"}, + {file = "PyYAML-6.0.2-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:ce826d6ef20b1bc864f0a68340c8b3287705cae2f8b4b1d932177dcc76721725"}, + {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1f71ea527786de97d1a0cc0eacd1defc0985dcf6b3f17bb77dcfc8c34bec4dc5"}, + {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9b22676e8097e9e22e36d6b7bda33190d0d400f345f23d4065d48f4ca7ae0425"}, + {file = "PyYAML-6.0.2-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:80bab7bfc629882493af4aa31a4cfa43a4c57c83813253626916b8c7ada83476"}, + {file = "PyYAML-6.0.2-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48"}, + {file = "PyYAML-6.0.2-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:8b9c7197f7cb2738065c481a0461e50ad02f18c78cd75775628afb4d7137fb3b"}, + {file = "PyYAML-6.0.2-cp312-cp312-win32.whl", hash = "sha256:ef6107725bd54b262d6dedcc2af448a266975032bc85ef0172c5f059da6325b4"}, + {file = "PyYAML-6.0.2-cp312-cp312-win_amd64.whl", hash = "sha256:7e7401d0de89a9a855c839bc697c079a4af81cf878373abd7dc625847d25cbd8"}, + {file = "PyYAML-6.0.2-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:efdca5630322a10774e8e98e1af481aad470dd62c3170801852d752aa7a783ba"}, + {file = "PyYAML-6.0.2-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:50187695423ffe49e2deacb8cd10510bc361faac997de9efef88badc3bb9e2d1"}, + {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0ffe8360bab4910ef1b9e87fb812d8bc0a308b0d0eef8c8f44e0254ab3b07133"}, + {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:17e311b6c678207928d649faa7cb0d7b4c26a0ba73d41e99c4fff6b6c3276484"}, + {file = "PyYAML-6.0.2-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:70b189594dbe54f75ab3a1acec5f1e3faa7e8cf2f1e08d9b561cb41b845f69d5"}, + {file = "PyYAML-6.0.2-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:41e4e3953a79407c794916fa277a82531dd93aad34e29c2a514c2c0c5fe971cc"}, + {file = "PyYAML-6.0.2-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:68ccc6023a3400877818152ad9a1033e3db8625d899c72eacb5a668902e4d652"}, + {file = "PyYAML-6.0.2-cp313-cp313-win32.whl", hash = "sha256:bc2fa7c6b47d6bc618dd7fb02ef6fdedb1090ec036abab80d4681424b84c1183"}, + {file = "PyYAML-6.0.2-cp313-cp313-win_amd64.whl", hash = "sha256:8388ee1976c416731879ac16da0aff3f63b286ffdd57cdeb95f3f2e085687563"}, + {file = "PyYAML-6.0.2-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:24471b829b3bf607e04e88d79542a9d48bb037c2267d7927a874e6c205ca7e9a"}, + {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7fded462629cfa4b685c5416b949ebad6cec74af5e2d42905d41e257e0869f5"}, + {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d84a1718ee396f54f3a086ea0a66d8e552b2ab2017ef8b420e92edbc841c352d"}, + {file = "PyYAML-6.0.2-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9056c1ecd25795207ad294bcf39f2db3d845767be0ea6e6a34d856f006006083"}, + {file = "PyYAML-6.0.2-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:82d09873e40955485746739bcb8b4586983670466c23382c19cffecbf1fd8706"}, + {file = "PyYAML-6.0.2-cp38-cp38-win32.whl", hash = "sha256:43fa96a3ca0d6b1812e01ced1044a003533c47f6ee8aca31724f78e93ccc089a"}, + {file = "PyYAML-6.0.2-cp38-cp38-win_amd64.whl", hash = "sha256:01179a4a8559ab5de078078f37e5c1a30d76bb88519906844fd7bdea1b7729ff"}, + {file = "PyYAML-6.0.2-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:688ba32a1cffef67fd2e9398a2efebaea461578b0923624778664cc1c914db5d"}, + {file = "PyYAML-6.0.2-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:a8786accb172bd8afb8be14490a16625cbc387036876ab6ba70912730faf8e1f"}, + {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d8e03406cac8513435335dbab54c0d385e4a49e4945d2909a581c83647ca0290"}, + {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f753120cb8181e736c57ef7636e83f31b9c0d1722c516f7e86cf15b7aa57ff12"}, + {file = "PyYAML-6.0.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3b1fdb9dc17f5a7677423d508ab4f243a726dea51fa5e70992e59a7411c89d19"}, + {file = "PyYAML-6.0.2-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:0b69e4ce7a131fe56b7e4d770c67429700908fc0752af059838b1cfb41960e4e"}, + {file = "PyYAML-6.0.2-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:a9f8c2e67970f13b16084e04f134610fd1d374bf477b17ec1599185cf611d725"}, + {file = "PyYAML-6.0.2-cp39-cp39-win32.whl", hash = "sha256:6395c297d42274772abc367baaa79683958044e5d3835486c16da75d2a694631"}, + {file = "PyYAML-6.0.2-cp39-cp39-win_amd64.whl", hash = "sha256:39693e1f8320ae4f43943590b49779ffb98acb81f788220ea932a6b6c51004d8"}, + {file = "pyyaml-6.0.2.tar.gz", hash = "sha256:d584d9ec91ad65861cc08d42e834324ef890a082e591037abe114850ff7bbc3e"}, +] + +[[package]] +name = "pyzmq" +version = "26.2.0" +description = "Python bindings for 0MQ" +optional = true +python-versions = ">=3.7" +files = [ + {file = "pyzmq-26.2.0-cp310-cp310-macosx_10_15_universal2.whl", hash = "sha256:ddf33d97d2f52d89f6e6e7ae66ee35a4d9ca6f36eda89c24591b0c40205a3629"}, + {file = "pyzmq-26.2.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:dacd995031a01d16eec825bf30802fceb2c3791ef24bcce48fa98ce40918c27b"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:89289a5ee32ef6c439086184529ae060c741334b8970a6855ec0b6ad3ff28764"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5506f06d7dc6ecf1efacb4a013b1f05071bb24b76350832c96449f4a2d95091c"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8ea039387c10202ce304af74def5021e9adc6297067f3441d348d2b633e8166a"}, + {file = "pyzmq-26.2.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:a2224fa4a4c2ee872886ed00a571f5e967c85e078e8e8c2530a2fb01b3309b88"}, + {file = "pyzmq-26.2.0-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:28ad5233e9c3b52d76196c696e362508959741e1a005fb8fa03b51aea156088f"}, + {file = "pyzmq-26.2.0-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:1c17211bc037c7d88e85ed8b7d8f7e52db6dc8eca5590d162717c654550f7282"}, + {file = "pyzmq-26.2.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:b8f86dd868d41bea9a5f873ee13bf5551c94cf6bc51baebc6f85075971fe6eea"}, + {file = "pyzmq-26.2.0-cp310-cp310-win32.whl", hash = "sha256:46a446c212e58456b23af260f3d9fb785054f3e3653dbf7279d8f2b5546b21c2"}, + {file = "pyzmq-26.2.0-cp310-cp310-win_amd64.whl", hash = "sha256:49d34ab71db5a9c292a7644ce74190b1dd5a3475612eefb1f8be1d6961441971"}, + {file = "pyzmq-26.2.0-cp310-cp310-win_arm64.whl", hash = "sha256:bfa832bfa540e5b5c27dcf5de5d82ebc431b82c453a43d141afb1e5d2de025fa"}, + {file = "pyzmq-26.2.0-cp311-cp311-macosx_10_15_universal2.whl", hash = "sha256:8f7e66c7113c684c2b3f1c83cdd3376103ee0ce4c49ff80a648643e57fb22218"}, + {file = "pyzmq-26.2.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3a495b30fc91db2db25120df5847d9833af237546fd59170701acd816ccc01c4"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:77eb0968da535cba0470a5165468b2cac7772cfb569977cff92e240f57e31bef"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6ace4f71f1900a548f48407fc9be59c6ba9d9aaf658c2eea6cf2779e72f9f317"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:92a78853d7280bffb93df0a4a6a2498cba10ee793cc8076ef797ef2f74d107cf"}, + {file = "pyzmq-26.2.0-cp311-cp311-manylinux_2_28_x86_64.whl", hash = "sha256:689c5d781014956a4a6de61d74ba97b23547e431e9e7d64f27d4922ba96e9d6e"}, + {file = "pyzmq-26.2.0-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:0aca98bc423eb7d153214b2df397c6421ba6373d3397b26c057af3c904452e37"}, + {file = "pyzmq-26.2.0-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:1f3496d76b89d9429a656293744ceca4d2ac2a10ae59b84c1da9b5165f429ad3"}, + {file = "pyzmq-26.2.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:5c2b3bfd4b9689919db068ac6c9911f3fcb231c39f7dd30e3138be94896d18e6"}, + {file = "pyzmq-26.2.0-cp311-cp311-win32.whl", hash = "sha256:eac5174677da084abf378739dbf4ad245661635f1600edd1221f150b165343f4"}, + {file = "pyzmq-26.2.0-cp311-cp311-win_amd64.whl", hash = "sha256:5a509df7d0a83a4b178d0f937ef14286659225ef4e8812e05580776c70e155d5"}, + {file = "pyzmq-26.2.0-cp311-cp311-win_arm64.whl", hash = "sha256:c0e6091b157d48cbe37bd67233318dbb53e1e6327d6fc3bb284afd585d141003"}, + {file = "pyzmq-26.2.0-cp312-cp312-macosx_10_15_universal2.whl", hash = "sha256:ded0fc7d90fe93ae0b18059930086c51e640cdd3baebdc783a695c77f123dcd9"}, + {file = "pyzmq-26.2.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:17bf5a931c7f6618023cdacc7081f3f266aecb68ca692adac015c383a134ca52"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:55cf66647e49d4621a7e20c8d13511ef1fe1efbbccf670811864452487007e08"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:4661c88db4a9e0f958c8abc2b97472e23061f0bc737f6f6179d7a27024e1faa5"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ea7f69de383cb47522c9c208aec6dd17697db7875a4674c4af3f8cfdac0bdeae"}, + {file = "pyzmq-26.2.0-cp312-cp312-manylinux_2_28_x86_64.whl", hash = "sha256:7f98f6dfa8b8ccaf39163ce872bddacca38f6a67289116c8937a02e30bbe9711"}, + {file = "pyzmq-26.2.0-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:e3e0210287329272539eea617830a6a28161fbbd8a3271bf4150ae3e58c5d0e6"}, + {file = "pyzmq-26.2.0-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:6b274e0762c33c7471f1a7471d1a2085b1a35eba5cdc48d2ae319f28b6fc4de3"}, + {file = "pyzmq-26.2.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:29c6a4635eef69d68a00321e12a7d2559fe2dfccfa8efae3ffb8e91cd0b36a8b"}, + {file = "pyzmq-26.2.0-cp312-cp312-win32.whl", hash = "sha256:989d842dc06dc59feea09e58c74ca3e1678c812a4a8a2a419046d711031f69c7"}, + {file = "pyzmq-26.2.0-cp312-cp312-win_amd64.whl", hash = "sha256:2a50625acdc7801bc6f74698c5c583a491c61d73c6b7ea4dee3901bb99adb27a"}, + {file = "pyzmq-26.2.0-cp312-cp312-win_arm64.whl", hash = "sha256:4d29ab8592b6ad12ebbf92ac2ed2bedcfd1cec192d8e559e2e099f648570e19b"}, + {file = "pyzmq-26.2.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:9dd8cd1aeb00775f527ec60022004d030ddc51d783d056e3e23e74e623e33726"}, + {file = "pyzmq-26.2.0-cp313-cp313-macosx_10_15_universal2.whl", hash = "sha256:28c812d9757fe8acecc910c9ac9dafd2ce968c00f9e619db09e9f8f54c3a68a3"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4d80b1dd99c1942f74ed608ddb38b181b87476c6a966a88a950c7dee118fdf50"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8c997098cc65e3208eca09303630e84d42718620e83b733d0fd69543a9cab9cb"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7ad1bc8d1b7a18497dda9600b12dc193c577beb391beae5cd2349184db40f187"}, + {file = "pyzmq-26.2.0-cp313-cp313-manylinux_2_28_x86_64.whl", hash = "sha256:bea2acdd8ea4275e1278350ced63da0b166421928276c7c8e3f9729d7402a57b"}, + {file = "pyzmq-26.2.0-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:23f4aad749d13698f3f7b64aad34f5fc02d6f20f05999eebc96b89b01262fb18"}, + {file = "pyzmq-26.2.0-cp313-cp313-musllinux_1_1_i686.whl", hash = "sha256:a4f96f0d88accc3dbe4a9025f785ba830f968e21e3e2c6321ccdfc9aef755115"}, + {file = "pyzmq-26.2.0-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:ced65e5a985398827cc9276b93ef6dfabe0273c23de8c7931339d7e141c2818e"}, + {file = "pyzmq-26.2.0-cp313-cp313-win32.whl", hash = "sha256:31507f7b47cc1ead1f6e86927f8ebb196a0bab043f6345ce070f412a59bf87b5"}, + {file = "pyzmq-26.2.0-cp313-cp313-win_amd64.whl", hash = "sha256:70fc7fcf0410d16ebdda9b26cbd8bf8d803d220a7f3522e060a69a9c87bf7bad"}, + {file = "pyzmq-26.2.0-cp313-cp313-win_arm64.whl", hash = "sha256:c3789bd5768ab5618ebf09cef6ec2b35fed88709b104351748a63045f0ff9797"}, + {file = "pyzmq-26.2.0-cp313-cp313t-macosx_10_13_x86_64.whl", hash = "sha256:034da5fc55d9f8da09015d368f519478a52675e558c989bfcb5cf6d4e16a7d2a"}, + {file = "pyzmq-26.2.0-cp313-cp313t-macosx_10_15_universal2.whl", hash = "sha256:c92d73464b886931308ccc45b2744e5968cbaade0b1d6aeb40d8ab537765f5bc"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:794a4562dcb374f7dbbfb3f51d28fb40123b5a2abadee7b4091f93054909add5"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:aee22939bb6075e7afededabad1a56a905da0b3c4e3e0c45e75810ebe3a52672"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2ae90ff9dad33a1cfe947d2c40cb9cb5e600d759ac4f0fd22616ce6540f72797"}, + {file = "pyzmq-26.2.0-cp313-cp313t-manylinux_2_28_x86_64.whl", hash = "sha256:43a47408ac52647dfabbc66a25b05b6a61700b5165807e3fbd40063fcaf46386"}, + {file = "pyzmq-26.2.0-cp313-cp313t-musllinux_1_1_aarch64.whl", hash = "sha256:25bf2374a2a8433633c65ccb9553350d5e17e60c8eb4de4d92cc6bd60f01d306"}, + {file = "pyzmq-26.2.0-cp313-cp313t-musllinux_1_1_i686.whl", hash = "sha256:007137c9ac9ad5ea21e6ad97d3489af654381324d5d3ba614c323f60dab8fae6"}, + {file = "pyzmq-26.2.0-cp313-cp313t-musllinux_1_1_x86_64.whl", hash = "sha256:470d4a4f6d48fb34e92d768b4e8a5cc3780db0d69107abf1cd7ff734b9766eb0"}, + {file = "pyzmq-26.2.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:3b55a4229ce5da9497dd0452b914556ae58e96a4381bb6f59f1305dfd7e53fc8"}, + {file = "pyzmq-26.2.0-cp37-cp37m-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:9cb3a6460cdea8fe8194a76de8895707e61ded10ad0be97188cc8463ffa7e3a8"}, + {file = "pyzmq-26.2.0-cp37-cp37m-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:8ab5cad923cc95c87bffee098a27856c859bd5d0af31bd346035aa816b081fe1"}, + {file = "pyzmq-26.2.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9ed69074a610fad1c2fda66180e7b2edd4d31c53f2d1872bc2d1211563904cd9"}, + {file = "pyzmq-26.2.0-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:cccba051221b916a4f5e538997c45d7d136a5646442b1231b916d0164067ea27"}, + {file = "pyzmq-26.2.0-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:0eaa83fc4c1e271c24eaf8fb083cbccef8fde77ec8cd45f3c35a9a123e6da097"}, + {file = "pyzmq-26.2.0-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:9edda2df81daa129b25a39b86cb57dfdfe16f7ec15b42b19bfac503360d27a93"}, + {file = "pyzmq-26.2.0-cp37-cp37m-win32.whl", hash = "sha256:ea0eb6af8a17fa272f7b98d7bebfab7836a0d62738e16ba380f440fceca2d951"}, + {file = "pyzmq-26.2.0-cp37-cp37m-win_amd64.whl", hash = "sha256:4ff9dc6bc1664bb9eec25cd17506ef6672d506115095411e237d571e92a58231"}, + {file = "pyzmq-26.2.0-cp38-cp38-macosx_10_15_universal2.whl", hash = "sha256:2eb7735ee73ca1b0d71e0e67c3739c689067f055c764f73aac4cc8ecf958ee3f"}, + {file = "pyzmq-26.2.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:1a534f43bc738181aa7cbbaf48e3eca62c76453a40a746ab95d4b27b1111a7d2"}, + {file = "pyzmq-26.2.0-cp38-cp38-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:aedd5dd8692635813368e558a05266b995d3d020b23e49581ddd5bbe197a8ab6"}, + {file = "pyzmq-26.2.0-cp38-cp38-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:8be4700cd8bb02cc454f630dcdf7cfa99de96788b80c51b60fe2fe1dac480289"}, + {file = "pyzmq-26.2.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1fcc03fa4997c447dce58264e93b5aa2d57714fbe0f06c07b7785ae131512732"}, + {file = "pyzmq-26.2.0-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:402b190912935d3db15b03e8f7485812db350d271b284ded2b80d2e5704be780"}, + {file = "pyzmq-26.2.0-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:8685fa9c25ff00f550c1fec650430c4b71e4e48e8d852f7ddcf2e48308038640"}, + {file = "pyzmq-26.2.0-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:76589c020680778f06b7e0b193f4b6dd66d470234a16e1df90329f5e14a171cd"}, + {file = "pyzmq-26.2.0-cp38-cp38-win32.whl", hash = "sha256:8423c1877d72c041f2c263b1ec6e34360448decfb323fa8b94e85883043ef988"}, + {file = "pyzmq-26.2.0-cp38-cp38-win_amd64.whl", hash = "sha256:76589f2cd6b77b5bdea4fca5992dc1c23389d68b18ccc26a53680ba2dc80ff2f"}, + {file = "pyzmq-26.2.0-cp39-cp39-macosx_10_15_universal2.whl", hash = "sha256:b1d464cb8d72bfc1a3adc53305a63a8e0cac6bc8c5a07e8ca190ab8d3faa43c2"}, + {file = "pyzmq-26.2.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:4da04c48873a6abdd71811c5e163bd656ee1b957971db7f35140a2d573f6949c"}, + {file = "pyzmq-26.2.0-cp39-cp39-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:d049df610ac811dcffdc147153b414147428567fbbc8be43bb8885f04db39d98"}, + {file = "pyzmq-26.2.0-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:05590cdbc6b902101d0e65d6a4780af14dc22914cc6ab995d99b85af45362cc9"}, + {file = "pyzmq-26.2.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c811cfcd6a9bf680236c40c6f617187515269ab2912f3d7e8c0174898e2519db"}, + {file = "pyzmq-26.2.0-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:6835dd60355593de10350394242b5757fbbd88b25287314316f266e24c61d073"}, + {file = "pyzmq-26.2.0-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:bc6bee759a6bddea5db78d7dcd609397449cb2d2d6587f48f3ca613b19410cfc"}, + {file = "pyzmq-26.2.0-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:c530e1eecd036ecc83c3407f77bb86feb79916d4a33d11394b8234f3bd35b940"}, + {file = "pyzmq-26.2.0-cp39-cp39-win32.whl", hash = "sha256:367b4f689786fca726ef7a6c5ba606958b145b9340a5e4808132cc65759abd44"}, + {file = "pyzmq-26.2.0-cp39-cp39-win_amd64.whl", hash = "sha256:e6fa2e3e683f34aea77de8112f6483803c96a44fd726d7358b9888ae5bb394ec"}, + {file = "pyzmq-26.2.0-cp39-cp39-win_arm64.whl", hash = "sha256:7445be39143a8aa4faec43b076e06944b8f9d0701b669df4af200531b21e40bb"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:706e794564bec25819d21a41c31d4df2d48e1cc4b061e8d345d7fb4dd3e94072"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8b435f2753621cd36e7c1762156815e21c985c72b19135dac43a7f4f31d28dd1"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:160c7e0a5eb178011e72892f99f918c04a131f36056d10d9c1afb223fc952c2d"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2c4a71d5d6e7b28a47a394c0471b7e77a0661e2d651e7ae91e0cab0a587859ca"}, + {file = "pyzmq-26.2.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:90412f2db8c02a3864cbfc67db0e3dcdbda336acf1c469526d3e869394fe001c"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:2ea4ad4e6a12e454de05f2949d4beddb52460f3de7c8b9d5c46fbb7d7222e02c"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:fc4f7a173a5609631bb0c42c23d12c49df3966f89f496a51d3eb0ec81f4519d6"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:878206a45202247781472a2d99df12a176fef806ca175799e1c6ad263510d57c"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:17c412bad2eb9468e876f556eb4ee910e62d721d2c7a53c7fa31e643d35352e6"}, + {file = "pyzmq-26.2.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:0d987a3ae5a71c6226b203cfd298720e0086c7fe7c74f35fa8edddfbd6597eed"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:39887ac397ff35b7b775db7201095fc6310a35fdbae85bac4523f7eb3b840e20"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-manylinux_2_12_i686.manylinux2010_i686.whl", hash = "sha256:fdb5b3e311d4d4b0eb8b3e8b4d1b0a512713ad7e6a68791d0923d1aec433d919"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:226af7dcb51fdb0109f0016449b357e182ea0ceb6b47dfb5999d569e5db161d5"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0bed0e799e6120b9c32756203fb9dfe8ca2fb8467fed830c34c877e25638c3fc"}, + {file = "pyzmq-26.2.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:29c7947c594e105cb9e6c466bace8532dc1ca02d498684128b339799f5248277"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:cdeabcff45d1c219636ee2e54d852262e5c2e085d6cb476d938aee8d921356b3"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:35cffef589bcdc587d06f9149f8d5e9e8859920a071df5a2671de2213bef592a"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:18c8dc3b7468d8b4bdf60ce9d7141897da103c7a4690157b32b60acb45e333e6"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7133d0a1677aec369d67dd78520d3fa96dd7f3dcec99d66c1762870e5ea1a50a"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-manylinux_2_28_x86_64.whl", hash = "sha256:6a96179a24b14fa6428cbfc08641c779a53f8fcec43644030328f44034c7f1f4"}, + {file = "pyzmq-26.2.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:4f78c88905461a9203eac9faac157a2a0dbba84a0fd09fd29315db27be40af9f"}, + {file = "pyzmq-26.2.0.tar.gz", hash = "sha256:070672c258581c8e4f640b5159297580a9974b026043bd4ab0470be9ed324f1f"}, +] + +[package.dependencies] +cffi = {version = "*", markers = "implementation_name == \"pypy\""} + +[[package]] +name = "referencing" +version = "0.35.1" +description = "JSON Referencing + Python" +optional = true +python-versions = ">=3.8" +files = [ + {file = "referencing-0.35.1-py3-none-any.whl", hash = "sha256:eda6d3234d62814d1c64e305c1331c9a3a6132da475ab6382eaa997b21ee75de"}, + {file = "referencing-0.35.1.tar.gz", hash = "sha256:25b42124a6c8b632a425174f24087783efb348a6f1e0008e63cd4466fedf703c"}, ] +[package.dependencies] +attrs = ">=22.2.0" +rpds-py = ">=0.7.0" + [[package]] name = "regex" -version = "2024.5.15" +version = "2024.9.11" description = "Alternative regular expression module, to replace re." optional = false python-versions = ">=3.8" files = [ - {file = "regex-2024.5.15-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:a81e3cfbae20378d75185171587cbf756015ccb14840702944f014e0d93ea09f"}, - {file = "regex-2024.5.15-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:7b59138b219ffa8979013be7bc85bb60c6f7b7575df3d56dc1e403a438c7a3f6"}, - {file = "regex-2024.5.15-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:a0bd000c6e266927cb7a1bc39d55be95c4b4f65c5be53e659537537e019232b1"}, - {file = "regex-2024.5.15-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:5eaa7ddaf517aa095fa8da0b5015c44d03da83f5bd49c87961e3c997daed0de7"}, - {file = "regex-2024.5.15-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ba68168daedb2c0bab7fd7e00ced5ba90aebf91024dea3c88ad5063c2a562cca"}, - {file = "regex-2024.5.15-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:6e8d717bca3a6e2064fc3a08df5cbe366369f4b052dcd21b7416e6d71620dca1"}, - {file = "regex-2024.5.15-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1337b7dbef9b2f71121cdbf1e97e40de33ff114801263b275aafd75303bd62b5"}, - {file = "regex-2024.5.15-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:f9ebd0a36102fcad2f03696e8af4ae682793a5d30b46c647eaf280d6cfb32796"}, - {file = "regex-2024.5.15-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:9efa1a32ad3a3ea112224897cdaeb6aa00381627f567179c0314f7b65d354c62"}, - {file = "regex-2024.5.15-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:1595f2d10dff3d805e054ebdc41c124753631b6a471b976963c7b28543cf13b0"}, - {file = "regex-2024.5.15-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:b802512f3e1f480f41ab5f2cfc0e2f761f08a1f41092d6718868082fc0d27143"}, - {file = "regex-2024.5.15-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:a0981022dccabca811e8171f913de05720590c915b033b7e601f35ce4ea7019f"}, - {file = "regex-2024.5.15-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:19068a6a79cf99a19ccefa44610491e9ca02c2be3305c7760d3831d38a467a6f"}, - {file = "regex-2024.5.15-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:1b5269484f6126eee5e687785e83c6b60aad7663dafe842b34691157e5083e53"}, - {file = "regex-2024.5.15-cp310-cp310-win32.whl", hash = "sha256:ada150c5adfa8fbcbf321c30c751dc67d2f12f15bd183ffe4ec7cde351d945b3"}, - {file = "regex-2024.5.15-cp310-cp310-win_amd64.whl", hash = "sha256:ac394ff680fc46b97487941f5e6ae49a9f30ea41c6c6804832063f14b2a5a145"}, - {file = "regex-2024.5.15-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:f5b1dff3ad008dccf18e652283f5e5339d70bf8ba7c98bf848ac33db10f7bc7a"}, - {file = "regex-2024.5.15-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:c6a2b494a76983df8e3d3feea9b9ffdd558b247e60b92f877f93a1ff43d26656"}, - {file = "regex-2024.5.15-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:a32b96f15c8ab2e7d27655969a23895eb799de3665fa94349f3b2fbfd547236f"}, - {file = "regex-2024.5.15-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:10002e86e6068d9e1c91eae8295ef690f02f913c57db120b58fdd35a6bb1af35"}, - {file = "regex-2024.5.15-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ec54d5afa89c19c6dd8541a133be51ee1017a38b412b1321ccb8d6ddbeb4cf7d"}, - {file = "regex-2024.5.15-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:10e4ce0dca9ae7a66e6089bb29355d4432caed736acae36fef0fdd7879f0b0cb"}, - {file = "regex-2024.5.15-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3e507ff1e74373c4d3038195fdd2af30d297b4f0950eeda6f515ae3d84a1770f"}, - {file = "regex-2024.5.15-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d1f059a4d795e646e1c37665b9d06062c62d0e8cc3c511fe01315973a6542e40"}, - {file = "regex-2024.5.15-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:0721931ad5fe0dda45d07f9820b90b2148ccdd8e45bb9e9b42a146cb4f695649"}, - {file = "regex-2024.5.15-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:833616ddc75ad595dee848ad984d067f2f31be645d603e4d158bba656bbf516c"}, - {file = "regex-2024.5.15-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:287eb7f54fc81546346207c533ad3c2c51a8d61075127d7f6d79aaf96cdee890"}, - {file = "regex-2024.5.15-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:19dfb1c504781a136a80ecd1fff9f16dddf5bb43cec6871778c8a907a085bb3d"}, - {file = "regex-2024.5.15-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:119af6e56dce35e8dfb5222573b50c89e5508d94d55713c75126b753f834de68"}, - {file = "regex-2024.5.15-cp311-cp311-win32.whl", hash = "sha256:1c1c174d6ec38d6c8a7504087358ce9213d4332f6293a94fbf5249992ba54efa"}, - {file = "regex-2024.5.15-cp311-cp311-win_amd64.whl", hash = "sha256:9e717956dcfd656f5055cc70996ee2cc82ac5149517fc8e1b60261b907740201"}, - {file = "regex-2024.5.15-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:632b01153e5248c134007209b5c6348a544ce96c46005d8456de1d552455b014"}, - {file = "regex-2024.5.15-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:e64198f6b856d48192bf921421fdd8ad8eb35e179086e99e99f711957ffedd6e"}, - {file = "regex-2024.5.15-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:68811ab14087b2f6e0fc0c2bae9ad689ea3584cad6917fc57be6a48bbd012c49"}, - {file = "regex-2024.5.15-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f8ec0c2fea1e886a19c3bee0cd19d862b3aa75dcdfb42ebe8ed30708df64687a"}, - {file = "regex-2024.5.15-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d0c0c0003c10f54a591d220997dd27d953cd9ccc1a7294b40a4be5312be8797b"}, - {file = "regex-2024.5.15-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2431b9e263af1953c55abbd3e2efca67ca80a3de8a0437cb58e2421f8184717a"}, - {file = "regex-2024.5.15-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4a605586358893b483976cffc1723fb0f83e526e8f14c6e6614e75919d9862cf"}, - {file = "regex-2024.5.15-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:391d7f7f1e409d192dba8bcd42d3e4cf9e598f3979cdaed6ab11288da88cb9f2"}, - {file = "regex-2024.5.15-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:9ff11639a8d98969c863d4617595eb5425fd12f7c5ef6621a4b74b71ed8726d5"}, - {file = "regex-2024.5.15-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:4eee78a04e6c67e8391edd4dad3279828dd66ac4b79570ec998e2155d2e59fd5"}, - {file = "regex-2024.5.15-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:8fe45aa3f4aa57faabbc9cb46a93363edd6197cbc43523daea044e9ff2fea83e"}, - {file = "regex-2024.5.15-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:d0a3d8d6acf0c78a1fff0e210d224b821081330b8524e3e2bc5a68ef6ab5803d"}, - {file = "regex-2024.5.15-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:c486b4106066d502495b3025a0a7251bf37ea9540433940a23419461ab9f2a80"}, - {file = "regex-2024.5.15-cp312-cp312-win32.whl", hash = "sha256:c49e15eac7c149f3670b3e27f1f28a2c1ddeccd3a2812cba953e01be2ab9b5fe"}, - {file = "regex-2024.5.15-cp312-cp312-win_amd64.whl", hash = "sha256:673b5a6da4557b975c6c90198588181029c60793835ce02f497ea817ff647cb2"}, - {file = "regex-2024.5.15-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:87e2a9c29e672fc65523fb47a90d429b70ef72b901b4e4b1bd42387caf0d6835"}, - {file = "regex-2024.5.15-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:c3bea0ba8b73b71b37ac833a7f3fd53825924165da6a924aec78c13032f20850"}, - {file = "regex-2024.5.15-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:bfc4f82cabe54f1e7f206fd3d30fda143f84a63fe7d64a81558d6e5f2e5aaba9"}, - {file = "regex-2024.5.15-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e5bb9425fe881d578aeca0b2b4b3d314ec88738706f66f219c194d67179337cb"}, - {file = "regex-2024.5.15-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:64c65783e96e563103d641760664125e91bd85d8e49566ee560ded4da0d3e704"}, - {file = "regex-2024.5.15-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:cf2430df4148b08fb4324b848672514b1385ae3807651f3567871f130a728cc3"}, - {file = "regex-2024.5.15-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5397de3219a8b08ae9540c48f602996aa6b0b65d5a61683e233af8605c42b0f2"}, - {file = "regex-2024.5.15-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:455705d34b4154a80ead722f4f185b04c4237e8e8e33f265cd0798d0e44825fa"}, - {file = "regex-2024.5.15-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:b2b6f1b3bb6f640c1a92be3bbfbcb18657b125b99ecf141fb3310b5282c7d4ed"}, - {file = "regex-2024.5.15-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:3ad070b823ca5890cab606c940522d05d3d22395d432f4aaaf9d5b1653e47ced"}, - {file = "regex-2024.5.15-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:5b5467acbfc153847d5adb21e21e29847bcb5870e65c94c9206d20eb4e99a384"}, - {file = "regex-2024.5.15-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:e6662686aeb633ad65be2a42b4cb00178b3fbf7b91878f9446075c404ada552f"}, - {file = "regex-2024.5.15-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:2b4c884767504c0e2401babe8b5b7aea9148680d2e157fa28f01529d1f7fcf67"}, - {file = "regex-2024.5.15-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:3cd7874d57f13bf70078f1ff02b8b0aa48d5b9ed25fc48547516c6aba36f5741"}, - {file = "regex-2024.5.15-cp38-cp38-win32.whl", hash = "sha256:e4682f5ba31f475d58884045c1a97a860a007d44938c4c0895f41d64481edbc9"}, - {file = "regex-2024.5.15-cp38-cp38-win_amd64.whl", hash = "sha256:d99ceffa25ac45d150e30bd9ed14ec6039f2aad0ffa6bb87a5936f5782fc1569"}, - {file = "regex-2024.5.15-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:13cdaf31bed30a1e1c2453ef6015aa0983e1366fad2667657dbcac7b02f67133"}, - {file = "regex-2024.5.15-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:cac27dcaa821ca271855a32188aa61d12decb6fe45ffe3e722401fe61e323cd1"}, - {file = "regex-2024.5.15-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:7dbe2467273b875ea2de38ded4eba86cbcbc9a1a6d0aa11dcf7bd2e67859c435"}, - {file = "regex-2024.5.15-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:64f18a9a3513a99c4bef0e3efd4c4a5b11228b48aa80743be822b71e132ae4f5"}, - {file = "regex-2024.5.15-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d347a741ea871c2e278fde6c48f85136c96b8659b632fb57a7d1ce1872547600"}, - {file = "regex-2024.5.15-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1878b8301ed011704aea4c806a3cadbd76f84dece1ec09cc9e4dc934cfa5d4da"}, - {file = "regex-2024.5.15-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4babf07ad476aaf7830d77000874d7611704a7fcf68c9c2ad151f5d94ae4bfc4"}, - {file = "regex-2024.5.15-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:35cb514e137cb3488bce23352af3e12fb0dbedd1ee6e60da053c69fb1b29cc6c"}, - {file = "regex-2024.5.15-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:cdd09d47c0b2efee9378679f8510ee6955d329424c659ab3c5e3a6edea696294"}, - {file = "regex-2024.5.15-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:72d7a99cd6b8f958e85fc6ca5b37c4303294954eac1376535b03c2a43eb72629"}, - {file = "regex-2024.5.15-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:a094801d379ab20c2135529948cb84d417a2169b9bdceda2a36f5f10977ebc16"}, - {file = "regex-2024.5.15-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:c0c18345010870e58238790a6779a1219b4d97bd2e77e1140e8ee5d14df071aa"}, - {file = "regex-2024.5.15-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:16093f563098448ff6b1fa68170e4acbef94e6b6a4e25e10eae8598bb1694b5d"}, - {file = "regex-2024.5.15-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:e38a7d4e8f633a33b4c7350fbd8bad3b70bf81439ac67ac38916c4a86b465456"}, - {file = "regex-2024.5.15-cp39-cp39-win32.whl", hash = "sha256:71a455a3c584a88f654b64feccc1e25876066c4f5ef26cd6dd711308aa538694"}, - {file = "regex-2024.5.15-cp39-cp39-win_amd64.whl", hash = "sha256:cab12877a9bdafde5500206d1020a584355a97884dfd388af3699e9137bf7388"}, - {file = "regex-2024.5.15.tar.gz", hash = "sha256:d3ee02d9e5f482cc8309134a91eeaacbdd2261ba111b0fef3748eeb4913e6a2c"}, + {file = "regex-2024.9.11-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:1494fa8725c285a81d01dc8c06b55287a1ee5e0e382d8413adc0a9197aac6408"}, + {file = "regex-2024.9.11-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:0e12c481ad92d129c78f13a2a3662317e46ee7ef96c94fd332e1c29131875b7d"}, + {file = "regex-2024.9.11-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:16e13a7929791ac1216afde26f712802e3df7bf0360b32e4914dca3ab8baeea5"}, + {file = "regex-2024.9.11-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:46989629904bad940bbec2106528140a218b4a36bb3042d8406980be1941429c"}, + {file = "regex-2024.9.11-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a906ed5e47a0ce5f04b2c981af1c9acf9e8696066900bf03b9d7879a6f679fc8"}, + {file = "regex-2024.9.11-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e9a091b0550b3b0207784a7d6d0f1a00d1d1c8a11699c1a4d93db3fbefc3ad35"}, + {file = "regex-2024.9.11-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5ddcd9a179c0a6fa8add279a4444015acddcd7f232a49071ae57fa6e278f1f71"}, + {file = "regex-2024.9.11-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6b41e1adc61fa347662b09398e31ad446afadff932a24807d3ceb955ed865cc8"}, + {file = "regex-2024.9.11-cp310-cp310-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:ced479f601cd2f8ca1fd7b23925a7e0ad512a56d6e9476f79b8f381d9d37090a"}, + {file = "regex-2024.9.11-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:635a1d96665f84b292e401c3d62775851aedc31d4f8784117b3c68c4fcd4118d"}, + {file = "regex-2024.9.11-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:c0256beda696edcf7d97ef16b2a33a8e5a875affd6fa6567b54f7c577b30a137"}, + {file = "regex-2024.9.11-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:3ce4f1185db3fbde8ed8aa223fc9620f276c58de8b0d4f8cc86fd1360829edb6"}, + {file = "regex-2024.9.11-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:09d77559e80dcc9d24570da3745ab859a9cf91953062e4ab126ba9d5993688ca"}, + {file = "regex-2024.9.11-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:7a22ccefd4db3f12b526eccb129390942fe874a3a9fdbdd24cf55773a1faab1a"}, + {file = "regex-2024.9.11-cp310-cp310-win32.whl", hash = "sha256:f745ec09bc1b0bd15cfc73df6fa4f726dcc26bb16c23a03f9e3367d357eeedd0"}, + {file = "regex-2024.9.11-cp310-cp310-win_amd64.whl", hash = "sha256:01c2acb51f8a7d6494c8c5eafe3d8e06d76563d8a8a4643b37e9b2dd8a2ff623"}, + {file = "regex-2024.9.11-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:2cce2449e5927a0bf084d346da6cd5eb016b2beca10d0013ab50e3c226ffc0df"}, + {file = "regex-2024.9.11-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:3b37fa423beefa44919e009745ccbf353d8c981516e807995b2bd11c2c77d268"}, + {file = "regex-2024.9.11-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:64ce2799bd75039b480cc0360907c4fb2f50022f030bf9e7a8705b636e408fad"}, + {file = "regex-2024.9.11-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a4cc92bb6db56ab0c1cbd17294e14f5e9224f0cc6521167ef388332604e92679"}, + {file = "regex-2024.9.11-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d05ac6fa06959c4172eccd99a222e1fbf17b5670c4d596cb1e5cde99600674c4"}, + {file = "regex-2024.9.11-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:040562757795eeea356394a7fb13076ad4f99d3c62ab0f8bdfb21f99a1f85664"}, + {file = "regex-2024.9.11-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6113c008a7780792efc80f9dfe10ba0cd043cbf8dc9a76ef757850f51b4edc50"}, + {file = "regex-2024.9.11-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8e5fb5f77c8745a60105403a774fe2c1759b71d3e7b4ca237a5e67ad066c7199"}, + {file = "regex-2024.9.11-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:54d9ff35d4515debf14bc27f1e3b38bfc453eff3220f5bce159642fa762fe5d4"}, + {file = "regex-2024.9.11-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:df5cbb1fbc74a8305b6065d4ade43b993be03dbe0f8b30032cced0d7740994bd"}, + {file = "regex-2024.9.11-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:7fb89ee5d106e4a7a51bce305ac4efb981536301895f7bdcf93ec92ae0d91c7f"}, + {file = "regex-2024.9.11-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:a738b937d512b30bf75995c0159c0ddf9eec0775c9d72ac0202076c72f24aa96"}, + {file = "regex-2024.9.11-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:e28f9faeb14b6f23ac55bfbbfd3643f5c7c18ede093977f1df249f73fd22c7b1"}, + {file = "regex-2024.9.11-cp311-cp311-win32.whl", hash = "sha256:18e707ce6c92d7282dfce370cd205098384b8ee21544e7cb29b8aab955b66fa9"}, + {file = "regex-2024.9.11-cp311-cp311-win_amd64.whl", hash = "sha256:313ea15e5ff2a8cbbad96ccef6be638393041b0a7863183c2d31e0c6116688cf"}, + {file = "regex-2024.9.11-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:b0d0a6c64fcc4ef9c69bd5b3b3626cc3776520a1637d8abaa62b9edc147a58f7"}, + {file = "regex-2024.9.11-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:49b0e06786ea663f933f3710a51e9385ce0cba0ea56b67107fd841a55d56a231"}, + {file = "regex-2024.9.11-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:5b513b6997a0b2f10e4fd3a1313568e373926e8c252bd76c960f96fd039cd28d"}, + {file = "regex-2024.9.11-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ee439691d8c23e76f9802c42a95cfeebf9d47cf4ffd06f18489122dbb0a7ad64"}, + {file = "regex-2024.9.11-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:a8f877c89719d759e52783f7fe6e1c67121076b87b40542966c02de5503ace42"}, + {file = "regex-2024.9.11-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:23b30c62d0f16827f2ae9f2bb87619bc4fba2044911e2e6c2eb1af0161cdb766"}, + {file = "regex-2024.9.11-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:85ab7824093d8f10d44330fe1e6493f756f252d145323dd17ab6b48733ff6c0a"}, + {file = "regex-2024.9.11-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8dee5b4810a89447151999428fe096977346cf2f29f4d5e29609d2e19e0199c9"}, + {file = "regex-2024.9.11-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:98eeee2f2e63edae2181c886d7911ce502e1292794f4c5ee71e60e23e8d26b5d"}, + {file = "regex-2024.9.11-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:57fdd2e0b2694ce6fc2e5ccf189789c3e2962916fb38779d3e3521ff8fe7a822"}, + {file = "regex-2024.9.11-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:d552c78411f60b1fdaafd117a1fca2f02e562e309223b9d44b7de8be451ec5e0"}, + {file = "regex-2024.9.11-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:a0b2b80321c2ed3fcf0385ec9e51a12253c50f146fddb2abbb10f033fe3d049a"}, + {file = "regex-2024.9.11-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:18406efb2f5a0e57e3a5881cd9354c1512d3bb4f5c45d96d110a66114d84d23a"}, + {file = "regex-2024.9.11-cp312-cp312-win32.whl", hash = "sha256:e464b467f1588e2c42d26814231edecbcfe77f5ac414d92cbf4e7b55b2c2a776"}, + {file = "regex-2024.9.11-cp312-cp312-win_amd64.whl", hash = "sha256:9e8719792ca63c6b8340380352c24dcb8cd7ec49dae36e963742a275dfae6009"}, + {file = "regex-2024.9.11-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:c157bb447303070f256e084668b702073db99bbb61d44f85d811025fcf38f784"}, + {file = "regex-2024.9.11-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:4db21ece84dfeefc5d8a3863f101995de646c6cb0536952c321a2650aa202c36"}, + {file = "regex-2024.9.11-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:220e92a30b426daf23bb67a7962900ed4613589bab80382be09b48896d211e92"}, + {file = "regex-2024.9.11-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:eb1ae19e64c14c7ec1995f40bd932448713d3c73509e82d8cd7744dc00e29e86"}, + {file = "regex-2024.9.11-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:f47cd43a5bfa48f86925fe26fbdd0a488ff15b62468abb5d2a1e092a4fb10e85"}, + {file = "regex-2024.9.11-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9d4a76b96f398697fe01117093613166e6aa8195d63f1b4ec3f21ab637632963"}, + {file = "regex-2024.9.11-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0ea51dcc0835eea2ea31d66456210a4e01a076d820e9039b04ae8d17ac11dee6"}, + {file = "regex-2024.9.11-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:b7aaa315101c6567a9a45d2839322c51c8d6e81f67683d529512f5bcfb99c802"}, + {file = "regex-2024.9.11-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:c57d08ad67aba97af57a7263c2d9006d5c404d721c5f7542f077f109ec2a4a29"}, + {file = "regex-2024.9.11-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:f8404bf61298bb6f8224bb9176c1424548ee1181130818fcd2cbffddc768bed8"}, + {file = "regex-2024.9.11-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:dd4490a33eb909ef5078ab20f5f000087afa2a4daa27b4c072ccb3cb3050ad84"}, + {file = "regex-2024.9.11-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:eee9130eaad130649fd73e5cd92f60e55708952260ede70da64de420cdcad554"}, + {file = "regex-2024.9.11-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:6a2644a93da36c784e546de579ec1806bfd2763ef47babc1b03d765fe560c9f8"}, + {file = "regex-2024.9.11-cp313-cp313-win32.whl", hash = "sha256:e997fd30430c57138adc06bba4c7c2968fb13d101e57dd5bb9355bf8ce3fa7e8"}, + {file = "regex-2024.9.11-cp313-cp313-win_amd64.whl", hash = "sha256:042c55879cfeb21a8adacc84ea347721d3d83a159da6acdf1116859e2427c43f"}, + {file = "regex-2024.9.11-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:35f4a6f96aa6cb3f2f7247027b07b15a374f0d5b912c0001418d1d55024d5cb4"}, + {file = "regex-2024.9.11-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:55b96e7ce3a69a8449a66984c268062fbaa0d8ae437b285428e12797baefce7e"}, + {file = "regex-2024.9.11-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:cb130fccd1a37ed894824b8c046321540263013da72745d755f2d35114b81a60"}, + {file = "regex-2024.9.11-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:323c1f04be6b2968944d730e5c2091c8c89767903ecaa135203eec4565ed2b2b"}, + {file = "regex-2024.9.11-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:be1c8ed48c4c4065ecb19d882a0ce1afe0745dfad8ce48c49586b90a55f02366"}, + {file = "regex-2024.9.11-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b5b029322e6e7b94fff16cd120ab35a253236a5f99a79fb04fda7ae71ca20ae8"}, + {file = "regex-2024.9.11-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f6fff13ef6b5f29221d6904aa816c34701462956aa72a77f1f151a8ec4f56aeb"}, + {file = "regex-2024.9.11-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:587d4af3979376652010e400accc30404e6c16b7df574048ab1f581af82065e4"}, + {file = "regex-2024.9.11-cp38-cp38-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:079400a8269544b955ffa9e31f186f01d96829110a3bf79dc338e9910f794fca"}, + {file = "regex-2024.9.11-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:f9268774428ec173654985ce55fc6caf4c6d11ade0f6f914d48ef4719eb05ebb"}, + {file = "regex-2024.9.11-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:23f9985c8784e544d53fc2930fc1ac1a7319f5d5332d228437acc9f418f2f168"}, + {file = "regex-2024.9.11-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:ae2941333154baff9838e88aa71c1d84f4438189ecc6021a12c7573728b5838e"}, + {file = "regex-2024.9.11-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:e93f1c331ca8e86fe877a48ad64e77882c0c4da0097f2212873a69bbfea95d0c"}, + {file = "regex-2024.9.11-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:846bc79ee753acf93aef4184c040d709940c9d001029ceb7b7a52747b80ed2dd"}, + {file = "regex-2024.9.11-cp38-cp38-win32.whl", hash = "sha256:c94bb0a9f1db10a1d16c00880bdebd5f9faf267273b8f5bd1878126e0fbde771"}, + {file = "regex-2024.9.11-cp38-cp38-win_amd64.whl", hash = "sha256:2b08fce89fbd45664d3df6ad93e554b6c16933ffa9d55cb7e01182baaf971508"}, + {file = "regex-2024.9.11-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:07f45f287469039ffc2c53caf6803cd506eb5f5f637f1d4acb37a738f71dd066"}, + {file = "regex-2024.9.11-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:4838e24ee015101d9f901988001038f7f0d90dc0c3b115541a1365fb439add62"}, + {file = "regex-2024.9.11-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:6edd623bae6a737f10ce853ea076f56f507fd7726bee96a41ee3d68d347e4d16"}, + {file = "regex-2024.9.11-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c69ada171c2d0e97a4b5aa78fbb835e0ffbb6b13fc5da968c09811346564f0d3"}, + {file = "regex-2024.9.11-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:02087ea0a03b4af1ed6ebab2c54d7118127fee8d71b26398e8e4b05b78963199"}, + {file = "regex-2024.9.11-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:69dee6a020693d12a3cf892aba4808fe168d2a4cef368eb9bf74f5398bfd4ee8"}, + {file = "regex-2024.9.11-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:297f54910247508e6e5cae669f2bc308985c60540a4edd1c77203ef19bfa63ca"}, + {file = "regex-2024.9.11-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ecea58b43a67b1b79805f1a0255730edaf5191ecef84dbc4cc85eb30bc8b63b9"}, + {file = "regex-2024.9.11-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl", hash = "sha256:eab4bb380f15e189d1313195b062a6aa908f5bd687a0ceccd47c8211e9cf0d4a"}, + {file = "regex-2024.9.11-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:0cbff728659ce4bbf4c30b2a1be040faafaa9eca6ecde40aaff86f7889f4ab39"}, + {file = "regex-2024.9.11-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:54c4a097b8bc5bb0dfc83ae498061d53ad7b5762e00f4adaa23bee22b012e6ba"}, + {file = "regex-2024.9.11-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:73d6d2f64f4d894c96626a75578b0bf7d9e56dcda8c3d037a2118fdfe9b1c664"}, + {file = "regex-2024.9.11-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:e53b5fbab5d675aec9f0c501274c467c0f9a5d23696cfc94247e1fb56501ed89"}, + {file = "regex-2024.9.11-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:0ffbcf9221e04502fc35e54d1ce9567541979c3fdfb93d2c554f0ca583a19b35"}, + {file = "regex-2024.9.11-cp39-cp39-win32.whl", hash = "sha256:e4c22e1ac1f1ec1e09f72e6c44d8f2244173db7eb9629cc3a346a8d7ccc31142"}, + {file = "regex-2024.9.11-cp39-cp39-win_amd64.whl", hash = "sha256:faa3c142464efec496967359ca99696c896c591c56c53506bac1ad465f66e919"}, + {file = "regex-2024.9.11.tar.gz", hash = "sha256:6c188c307e8433bcb63dc1915022deb553b4203a70722fc542c363bf120a01fd"}, +] + +[[package]] +name = "renamed-opencv-python-inference-engine" +version = "2022.1.5" +description = "Wrapper package for OpenCV with Inference Engine python bindings, but compiled under another namespace to prevent conflicts with the default OpenCV python packages" +optional = true +python-versions = "*" +files = [ + {file = "renamed_opencv_python_inference_engine-2022.1.5-py3-none-manylinux1_x86_64.whl", hash = "sha256:c92666acfd75f8b29b9f1aa566d4ad3851387fcea3992f113f72adf449477523"}, ] +[package.dependencies] +numpy = "*" + [[package]] name = "requests" version = "2.32.3" @@ -3493,16 +5740,16 @@ use-chardet-on-py3 = ["chardet (>=3.0.2,<6)"] [[package]] name = "rerun-sdk" -version = "0.17.0" +version = "0.18.2" description = "The Rerun Logging SDK" optional = false python-versions = "<3.13,>=3.8" files = [ - {file = "rerun_sdk-0.17.0-cp38-abi3-macosx_10_12_x86_64.whl", hash = "sha256:abd34f746eada83b8bb0bc50007183151981d7ccf18306f3d42165819a3f6fcb"}, - {file = "rerun_sdk-0.17.0-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:8b0a8a6feab3f8e679801d158216a71d88a81480021587719330f50d083c4d26"}, - {file = "rerun_sdk-0.17.0-cp38-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:ad55807abafb01e527846742e087819aac8e103f1ec15aadc563a4038bb44e1d"}, - {file = "rerun_sdk-0.17.0-cp38-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:9d41f1f475270b1e0d50ddb8cb62e0d828988f0c371ac8457af25c8be5aa1dc0"}, - {file = "rerun_sdk-0.17.0-cp38-abi3-win_amd64.whl", hash = "sha256:34e5595a326cbdddfebdf00b08e877358c564fce74cc8c6d617fc89ef3a6aa70"}, + {file = "rerun_sdk-0.18.2-cp38-abi3-macosx_10_12_x86_64.whl", hash = "sha256:bc4e73275f428e4e9feb8e85f88db7a9fd18b997b1570de62f949a926978f1b2"}, + {file = "rerun_sdk-0.18.2-cp38-abi3-macosx_11_0_arm64.whl", hash = "sha256:efbba40a59710ae83607cb0dc140398a35979c2d2acf5190c9def2ac4697f6a8"}, + {file = "rerun_sdk-0.18.2-cp38-abi3-manylinux_2_31_aarch64.whl", hash = "sha256:2a5e3b618b6d1bfde09bd5614a898995f3c318cc69d8f6d569924a2cd41536ce"}, + {file = "rerun_sdk-0.18.2-cp38-abi3-manylinux_2_31_x86_64.whl", hash = "sha256:8fdfc4c51ef2e75cb68d39e56f0d7c196eff250cb9a0260c07d5e2d6736e31b0"}, + {file = "rerun_sdk-0.18.2-cp38-abi3-win_amd64.whl", hash = "sha256:c929ade91d3be301b26671b25e70fb529524ced915523d266641c6fc667a1eb5"}, ] [package.dependencies] @@ -3513,116 +5760,308 @@ pyarrow = ">=14.0.2" typing-extensions = ">=4.5" [package.extras] -notebook = ["rerun-notebook (==0.17.0)"] +notebook = ["rerun-notebook (==0.18.2)"] tests = ["pytest (==7.1.2)"] +[[package]] +name = "retrying" +version = "1.3.4" +description = "Retrying" +optional = true +python-versions = "*" +files = [ + {file = "retrying-1.3.4-py3-none-any.whl", hash = "sha256:8cc4d43cb8e1125e0ff3344e9de678fefd85db3b750b81b2240dc0183af37b35"}, + {file = "retrying-1.3.4.tar.gz", hash = "sha256:345da8c5765bd982b1d1915deb9102fd3d1f7ad16bd84a9700b85f64d24e8f3e"}, +] + +[package.dependencies] +six = ">=1.7.0" + +[[package]] +name = "rfc3339-validator" +version = "0.1.4" +description = "A pure python RFC3339 validator" +optional = true +python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" +files = [ + {file = "rfc3339_validator-0.1.4-py2.py3-none-any.whl", hash = "sha256:24f6ec1eda14ef823da9e36ec7113124b39c04d50a4d3d3a3c2859577e7791fa"}, + {file = "rfc3339_validator-0.1.4.tar.gz", hash = "sha256:138a2abdf93304ad60530167e51d2dfb9549521a836871b88d7f4695d0022f6b"}, +] + +[package.dependencies] +six = "*" + +[[package]] +name = "rfc3986-validator" +version = "0.1.1" +description = "Pure python rfc3986 validator" +optional = true +python-versions = ">=2.7, !=3.0.*, !=3.1.*, !=3.2.*, !=3.3.*, !=3.4.*" +files = [ + {file = "rfc3986_validator-0.1.1-py2.py3-none-any.whl", hash = "sha256:2f235c432ef459970b4306369336b9d5dbdda31b510ca1e327636e01f528bfa9"}, + {file = "rfc3986_validator-0.1.1.tar.gz", hash = "sha256:3d44bde7921b3b9ec3ae4e3adca370438eccebc676456449b145d533b240d055"}, +] + +[[package]] +name = "rich" +version = "13.8.1" +description = "Render rich text, tables, progress bars, syntax highlighting, markdown and more to the terminal" +optional = true +python-versions = ">=3.7.0" +files = [ + {file = "rich-13.8.1-py3-none-any.whl", hash = "sha256:1760a3c0848469b97b558fc61c85233e3dafb69c7a071b4d60c38099d3cd4c06"}, + {file = "rich-13.8.1.tar.gz", hash = "sha256:8260cda28e3db6bf04d2d1ef4dbc03ba80a824c88b0e7668a0f23126a424844a"}, +] + +[package.dependencies] +markdown-it-py = ">=2.2.0" +pygments = ">=2.13.0,<3.0.0" + +[package.extras] +jupyter = ["ipywidgets (>=7.5.1,<9)"] + +[[package]] +name = "rpds-py" +version = "0.20.0" +description = "Python bindings to Rust's persistent data structures (rpds)" +optional = true +python-versions = ">=3.8" +files = [ + {file = "rpds_py-0.20.0-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:3ad0fda1635f8439cde85c700f964b23ed5fc2d28016b32b9ee5fe30da5c84e2"}, + {file = "rpds_py-0.20.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:9bb4a0d90fdb03437c109a17eade42dfbf6190408f29b2744114d11586611d6f"}, + {file = "rpds_py-0.20.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c6377e647bbfd0a0b159fe557f2c6c602c159fc752fa316572f012fc0bf67150"}, + {file = "rpds_py-0.20.0-cp310-cp310-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:eb851b7df9dda52dc1415ebee12362047ce771fc36914586b2e9fcbd7d293b3e"}, + {file = "rpds_py-0.20.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:1e0f80b739e5a8f54837be5d5c924483996b603d5502bfff79bf33da06164ee2"}, + {file = "rpds_py-0.20.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5a8c94dad2e45324fc74dce25e1645d4d14df9a4e54a30fa0ae8bad9a63928e3"}, + {file = "rpds_py-0.20.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f8e604fe73ba048c06085beaf51147eaec7df856824bfe7b98657cf436623daf"}, + {file = "rpds_py-0.20.0-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:df3de6b7726b52966edf29663e57306b23ef775faf0ac01a3e9f4012a24a4140"}, + {file = "rpds_py-0.20.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:cf258ede5bc22a45c8e726b29835b9303c285ab46fc7c3a4cc770736b5304c9f"}, + {file = "rpds_py-0.20.0-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:55fea87029cded5df854ca7e192ec7bdb7ecd1d9a3f63d5c4eb09148acf4a7ce"}, + {file = "rpds_py-0.20.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:ae94bd0b2f02c28e199e9bc51485d0c5601f58780636185660f86bf80c89af94"}, + {file = "rpds_py-0.20.0-cp310-none-win32.whl", hash = "sha256:28527c685f237c05445efec62426d285e47a58fb05ba0090a4340b73ecda6dee"}, + {file = "rpds_py-0.20.0-cp310-none-win_amd64.whl", hash = "sha256:238a2d5b1cad28cdc6ed15faf93a998336eb041c4e440dd7f902528b8891b399"}, + {file = "rpds_py-0.20.0-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:ac2f4f7a98934c2ed6505aead07b979e6f999389f16b714448fb39bbaa86a489"}, + {file = "rpds_py-0.20.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:220002c1b846db9afd83371d08d239fdc865e8f8c5795bbaec20916a76db3318"}, + {file = "rpds_py-0.20.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8d7919548df3f25374a1f5d01fbcd38dacab338ef5f33e044744b5c36729c8db"}, + {file = "rpds_py-0.20.0-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:758406267907b3781beee0f0edfe4a179fbd97c0be2e9b1154d7f0a1279cf8e5"}, + {file = "rpds_py-0.20.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:3d61339e9f84a3f0767b1995adfb171a0d00a1185192718a17af6e124728e0f5"}, + {file = "rpds_py-0.20.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1259c7b3705ac0a0bd38197565a5d603218591d3f6cee6e614e380b6ba61c6f6"}, + {file = "rpds_py-0.20.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5c1dc0f53856b9cc9a0ccca0a7cc61d3d20a7088201c0937f3f4048c1718a209"}, + {file = "rpds_py-0.20.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:7e60cb630f674a31f0368ed32b2a6b4331b8350d67de53c0359992444b116dd3"}, + {file = "rpds_py-0.20.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:dbe982f38565bb50cb7fb061ebf762c2f254ca3d8c20d4006878766e84266272"}, + {file = "rpds_py-0.20.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:514b3293b64187172bc77c8fb0cdae26981618021053b30d8371c3a902d4d5ad"}, + {file = "rpds_py-0.20.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:d0a26ffe9d4dd35e4dfdd1e71f46401cff0181c75ac174711ccff0459135fa58"}, + {file = "rpds_py-0.20.0-cp311-none-win32.whl", hash = "sha256:89c19a494bf3ad08c1da49445cc5d13d8fefc265f48ee7e7556839acdacf69d0"}, + {file = "rpds_py-0.20.0-cp311-none-win_amd64.whl", hash = "sha256:c638144ce971df84650d3ed0096e2ae7af8e62ecbbb7b201c8935c370df00a2c"}, + {file = "rpds_py-0.20.0-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:a84ab91cbe7aab97f7446652d0ed37d35b68a465aeef8fc41932a9d7eee2c1a6"}, + {file = "rpds_py-0.20.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:56e27147a5a4c2c21633ff8475d185734c0e4befd1c989b5b95a5d0db699b21b"}, + {file = "rpds_py-0.20.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2580b0c34583b85efec8c5c5ec9edf2dfe817330cc882ee972ae650e7b5ef739"}, + {file = "rpds_py-0.20.0-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:b80d4a7900cf6b66bb9cee5c352b2d708e29e5a37fe9bf784fa97fc11504bf6c"}, + {file = "rpds_py-0.20.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:50eccbf054e62a7b2209b28dc7a22d6254860209d6753e6b78cfaeb0075d7bee"}, + {file = "rpds_py-0.20.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:49a8063ea4296b3a7e81a5dfb8f7b2d73f0b1c20c2af401fb0cdf22e14711a96"}, + {file = "rpds_py-0.20.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ea438162a9fcbee3ecf36c23e6c68237479f89f962f82dae83dc15feeceb37e4"}, + {file = "rpds_py-0.20.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:18d7585c463087bddcfa74c2ba267339f14f2515158ac4db30b1f9cbdb62c8ef"}, + {file = "rpds_py-0.20.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:d4c7d1a051eeb39f5c9547e82ea27cbcc28338482242e3e0b7768033cb083821"}, + {file = "rpds_py-0.20.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:e4df1e3b3bec320790f699890d41c59d250f6beda159ea3c44c3f5bac1976940"}, + {file = "rpds_py-0.20.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:2cf126d33a91ee6eedc7f3197b53e87a2acdac63602c0f03a02dd69e4b138174"}, + {file = "rpds_py-0.20.0-cp312-none-win32.whl", hash = "sha256:8bc7690f7caee50b04a79bf017a8d020c1f48c2a1077ffe172abec59870f1139"}, + {file = "rpds_py-0.20.0-cp312-none-win_amd64.whl", hash = "sha256:0e13e6952ef264c40587d510ad676a988df19adea20444c2b295e536457bc585"}, + {file = "rpds_py-0.20.0-cp313-cp313-macosx_10_12_x86_64.whl", hash = "sha256:aa9a0521aeca7d4941499a73ad7d4f8ffa3d1affc50b9ea11d992cd7eff18a29"}, + {file = "rpds_py-0.20.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:4a1f1d51eccb7e6c32ae89243cb352389228ea62f89cd80823ea7dd1b98e0b91"}, + {file = "rpds_py-0.20.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:8a86a9b96070674fc88b6f9f71a97d2c1d3e5165574615d1f9168ecba4cecb24"}, + {file = "rpds_py-0.20.0-cp313-cp313-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:6c8ef2ebf76df43f5750b46851ed1cdf8f109d7787ca40035fe19fbdc1acc5a7"}, + {file = "rpds_py-0.20.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b74b25f024b421d5859d156750ea9a65651793d51b76a2e9238c05c9d5f203a9"}, + {file = "rpds_py-0.20.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:57eb94a8c16ab08fef6404301c38318e2c5a32216bf5de453e2714c964c125c8"}, + {file = "rpds_py-0.20.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e1940dae14e715e2e02dfd5b0f64a52e8374a517a1e531ad9412319dc3ac7879"}, + {file = "rpds_py-0.20.0-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:d20277fd62e1b992a50c43f13fbe13277a31f8c9f70d59759c88f644d66c619f"}, + {file = "rpds_py-0.20.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:06db23d43f26478303e954c34c75182356ca9aa7797d22c5345b16871ab9c45c"}, + {file = "rpds_py-0.20.0-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:b2a5db5397d82fa847e4c624b0c98fe59d2d9b7cf0ce6de09e4d2e80f8f5b3f2"}, + {file = "rpds_py-0.20.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:5a35df9f5548fd79cb2f52d27182108c3e6641a4feb0f39067911bf2adaa3e57"}, + {file = "rpds_py-0.20.0-cp313-none-win32.whl", hash = "sha256:fd2d84f40633bc475ef2d5490b9c19543fbf18596dcb1b291e3a12ea5d722f7a"}, + {file = "rpds_py-0.20.0-cp313-none-win_amd64.whl", hash = "sha256:9bc2d153989e3216b0559251b0c260cfd168ec78b1fac33dd485750a228db5a2"}, + {file = "rpds_py-0.20.0-cp38-cp38-macosx_10_12_x86_64.whl", hash = "sha256:f2fbf7db2012d4876fb0d66b5b9ba6591197b0f165db8d99371d976546472a24"}, + {file = "rpds_py-0.20.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:1e5f3cd7397c8f86c8cc72d5a791071431c108edd79872cdd96e00abd8497d29"}, + {file = "rpds_py-0.20.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ce9845054c13696f7af7f2b353e6b4f676dab1b4b215d7fe5e05c6f8bb06f965"}, + {file = "rpds_py-0.20.0-cp38-cp38-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:c3e130fd0ec56cb76eb49ef52faead8ff09d13f4527e9b0c400307ff72b408e1"}, + {file = "rpds_py-0.20.0-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4b16aa0107ecb512b568244ef461f27697164d9a68d8b35090e9b0c1c8b27752"}, + {file = "rpds_py-0.20.0-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:aa7f429242aae2947246587d2964fad750b79e8c233a2367f71b554e9447949c"}, + {file = "rpds_py-0.20.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:af0fc424a5842a11e28956e69395fbbeab2c97c42253169d87e90aac2886d751"}, + {file = "rpds_py-0.20.0-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:b8c00a3b1e70c1d3891f0db1b05292747f0dbcfb49c43f9244d04c70fbc40eb8"}, + {file = "rpds_py-0.20.0-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:40ce74fc86ee4645d0a225498d091d8bc61f39b709ebef8204cb8b5a464d3c0e"}, + {file = "rpds_py-0.20.0-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:4fe84294c7019456e56d93e8ababdad5a329cd25975be749c3f5f558abb48253"}, + {file = "rpds_py-0.20.0-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:338ca4539aad4ce70a656e5187a3a31c5204f261aef9f6ab50e50bcdffaf050a"}, + {file = "rpds_py-0.20.0-cp38-none-win32.whl", hash = "sha256:54b43a2b07db18314669092bb2de584524d1ef414588780261e31e85846c26a5"}, + {file = "rpds_py-0.20.0-cp38-none-win_amd64.whl", hash = "sha256:a1862d2d7ce1674cffa6d186d53ca95c6e17ed2b06b3f4c476173565c862d232"}, + {file = "rpds_py-0.20.0-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:3fde368e9140312b6e8b6c09fb9f8c8c2f00999d1823403ae90cc00480221b22"}, + {file = "rpds_py-0.20.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:9824fb430c9cf9af743cf7aaf6707bf14323fb51ee74425c380f4c846ea70789"}, + {file = "rpds_py-0.20.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:11ef6ce74616342888b69878d45e9f779b95d4bd48b382a229fe624a409b72c5"}, + {file = "rpds_py-0.20.0-cp39-cp39-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:c52d3f2f82b763a24ef52f5d24358553e8403ce05f893b5347098014f2d9eff2"}, + {file = "rpds_py-0.20.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9d35cef91e59ebbeaa45214861874bc6f19eb35de96db73e467a8358d701a96c"}, + {file = "rpds_py-0.20.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d72278a30111e5b5525c1dd96120d9e958464316f55adb030433ea905866f4de"}, + {file = "rpds_py-0.20.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b4c29cbbba378759ac5786730d1c3cb4ec6f8ababf5c42a9ce303dc4b3d08cda"}, + {file = "rpds_py-0.20.0-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:6632f2d04f15d1bd6fe0eedd3b86d9061b836ddca4c03d5cf5c7e9e6b7c14580"}, + {file = "rpds_py-0.20.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:d0b67d87bb45ed1cd020e8fbf2307d449b68abc45402fe1a4ac9e46c3c8b192b"}, + {file = "rpds_py-0.20.0-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:ec31a99ca63bf3cd7f1a5ac9fe95c5e2d060d3c768a09bc1d16e235840861420"}, + {file = "rpds_py-0.20.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:22e6c9976e38f4d8c4a63bd8a8edac5307dffd3ee7e6026d97f3cc3a2dc02a0b"}, + {file = "rpds_py-0.20.0-cp39-none-win32.whl", hash = "sha256:569b3ea770c2717b730b61998b6c54996adee3cef69fc28d444f3e7920313cf7"}, + {file = "rpds_py-0.20.0-cp39-none-win_amd64.whl", hash = "sha256:e6900ecdd50ce0facf703f7a00df12374b74bbc8ad9fe0f6559947fb20f82364"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-macosx_10_12_x86_64.whl", hash = "sha256:617c7357272c67696fd052811e352ac54ed1d9b49ab370261a80d3b6ce385045"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:9426133526f69fcaba6e42146b4e12d6bc6c839b8b555097020e2b78ce908dcc"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:deb62214c42a261cb3eb04d474f7155279c1a8a8c30ac89b7dcb1721d92c3c02"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:fcaeb7b57f1a1e071ebd748984359fef83ecb026325b9d4ca847c95bc7311c92"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d454b8749b4bd70dd0a79f428731ee263fa6995f83ccb8bada706e8d1d3ff89d"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d807dc2051abe041b6649681dce568f8e10668e3c1c6543ebae58f2d7e617855"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c3c20f0ddeb6e29126d45f89206b8291352b8c5b44384e78a6499d68b52ae511"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:b7f19250ceef892adf27f0399b9e5afad019288e9be756d6919cb58892129f51"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-musllinux_1_2_aarch64.whl", hash = "sha256:4f1ed4749a08379555cebf4650453f14452eaa9c43d0a95c49db50c18b7da075"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-musllinux_1_2_i686.whl", hash = "sha256:dcedf0b42bcb4cfff4101d7771a10532415a6106062f005ab97d1d0ab5681c60"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-musllinux_1_2_x86_64.whl", hash = "sha256:39ed0d010457a78f54090fafb5d108501b5aa5604cc22408fc1c0c77eac14344"}, + {file = "rpds_py-0.20.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:bb273176be34a746bdac0b0d7e4e2c467323d13640b736c4c477881a3220a989"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-macosx_10_12_x86_64.whl", hash = "sha256:f918a1a130a6dfe1d7fe0f105064141342e7dd1611f2e6a21cd2f5c8cb1cfb3e"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:f60012a73aa396be721558caa3a6fd49b3dd0033d1675c6d59c4502e870fcf0c"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3d2b1ad682a3dfda2a4e8ad8572f3100f95fad98cb99faf37ff0ddfe9cbf9d03"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:614fdafe9f5f19c63ea02817fa4861c606a59a604a77c8cdef5aa01d28b97921"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fa518bcd7600c584bf42e6617ee8132869e877db2f76bcdc281ec6a4113a53ab"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f0475242f447cc6cb8a9dd486d68b2ef7fbee84427124c232bff5f63b1fe11e5"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f90a4cd061914a60bd51c68bcb4357086991bd0bb93d8aa66a6da7701370708f"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:def7400461c3a3f26e49078302e1c1b38f6752342c77e3cf72ce91ca69fb1bc1"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-musllinux_1_2_aarch64.whl", hash = "sha256:65794e4048ee837494aea3c21a28ad5fc080994dfba5b036cf84de37f7ad5074"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-musllinux_1_2_i686.whl", hash = "sha256:faefcc78f53a88f3076b7f8be0a8f8d35133a3ecf7f3770895c25f8813460f08"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-musllinux_1_2_x86_64.whl", hash = "sha256:5b4f105deeffa28bbcdff6c49b34e74903139afa690e35d2d9e3c2c2fba18cec"}, + {file = "rpds_py-0.20.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:fdfc3a892927458d98f3d55428ae46b921d1f7543b89382fdb483f5640daaec8"}, + {file = "rpds_py-0.20.0.tar.gz", hash = "sha256:d72a210824facfdaf8768cf2d7ca25a042c30320b3020de2fa04640920d4e121"}, +] + +[[package]] +name = "rplidar-roboticia" +version = "0.9.5" +description = "Simple and lightweight module for working with RPLidar laser scanners" +optional = true +python-versions = "*" +files = [ + {file = "rplidar-roboticia-0.9.5.tar.gz", hash = "sha256:709e9143f7701d69e8439231b065e676f7d5a6086cd2922113b055bedf99f0e3"}, +] + +[package.dependencies] +pyserial = "*" + [[package]] name = "safetensors" -version = "0.4.3" +version = "0.4.5" description = "" optional = false python-versions = ">=3.7" files = [ - {file = "safetensors-0.4.3-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:dcf5705cab159ce0130cd56057f5f3425023c407e170bca60b4868048bae64fd"}, - {file = "safetensors-0.4.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:bb4f8c5d0358a31e9a08daeebb68f5e161cdd4018855426d3f0c23bb51087055"}, - {file = "safetensors-0.4.3-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:70a5319ef409e7f88686a46607cbc3c428271069d8b770076feaf913664a07ac"}, - {file = "safetensors-0.4.3-cp310-cp310-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:fb9c65bd82f9ef3ce4970dc19ee86be5f6f93d032159acf35e663c6bea02b237"}, - {file = "safetensors-0.4.3-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:edb5698a7bc282089f64c96c477846950358a46ede85a1c040e0230344fdde10"}, - {file = "safetensors-0.4.3-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:efcc860be094b8d19ac61b452ec635c7acb9afa77beb218b1d7784c6d41fe8ad"}, - {file = "safetensors-0.4.3-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d88b33980222085dd6001ae2cad87c6068e0991d4f5ccf44975d216db3b57376"}, - {file = "safetensors-0.4.3-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:5fc6775529fb9f0ce2266edd3e5d3f10aab068e49f765e11f6f2a63b5367021d"}, - {file = "safetensors-0.4.3-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:9c6ad011c1b4e3acff058d6b090f1da8e55a332fbf84695cf3100c649cc452d1"}, - {file = "safetensors-0.4.3-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:8c496c5401c1b9c46d41a7688e8ff5b0310a3b9bae31ce0f0ae870e1ea2b8caf"}, - {file = "safetensors-0.4.3-cp310-none-win32.whl", hash = "sha256:38e2a8666178224a51cca61d3cb4c88704f696eac8f72a49a598a93bbd8a4af9"}, - {file = "safetensors-0.4.3-cp310-none-win_amd64.whl", hash = "sha256:393e6e391467d1b2b829c77e47d726f3b9b93630e6a045b1d1fca67dc78bf632"}, - {file = "safetensors-0.4.3-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:22f3b5d65e440cec0de8edaa672efa888030802e11c09b3d6203bff60ebff05a"}, - {file = "safetensors-0.4.3-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:7c4fa560ebd4522adddb71dcd25d09bf211b5634003f015a4b815b7647d62ebe"}, - {file = "safetensors-0.4.3-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e9afd5358719f1b2cf425fad638fc3c887997d6782da317096877e5b15b2ce93"}, - {file = "safetensors-0.4.3-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:d8c5093206ef4b198600ae484230402af6713dab1bd5b8e231905d754022bec7"}, - {file = "safetensors-0.4.3-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e0b2104df1579d6ba9052c0ae0e3137c9698b2d85b0645507e6fd1813b70931a"}, - {file = "safetensors-0.4.3-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8cf18888606dad030455d18f6c381720e57fc6a4170ee1966adb7ebc98d4d6a3"}, - {file = "safetensors-0.4.3-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:0bf4f9d6323d9f86eef5567eabd88f070691cf031d4c0df27a40d3b4aaee755b"}, - {file = "safetensors-0.4.3-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:585c9ae13a205807b63bef8a37994f30c917ff800ab8a1ca9c9b5d73024f97ee"}, - {file = "safetensors-0.4.3-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:faefeb3b81bdfb4e5a55b9bbdf3d8d8753f65506e1d67d03f5c851a6c87150e9"}, - {file = "safetensors-0.4.3-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:befdf0167ad626f22f6aac6163477fcefa342224a22f11fdd05abb3995c1783c"}, - {file = "safetensors-0.4.3-cp311-none-win32.whl", hash = "sha256:a7cef55929dcbef24af3eb40bedec35d82c3c2fa46338bb13ecf3c5720af8a61"}, - {file = "safetensors-0.4.3-cp311-none-win_amd64.whl", hash = "sha256:840b7ac0eff5633e1d053cc9db12fdf56b566e9403b4950b2dc85393d9b88d67"}, - {file = "safetensors-0.4.3-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:22d21760dc6ebae42e9c058d75aa9907d9f35e38f896e3c69ba0e7b213033856"}, - {file = "safetensors-0.4.3-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:8d22c1a10dff3f64d0d68abb8298a3fd88ccff79f408a3e15b3e7f637ef5c980"}, - {file = "safetensors-0.4.3-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b1648568667f820b8c48317c7006221dc40aced1869908c187f493838a1362bc"}, - {file = "safetensors-0.4.3-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:446e9fe52c051aeab12aac63d1017e0f68a02a92a027b901c4f8e931b24e5397"}, - {file = "safetensors-0.4.3-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:fef5d70683643618244a4f5221053567ca3e77c2531e42ad48ae05fae909f542"}, - {file = "safetensors-0.4.3-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2a1f4430cc0c9d6afa01214a4b3919d0a029637df8e09675ceef1ca3f0dfa0df"}, - {file = "safetensors-0.4.3-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2d603846a8585b9432a0fd415db1d4c57c0f860eb4aea21f92559ff9902bae4d"}, - {file = "safetensors-0.4.3-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:a844cdb5d7cbc22f5f16c7e2a0271170750763c4db08381b7f696dbd2c78a361"}, - {file = "safetensors-0.4.3-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:88887f69f7a00cf02b954cdc3034ffb383b2303bc0ab481d4716e2da51ddc10e"}, - {file = "safetensors-0.4.3-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:ee463219d9ec6c2be1d331ab13a8e0cd50d2f32240a81d498266d77d07b7e71e"}, - {file = "safetensors-0.4.3-cp312-none-win32.whl", hash = "sha256:d0dd4a1db09db2dba0f94d15addc7e7cd3a7b0d393aa4c7518c39ae7374623c3"}, - {file = "safetensors-0.4.3-cp312-none-win_amd64.whl", hash = "sha256:d14d30c25897b2bf19b6fb5ff7e26cc40006ad53fd4a88244fdf26517d852dd7"}, - {file = "safetensors-0.4.3-cp37-cp37m-macosx_10_12_x86_64.whl", hash = "sha256:d1456f814655b224d4bf6e7915c51ce74e389b413be791203092b7ff78c936dd"}, - {file = "safetensors-0.4.3-cp37-cp37m-macosx_11_0_arm64.whl", hash = "sha256:455d538aa1aae4a8b279344a08136d3f16334247907b18a5c3c7fa88ef0d3c46"}, - {file = "safetensors-0.4.3-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cf476bca34e1340ee3294ef13e2c625833f83d096cfdf69a5342475602004f95"}, - {file = "safetensors-0.4.3-cp37-cp37m-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:02ef3a24face643456020536591fbd3c717c5abaa2737ec428ccbbc86dffa7a4"}, - {file = "safetensors-0.4.3-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7de32d0d34b6623bb56ca278f90db081f85fb9c5d327e3c18fd23ac64f465768"}, - {file = "safetensors-0.4.3-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2a0deb16a1d3ea90c244ceb42d2c6c276059616be21a19ac7101aa97da448faf"}, - {file = "safetensors-0.4.3-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c59d51f182c729f47e841510b70b967b0752039f79f1de23bcdd86462a9b09ee"}, - {file = "safetensors-0.4.3-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:1f598b713cc1a4eb31d3b3203557ac308acf21c8f41104cdd74bf640c6e538e3"}, - {file = "safetensors-0.4.3-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:5757e4688f20df083e233b47de43845d1adb7e17b6cf7da5f8444416fc53828d"}, - {file = "safetensors-0.4.3-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:fe746d03ed8d193674a26105e4f0fe6c726f5bb602ffc695b409eaf02f04763d"}, - {file = "safetensors-0.4.3-cp37-none-win32.whl", hash = "sha256:0d5ffc6a80f715c30af253e0e288ad1cd97a3d0086c9c87995e5093ebc075e50"}, - {file = "safetensors-0.4.3-cp37-none-win_amd64.whl", hash = "sha256:a11c374eb63a9c16c5ed146457241182f310902bd2a9c18255781bb832b6748b"}, - {file = "safetensors-0.4.3-cp38-cp38-macosx_10_12_x86_64.whl", hash = "sha256:b1e31be7945f66be23f4ec1682bb47faa3df34cb89fc68527de6554d3c4258a4"}, - {file = "safetensors-0.4.3-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:03a4447c784917c9bf01d8f2ac5080bc15c41692202cd5f406afba16629e84d6"}, - {file = "safetensors-0.4.3-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d244bcafeb1bc06d47cfee71727e775bca88a8efda77a13e7306aae3813fa7e4"}, - {file = "safetensors-0.4.3-cp38-cp38-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:53c4879b9c6bd7cd25d114ee0ef95420e2812e676314300624594940a8d6a91f"}, - {file = "safetensors-0.4.3-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:74707624b81f1b7f2b93f5619d4a9f00934d5948005a03f2c1845ffbfff42212"}, - {file = "safetensors-0.4.3-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0d52c958dc210265157573f81d34adf54e255bc2b59ded6218500c9b15a750eb"}, - {file = "safetensors-0.4.3-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6f9568f380f513a60139971169c4a358b8731509cc19112369902eddb33faa4d"}, - {file = "safetensors-0.4.3-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:0d9cd8e1560dfc514b6d7859247dc6a86ad2f83151a62c577428d5102d872721"}, - {file = "safetensors-0.4.3-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:89f9f17b0dacb913ed87d57afbc8aad85ea42c1085bd5de2f20d83d13e9fc4b2"}, - {file = "safetensors-0.4.3-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:1139eb436fd201c133d03c81209d39ac57e129f5e74e34bb9ab60f8d9b726270"}, - {file = "safetensors-0.4.3-cp38-none-win32.whl", hash = "sha256:d9c289f140a9ae4853fc2236a2ffc9a9f2d5eae0cb673167e0f1b8c18c0961ac"}, - {file = "safetensors-0.4.3-cp38-none-win_amd64.whl", hash = "sha256:622afd28968ef3e9786562d352659a37de4481a4070f4ebac883f98c5836563e"}, - {file = "safetensors-0.4.3-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:8651c7299cbd8b4161a36cd6a322fa07d39cd23535b144d02f1c1972d0c62f3c"}, - {file = "safetensors-0.4.3-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e375d975159ac534c7161269de24ddcd490df2157b55c1a6eeace6cbb56903f0"}, - {file = "safetensors-0.4.3-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:084fc436e317f83f7071fc6a62ca1c513b2103db325cd09952914b50f51cf78f"}, - {file = "safetensors-0.4.3-cp39-cp39-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:41a727a7f5e6ad9f1db6951adee21bbdadc632363d79dc434876369a17de6ad6"}, - {file = "safetensors-0.4.3-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e7dbbde64b6c534548696808a0e01276d28ea5773bc9a2dfb97a88cd3dffe3df"}, - {file = "safetensors-0.4.3-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:bbae3b4b9d997971431c346edbfe6e41e98424a097860ee872721e176040a893"}, - {file = "safetensors-0.4.3-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:01e4b22e3284cd866edeabe4f4d896229495da457229408d2e1e4810c5187121"}, - {file = "safetensors-0.4.3-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:0dd37306546b58d3043eb044c8103a02792cc024b51d1dd16bd3dd1f334cb3ed"}, - {file = "safetensors-0.4.3-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:d8815b5e1dac85fc534a97fd339e12404db557878c090f90442247e87c8aeaea"}, - {file = "safetensors-0.4.3-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:e011cc162503c19f4b1fd63dfcddf73739c7a243a17dac09b78e57a00983ab35"}, - {file = "safetensors-0.4.3-cp39-none-win32.whl", hash = "sha256:01feb3089e5932d7e662eda77c3ecc389f97c0883c4a12b5cfdc32b589a811c3"}, - {file = "safetensors-0.4.3-cp39-none-win_amd64.whl", hash = "sha256:3f9cdca09052f585e62328c1c2923c70f46814715c795be65f0b93f57ec98a02"}, - {file = "safetensors-0.4.3-pp310-pypy310_pp73-macosx_10_12_x86_64.whl", hash = "sha256:1b89381517891a7bb7d1405d828b2bf5d75528299f8231e9346b8eba092227f9"}, - {file = "safetensors-0.4.3-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:cd6fff9e56df398abc5866b19a32124815b656613c1c5ec0f9350906fd798aac"}, - {file = "safetensors-0.4.3-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:840caf38d86aa7014fe37ade5d0d84e23dcfbc798b8078015831996ecbc206a3"}, - {file = "safetensors-0.4.3-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f9650713b2cfa9537a2baf7dd9fee458b24a0aaaa6cafcea8bdd5fb2b8efdc34"}, - {file = "safetensors-0.4.3-pp310-pypy310_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:e4119532cd10dba04b423e0f86aecb96cfa5a602238c0aa012f70c3a40c44b50"}, - {file = "safetensors-0.4.3-pp310-pypy310_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:e066e8861eef6387b7c772344d1fe1f9a72800e04ee9a54239d460c400c72aab"}, - {file = "safetensors-0.4.3-pp310-pypy310_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:90964917f5b0fa0fa07e9a051fbef100250c04d150b7026ccbf87a34a54012e0"}, - {file = "safetensors-0.4.3-pp37-pypy37_pp73-macosx_10_12_x86_64.whl", hash = "sha256:c41e1893d1206aa7054029681778d9a58b3529d4c807002c156d58426c225173"}, - {file = "safetensors-0.4.3-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ae7613a119a71a497d012ccc83775c308b9c1dab454806291427f84397d852fd"}, - {file = "safetensors-0.4.3-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4f9bac020faba7f5dc481e881b14b6425265feabb5bfc552551d21189c0eddc3"}, - {file = "safetensors-0.4.3-pp37-pypy37_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:420a98f593ff9930f5822560d14c395ccbc57342ddff3b463bc0b3d6b1951550"}, - {file = "safetensors-0.4.3-pp37-pypy37_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:f5e6883af9a68c0028f70a4c19d5a6ab6238a379be36ad300a22318316c00cb0"}, - {file = "safetensors-0.4.3-pp37-pypy37_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:cdd0a3b5da66e7f377474599814dbf5cbf135ff059cc73694de129b58a5e8a2c"}, - {file = "safetensors-0.4.3-pp38-pypy38_pp73-macosx_10_12_x86_64.whl", hash = "sha256:9bfb92f82574d9e58401d79c70c716985dc049b635fef6eecbb024c79b2c46ad"}, - {file = "safetensors-0.4.3-pp38-pypy38_pp73-macosx_11_0_arm64.whl", hash = "sha256:3615a96dd2dcc30eb66d82bc76cda2565f4f7bfa89fcb0e31ba3cea8a1a9ecbb"}, - {file = "safetensors-0.4.3-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:868ad1b6fc41209ab6bd12f63923e8baeb1a086814cb2e81a65ed3d497e0cf8f"}, - {file = "safetensors-0.4.3-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b7ffba80aa49bd09195145a7fd233a7781173b422eeb995096f2b30591639517"}, - {file = "safetensors-0.4.3-pp38-pypy38_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:c0acbe31340ab150423347e5b9cc595867d814244ac14218932a5cf1dd38eb39"}, - {file = "safetensors-0.4.3-pp38-pypy38_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:19bbdf95de2cf64f25cd614c5236c8b06eb2cfa47cbf64311f4b5d80224623a3"}, - {file = "safetensors-0.4.3-pp38-pypy38_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:b852e47eb08475c2c1bd8131207b405793bfc20d6f45aff893d3baaad449ed14"}, - {file = "safetensors-0.4.3-pp39-pypy39_pp73-macosx_10_12_x86_64.whl", hash = "sha256:5d07cbca5b99babb692d76d8151bec46f461f8ad8daafbfd96b2fca40cadae65"}, - {file = "safetensors-0.4.3-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:1ab6527a20586d94291c96e00a668fa03f86189b8a9defa2cdd34a1a01acc7d5"}, - {file = "safetensors-0.4.3-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:02318f01e332cc23ffb4f6716e05a492c5f18b1d13e343c49265149396284a44"}, - {file = "safetensors-0.4.3-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ec4b52ce9a396260eb9731eb6aea41a7320de22ed73a1042c2230af0212758ce"}, - {file = "safetensors-0.4.3-pp39-pypy39_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:018b691383026a2436a22b648873ed11444a364324e7088b99cd2503dd828400"}, - {file = "safetensors-0.4.3-pp39-pypy39_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:309b10dbcab63269ecbf0e2ca10ce59223bb756ca5d431ce9c9eeabd446569da"}, - {file = "safetensors-0.4.3-pp39-pypy39_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:b277482120df46e27a58082df06a15aebda4481e30a1c21eefd0921ae7e03f65"}, - {file = "safetensors-0.4.3.tar.gz", hash = "sha256:2f85fc50c4e07a21e95c24e07460fe6f7e2859d0ce88092838352b798ce711c2"}, + {file = "safetensors-0.4.5-cp310-cp310-macosx_10_12_x86_64.whl", hash = "sha256:a63eaccd22243c67e4f2b1c3e258b257effc4acd78f3b9d397edc8cf8f1298a7"}, + {file = "safetensors-0.4.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:23fc9b4ec7b602915cbb4ec1a7c1ad96d2743c322f20ab709e2c35d1b66dad27"}, + {file = "safetensors-0.4.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6885016f34bef80ea1085b7e99b3c1f92cb1be78a49839203060f67b40aee761"}, + {file = "safetensors-0.4.5-cp310-cp310-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:133620f443450429322f238fda74d512c4008621227fccf2f8cf4a76206fea7c"}, + {file = "safetensors-0.4.5-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:4fb3e0609ec12d2a77e882f07cced530b8262027f64b75d399f1504ffec0ba56"}, + {file = "safetensors-0.4.5-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d0f1dd769f064adc33831f5e97ad07babbd728427f98e3e1db6902e369122737"}, + {file = "safetensors-0.4.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c6d156bdb26732feada84f9388a9f135528c1ef5b05fae153da365ad4319c4c5"}, + {file = "safetensors-0.4.5-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:9e347d77e2c77eb7624400ccd09bed69d35c0332f417ce8c048d404a096c593b"}, + {file = "safetensors-0.4.5-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:9f556eea3aec1d3d955403159fe2123ddd68e880f83954ee9b4a3f2e15e716b6"}, + {file = "safetensors-0.4.5-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:9483f42be3b6bc8ff77dd67302de8ae411c4db39f7224dec66b0eb95822e4163"}, + {file = "safetensors-0.4.5-cp310-none-win32.whl", hash = "sha256:7389129c03fadd1ccc37fd1ebbc773f2b031483b04700923c3511d2a939252cc"}, + {file = "safetensors-0.4.5-cp310-none-win_amd64.whl", hash = "sha256:e98ef5524f8b6620c8cdef97220c0b6a5c1cef69852fcd2f174bb96c2bb316b1"}, + {file = "safetensors-0.4.5-cp311-cp311-macosx_10_12_x86_64.whl", hash = "sha256:21f848d7aebd5954f92538552d6d75f7c1b4500f51664078b5b49720d180e47c"}, + {file = "safetensors-0.4.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:bb07000b19d41e35eecef9a454f31a8b4718a185293f0d0b1c4b61d6e4487971"}, + {file = "safetensors-0.4.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:09dedf7c2fda934ee68143202acff6e9e8eb0ddeeb4cfc24182bef999efa9f42"}, + {file = "safetensors-0.4.5-cp311-cp311-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:59b77e4b7a708988d84f26de3ebead61ef1659c73dcbc9946c18f3b1786d2688"}, + {file = "safetensors-0.4.5-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5d3bc83e14d67adc2e9387e511097f254bd1b43c3020440e708858c684cbac68"}, + {file = "safetensors-0.4.5-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:39371fc551c1072976073ab258c3119395294cf49cdc1f8476794627de3130df"}, + {file = "safetensors-0.4.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a6c19feda32b931cae0acd42748a670bdf56bee6476a046af20181ad3fee4090"}, + {file = "safetensors-0.4.5-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:a659467495de201e2f282063808a41170448c78bada1e62707b07a27b05e6943"}, + {file = "safetensors-0.4.5-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:bad5e4b2476949bcd638a89f71b6916fa9a5cae5c1ae7eede337aca2100435c0"}, + {file = "safetensors-0.4.5-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:a3a315a6d0054bc6889a17f5668a73f94f7fe55121ff59e0a199e3519c08565f"}, + {file = "safetensors-0.4.5-cp311-none-win32.whl", hash = "sha256:a01e232e6d3d5cf8b1667bc3b657a77bdab73f0743c26c1d3c5dd7ce86bd3a92"}, + {file = "safetensors-0.4.5-cp311-none-win_amd64.whl", hash = "sha256:cbd39cae1ad3e3ef6f63a6f07296b080c951f24cec60188378e43d3713000c04"}, + {file = "safetensors-0.4.5-cp312-cp312-macosx_10_12_x86_64.whl", hash = "sha256:473300314e026bd1043cef391bb16a8689453363381561b8a3e443870937cc1e"}, + {file = "safetensors-0.4.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:801183a0f76dc647f51a2d9141ad341f9665602a7899a693207a82fb102cc53e"}, + {file = "safetensors-0.4.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1524b54246e422ad6fb6aea1ac71edeeb77666efa67230e1faf6999df9b2e27f"}, + {file = "safetensors-0.4.5-cp312-cp312-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:b3139098e3e8b2ad7afbca96d30ad29157b50c90861084e69fcb80dec7430461"}, + {file = "safetensors-0.4.5-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:65573dc35be9059770808e276b017256fa30058802c29e1038eb1c00028502ea"}, + {file = "safetensors-0.4.5-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:fd33da8e9407559f8779c82a0448e2133737f922d71f884da27184549416bfed"}, + {file = "safetensors-0.4.5-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3685ce7ed036f916316b567152482b7e959dc754fcc4a8342333d222e05f407c"}, + {file = "safetensors-0.4.5-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:dde2bf390d25f67908278d6f5d59e46211ef98e44108727084d4637ee70ab4f1"}, + {file = "safetensors-0.4.5-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:7469d70d3de970b1698d47c11ebbf296a308702cbaae7fcb993944751cf985f4"}, + {file = "safetensors-0.4.5-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:3a6ba28118636a130ccbb968bc33d4684c48678695dba2590169d5ab03a45646"}, + {file = "safetensors-0.4.5-cp312-none-win32.whl", hash = "sha256:c859c7ed90b0047f58ee27751c8e56951452ed36a67afee1b0a87847d065eec6"}, + {file = "safetensors-0.4.5-cp312-none-win_amd64.whl", hash = "sha256:b5a8810ad6a6f933fff6c276eae92c1da217b39b4d8b1bc1c0b8af2d270dc532"}, + {file = "safetensors-0.4.5-cp313-cp313-macosx_10_12_x86_64.whl", hash = "sha256:25e5f8e2e92a74f05b4ca55686234c32aac19927903792b30ee6d7bd5653d54e"}, + {file = "safetensors-0.4.5-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:81efb124b58af39fcd684254c645e35692fea81c51627259cdf6d67ff4458916"}, + {file = "safetensors-0.4.5-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:585f1703a518b437f5103aa9cf70e9bd437cb78eea9c51024329e4fb8a3e3679"}, + {file = "safetensors-0.4.5-cp313-cp313-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:4b99fbf72e3faf0b2f5f16e5e3458b93b7d0a83984fe8d5364c60aa169f2da89"}, + {file = "safetensors-0.4.5-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b17b299ca9966ca983ecda1c0791a3f07f9ca6ab5ded8ef3d283fff45f6bcd5f"}, + {file = "safetensors-0.4.5-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:76ded72f69209c9780fdb23ea89e56d35c54ae6abcdec67ccb22af8e696e449a"}, + {file = "safetensors-0.4.5-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2783956926303dcfeb1de91a4d1204cd4089ab441e622e7caee0642281109db3"}, + {file = "safetensors-0.4.5-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:d94581aab8c6b204def4d7320f07534d6ee34cd4855688004a4354e63b639a35"}, + {file = "safetensors-0.4.5-cp313-cp313-musllinux_1_1_aarch64.whl", hash = "sha256:67e1e7cb8678bb1b37ac48ec0df04faf689e2f4e9e81e566b5c63d9f23748523"}, + {file = "safetensors-0.4.5-cp313-cp313-musllinux_1_1_x86_64.whl", hash = "sha256:dbd280b07e6054ea68b0cb4b16ad9703e7d63cd6890f577cb98acc5354780142"}, + {file = "safetensors-0.4.5-cp37-cp37m-macosx_10_12_x86_64.whl", hash = "sha256:77d9b228da8374c7262046a36c1f656ba32a93df6cc51cd4453af932011e77f1"}, + {file = "safetensors-0.4.5-cp37-cp37m-macosx_11_0_arm64.whl", hash = "sha256:500cac01d50b301ab7bb192353317035011c5ceeef0fca652f9f43c000bb7f8d"}, + {file = "safetensors-0.4.5-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:75331c0c746f03158ded32465b7d0b0e24c5a22121743662a2393439c43a45cf"}, + {file = "safetensors-0.4.5-cp37-cp37m-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:670e95fe34e0d591d0529e5e59fd9d3d72bc77b1444fcaa14dccda4f36b5a38b"}, + {file = "safetensors-0.4.5-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:098923e2574ff237c517d6e840acada8e5b311cb1fa226019105ed82e9c3b62f"}, + {file = "safetensors-0.4.5-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:13ca0902d2648775089fa6a0c8fc9e6390c5f8ee576517d33f9261656f851e3f"}, + {file = "safetensors-0.4.5-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5f0032bedc869c56f8d26259fe39cd21c5199cd57f2228d817a0e23e8370af25"}, + {file = "safetensors-0.4.5-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:f4b15f51b4f8f2a512341d9ce3475cacc19c5fdfc5db1f0e19449e75f95c7dc8"}, + {file = "safetensors-0.4.5-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:f6594d130d0ad933d885c6a7b75c5183cb0e8450f799b80a39eae2b8508955eb"}, + {file = "safetensors-0.4.5-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:60c828a27e852ded2c85fc0f87bf1ec20e464c5cd4d56ff0e0711855cc2e17f8"}, + {file = "safetensors-0.4.5-cp37-none-win32.whl", hash = "sha256:6d3de65718b86c3eeaa8b73a9c3d123f9307a96bbd7be9698e21e76a56443af5"}, + {file = "safetensors-0.4.5-cp37-none-win_amd64.whl", hash = "sha256:5a2d68a523a4cefd791156a4174189a4114cf0bf9c50ceb89f261600f3b2b81a"}, + {file = "safetensors-0.4.5-cp38-cp38-macosx_10_12_x86_64.whl", hash = "sha256:e7a97058f96340850da0601a3309f3d29d6191b0702b2da201e54c6e3e44ccf0"}, + {file = "safetensors-0.4.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:63bfd425e25f5c733f572e2246e08a1c38bd6f2e027d3f7c87e2e43f228d1345"}, + {file = "safetensors-0.4.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f3664ac565d0e809b0b929dae7ccd74e4d3273cd0c6d1220c6430035befb678e"}, + {file = "safetensors-0.4.5-cp38-cp38-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:313514b0b9b73ff4ddfb4edd71860696dbe3c1c9dc4d5cc13dbd74da283d2cbf"}, + {file = "safetensors-0.4.5-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:31fa33ee326f750a2f2134a6174773c281d9a266ccd000bd4686d8021f1f3dac"}, + {file = "safetensors-0.4.5-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:09566792588d77b68abe53754c9f1308fadd35c9f87be939e22c623eaacbed6b"}, + {file = "safetensors-0.4.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:309aaec9b66cbf07ad3a2e5cb8a03205663324fea024ba391594423d0f00d9fe"}, + {file = "safetensors-0.4.5-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:53946c5813b8f9e26103c5efff4a931cc45d874f45229edd68557ffb35ffb9f8"}, + {file = "safetensors-0.4.5-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:868f9df9e99ad1e7f38c52194063a982bc88fedc7d05096f4f8160403aaf4bd6"}, + {file = "safetensors-0.4.5-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:9cc9449bd0b0bc538bd5e268221f0c5590bc5c14c1934a6ae359d44410dc68c4"}, + {file = "safetensors-0.4.5-cp38-none-win32.whl", hash = "sha256:83c4f13a9e687335c3928f615cd63a37e3f8ef072a3f2a0599fa09f863fb06a2"}, + {file = "safetensors-0.4.5-cp38-none-win_amd64.whl", hash = "sha256:b98d40a2ffa560653f6274e15b27b3544e8e3713a44627ce268f419f35c49478"}, + {file = "safetensors-0.4.5-cp39-cp39-macosx_10_12_x86_64.whl", hash = "sha256:cf727bb1281d66699bef5683b04d98c894a2803442c490a8d45cd365abfbdeb2"}, + {file = "safetensors-0.4.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:96f1d038c827cdc552d97e71f522e1049fef0542be575421f7684756a748e457"}, + {file = "safetensors-0.4.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:139fbee92570ecea774e6344fee908907db79646d00b12c535f66bc78bd5ea2c"}, + {file = "safetensors-0.4.5-cp39-cp39-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:c36302c1c69eebb383775a89645a32b9d266878fab619819ce660309d6176c9b"}, + {file = "safetensors-0.4.5-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:d641f5b8149ea98deb5ffcf604d764aad1de38a8285f86771ce1abf8e74c4891"}, + {file = "safetensors-0.4.5-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:b4db6a61d968de73722b858038c616a1bebd4a86abe2688e46ca0cc2d17558f2"}, + {file = "safetensors-0.4.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b75a616e02f21b6f1d5785b20cecbab5e2bd3f6358a90e8925b813d557666ec1"}, + {file = "safetensors-0.4.5-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:788ee7d04cc0e0e7f944c52ff05f52a4415b312f5efd2ee66389fb7685ee030c"}, + {file = "safetensors-0.4.5-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:87bc42bd04fd9ca31396d3ca0433db0be1411b6b53ac5a32b7845a85d01ffc2e"}, + {file = "safetensors-0.4.5-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:4037676c86365a721a8c9510323a51861d703b399b78a6b4486a54a65a975fca"}, + {file = "safetensors-0.4.5-cp39-none-win32.whl", hash = "sha256:1500418454529d0ed5c1564bda376c4ddff43f30fce9517d9bee7bcce5a8ef50"}, + {file = "safetensors-0.4.5-cp39-none-win_amd64.whl", hash = "sha256:9d1a94b9d793ed8fe35ab6d5cea28d540a46559bafc6aae98f30ee0867000cab"}, + {file = "safetensors-0.4.5-pp310-pypy310_pp73-macosx_10_12_x86_64.whl", hash = "sha256:fdadf66b5a22ceb645d5435a0be7a0292ce59648ca1d46b352f13cff3ea80410"}, + {file = "safetensors-0.4.5-pp310-pypy310_pp73-macosx_11_0_arm64.whl", hash = "sha256:d42ffd4c2259f31832cb17ff866c111684c87bd930892a1ba53fed28370c918c"}, + {file = "safetensors-0.4.5-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:dd8a1f6d2063a92cd04145c7fd9e31a1c7d85fbec20113a14b487563fdbc0597"}, + {file = "safetensors-0.4.5-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:951d2fcf1817f4fb0ef0b48f6696688a4e852a95922a042b3f96aaa67eedc920"}, + {file = "safetensors-0.4.5-pp310-pypy310_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:6ac85d9a8c1af0e3132371d9f2d134695a06a96993c2e2f0bbe25debb9e3f67a"}, + {file = "safetensors-0.4.5-pp310-pypy310_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:e3cec4a29eb7fe8da0b1c7988bc3828183080439dd559f720414450de076fcab"}, + {file = "safetensors-0.4.5-pp310-pypy310_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:21742b391b859e67b26c0b2ac37f52c9c0944a879a25ad2f9f9f3cd61e7fda8f"}, + {file = "safetensors-0.4.5-pp37-pypy37_pp73-macosx_10_12_x86_64.whl", hash = "sha256:c7db3006a4915151ce1913652e907cdede299b974641a83fbc092102ac41b644"}, + {file = "safetensors-0.4.5-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f68bf99ea970960a237f416ea394e266e0361895753df06e3e06e6ea7907d98b"}, + {file = "safetensors-0.4.5-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8158938cf3324172df024da511839d373c40fbfaa83e9abf467174b2910d7b4c"}, + {file = "safetensors-0.4.5-pp37-pypy37_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:540ce6c4bf6b58cb0fd93fa5f143bc0ee341c93bb4f9287ccd92cf898cc1b0dd"}, + {file = "safetensors-0.4.5-pp37-pypy37_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:bfeaa1a699c6b9ed514bd15e6a91e74738b71125a9292159e3d6b7f0a53d2cde"}, + {file = "safetensors-0.4.5-pp37-pypy37_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:01c8f00da537af711979e1b42a69a8ec9e1d7112f208e0e9b8a35d2c381085ef"}, + {file = "safetensors-0.4.5-pp38-pypy38_pp73-macosx_10_12_x86_64.whl", hash = "sha256:a0dd565f83b30f2ca79b5d35748d0d99dd4b3454f80e03dfb41f0038e3bdf180"}, + {file = "safetensors-0.4.5-pp38-pypy38_pp73-macosx_11_0_arm64.whl", hash = "sha256:023b6e5facda76989f4cba95a861b7e656b87e225f61811065d5c501f78cdb3f"}, + {file = "safetensors-0.4.5-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9633b663393d5796f0b60249549371e392b75a0b955c07e9c6f8708a87fc841f"}, + {file = "safetensors-0.4.5-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:78dd8adfb48716233c45f676d6e48534d34b4bceb50162c13d1f0bdf6f78590a"}, + {file = "safetensors-0.4.5-pp38-pypy38_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:8e8deb16c4321d61ae72533b8451ec4a9af8656d1c61ff81aa49f966406e4b68"}, + {file = "safetensors-0.4.5-pp38-pypy38_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:52452fa5999dc50c4decaf0c53aa28371f7f1e0fe5c2dd9129059fbe1e1599c7"}, + {file = "safetensors-0.4.5-pp38-pypy38_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:d5f23198821e227cfc52d50fa989813513db381255c6d100927b012f0cfec63d"}, + {file = "safetensors-0.4.5-pp39-pypy39_pp73-macosx_10_12_x86_64.whl", hash = "sha256:f4beb84b6073b1247a773141a6331117e35d07134b3bb0383003f39971d414bb"}, + {file = "safetensors-0.4.5-pp39-pypy39_pp73-macosx_11_0_arm64.whl", hash = "sha256:68814d599d25ed2fdd045ed54d370d1d03cf35e02dce56de44c651f828fb9b7b"}, + {file = "safetensors-0.4.5-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f0b6453c54c57c1781292c46593f8a37254b8b99004c68d6c3ce229688931a22"}, + {file = "safetensors-0.4.5-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:adaa9c6dead67e2dd90d634f89131e43162012479d86e25618e821a03d1eb1dc"}, + {file = "safetensors-0.4.5-pp39-pypy39_pp73-manylinux_2_5_i686.manylinux1_i686.whl", hash = "sha256:73e7d408e9012cd17511b382b43547850969c7979efc2bc353f317abaf23c84c"}, + {file = "safetensors-0.4.5-pp39-pypy39_pp73-musllinux_1_1_aarch64.whl", hash = "sha256:775409ce0fcc58b10773fdb4221ed1eb007de10fe7adbdf8f5e8a56096b6f0bc"}, + {file = "safetensors-0.4.5-pp39-pypy39_pp73-musllinux_1_1_x86_64.whl", hash = "sha256:834001bed193e4440c4a3950a31059523ee5090605c907c66808664c932b549c"}, + {file = "safetensors-0.4.5.tar.gz", hash = "sha256:d73de19682deabb02524b3d5d1f8b3aaba94c72f1bbfc7911b9b9d5d391c0310"}, ] [package.extras] @@ -3688,36 +6127,44 @@ test = ["asv", "numpydoc (>=1.7)", "pooch (>=1.6.0)", "pytest (>=7.0)", "pytest- [[package]] name = "scipy" -version = "1.14.0" +version = "1.14.1" description = "Fundamental algorithms for scientific computing in Python" optional = true python-versions = ">=3.10" files = [ - {file = "scipy-1.14.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:7e911933d54ead4d557c02402710c2396529540b81dd554fc1ba270eb7308484"}, - {file = "scipy-1.14.0-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:687af0a35462402dd851726295c1a5ae5f987bd6e9026f52e9505994e2f84ef6"}, - {file = "scipy-1.14.0-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:07e179dc0205a50721022344fb85074f772eadbda1e1b3eecdc483f8033709b7"}, - {file = "scipy-1.14.0-cp310-cp310-macosx_14_0_x86_64.whl", hash = "sha256:6a9c9a9b226d9a21e0a208bdb024c3982932e43811b62d202aaf1bb59af264b1"}, - {file = "scipy-1.14.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:076c27284c768b84a45dcf2e914d4000aac537da74236a0d45d82c6fa4b7b3c0"}, - {file = "scipy-1.14.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:42470ea0195336df319741e230626b6225a740fd9dce9642ca13e98f667047c0"}, - {file = "scipy-1.14.0-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:176c6f0d0470a32f1b2efaf40c3d37a24876cebf447498a4cefb947a79c21e9d"}, - {file = "scipy-1.14.0-cp310-cp310-win_amd64.whl", hash = "sha256:ad36af9626d27a4326c8e884917b7ec321d8a1841cd6dacc67d2a9e90c2f0359"}, - {file = "scipy-1.14.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:6d056a8709ccda6cf36cdd2eac597d13bc03dba38360f418560a93050c76a16e"}, - {file = "scipy-1.14.0-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:f0a50da861a7ec4573b7c716b2ebdcdf142b66b756a0d392c236ae568b3a93fb"}, - {file = "scipy-1.14.0-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:94c164a9e2498e68308e6e148646e486d979f7fcdb8b4cf34b5441894bdb9caf"}, - {file = "scipy-1.14.0-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:a7d46c3e0aea5c064e734c3eac5cf9eb1f8c4ceee756262f2c7327c4c2691c86"}, - {file = "scipy-1.14.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:9eee2989868e274aae26125345584254d97c56194c072ed96cb433f32f692ed8"}, - {file = "scipy-1.14.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9e3154691b9f7ed73778d746da2df67a19d046a6c8087c8b385bc4cdb2cfca74"}, - {file = "scipy-1.14.0-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:c40003d880f39c11c1edbae8144e3813904b10514cd3d3d00c277ae996488cdb"}, - {file = "scipy-1.14.0-cp311-cp311-win_amd64.whl", hash = "sha256:5b083c8940028bb7e0b4172acafda6df762da1927b9091f9611b0bcd8676f2bc"}, - {file = "scipy-1.14.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:bff2438ea1330e06e53c424893ec0072640dac00f29c6a43a575cbae4c99b2b9"}, - {file = "scipy-1.14.0-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:bbc0471b5f22c11c389075d091d3885693fd3f5e9a54ce051b46308bc787e5d4"}, - {file = "scipy-1.14.0-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:64b2ff514a98cf2bb734a9f90d32dc89dc6ad4a4a36a312cd0d6327170339eb0"}, - {file = "scipy-1.14.0-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:7d3da42fbbbb860211a811782504f38ae7aaec9de8764a9bef6b262de7a2b50f"}, - {file = "scipy-1.14.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d91db2c41dd6c20646af280355d41dfa1ec7eead235642178bd57635a3f82209"}, - {file = "scipy-1.14.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a01cc03bcdc777c9da3cfdcc74b5a75caffb48a6c39c8450a9a05f82c4250a14"}, - {file = "scipy-1.14.0-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:65df4da3c12a2bb9ad52b86b4dcf46813e869afb006e58be0f516bc370165159"}, - {file = "scipy-1.14.0-cp312-cp312-win_amd64.whl", hash = "sha256:4c4161597c75043f7154238ef419c29a64ac4a7c889d588ea77690ac4d0d9b20"}, - {file = "scipy-1.14.0.tar.gz", hash = "sha256:b5923f48cb840380f9854339176ef21763118a7300a88203ccd0bdd26e58527b"}, + {file = "scipy-1.14.1-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:b28d2ca4add7ac16ae8bb6632a3c86e4b9e4d52d3e34267f6e1b0c1f8d87e389"}, + {file = "scipy-1.14.1-cp310-cp310-macosx_12_0_arm64.whl", hash = "sha256:d0d2821003174de06b69e58cef2316a6622b60ee613121199cb2852a873f8cf3"}, + {file = "scipy-1.14.1-cp310-cp310-macosx_14_0_arm64.whl", hash = "sha256:8bddf15838ba768bb5f5083c1ea012d64c9a444e16192762bd858f1e126196d0"}, + {file = "scipy-1.14.1-cp310-cp310-macosx_14_0_x86_64.whl", hash = "sha256:97c5dddd5932bd2a1a31c927ba5e1463a53b87ca96b5c9bdf5dfd6096e27efc3"}, + {file = "scipy-1.14.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2ff0a7e01e422c15739ecd64432743cf7aae2b03f3084288f399affcefe5222d"}, + {file = "scipy-1.14.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8e32dced201274bf96899e6491d9ba3e9a5f6b336708656466ad0522d8528f69"}, + {file = "scipy-1.14.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:8426251ad1e4ad903a4514712d2fa8fdd5382c978010d1c6f5f37ef286a713ad"}, + {file = "scipy-1.14.1-cp310-cp310-win_amd64.whl", hash = "sha256:a49f6ed96f83966f576b33a44257d869756df6cf1ef4934f59dd58b25e0327e5"}, + {file = "scipy-1.14.1-cp311-cp311-macosx_10_13_x86_64.whl", hash = "sha256:2da0469a4ef0ecd3693761acbdc20f2fdeafb69e6819cc081308cc978153c675"}, + {file = "scipy-1.14.1-cp311-cp311-macosx_12_0_arm64.whl", hash = "sha256:c0ee987efa6737242745f347835da2cc5bb9f1b42996a4d97d5c7ff7928cb6f2"}, + {file = "scipy-1.14.1-cp311-cp311-macosx_14_0_arm64.whl", hash = "sha256:3a1b111fac6baec1c1d92f27e76511c9e7218f1695d61b59e05e0fe04dc59617"}, + {file = "scipy-1.14.1-cp311-cp311-macosx_14_0_x86_64.whl", hash = "sha256:8475230e55549ab3f207bff11ebfc91c805dc3463ef62eda3ccf593254524ce8"}, + {file = "scipy-1.14.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:278266012eb69f4a720827bdd2dc54b2271c97d84255b2faaa8f161a158c3b37"}, + {file = "scipy-1.14.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fef8c87f8abfb884dac04e97824b61299880c43f4ce675dd2cbeadd3c9b466d2"}, + {file = "scipy-1.14.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:b05d43735bb2f07d689f56f7b474788a13ed8adc484a85aa65c0fd931cf9ccd2"}, + {file = "scipy-1.14.1-cp311-cp311-win_amd64.whl", hash = "sha256:716e389b694c4bb564b4fc0c51bc84d381735e0d39d3f26ec1af2556ec6aad94"}, + {file = "scipy-1.14.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:631f07b3734d34aced009aaf6fedfd0eb3498a97e581c3b1e5f14a04164a456d"}, + {file = "scipy-1.14.1-cp312-cp312-macosx_12_0_arm64.whl", hash = "sha256:af29a935803cc707ab2ed7791c44288a682f9c8107bc00f0eccc4f92c08d6e07"}, + {file = "scipy-1.14.1-cp312-cp312-macosx_14_0_arm64.whl", hash = "sha256:2843f2d527d9eebec9a43e6b406fb7266f3af25a751aa91d62ff416f54170bc5"}, + {file = "scipy-1.14.1-cp312-cp312-macosx_14_0_x86_64.whl", hash = "sha256:eb58ca0abd96911932f688528977858681a59d61a7ce908ffd355957f7025cfc"}, + {file = "scipy-1.14.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:30ac8812c1d2aab7131a79ba62933a2a76f582d5dbbc695192453dae67ad6310"}, + {file = "scipy-1.14.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8f9ea80f2e65bdaa0b7627fb00cbeb2daf163caa015e59b7516395fe3bd1e066"}, + {file = "scipy-1.14.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:edaf02b82cd7639db00dbff629995ef185c8df4c3ffa71a5562a595765a06ce1"}, + {file = "scipy-1.14.1-cp312-cp312-win_amd64.whl", hash = "sha256:2ff38e22128e6c03ff73b6bb0f85f897d2362f8c052e3b8ad00532198fbdae3f"}, + {file = "scipy-1.14.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:1729560c906963fc8389f6aac023739ff3983e727b1a4d87696b7bf108316a79"}, + {file = "scipy-1.14.1-cp313-cp313-macosx_12_0_arm64.whl", hash = "sha256:4079b90df244709e675cdc8b93bfd8a395d59af40b72e339c2287c91860deb8e"}, + {file = "scipy-1.14.1-cp313-cp313-macosx_14_0_arm64.whl", hash = "sha256:e0cf28db0f24a38b2a0ca33a85a54852586e43cf6fd876365c86e0657cfe7d73"}, + {file = "scipy-1.14.1-cp313-cp313-macosx_14_0_x86_64.whl", hash = "sha256:0c2f95de3b04e26f5f3ad5bb05e74ba7f68b837133a4492414b3afd79dfe540e"}, + {file = "scipy-1.14.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b99722ea48b7ea25e8e015e8341ae74624f72e5f21fc2abd45f3a93266de4c5d"}, + {file = "scipy-1.14.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5149e3fd2d686e42144a093b206aef01932a0059c2a33ddfa67f5f035bdfe13e"}, + {file = "scipy-1.14.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:e4f5a7c49323533f9103d4dacf4e4f07078f360743dec7f7596949149efeec06"}, + {file = "scipy-1.14.1-cp313-cp313-win_amd64.whl", hash = "sha256:baff393942b550823bfce952bb62270ee17504d02a1801d7fd0719534dfb9c84"}, + {file = "scipy-1.14.1.tar.gz", hash = "sha256:5a275584e726026a5699459aa72f828a610821006228e841b94275c4a7c08417"}, ] [package.dependencies] @@ -3725,18 +6172,34 @@ numpy = ">=1.23.5,<2.3" [package.extras] dev = ["cython-lint (>=0.12.2)", "doit (>=0.36.0)", "mypy (==1.10.0)", "pycodestyle", "pydevtool", "rich-click", "ruff (>=0.0.292)", "types-psutil", "typing_extensions"] -doc = ["jupyterlite-pyodide-kernel", "jupyterlite-sphinx (>=0.13.1)", "jupytext", "matplotlib (>=3.5)", "myst-nb", "numpydoc", "pooch", "pydata-sphinx-theme (>=0.15.2)", "sphinx (>=5.0.0)", "sphinx-design (>=0.4.0)"] -test = ["Cython", "array-api-strict", "asv", "gmpy2", "hypothesis (>=6.30)", "meson", "mpmath", "ninja", "pooch", "pytest", "pytest-cov", "pytest-timeout", "pytest-xdist", "scikit-umfpack", "threadpoolctl"] +doc = ["jupyterlite-pyodide-kernel", "jupyterlite-sphinx (>=0.13.1)", "jupytext", "matplotlib (>=3.5)", "myst-nb", "numpydoc", "pooch", "pydata-sphinx-theme (>=0.15.2)", "sphinx (>=5.0.0,<=7.3.7)", "sphinx-design (>=0.4.0)"] +test = ["Cython", "array-api-strict (>=2.0)", "asv", "gmpy2", "hypothesis (>=6.30)", "meson", "mpmath", "ninja", "pooch", "pytest", "pytest-cov", "pytest-timeout", "pytest-xdist", "scikit-umfpack", "threadpoolctl"] + +[[package]] +name = "send2trash" +version = "1.8.3" +description = "Send file to trash natively under Mac OS X, Windows and Linux" +optional = true +python-versions = "!=3.0.*,!=3.1.*,!=3.2.*,!=3.3.*,!=3.4.*,!=3.5.*,>=2.7" +files = [ + {file = "Send2Trash-1.8.3-py3-none-any.whl", hash = "sha256:0c31227e0bd08961c7665474a3d1ef7193929fedda4233843689baa056be46c9"}, + {file = "Send2Trash-1.8.3.tar.gz", hash = "sha256:b18e7a3966d99871aefeb00cfbcfdced55ce4871194810fc71f4aa484b953abf"}, +] + +[package.extras] +nativelib = ["pyobjc-framework-Cocoa", "pywin32"] +objc = ["pyobjc-framework-Cocoa"] +win32 = ["pywin32"] [[package]] name = "sentry-sdk" -version = "2.10.0" +version = "2.14.0" description = "Python client for Sentry (https://sentry.io)" optional = false python-versions = ">=3.6" files = [ - {file = "sentry_sdk-2.10.0-py2.py3-none-any.whl", hash = "sha256:87b3d413c87d8e7f816cc9334bff255a83d8b577db2b22042651c30c19c09190"}, - {file = "sentry_sdk-2.10.0.tar.gz", hash = "sha256:545fcc6e36c335faa6d6cda84669b6e17025f31efbf3b2211ec14efe008b75d1"}, + {file = "sentry_sdk-2.14.0-py2.py3-none-any.whl", hash = "sha256:b8bc3dc51d06590df1291b7519b85c75e2ced4f28d9ea655b6d54033503b5bf4"}, + {file = "sentry_sdk-2.14.0.tar.gz", hash = "sha256:1e0e2eaf6dad918c7d1e0edac868a7bf20017b177f242cefe2a6bcd47955961d"}, ] [package.dependencies] @@ -3763,10 +6226,11 @@ httpx = ["httpx (>=0.16.0)"] huey = ["huey (>=2)"] huggingface-hub = ["huggingface-hub (>=0.22)"] langchain = ["langchain (>=0.0.210)"] +litestar = ["litestar (>=2.0.0)"] loguru = ["loguru (>=0.5)"] openai = ["openai (>=1.0.0)", "tiktoken (>=0.3.0)"] opentelemetry = ["opentelemetry-distro (>=0.35b0)"] -opentelemetry-experimental = ["opentelemetry-instrumentation-aio-pika (==0.46b0)", "opentelemetry-instrumentation-aiohttp-client (==0.46b0)", "opentelemetry-instrumentation-aiopg (==0.46b0)", "opentelemetry-instrumentation-asgi (==0.46b0)", "opentelemetry-instrumentation-asyncio (==0.46b0)", "opentelemetry-instrumentation-asyncpg (==0.46b0)", "opentelemetry-instrumentation-aws-lambda (==0.46b0)", "opentelemetry-instrumentation-boto (==0.46b0)", "opentelemetry-instrumentation-boto3sqs (==0.46b0)", "opentelemetry-instrumentation-botocore (==0.46b0)", "opentelemetry-instrumentation-cassandra (==0.46b0)", "opentelemetry-instrumentation-celery (==0.46b0)", "opentelemetry-instrumentation-confluent-kafka (==0.46b0)", "opentelemetry-instrumentation-dbapi (==0.46b0)", "opentelemetry-instrumentation-django (==0.46b0)", "opentelemetry-instrumentation-elasticsearch (==0.46b0)", "opentelemetry-instrumentation-falcon (==0.46b0)", "opentelemetry-instrumentation-fastapi (==0.46b0)", "opentelemetry-instrumentation-flask (==0.46b0)", "opentelemetry-instrumentation-grpc (==0.46b0)", "opentelemetry-instrumentation-httpx (==0.46b0)", "opentelemetry-instrumentation-jinja2 (==0.46b0)", "opentelemetry-instrumentation-kafka-python (==0.46b0)", "opentelemetry-instrumentation-logging (==0.46b0)", "opentelemetry-instrumentation-mysql (==0.46b0)", "opentelemetry-instrumentation-mysqlclient (==0.46b0)", "opentelemetry-instrumentation-pika (==0.46b0)", "opentelemetry-instrumentation-psycopg (==0.46b0)", "opentelemetry-instrumentation-psycopg2 (==0.46b0)", "opentelemetry-instrumentation-pymemcache (==0.46b0)", "opentelemetry-instrumentation-pymongo (==0.46b0)", "opentelemetry-instrumentation-pymysql (==0.46b0)", "opentelemetry-instrumentation-pyramid (==0.46b0)", "opentelemetry-instrumentation-redis (==0.46b0)", "opentelemetry-instrumentation-remoulade (==0.46b0)", "opentelemetry-instrumentation-requests (==0.46b0)", "opentelemetry-instrumentation-sklearn (==0.46b0)", "opentelemetry-instrumentation-sqlalchemy (==0.46b0)", "opentelemetry-instrumentation-sqlite3 (==0.46b0)", "opentelemetry-instrumentation-starlette (==0.46b0)", "opentelemetry-instrumentation-system-metrics (==0.46b0)", "opentelemetry-instrumentation-threading (==0.46b0)", "opentelemetry-instrumentation-tornado (==0.46b0)", "opentelemetry-instrumentation-tortoiseorm (==0.46b0)", "opentelemetry-instrumentation-urllib (==0.46b0)", "opentelemetry-instrumentation-urllib3 (==0.46b0)", "opentelemetry-instrumentation-wsgi (==0.46b0)"] +opentelemetry-experimental = ["opentelemetry-distro"] pure-eval = ["asttokens", "executing", "pure-eval"] pymongo = ["pymongo (>=3.1)"] pyspark = ["pyspark (>=2.4.4)"] @@ -3880,63 +6344,84 @@ test = ["pytest"] [[package]] name = "setuptools" -version = "71.0.0" +version = "75.1.0" description = "Easily download, build, install, upgrade, and uninstall Python packages" optional = false python-versions = ">=3.8" files = [ - {file = "setuptools-71.0.0-py3-none-any.whl", hash = "sha256:f06fbe978a91819d250a30e0dc4ca79df713d909e24438a42d0ec300fc52247f"}, - {file = "setuptools-71.0.0.tar.gz", hash = "sha256:98da3b8aca443b9848a209ae4165e2edede62633219afa493a58fbba57f72e2e"}, + {file = "setuptools-75.1.0-py3-none-any.whl", hash = "sha256:35ab7fd3bcd95e6b7fd704e4a1539513edad446c097797f2985e0e4b960772f2"}, + {file = "setuptools-75.1.0.tar.gz", hash = "sha256:d59a21b17a275fb872a9c3dae73963160ae079f1049ed956880cd7c09b120538"}, ] [package.extras] -core = ["importlib-metadata (>=6)", "importlib-resources (>=5.10.2)", "jaraco.text (>=3.7)", "more-itertools (>=8.8)", "ordered-set (>=3.1.1)", "packaging (>=24)", "platformdirs (>=2.6.2)", "tomli (>=2.0.1)", "wheel (>=0.43.0)"] -doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "pygments-github-lexers (==0.0.5)", "pyproject-hooks (!=1.1)", "rst.linker (>=1.9)", "sphinx (<7.4)", "sphinx (>=3.5)", "sphinx-favicon", "sphinx-inline-tabs", "sphinx-lint", "sphinx-notfound-page (>=1,<2)", "sphinx-reredirects", "sphinxcontrib-towncrier"] -test = ["build[virtualenv] (>=1.0.3)", "filelock (>=3.4.0)", "importlib-metadata", "ini2toml[lite] (>=0.14)", "jaraco.develop (>=7.21)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "jaraco.test", "mypy (==1.10.0)", "packaging (>=23.2)", "pip (>=19.1)", "pyproject-hooks (!=1.1)", "pytest (>=6,!=8.1.*)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-home (>=0.5)", "pytest-mypy", "pytest-perf", "pytest-ruff (<0.4)", "pytest-ruff (>=0.2.1)", "pytest-ruff (>=0.3.2)", "pytest-subprocess", "pytest-timeout", "pytest-xdist (>=3)", "tomli", "tomli-w (>=1.0.0)", "virtualenv (>=13.0.0)", "wheel"] +check = ["pytest-checkdocs (>=2.4)", "pytest-ruff (>=0.2.1)", "ruff (>=0.5.2)"] +core = ["importlib-metadata (>=6)", "importlib-resources (>=5.10.2)", "jaraco.collections", "jaraco.functools", "jaraco.text (>=3.7)", "more-itertools", "more-itertools (>=8.8)", "packaging", "packaging (>=24)", "platformdirs (>=2.6.2)", "tomli (>=2.0.1)", "wheel (>=0.43.0)"] +cover = ["pytest-cov"] +doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "pygments-github-lexers (==0.0.5)", "pyproject-hooks (!=1.1)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-favicon", "sphinx-inline-tabs", "sphinx-lint", "sphinx-notfound-page (>=1,<2)", "sphinx-reredirects", "sphinxcontrib-towncrier", "towncrier (<24.7)"] +enabler = ["pytest-enabler (>=2.2)"] +test = ["build[virtualenv] (>=1.0.3)", "filelock (>=3.4.0)", "ini2toml[lite] (>=0.14)", "jaraco.develop (>=7.21)", "jaraco.envs (>=2.2)", "jaraco.path (>=3.2.0)", "jaraco.test", "packaging (>=23.2)", "pip (>=19.1)", "pyproject-hooks (!=1.1)", "pytest (>=6,!=8.1.*)", "pytest-home (>=0.5)", "pytest-perf", "pytest-subprocess", "pytest-timeout", "pytest-xdist (>=3)", "tomli-w (>=1.0.0)", "virtualenv (>=13.0.0)", "wheel (>=0.44.0)"] +type = ["importlib-metadata (>=7.0.2)", "jaraco.develop (>=7.21)", "mypy (==1.11.*)", "pytest-mypy"] + +[[package]] +name = "sh" +version = "2.0.7" +description = "Python subprocess replacement" +optional = true +python-versions = "<4.0,>=3.8.1" +files = [ + {file = "sh-2.0.7-py3-none-any.whl", hash = "sha256:2f2f79a65abd00696cf2e9ad26508cf8abb6dba5745f40255f1c0ded2876926d"}, + {file = "sh-2.0.7.tar.gz", hash = "sha256:029d45198902bfb967391eccfd13a88d92f7cebd200411e93f99ebacc6afbb35"}, +] [[package]] name = "shapely" -version = "2.0.5" +version = "2.0.6" description = "Manipulation and analysis of geometric objects" optional = true python-versions = ">=3.7" files = [ - {file = "shapely-2.0.5-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:89d34787c44f77a7d37d55ae821f3a784fa33592b9d217a45053a93ade899375"}, - {file = "shapely-2.0.5-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:798090b426142df2c5258779c1d8d5734ec6942f778dab6c6c30cfe7f3bf64ff"}, - {file = "shapely-2.0.5-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:45211276900c4790d6bfc6105cbf1030742da67594ea4161a9ce6812a6721e68"}, - {file = "shapely-2.0.5-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2e119444bc27ca33e786772b81760f2028d930ac55dafe9bc50ef538b794a8e1"}, - {file = "shapely-2.0.5-cp310-cp310-win32.whl", hash = "sha256:9a4492a2b2ccbeaebf181e7310d2dfff4fdd505aef59d6cb0f217607cb042fb3"}, - {file = "shapely-2.0.5-cp310-cp310-win_amd64.whl", hash = "sha256:1e5cb5ee72f1bc7ace737c9ecd30dc174a5295fae412972d3879bac2e82c8fae"}, - {file = "shapely-2.0.5-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:5bbfb048a74cf273db9091ff3155d373020852805a37dfc846ab71dde4be93ec"}, - {file = "shapely-2.0.5-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:93be600cbe2fbaa86c8eb70656369f2f7104cd231f0d6585c7d0aa555d6878b8"}, - {file = "shapely-2.0.5-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0f8e71bb9a46814019f6644c4e2560a09d44b80100e46e371578f35eaaa9da1c"}, - {file = "shapely-2.0.5-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:d5251c28a29012e92de01d2e84f11637eb1d48184ee8f22e2df6c8c578d26760"}, - {file = "shapely-2.0.5-cp311-cp311-win32.whl", hash = "sha256:35110e80070d664781ec7955c7de557456b25727a0257b354830abb759bf8311"}, - {file = "shapely-2.0.5-cp311-cp311-win_amd64.whl", hash = "sha256:6c6b78c0007a34ce7144f98b7418800e0a6a5d9a762f2244b00ea560525290c9"}, - {file = "shapely-2.0.5-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:03bd7b5fa5deb44795cc0a503999d10ae9d8a22df54ae8d4a4cd2e8a93466195"}, - {file = "shapely-2.0.5-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2ff9521991ed9e201c2e923da014e766c1aa04771bc93e6fe97c27dcf0d40ace"}, - {file = "shapely-2.0.5-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1b65365cfbf657604e50d15161ffcc68de5cdb22a601bbf7823540ab4918a98d"}, - {file = "shapely-2.0.5-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:21f64e647a025b61b19585d2247137b3a38a35314ea68c66aaf507a1c03ef6fe"}, - {file = "shapely-2.0.5-cp312-cp312-win32.whl", hash = "sha256:3ac7dc1350700c139c956b03d9c3df49a5b34aaf91d024d1510a09717ea39199"}, - {file = "shapely-2.0.5-cp312-cp312-win_amd64.whl", hash = "sha256:30e8737983c9d954cd17feb49eb169f02f1da49e24e5171122cf2c2b62d65c95"}, - {file = "shapely-2.0.5-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:ff7731fea5face9ec08a861ed351734a79475631b7540ceb0b66fb9732a5f529"}, - {file = "shapely-2.0.5-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ff9e520af0c5a578e174bca3c18713cd47a6c6a15b6cf1f50ac17dc8bb8db6a2"}, - {file = "shapely-2.0.5-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:49b299b91557b04acb75e9732645428470825061f871a2edc36b9417d66c1fc5"}, - {file = "shapely-2.0.5-cp37-cp37m-win32.whl", hash = "sha256:b5870633f8e684bf6d1ae4df527ddcb6f3895f7b12bced5c13266ac04f47d231"}, - {file = "shapely-2.0.5-cp37-cp37m-win_amd64.whl", hash = "sha256:401cb794c5067598f50518e5a997e270cd7642c4992645479b915c503866abed"}, - {file = "shapely-2.0.5-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:e91ee179af539100eb520281ba5394919067c6b51824e6ab132ad4b3b3e76dd0"}, - {file = "shapely-2.0.5-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:8af6f7260f809c0862741ad08b1b89cb60c130ae30efab62320bbf4ee9cc71fa"}, - {file = "shapely-2.0.5-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f5456dd522800306ba3faef77c5ba847ec30a0bd73ab087a25e0acdd4db2514f"}, - {file = "shapely-2.0.5-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b714a840402cde66fd7b663bb08cacb7211fa4412ea2a209688f671e0d0631fd"}, - {file = "shapely-2.0.5-cp38-cp38-win32.whl", hash = "sha256:7e8cf5c252fac1ea51b3162be2ec3faddedc82c256a1160fc0e8ddbec81b06d2"}, - {file = "shapely-2.0.5-cp38-cp38-win_amd64.whl", hash = "sha256:4461509afdb15051e73ab178fae79974387f39c47ab635a7330d7fee02c68a3f"}, - {file = "shapely-2.0.5-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:7545a39c55cad1562be302d74c74586f79e07b592df8ada56b79a209731c0219"}, - {file = "shapely-2.0.5-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:4c83a36f12ec8dee2066946d98d4d841ab6512a6ed7eb742e026a64854019b5f"}, - {file = "shapely-2.0.5-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:89e640c2cd37378480caf2eeda9a51be64201f01f786d127e78eaeff091ec897"}, - {file = "shapely-2.0.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:06efe39beafde3a18a21dde169d32f315c57da962826a6d7d22630025200c5e6"}, - {file = "shapely-2.0.5-cp39-cp39-win32.whl", hash = "sha256:8203a8b2d44dcb366becbc8c3d553670320e4acf0616c39e218c9561dd738d92"}, - {file = "shapely-2.0.5-cp39-cp39-win_amd64.whl", hash = "sha256:7fed9dbfbcfec2682d9a047b9699db8dcc890dfca857ecba872c42185fc9e64e"}, - {file = "shapely-2.0.5.tar.gz", hash = "sha256:bff2366bc786bfa6cb353d6b47d0443c570c32776612e527ee47b6df63fcfe32"}, + {file = "shapely-2.0.6-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:29a34e068da2d321e926b5073539fd2a1d4429a2c656bd63f0bd4c8f5b236d0b"}, + {file = "shapely-2.0.6-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:e1c84c3f53144febf6af909d6b581bc05e8785d57e27f35ebaa5c1ab9baba13b"}, + {file = "shapely-2.0.6-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2ad2fae12dca8d2b727fa12b007e46fbc522148a584f5d6546c539f3464dccde"}, + {file = "shapely-2.0.6-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b3304883bd82d44be1b27a9d17f1167fda8c7f5a02a897958d86c59ec69b705e"}, + {file = "shapely-2.0.6-cp310-cp310-win32.whl", hash = "sha256:3ec3a0eab496b5e04633a39fa3d5eb5454628228201fb24903d38174ee34565e"}, + {file = "shapely-2.0.6-cp310-cp310-win_amd64.whl", hash = "sha256:28f87cdf5308a514763a5c38de295544cb27429cfa655d50ed8431a4796090c4"}, + {file = "shapely-2.0.6-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:5aeb0f51a9db176da9a30cb2f4329b6fbd1e26d359012bb0ac3d3c7781667a9e"}, + {file = "shapely-2.0.6-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:9a7a78b0d51257a367ee115f4d41ca4d46edbd0dd280f697a8092dd3989867b2"}, + {file = "shapely-2.0.6-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f32c23d2f43d54029f986479f7c1f6e09c6b3a19353a3833c2ffb226fb63a855"}, + {file = "shapely-2.0.6-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b3dc9fb0eb56498912025f5eb352b5126f04801ed0e8bdbd867d21bdbfd7cbd0"}, + {file = "shapely-2.0.6-cp311-cp311-win32.whl", hash = "sha256:d93b7e0e71c9f095e09454bf18dad5ea716fb6ced5df3cb044564a00723f339d"}, + {file = "shapely-2.0.6-cp311-cp311-win_amd64.whl", hash = "sha256:c02eb6bf4cfb9fe6568502e85bb2647921ee49171bcd2d4116c7b3109724ef9b"}, + {file = "shapely-2.0.6-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:cec9193519940e9d1b86a3b4f5af9eb6910197d24af02f247afbfb47bcb3fab0"}, + {file = "shapely-2.0.6-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:83b94a44ab04a90e88be69e7ddcc6f332da7c0a0ebb1156e1c4f568bbec983c3"}, + {file = "shapely-2.0.6-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:537c4b2716d22c92036d00b34aac9d3775e3691f80c7aa517c2c290351f42cd8"}, + {file = "shapely-2.0.6-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:98fea108334be345c283ce74bf064fa00cfdd718048a8af7343c59eb40f59726"}, + {file = "shapely-2.0.6-cp312-cp312-win32.whl", hash = "sha256:42fd4cd4834747e4990227e4cbafb02242c0cffe9ce7ef9971f53ac52d80d55f"}, + {file = "shapely-2.0.6-cp312-cp312-win_amd64.whl", hash = "sha256:665990c84aece05efb68a21b3523a6b2057e84a1afbef426ad287f0796ef8a48"}, + {file = "shapely-2.0.6-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:42805ef90783ce689a4dde2b6b2f261e2c52609226a0438d882e3ced40bb3013"}, + {file = "shapely-2.0.6-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:6d2cb146191a47bd0cee8ff5f90b47547b82b6345c0d02dd8b25b88b68af62d7"}, + {file = "shapely-2.0.6-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e3fdef0a1794a8fe70dc1f514440aa34426cc0ae98d9a1027fb299d45741c381"}, + {file = "shapely-2.0.6-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2c665a0301c645615a107ff7f52adafa2153beab51daf34587170d85e8ba6805"}, + {file = "shapely-2.0.6-cp313-cp313-win32.whl", hash = "sha256:0334bd51828f68cd54b87d80b3e7cee93f249d82ae55a0faf3ea21c9be7b323a"}, + {file = "shapely-2.0.6-cp313-cp313-win_amd64.whl", hash = "sha256:d37d070da9e0e0f0a530a621e17c0b8c3c9d04105655132a87cfff8bd77cc4c2"}, + {file = "shapely-2.0.6-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:fa7468e4f5b92049c0f36d63c3e309f85f2775752e076378e36c6387245c5462"}, + {file = "shapely-2.0.6-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:ed5867e598a9e8ac3291da6cc9baa62ca25706eea186117034e8ec0ea4355653"}, + {file = "shapely-2.0.6-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:81d9dfe155f371f78c8d895a7b7f323bb241fb148d848a2bf2244f79213123fe"}, + {file = "shapely-2.0.6-cp37-cp37m-win32.whl", hash = "sha256:fbb7bf02a7542dba55129062570211cfb0defa05386409b3e306c39612e7fbcc"}, + {file = "shapely-2.0.6-cp37-cp37m-win_amd64.whl", hash = "sha256:837d395fac58aa01aa544495b97940995211e3e25f9aaf87bc3ba5b3a8cd1ac7"}, + {file = "shapely-2.0.6-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:c6d88ade96bf02f6bfd667ddd3626913098e243e419a0325ebef2bbd481d1eb6"}, + {file = "shapely-2.0.6-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:8b3b818c4407eaa0b4cb376fd2305e20ff6df757bf1356651589eadc14aab41b"}, + {file = "shapely-2.0.6-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1bbc783529a21f2bd50c79cef90761f72d41c45622b3e57acf78d984c50a5d13"}, + {file = "shapely-2.0.6-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2423f6c0903ebe5df6d32e0066b3d94029aab18425ad4b07bf98c3972a6e25a1"}, + {file = "shapely-2.0.6-cp38-cp38-win32.whl", hash = "sha256:2de00c3bfa80d6750832bde1d9487e302a6dd21d90cb2f210515cefdb616e5f5"}, + {file = "shapely-2.0.6-cp38-cp38-win_amd64.whl", hash = "sha256:3a82d58a1134d5e975f19268710e53bddd9c473743356c90d97ce04b73e101ee"}, + {file = "shapely-2.0.6-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:392f66f458a0a2c706254f473290418236e52aa4c9b476a072539d63a2460595"}, + {file = "shapely-2.0.6-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:eba5bae271d523c938274c61658ebc34de6c4b33fdf43ef7e938b5776388c1be"}, + {file = "shapely-2.0.6-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7060566bc4888b0c8ed14b5d57df8a0ead5c28f9b69fb6bed4476df31c51b0af"}, + {file = "shapely-2.0.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b02154b3e9d076a29a8513dffcb80f047a5ea63c897c0cd3d3679f29363cf7e5"}, + {file = "shapely-2.0.6-cp39-cp39-win32.whl", hash = "sha256:44246d30124a4f1a638a7d5419149959532b99dfa25b54393512e6acc9c211ac"}, + {file = "shapely-2.0.6-cp39-cp39-win_amd64.whl", hash = "sha256:2b542d7f1dbb89192d3512c52b679c822ba916f93479fa5d4fc2fe4fa0b3c9e8"}, + {file = "shapely-2.0.6.tar.gz", hash = "sha256:997f6159b1484059ec239cacaa53467fd8b5564dabe186cd84ac2944663b0bf6"}, ] [package.dependencies] @@ -3968,26 +6453,101 @@ files = [ {file = "smmap-5.0.1.tar.gz", hash = "sha256:dceeb6c0028fdb6734471eb07c0cd2aae706ccaecab45965ee83f11c8d3b1f62"}, ] +[[package]] +name = "snakeviz" +version = "2.2.0" +description = "A web-based viewer for Python profiler output" +optional = true +python-versions = ">=3.7" +files = [ + {file = "snakeviz-2.2.0-py2.py3-none-any.whl", hash = "sha256:569e2d71c47f80a886aa6e70d6405cb6d30aa3520969ad956b06f824c5f02b8e"}, + {file = "snakeviz-2.2.0.tar.gz", hash = "sha256:7bfd00be7ae147eb4a170a471578e1cd3f41f803238958b6b8efcf2c698a6aa9"}, +] + +[package.dependencies] +tornado = ">=2.0" + +[[package]] +name = "sniffio" +version = "1.3.1" +description = "Sniff out which async library your code is running under" +optional = true +python-versions = ">=3.7" +files = [ + {file = "sniffio-1.3.1-py3-none-any.whl", hash = "sha256:2f6da418d1f1e0fddd844478f41680e794e6051915791a034ff65e5f100525a2"}, + {file = "sniffio-1.3.1.tar.gz", hash = "sha256:f4324edc670a0f49750a81b895f35c3adb843cca46f0530f79fc1babb23789dc"}, +] + [[package]] name = "soupsieve" -version = "2.5" +version = "2.6" description = "A modern CSS selector implementation for Beautiful Soup." optional = false python-versions = ">=3.8" files = [ - {file = "soupsieve-2.5-py3-none-any.whl", hash = "sha256:eaa337ff55a1579b6549dc679565eac1e3d000563bcb1c8ab0d0fefbc0c2cdc7"}, - {file = "soupsieve-2.5.tar.gz", hash = "sha256:5663d5a7b3bfaeee0bc4372e7fc48f9cff4940b3eec54a6451cc5299f1097690"}, + {file = "soupsieve-2.6-py3-none-any.whl", hash = "sha256:e72c4ff06e4fb6e4b5a9f0f55fe6e81514581fca1515028625d0f299c602ccc9"}, + {file = "soupsieve-2.6.tar.gz", hash = "sha256:e2e68417777af359ec65daac1057404a3c8a5455bb8abc36f1a9866ab1a51abb"}, +] + +[[package]] +name = "speechrecognition" +version = "3.10.4" +description = "Library for performing speech recognition, with support for several engines and APIs, online and offline." +optional = true +python-versions = ">=3.8" +files = [ + {file = "SpeechRecognition-3.10.4-py2.py3-none-any.whl", hash = "sha256:723b8155692a8ed11a30013f15f89a3e57c5dc8bc73c8cb024bf9bd14c21fba5"}, + {file = "speechrecognition-3.10.4.tar.gz", hash = "sha256:986bafcf61f14625c2f3cea6a471838edd379ed68aeed7b8f3c0fb41e21f1125"}, +] + +[package.dependencies] +requests = ">=2.26.0" +typing-extensions = "*" + +[package.extras] +dev = ["flake8", "rstcheck"] +whisper-api = ["openai"] +whisper-local = ["openai-whisper", "soundfile"] + +[[package]] +name = "spidev" +version = "3.6" +description = "Python bindings for Linux SPI access through spidev" +optional = true +python-versions = "*" +files = [ + {file = "spidev-3.6-cp39-cp39-linux_armv7l.whl", hash = "sha256:280abc00a1ef7780ef62c3f294f52a2527b6c47d8c269fea98664970bcaf6da5"}, + {file = "spidev-3.6.tar.gz", hash = "sha256:14dbc37594a4aaef85403ab617985d3c3ef464d62bc9b769ef552db53701115b"}, +] + +[[package]] +name = "stack-data" +version = "0.6.3" +description = "Extract data from python stack frames and tracebacks for informative displays" +optional = true +python-versions = "*" +files = [ + {file = "stack_data-0.6.3-py3-none-any.whl", hash = "sha256:d5558e0c25a4cb0853cddad3d77da9891a08cb85dd9f9f91b9f8cd66e511e695"}, + {file = "stack_data-0.6.3.tar.gz", hash = "sha256:836a778de4fec4dcd1dcd89ed8abff8a221f58308462e1c4aa2a3cf30148f0b9"}, ] +[package.dependencies] +asttokens = ">=2.1.0" +executing = ">=1.2.0" +pure-eval = "*" + +[package.extras] +tests = ["cython", "littleutils", "pygments", "pytest", "typeguard"] + [[package]] name = "sympy" -version = "1.13.0" +version = "1.13.3" description = "Computer algebra system (CAS) in Python" optional = false python-versions = ">=3.8" files = [ - {file = "sympy-1.13.0-py3-none-any.whl", hash = "sha256:6b0b32a4673fb91bd3cac3b55406c8e01d53ae22780be467301cc452f6680c92"}, - {file = "sympy-1.13.0.tar.gz", hash = "sha256:3b6af8f4d008b9a1a6a4268b335b984b23835f26d1d60b0526ebc71d48a25f57"}, + {file = "sympy-1.13.3-py3-none-any.whl", hash = "sha256:54612cf55a62755ee71824ce692986f23c88ffa77207b30c1368eda4a7060f73"}, + {file = "sympy-1.13.3.tar.gz", hash = "sha256:b27fd2c6530e0ab39e275fc9b683895367e51d5da91baa8d3d64db2565fec4d9"}, ] [package.dependencies] @@ -3997,18 +6557,34 @@ mpmath = ">=1.1.0,<1.4" dev = ["hypothesis (>=6.70.0)", "pytest (>=7.1.0)"] [[package]] -name = "tbb" -version = "2021.13.0" -description = "Intel® oneAPI Threading Building Blocks (oneTBB)" -optional = false -python-versions = "*" +name = "tabulate" +version = "0.9.0" +description = "Pretty-print tabular data" +optional = true +python-versions = ">=3.7" +files = [ + {file = "tabulate-0.9.0-py3-none-any.whl", hash = "sha256:024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f"}, + {file = "tabulate-0.9.0.tar.gz", hash = "sha256:0095b12bf5966de529c0feb1fa08671671b3368eec77d7ef7ab114be2c068b3c"}, +] + +[package.extras] +widechars = ["wcwidth"] + +[[package]] +name = "tenacity" +version = "9.0.0" +description = "Retry code until it succeeds" +optional = true +python-versions = ">=3.8" files = [ - {file = "tbb-2021.13.0-py2.py3-none-manylinux1_i686.whl", hash = "sha256:a2567725329639519d46d92a2634cf61e76601dac2f777a05686fea546c4fe4f"}, - {file = "tbb-2021.13.0-py2.py3-none-manylinux1_x86_64.whl", hash = "sha256:aaf667e92849adb012b8874d6393282afc318aca4407fc62f912ee30a22da46a"}, - {file = "tbb-2021.13.0-py3-none-win32.whl", hash = "sha256:6669d26703e9943f6164c6407bd4a237a45007e79b8d3832fe6999576eaaa9ef"}, - {file = "tbb-2021.13.0-py3-none-win_amd64.whl", hash = "sha256:3528a53e4bbe64b07a6112b4c5a00ff3c61924ee46c9c68e004a1ac7ad1f09c3"}, + {file = "tenacity-9.0.0-py3-none-any.whl", hash = "sha256:93de0c98785b27fcf659856aa9f54bfbd399e29969b0621bc7f762bd441b4539"}, + {file = "tenacity-9.0.0.tar.gz", hash = "sha256:807f37ca97d62aa361264d497b0e31e92b8027044942bfa756160d908320d73b"}, ] +[package.extras] +doc = ["reno", "sphinx"] +test = ["pytest", "tornado (>=4.5)", "typeguard"] + [[package]] name = "termcolor" version = "2.4.0" @@ -4023,15 +6599,36 @@ files = [ [package.extras] tests = ["pytest", "pytest-cov"] +[[package]] +name = "terminado" +version = "0.18.1" +description = "Tornado websocket backend for the Xterm.js Javascript terminal emulator library." +optional = true +python-versions = ">=3.8" +files = [ + {file = "terminado-0.18.1-py3-none-any.whl", hash = "sha256:a4468e1b37bb318f8a86514f65814e1afc977cf29b3992a4500d9dd305dcceb0"}, + {file = "terminado-0.18.1.tar.gz", hash = "sha256:de09f2c4b85de4765f7714688fff57d3e75bad1f909b589fde880460c753fd2e"}, +] + +[package.dependencies] +ptyprocess = {version = "*", markers = "os_name != \"nt\""} +pywinpty = {version = ">=1.1.0", markers = "os_name == \"nt\""} +tornado = ">=6.1.0" + +[package.extras] +docs = ["myst-parser", "pydata-sphinx-theme", "sphinx"] +test = ["pre-commit", "pytest (>=7.0)", "pytest-timeout"] +typing = ["mypy (>=1.6,<2.0)", "traitlets (>=5.11.1)"] + [[package]] name = "tifffile" -version = "2024.7.2" +version = "2024.9.20" description = "Read and write TIFF files" optional = true -python-versions = ">=3.9" +python-versions = ">=3.10" files = [ - {file = "tifffile-2024.7.2-py3-none-any.whl", hash = "sha256:5a2ee608c9cc1f2e044d943dacebddc71d4827b6fad150ef4c644b7aefbe2d1a"}, - {file = "tifffile-2024.7.2.tar.gz", hash = "sha256:02e52e8872c0e9943add686d2fd8bcfb18f0a824760882cf5e35fcbc2c80e32c"}, + {file = "tifffile-2024.9.20-py3-none-any.whl", hash = "sha256:c54dc85bc1065d972cb8a6ffb3181389d597876aa80177933459733e4ed243dd"}, + {file = "tifffile-2024.9.20.tar.gz", hash = "sha256:3fbf3be2f995a7051a8ae05a4be70c96fc0789f22ed6f1c4104c973cf68a640b"}, ] [package.dependencies] @@ -4039,6 +6636,29 @@ numpy = "*" [package.extras] all = ["defusedxml", "fsspec", "imagecodecs (>=2023.8.12)", "lxml", "matplotlib", "zarr"] +codecs = ["imagecodecs (>=2023.8.12)"] +plot = ["matplotlib"] +test = ["cmapfile", "czifile", "dask", "defusedxml", "fsspec", "imagecodecs", "lfdfiles", "lxml", "ndtiff", "oiffile", "psdtags", "pytest", "roifile", "xarray", "zarr"] +xml = ["defusedxml", "lxml"] +zarr = ["fsspec", "zarr"] + +[[package]] +name = "tinycss2" +version = "1.3.0" +description = "A tiny CSS parser" +optional = true +python-versions = ">=3.8" +files = [ + {file = "tinycss2-1.3.0-py3-none-any.whl", hash = "sha256:54a8dbdffb334d536851be0226030e9505965bb2f30f21a4a82c55fb2a80fae7"}, + {file = "tinycss2-1.3.0.tar.gz", hash = "sha256:152f9acabd296a8375fbca5b84c961ff95971fcfc32e79550c8df8e29118c54d"}, +] + +[package.dependencies] +webencodings = ">=0.4" + +[package.extras] +doc = ["sphinx", "sphinx_rtd_theme"] +test = ["pytest", "ruff"] [[package]] name = "tomli" @@ -4053,104 +6673,125 @@ files = [ [[package]] name = "torch" -version = "2.3.1" +version = "2.4.1" description = "Tensors and Dynamic neural networks in Python with strong GPU acceleration" optional = false python-versions = ">=3.8.0" files = [ - {file = "torch-2.3.1-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:605a25b23944be5ab7c3467e843580e1d888b8066e5aaf17ff7bf9cc30001cc3"}, - {file = "torch-2.3.1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:f2357eb0965583a0954d6f9ad005bba0091f956aef879822274b1bcdb11bd308"}, - {file = "torch-2.3.1-cp310-cp310-win_amd64.whl", hash = "sha256:32b05fe0d1ada7f69c9f86c14ff69b0ef1957a5a54199bacba63d22d8fab720b"}, - {file = "torch-2.3.1-cp310-none-macosx_11_0_arm64.whl", hash = "sha256:7c09a94362778428484bcf995f6004b04952106aee0ef45ff0b4bab484f5498d"}, - {file = "torch-2.3.1-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:b2ec81b61bb094ea4a9dee1cd3f7b76a44555375719ad29f05c0ca8ef596ad39"}, - {file = "torch-2.3.1-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:490cc3d917d1fe0bd027057dfe9941dc1d6d8e3cae76140f5dd9a7e5bc7130ab"}, - {file = "torch-2.3.1-cp311-cp311-win_amd64.whl", hash = "sha256:5802530783bd465fe66c2df99123c9a54be06da118fbd785a25ab0a88123758a"}, - {file = "torch-2.3.1-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:a7dd4ed388ad1f3d502bf09453d5fe596c7b121de7e0cfaca1e2017782e9bbac"}, - {file = "torch-2.3.1-cp312-cp312-manylinux1_x86_64.whl", hash = "sha256:a486c0b1976a118805fc7c9641d02df7afbb0c21e6b555d3bb985c9f9601b61a"}, - {file = "torch-2.3.1-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:224259821fe3e4c6f7edf1528e4fe4ac779c77addaa74215eb0b63a5c474d66c"}, - {file = "torch-2.3.1-cp312-cp312-win_amd64.whl", hash = "sha256:e5fdccbf6f1334b2203a61a0e03821d5845f1421defe311dabeae2fc8fbeac2d"}, - {file = "torch-2.3.1-cp312-none-macosx_11_0_arm64.whl", hash = "sha256:3c333dc2ebc189561514eda06e81df22bf8fb64e2384746b2cb9f04f96d1d4c8"}, - {file = "torch-2.3.1-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:07e9ba746832b8d069cacb45f312cadd8ad02b81ea527ec9766c0e7404bb3feb"}, - {file = "torch-2.3.1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:462d1c07dbf6bb5d9d2f3316fee73a24f3d12cd8dacf681ad46ef6418f7f6626"}, - {file = "torch-2.3.1-cp38-cp38-win_amd64.whl", hash = "sha256:ff60bf7ce3de1d43ad3f6969983f321a31f0a45df3690921720bcad6a8596cc4"}, - {file = "torch-2.3.1-cp38-none-macosx_11_0_arm64.whl", hash = "sha256:bee0bd33dc58aa8fc8a7527876e9b9a0e812ad08122054a5bff2ce5abf005b10"}, - {file = "torch-2.3.1-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:aaa872abde9a3d4f91580f6396d54888620f4a0b92e3976a6034759df4b961ad"}, - {file = "torch-2.3.1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:3d7a7f7ef21a7520510553dc3938b0c57c116a7daee20736a9e25cbc0e832bdc"}, - {file = "torch-2.3.1-cp39-cp39-win_amd64.whl", hash = "sha256:4777f6cefa0c2b5fa87223c213e7b6f417cf254a45e5829be4ccd1b2a4ee1011"}, - {file = "torch-2.3.1-cp39-none-macosx_11_0_arm64.whl", hash = "sha256:2bb5af780c55be68fe100feb0528d2edebace1d55cb2e351de735809ba7391eb"}, + {file = "torch-2.4.1-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:362f82e23a4cd46341daabb76fba08f04cd646df9bfaf5da50af97cb60ca4971"}, + {file = "torch-2.4.1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:e8ac1985c3ff0f60d85b991954cfc2cc25f79c84545aead422763148ed2759e3"}, + {file = "torch-2.4.1-cp310-cp310-win_amd64.whl", hash = "sha256:91e326e2ccfb1496e3bee58f70ef605aeb27bd26be07ba64f37dcaac3d070ada"}, + {file = "torch-2.4.1-cp310-none-macosx_11_0_arm64.whl", hash = "sha256:d36a8ef100f5bff3e9c3cea934b9e0d7ea277cb8210c7152d34a9a6c5830eadd"}, + {file = "torch-2.4.1-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:0b5f88afdfa05a335d80351e3cea57d38e578c8689f751d35e0ff36bce872113"}, + {file = "torch-2.4.1-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:ef503165f2341942bfdf2bd520152f19540d0c0e34961232f134dc59ad435be8"}, + {file = "torch-2.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:092e7c2280c860eff762ac08c4bdcd53d701677851670695e0c22d6d345b269c"}, + {file = "torch-2.4.1-cp311-none-macosx_11_0_arm64.whl", hash = "sha256:ddddbd8b066e743934a4200b3d54267a46db02106876d21cf31f7da7a96f98ea"}, + {file = "torch-2.4.1-cp312-cp312-manylinux1_x86_64.whl", hash = "sha256:fdc4fe11db3eb93c1115d3e973a27ac7c1a8318af8934ffa36b0370efe28e042"}, + {file = "torch-2.4.1-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:18835374f599207a9e82c262153c20ddf42ea49bc76b6eadad8e5f49729f6e4d"}, + {file = "torch-2.4.1-cp312-cp312-win_amd64.whl", hash = "sha256:ebea70ff30544fc021d441ce6b219a88b67524f01170b1c538d7d3ebb5e7f56c"}, + {file = "torch-2.4.1-cp312-none-macosx_11_0_arm64.whl", hash = "sha256:72b484d5b6cec1a735bf3fa5a1c4883d01748698c5e9cfdbeb4ffab7c7987e0d"}, + {file = "torch-2.4.1-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:c99e1db4bf0c5347107845d715b4aa1097e601bdc36343d758963055e9599d93"}, + {file = "torch-2.4.1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:b57f07e92858db78c5b72857b4f0b33a65b00dc5d68e7948a8494b0314efb880"}, + {file = "torch-2.4.1-cp38-cp38-win_amd64.whl", hash = "sha256:f18197f3f7c15cde2115892b64f17c80dbf01ed72b008020e7da339902742cf6"}, + {file = "torch-2.4.1-cp38-none-macosx_11_0_arm64.whl", hash = "sha256:5fc1d4d7ed265ef853579caf272686d1ed87cebdcd04f2a498f800ffc53dab71"}, + {file = "torch-2.4.1-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:40f6d3fe3bae74efcf08cb7f8295eaddd8a838ce89e9d26929d4edd6d5e4329d"}, + {file = "torch-2.4.1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:c9299c16c9743001ecef515536ac45900247f4338ecdf70746f2461f9e4831db"}, + {file = "torch-2.4.1-cp39-cp39-win_amd64.whl", hash = "sha256:6bce130f2cd2d52ba4e2c6ada461808de7e5eccbac692525337cfb4c19421846"}, + {file = "torch-2.4.1-cp39-none-macosx_11_0_arm64.whl", hash = "sha256:a38de2803ee6050309aac032676536c3d3b6a9804248537e38e098d0e14817ec"}, ] [package.dependencies] filelock = "*" fsspec = "*" jinja2 = "*" -mkl = {version = ">=2021.1.1,<=2021.4.0", markers = "platform_system == \"Windows\""} networkx = "*" nvidia-cublas-cu12 = {version = "12.1.3.1", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-cuda-cupti-cu12 = {version = "12.1.105", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-cuda-nvrtc-cu12 = {version = "12.1.105", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-cuda-runtime-cu12 = {version = "12.1.105", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} -nvidia-cudnn-cu12 = {version = "8.9.2.26", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +nvidia-cudnn-cu12 = {version = "9.1.0.70", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-cufft-cu12 = {version = "11.0.2.54", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-curand-cu12 = {version = "10.3.2.106", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-cusolver-cu12 = {version = "11.4.5.107", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-cusparse-cu12 = {version = "12.1.0.106", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-nccl-cu12 = {version = "2.20.5", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} nvidia-nvtx-cu12 = {version = "12.1.105", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\""} +setuptools = "*" sympy = "*" -triton = {version = "2.3.1", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\" and python_version < \"3.12\""} +triton = {version = "3.0.0", markers = "platform_system == \"Linux\" and platform_machine == \"x86_64\" and python_version < \"3.13\""} typing-extensions = ">=4.8.0" [package.extras] opt-einsum = ["opt-einsum (>=3.3)"] -optree = ["optree (>=0.9.1)"] +optree = ["optree (>=0.11.0)"] [[package]] name = "torchvision" -version = "0.18.1" +version = "0.19.1" description = "image and video datasets and models for torch deep learning" optional = false python-versions = ">=3.8" files = [ - {file = "torchvision-0.18.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:3e694e54b0548dad99c12af6bf0c8e4f3350137d391dcd19af22a1c5f89322b3"}, - {file = "torchvision-0.18.1-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:0b3bda0aa5b416eeb547143b8eeaf17720bdba9cf516dc991aacb81811aa96a5"}, - {file = "torchvision-0.18.1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:573ff523c739405edb085f65cb592f482d28a30e29b0be4c4ba08040b3ae785f"}, - {file = "torchvision-0.18.1-cp310-cp310-win_amd64.whl", hash = "sha256:ef7bbbc60b38e831a75e547c66ca1784f2ac27100f9e4ddbe9614cef6cbcd942"}, - {file = "torchvision-0.18.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:80b5d794dd0fdba787adc22f1a367a5ead452327686473cb260dd94364bc56a6"}, - {file = "torchvision-0.18.1-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:9077cf590cdb3a5e8fdf5cdb71797f8c67713f974cf0228ecb17fcd670ab42f9"}, - {file = "torchvision-0.18.1-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:ceb993a882f1ae7ae373ed39c28d7e3e802205b0e59a7ed84ef4028f0bba8d7f"}, - {file = "torchvision-0.18.1-cp311-cp311-win_amd64.whl", hash = "sha256:52f7436140045dc2239cdc502aa76b2bd8bd676d64244ff154d304aa69852046"}, - {file = "torchvision-0.18.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:2be6f0bf7c455c89a51a1dbb6f668d36c6edc479f49ac912d745d10df5715657"}, - {file = "torchvision-0.18.1-cp312-cp312-manylinux1_x86_64.whl", hash = "sha256:f118d887bfde3a948a41d56587525401e5cac1b7db2eaca203324d6ed2b1caca"}, - {file = "torchvision-0.18.1-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:13d24d904f65e62d66a1e0c41faec630bc193867b8a4a01166769e8a8e8df8e9"}, - {file = "torchvision-0.18.1-cp312-cp312-win_amd64.whl", hash = "sha256:ed6340b69a63a625e512a66127210d412551d9c5f2ad2978130c6a45bf56cd4a"}, - {file = "torchvision-0.18.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:b1c3864fa9378c88bce8ad0ef3599f4f25397897ce612e1c245c74b97092f35e"}, - {file = "torchvision-0.18.1-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:02085a2ffc7461f5c0edb07d6f3455ee1806561f37736b903da820067eea58c7"}, - {file = "torchvision-0.18.1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:9726c316a2501df8503e5a5dc46a631afd4c515a958972e5b7f7b9c87d2125c0"}, - {file = "torchvision-0.18.1-cp38-cp38-win_amd64.whl", hash = "sha256:64a2662dbf30db9055d8b201d6e56f312a504e5ccd9d144c57c41622d3c524cb"}, - {file = "torchvision-0.18.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:975b8594c0f5288875408acbb74946eea786c5b008d129c0d045d0ead23742bc"}, - {file = "torchvision-0.18.1-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:da83c8bbd34d8bee48bfa1d1b40e0844bc3cba10ed825a5a8cbe3ce7b62264cd"}, - {file = "torchvision-0.18.1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:54bfcd352abb396d5c9c237d200167c178bd136051b138e1e8ef46ce367c2773"}, - {file = "torchvision-0.18.1-cp39-cp39-win_amd64.whl", hash = "sha256:5c8366a1aeee49e9ea9e64b30d199debdf06b1bd7610a76165eb5d7869c3bde5"}, + {file = "torchvision-0.19.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:54e8513099e6f586356c70f809d34f391af71ad182fe071cc328a28af2c40608"}, + {file = "torchvision-0.19.1-cp310-cp310-manylinux1_x86_64.whl", hash = "sha256:20a1f5e02bfdad7714e55fa3fa698347c11d829fa65e11e5a84df07d93350eed"}, + {file = "torchvision-0.19.1-cp310-cp310-manylinux2014_aarch64.whl", hash = "sha256:7b063116164be52fc6deb4762de7f8c90bfa3a65f8d5caf17f8e2d5aadc75a04"}, + {file = "torchvision-0.19.1-cp310-cp310-win_amd64.whl", hash = "sha256:f40b6acabfa886da1bc3768f47679c61feee6bde90deb979d9f300df8c8a0145"}, + {file = "torchvision-0.19.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:40514282b4896d62765b8e26d7091c32e17c35817d00ec4be2362ea3ba3d1787"}, + {file = "torchvision-0.19.1-cp311-cp311-manylinux1_x86_64.whl", hash = "sha256:5a91be061ae5d6d5b95e833b93e57ca4d3c56c5a57444dd15da2e3e7fba96050"}, + {file = "torchvision-0.19.1-cp311-cp311-manylinux2014_aarch64.whl", hash = "sha256:d71a6a6fe3a5281ca3487d4c56ad4aad20ff70f82f1d7c79bcb6e7b0c2af00c8"}, + {file = "torchvision-0.19.1-cp311-cp311-win_amd64.whl", hash = "sha256:70dea324174f5e9981b68e4b7cd524512c106ba64aedef560a86a0bbf2fbf62c"}, + {file = "torchvision-0.19.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:27ece277ff0f6cdc7fed0627279c632dcb2e58187da771eca24b0fbcf3f8590d"}, + {file = "torchvision-0.19.1-cp312-cp312-manylinux1_x86_64.whl", hash = "sha256:c659ff92a61f188a1a7baef2850f3c0b6c85685447453c03d0e645ba8f1dcc1c"}, + {file = "torchvision-0.19.1-cp312-cp312-manylinux2014_aarch64.whl", hash = "sha256:c07bf43c2a145d792ecd9d0503d6c73577147ece508d45600d8aac77e4cdfcf9"}, + {file = "torchvision-0.19.1-cp312-cp312-win_amd64.whl", hash = "sha256:b4283d283675556bb0eae31d29996f53861b17cbdcdf3509e6bc050414ac9289"}, + {file = "torchvision-0.19.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:4c4e4f5b24ea6b087b02ed492ab1e21bba3352c4577e2def14248cfc60732338"}, + {file = "torchvision-0.19.1-cp38-cp38-manylinux1_x86_64.whl", hash = "sha256:9281d63ead929bb19143731154cd1d8bf0b5e9873dff8578a40e90a6bec3c6fa"}, + {file = "torchvision-0.19.1-cp38-cp38-manylinux2014_aarch64.whl", hash = "sha256:4d10bc9083c4d5fadd7edd7b729700a7be48dab4f62278df3bc73fa48e48a155"}, + {file = "torchvision-0.19.1-cp38-cp38-win_amd64.whl", hash = "sha256:ccf085ef1824fb9e16f1901285bf89c298c62dfd93267a39e8ee42c71255242f"}, + {file = "torchvision-0.19.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:731f434d91586769e255b5d70ed1a4457e0a1394a95f4aacf0e1e7e21f80c098"}, + {file = "torchvision-0.19.1-cp39-cp39-manylinux1_x86_64.whl", hash = "sha256:febe4f14d4afcb47cc861d8be7760ab6a123cd0817f97faf5771488cb6aa90f4"}, + {file = "torchvision-0.19.1-cp39-cp39-manylinux2014_aarch64.whl", hash = "sha256:e328309b8670a2e889b2fe76a1c2744a099c11c984da9a822357bd9debd699a5"}, + {file = "torchvision-0.19.1-cp39-cp39-win_amd64.whl", hash = "sha256:6616f12e00a22e7f3fedbd0fccb0804c05e8fe22871668f10eae65cf3f283614"}, ] [package.dependencies] numpy = "*" pillow = ">=5.3.0,<8.3.dev0 || >=8.4.dev0" -torch = "2.3.1" +torch = "2.4.1" [package.extras] +gdown = ["gdown (>=4.7.3)"] scipy = ["scipy"] +[[package]] +name = "tornado" +version = "6.4.1" +description = "Tornado is a Python web framework and asynchronous networking library, originally developed at FriendFeed." +optional = true +python-versions = ">=3.8" +files = [ + {file = "tornado-6.4.1-cp38-abi3-macosx_10_9_universal2.whl", hash = "sha256:163b0aafc8e23d8cdc3c9dfb24c5368af84a81e3364745ccb4427669bf84aec8"}, + {file = "tornado-6.4.1-cp38-abi3-macosx_10_9_x86_64.whl", hash = "sha256:6d5ce3437e18a2b66fbadb183c1d3364fb03f2be71299e7d10dbeeb69f4b2a14"}, + {file = "tornado-6.4.1-cp38-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:e2e20b9113cd7293f164dc46fffb13535266e713cdb87bd2d15ddb336e96cfc4"}, + {file = "tornado-6.4.1-cp38-abi3-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8ae50a504a740365267b2a8d1a90c9fbc86b780a39170feca9bcc1787ff80842"}, + {file = "tornado-6.4.1-cp38-abi3-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:613bf4ddf5c7a95509218b149b555621497a6cc0d46ac341b30bd9ec19eac7f3"}, + {file = "tornado-6.4.1-cp38-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:25486eb223babe3eed4b8aecbac33b37e3dd6d776bc730ca14e1bf93888b979f"}, + {file = "tornado-6.4.1-cp38-abi3-musllinux_1_2_i686.whl", hash = "sha256:454db8a7ecfcf2ff6042dde58404164d969b6f5d58b926da15e6b23817950fc4"}, + {file = "tornado-6.4.1-cp38-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:a02a08cc7a9314b006f653ce40483b9b3c12cda222d6a46d4ac63bb6c9057698"}, + {file = "tornado-6.4.1-cp38-abi3-win32.whl", hash = "sha256:d9a566c40b89757c9aa8e6f032bcdb8ca8795d7c1a9762910c722b1635c9de4d"}, + {file = "tornado-6.4.1-cp38-abi3-win_amd64.whl", hash = "sha256:b24b8982ed444378d7f21d563f4180a2de31ced9d8d84443907a0a64da2072e7"}, + {file = "tornado-6.4.1.tar.gz", hash = "sha256:92d3ab53183d8c50f8204a51e6f91d18a15d5ef261e84d452800d4ff6fc504e9"}, +] + [[package]] name = "tqdm" -version = "4.66.4" +version = "4.66.5" description = "Fast, Extensible Progress Meter" optional = false python-versions = ">=3.7" files = [ - {file = "tqdm-4.66.4-py3-none-any.whl", hash = "sha256:b75ca56b413b030bc3f00af51fd2c1a1a5eac6a0c1cca83cbb37a5c52abce644"}, - {file = "tqdm-4.66.4.tar.gz", hash = "sha256:e4d936c9de8727928f3be6079590e97d9abfe8d39a590be678eb5919ffc186bb"}, + {file = "tqdm-4.66.5-py3-none-any.whl", hash = "sha256:90279a3770753eafc9194a0364852159802111925aa30eb3f9d85b0e805ac7cd"}, + {file = "tqdm-4.66.5.tar.gz", hash = "sha256:e1020aef2e5096702d8a025ac7d16b1577279c9d63f8375b63083e9a5f0fcbad"}, ] [package.dependencies] @@ -4162,19 +6803,68 @@ notebook = ["ipywidgets (>=6)"] slack = ["slack-sdk"] telegram = ["requests"] +[[package]] +name = "traitlets" +version = "5.14.3" +description = "Traitlets Python configuration system" +optional = true +python-versions = ">=3.8" +files = [ + {file = "traitlets-5.14.3-py3-none-any.whl", hash = "sha256:b74e89e397b1ed28cc831db7aea759ba6640cb3de13090ca145426688ff1ac4f"}, + {file = "traitlets-5.14.3.tar.gz", hash = "sha256:9ed0579d3502c94b4b3732ac120375cda96f923114522847de4b3bb98b96b6b7"}, +] + +[package.extras] +docs = ["myst-parser", "pydata-sphinx-theme", "sphinx"] +test = ["argcomplete (>=3.0.3)", "mypy (>=1.7.0)", "pre-commit", "pytest (>=7.0,<8.2)", "pytest-mock", "pytest-mypy-testing"] + +[[package]] +name = "transforms3d" +version = "0.4.2" +description = "Functions for 3D coordinate transformations" +optional = true +python-versions = ">=3.6" +files = [ + {file = "transforms3d-0.4.2-py3-none-any.whl", hash = "sha256:1c70399d9e9473ecc23311fd947f727f7c69ed0b063244828c383aa1aefa5941"}, + {file = "transforms3d-0.4.2.tar.gz", hash = "sha256:e8b5df30eaedbee556e81c6938e55aab5365894e47d0a17615d7db7fd2393680"}, +] + +[package.dependencies] +numpy = ">=1.15" + +[[package]] +name = "trimesh" +version = "4.4.7" +description = "Import, export, process, analyze and view triangular meshes." +optional = true +python-versions = ">=3.8" +files = [ + {file = "trimesh-4.4.7-py3-none-any.whl", hash = "sha256:6df98f3f5b971945b416f567b7ff6ee0c51b70f01b80a16a990fdcceb8dbd114"}, + {file = "trimesh-4.4.7.tar.gz", hash = "sha256:e6619c70c99006d41f175bd5e1ba2c8c3dfdb00c2b41d65059917942e2f6971a"}, +] + +[package.dependencies] +numpy = ">=1.20" + +[package.extras] +all = ["trimesh[deprecated,easy,recommend,test]"] +deprecated = ["gmsh (==4.12.2)"] +easy = ["chardet", "colorlog", "embreex", "httpx", "jsonschema", "lxml", "manifold3d (>=2.3.0)", "mapbox-earcut (>=1.0.2)", "networkx", "pillow", "pycollada", "rtree", "scipy", "setuptools", "shapely", "svg.path", "vhacdx", "xatlas", "xxhash"] +recommend = ["cascadio", "glooey", "meshio", "openctm", "psutil", "pyglet (<2)", "python-fcl", "scikit-image", "sympy"] +test = ["coveralls", "ezdxf", "matplotlib", "pyinstrument", "pymeshlab", "pyright", "pytest", "pytest-beartype", "pytest-cov", "ruff"] + [[package]] name = "triton" -version = "2.3.1" +version = "3.0.0" description = "A language and compiler for custom Deep Learning operations" optional = false python-versions = "*" files = [ - {file = "triton-2.3.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:3c84595cbe5e546b1b290d2a58b1494df5a2ef066dd890655e5b8a8a92205c33"}, - {file = "triton-2.3.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c9d64ae33bcb3a7a18081e3a746e8cf87ca8623ca13d2c362413ce7a486f893e"}, - {file = "triton-2.3.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:eaf80e8761a9e3498aa92e7bf83a085b31959c61f5e8ac14eedd018df6fccd10"}, - {file = "triton-2.3.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b13bf35a2b659af7159bf78e92798dc62d877aa991de723937329e2d382f1991"}, - {file = "triton-2.3.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:63381e35ded3304704ea867ffde3b7cfc42c16a55b3062d41e017ef510433d66"}, - {file = "triton-2.3.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1d968264523c7a07911c8fb51b4e0d1b920204dae71491b1fe7b01b62a31e124"}, + {file = "triton-3.0.0-1-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:e1efef76935b2febc365bfadf74bcb65a6f959a9872e5bddf44cc9e0adce1e1a"}, + {file = "triton-3.0.0-1-cp311-cp311-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:5ce8520437c602fb633f1324cc3871c47bee3b67acf9756c1a66309b60e3216c"}, + {file = "triton-3.0.0-1-cp312-cp312-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:34e509deb77f1c067d8640725ef00c5cbfcb2052a1a3cb6a6d343841f92624eb"}, + {file = "triton-3.0.0-1-cp38-cp38-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:bcbf3b1c48af6a28011a5c40a5b3b9b5330530c3827716b5fbf6d7adcc1e53e9"}, + {file = "triton-3.0.0-1-cp39-cp39-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:6e5727202f7078c56f91ff13ad0c1abab14a0e7f2c87e91b12b6f64f3e8ae609"}, ] [package.dependencies] @@ -4182,8 +6872,19 @@ filelock = "*" [package.extras] build = ["cmake (>=3.20)", "lit"] -tests = ["autopep8", "flake8", "isort", "numpy", "pytest", "scipy (>=1.7.1)", "torch"] -tutorials = ["matplotlib", "pandas", "tabulate", "torch"] +tests = ["autopep8", "flake8", "isort", "llnl-hatchet", "numpy", "pytest", "scipy (>=1.7.1)"] +tutorials = ["matplotlib", "pandas", "tabulate"] + +[[package]] +name = "types-python-dateutil" +version = "2.9.0.20240906" +description = "Typing stubs for python-dateutil" +optional = true +python-versions = ">=3.8" +files = [ + {file = "types-python-dateutil-2.9.0.20240906.tar.gz", hash = "sha256:9706c3b68284c25adffc47319ecc7947e5bb86b3773f843c73906fd598bc176e"}, + {file = "types_python_dateutil-2.9.0.20240906-py3-none-any.whl", hash = "sha256:27c8cc2d058ccb14946eebcaaa503088f4f6dbc4fb6093d3d456a49aef2753f6"}, +] [[package]] name = "typing-extensions" @@ -4198,24 +6899,78 @@ files = [ [[package]] name = "tzdata" -version = "2024.1" +version = "2024.2" description = "Provider of IANA time zone data" optional = false python-versions = ">=2" files = [ - {file = "tzdata-2024.1-py2.py3-none-any.whl", hash = "sha256:9068bc196136463f5245e51efda838afa15aaeca9903f49050dfa2679db4d252"}, - {file = "tzdata-2024.1.tar.gz", hash = "sha256:2674120f8d891909751c38abcdfd386ac0a5a1127954fbc332af6b5ceae07efd"}, + {file = "tzdata-2024.2-py2.py3-none-any.whl", hash = "sha256:a48093786cdcde33cad18c2555e8532f34422074448fbc874186f0abd79565cd"}, + {file = "tzdata-2024.2.tar.gz", hash = "sha256:7d85cc416e9382e69095b7bdf4afd9e3880418a2413feec7069d533d6b4e31cc"}, +] + +[[package]] +name = "urchin" +version = "0.0.27" +description = "URDF parser and manipulator for Python" +optional = true +python-versions = "*" +files = [ + {file = "urchin-0.0.27-py3-none-any.whl", hash = "sha256:e4cf43c8f52a44e0075e1778b76c203922085dd1fb9340cd703bf54188208611"}, + {file = "urchin-0.0.27.tar.gz", hash = "sha256:bda308ed7d2b80eb1e097dc3963fabe9e00a6cbd89a1f6be6f063c2a065d3671"}, +] + +[package.dependencies] +lxml = "*" +networkx = "*" +numpy = "*" +pillow = "*" +pycollada = ">=0.6" +pyribbit = ">=0.1.46" +scipy = "*" +six = "*" +trimesh = "*" + +[package.extras] +dev = ["flake8", "pre-commit", "pytest", "pytest-cov", "tox"] +docs = ["sphinx", "sphinx-automodapi", "sphinx-rtd-theme"] + +[[package]] +name = "urdf-parser-py" +version = "0.0.4" +description = "This package contains a python parser for the Unified Robot Description Format (URDF), which is an XML format for representing a robot model." +optional = true +python-versions = "*" +files = [ + {file = "urdf_parser_py-0.0.4.tar.gz", hash = "sha256:e983f637145fded67bcff6a542302069bb975b2edf1b18318c093abba1b794cc"}, +] + +[package.dependencies] +lxml = "*" +pyyaml = "*" + +[[package]] +name = "uri-template" +version = "1.3.0" +description = "RFC 6570 URI Template Processor" +optional = true +python-versions = ">=3.7" +files = [ + {file = "uri-template-1.3.0.tar.gz", hash = "sha256:0e00f8eb65e18c7de20d595a14336e9f337ead580c70934141624b6d1ffdacc7"}, + {file = "uri_template-1.3.0-py3-none-any.whl", hash = "sha256:a44a133ea12d44a0c0f06d7d42a52d71282e77e2f937d8abd5655b8d56fc1363"}, ] +[package.extras] +dev = ["flake8", "flake8-annotations", "flake8-bandit", "flake8-bugbear", "flake8-commas", "flake8-comprehensions", "flake8-continuation", "flake8-datetimez", "flake8-docstrings", "flake8-import-order", "flake8-literal", "flake8-modern-annotations", "flake8-noqa", "flake8-pyproject", "flake8-requirements", "flake8-typechecking-import", "flake8-use-fstring", "mypy", "pep8-naming", "types-PyYAML"] + [[package]] name = "urllib3" -version = "2.2.2" +version = "2.2.3" description = "HTTP library with thread-safe connection pooling, file post, and more." optional = false python-versions = ">=3.8" files = [ - {file = "urllib3-2.2.2-py3-none-any.whl", hash = "sha256:a448b2f64d686155468037e1ace9f2d2199776e17f0a46610480d311f73e3472"}, - {file = "urllib3-2.2.2.tar.gz", hash = "sha256:dd505485549a7a552833da5e6063639d0d177c04f23bc3864e41e5dc5f612168"}, + {file = "urllib3-2.2.3-py3-none-any.whl", hash = "sha256:ca899ca043dcb1bafa3e262d73aa25c465bfb49e0bd9dd5d59f1d0acba2f8fac"}, + {file = "urllib3-2.2.3.tar.gz", hash = "sha256:e7d814a81dad81e6caf2ec9fdedb284ecc9c73076b62654547cc64ccdcae26e9"}, ] [package.extras] @@ -4226,13 +6981,13 @@ zstd = ["zstandard (>=0.18.0)"] [[package]] name = "virtualenv" -version = "20.26.3" +version = "20.26.5" description = "Virtual Python Environment builder" optional = true python-versions = ">=3.7" files = [ - {file = "virtualenv-20.26.3-py3-none-any.whl", hash = "sha256:8cc4a31139e796e9a7de2cd5cf2489de1217193116a8fd42328f1bd65f434589"}, - {file = "virtualenv-20.26.3.tar.gz", hash = "sha256:4c43a2a236279d9ea36a0d76f98d84bd6ca94ac4e0f4a3b9d46d05e10fea542a"}, + {file = "virtualenv-20.26.5-py3-none-any.whl", hash = "sha256:4f3ac17b81fba3ce3bd6f4ead2749a72da5929c01774948e243db9ba41df4ff6"}, + {file = "virtualenv-20.26.5.tar.gz", hash = "sha256:ce489cac131aa58f4b25e321d6d186171f78e6cb13fafbf32a840cee67733ff4"}, ] [package.dependencies] @@ -4246,18 +7001,19 @@ test = ["covdefaults (>=2.3)", "coverage (>=7.2.7)", "coverage-enable-subprocess [[package]] name = "wandb" -version = "0.17.4" +version = "0.18.1" description = "A CLI and library for interacting with the Weights & Biases API." optional = false python-versions = ">=3.7" files = [ - {file = "wandb-0.17.4-py3-none-any.whl", hash = "sha256:807d600a86ee9e2df66b64af738caa6eb3b5e04a30b296b9a7c940ede759f4a7"}, - {file = "wandb-0.17.4-py3-none-macosx_10_9_x86_64.whl", hash = "sha256:02a00fe5e86ac04c07936d1fe7e7d9111d9546a3a844ac00d89735df0290cef8"}, - {file = "wandb-0.17.4-py3-none-macosx_11_0_arm64.whl", hash = "sha256:78eb7e6a530848fc47792e95563b406019bed7c4dadb54415a982cd4900b7c75"}, - {file = "wandb-0.17.4-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:91bd3bc5b76f880732c6169288ac64d59a016fd8227d3a74bdc69d457639ef17"}, - {file = "wandb-0.17.4-py3-none-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:40aa85e0fc6d875f9597c6c02e968bc35a571ddac1cbfac2223fcdb941bf1214"}, - {file = "wandb-0.17.4-py3-none-win32.whl", hash = "sha256:fec9378ae2ed8c4cf29bb5ef9bd2889f0085b6566d7b9dd7b789718519c46447"}, - {file = "wandb-0.17.4-py3-none-win_amd64.whl", hash = "sha256:94b78c1a74222a0970580cd953c21562bb57af1c2e14a4e48ab07b8fbcb64f08"}, + {file = "wandb-0.18.1-py3-none-any.whl", hash = "sha256:be936a193eeb940ce03d966f013b847562497e76256852d5fb170cdcdf50f185"}, + {file = "wandb-0.18.1-py3-none-macosx_11_0_arm64.whl", hash = "sha256:1f143b814b0fd51b5f1a676ad8b66bd06a5ee4ad22fc46bcbf24048d76c77d35"}, + {file = "wandb-0.18.1-py3-none-macosx_11_0_x86_64.whl", hash = "sha256:86b73a9f94f18b07f0e937ae945560244b560b57c16a9dfb8f03e2516d0cc666"}, + {file = "wandb-0.18.1-py3-none-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cc404682ebfb2477b48cb436a331e1bea0262e002d6fb3ccafe71d13657dd4ee"}, + {file = "wandb-0.18.1-py3-none-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd4c97d69242efd604c1a2077c8b56341e236cfaca78c40f59dcef9b95464fdc"}, + {file = "wandb-0.18.1-py3-none-win32.whl", hash = "sha256:33c5a0d74bc28879917b519f24d69b0e81530d72e99aba1c115189a2c9aac9cf"}, + {file = "wandb-0.18.1-py3-none-win_amd64.whl", hash = "sha256:559cbd6e9ab752622f7d6dacdc334ede7f1bc34f42df3f48ed32bde55db42c6e"}, + {file = "wandb-0.18.1.tar.gz", hash = "sha256:d625e94d53ff4ff961c58a9a17f0a1ea35720d98b9db710a458235924469fc6b"}, ] [package.dependencies] @@ -4265,7 +7021,7 @@ click = ">=7.1,<8.0.0 || >8.0.0" docker-pycreds = ">=0.4.0" gitpython = ">=1.0.0,<3.1.29 || >3.1.29" platformdirs = "*" -protobuf = {version = ">=3.19.0,<4.21.0 || >4.21.0,<6", markers = "python_version > \"3.9\" or sys_platform != \"linux\""} +protobuf = {version = ">=3.19.0,<4.21.0 || >4.21.0,<5.28.0 || >5.28.0,<6", markers = "python_version > \"3.9\" or sys_platform != \"linux\""} psutil = ">=5.0.0" pyyaml = "*" requests = ">=2.0.0,<3" @@ -4277,9 +7033,9 @@ setuptools = "*" aws = ["boto3"] azure = ["azure-identity", "azure-storage-blob"] gcp = ["google-cloud-storage"] -importers = ["filelock", "mlflow", "polars", "rich", "tenacity"] +importers = ["filelock", "mlflow", "polars (<=1.2.1)", "rich", "tenacity"] kubeflow = ["google-cloud-storage", "kubernetes", "minio", "sh"] -launch = ["awscli", "azure-containerregistry", "azure-identity", "azure-storage-blob", "boto3", "botocore", "chardet", "google-auth", "google-cloud-aiplatform", "google-cloud-artifact-registry", "google-cloud-compute", "google-cloud-storage", "iso8601", "kubernetes", "kubernetes-asyncio", "nbconvert", "nbformat", "optuna", "pydantic", "pyyaml (>=6.0.0)", "tomli", "typing-extensions"] +launch = ["awscli", "azure-containerregistry", "azure-identity", "azure-storage-blob", "boto3", "botocore", "chardet", "google-auth", "google-cloud-aiplatform", "google-cloud-artifact-registry", "google-cloud-compute", "google-cloud-storage", "iso8601", "jsonschema", "kubernetes", "kubernetes-asyncio", "nbconvert", "nbformat", "optuna", "pydantic", "pyyaml (>=6.0.0)", "tomli", "typing-extensions"] media = ["bokeh", "moviepy", "numpy", "pillow", "plotly (>=5.18.0)", "rdkit-pypi", "soundfile"] models = ["cloudpickle"] perf = ["orjson"] @@ -4297,15 +7053,57 @@ files = [ {file = "wcwidth-0.2.13.tar.gz", hash = "sha256:72ea0c06399eb286d978fdedb6923a9eb47e1c486ce63e9b4e64fc18303972b5"}, ] +[[package]] +name = "webcolors" +version = "24.8.0" +description = "A library for working with the color formats defined by HTML and CSS." +optional = true +python-versions = ">=3.8" +files = [ + {file = "webcolors-24.8.0-py3-none-any.whl", hash = "sha256:fc4c3b59358ada164552084a8ebee637c221e4059267d0f8325b3b560f6c7f0a"}, + {file = "webcolors-24.8.0.tar.gz", hash = "sha256:08b07af286a01bcd30d583a7acadf629583d1f79bfef27dd2c2c5c263817277d"}, +] + +[package.extras] +docs = ["furo", "sphinx", "sphinx-copybutton", "sphinx-inline-tabs", "sphinx-notfound-page", "sphinxext-opengraph"] +tests = ["coverage[toml]"] + +[[package]] +name = "webencodings" +version = "0.5.1" +description = "Character encoding aliases for legacy web content" +optional = true +python-versions = "*" +files = [ + {file = "webencodings-0.5.1-py2.py3-none-any.whl", hash = "sha256:a0af1213f3c2226497a97e2b3aa01a7e4bee4f403f95be16fc9acd2947514a78"}, + {file = "webencodings-0.5.1.tar.gz", hash = "sha256:b36a1c245f2d304965eb4e0a82848379241dc04b865afcc4aab16748587e1923"}, +] + +[[package]] +name = "websocket-client" +version = "1.8.0" +description = "WebSocket client for Python with low level API options" +optional = true +python-versions = ">=3.8" +files = [ + {file = "websocket_client-1.8.0-py3-none-any.whl", hash = "sha256:17b44cc997f5c498e809b22cdf2d9c7a9e71c02c8cc2b6c56e7c2d1239bfa526"}, + {file = "websocket_client-1.8.0.tar.gz", hash = "sha256:3239df9f44da632f96012472805d40a23281a991027ce11d2f45a6f24ac4c3da"}, +] + +[package.extras] +docs = ["Sphinx (>=6.0)", "myst-parser (>=2.0.0)", "sphinx-rtd-theme (>=1.1.0)"] +optional = ["python-socks", "wsaccel"] +test = ["websockets"] + [[package]] name = "werkzeug" -version = "3.0.3" +version = "3.0.4" description = "The comprehensive WSGI web application library." optional = false python-versions = ">=3.8" files = [ - {file = "werkzeug-3.0.3-py3-none-any.whl", hash = "sha256:fc9645dc43e03e4d630d23143a04a7f947a9a3b5727cd535fdfe155a17cc48c8"}, - {file = "werkzeug-3.0.3.tar.gz", hash = "sha256:097e5bfda9f0aba8da6b8545146def481d06aa7d3266e7448e2cccf67dd8bd18"}, + {file = "werkzeug-3.0.4-py3-none-any.whl", hash = "sha256:02c9eb92b7d6c06f31a782811505d2157837cea66aaede3e217c7c27c039476c"}, + {file = "werkzeug-3.0.4.tar.gz", hash = "sha256:34f2371506b250df4d4f84bfe7b0921e4762525762bbd936614909fe25cd7306"}, ] [package.dependencies] @@ -4314,220 +7112,259 @@ MarkupSafe = ">=2.1.1" [package.extras] watchdog = ["watchdog (>=2.3)"] +[[package]] +name = "widgetsnbextension" +version = "4.0.13" +description = "Jupyter interactive widgets for Jupyter Notebook" +optional = true +python-versions = ">=3.7" +files = [ + {file = "widgetsnbextension-4.0.13-py3-none-any.whl", hash = "sha256:74b2692e8500525cc38c2b877236ba51d34541e6385eeed5aec15a70f88a6c71"}, + {file = "widgetsnbextension-4.0.13.tar.gz", hash = "sha256:ffcb67bc9febd10234a362795f643927f4e0c05d9342c727b65d2384f8feacb6"}, +] + +[[package]] +name = "xmltodict" +version = "0.13.0" +description = "Makes working with XML feel like you are working with JSON" +optional = true +python-versions = ">=3.4" +files = [ + {file = "xmltodict-0.13.0-py2.py3-none-any.whl", hash = "sha256:aa89e8fd76320154a40d19a0df04a4695fb9dc5ba977cbb68ab3e4eb225e7852"}, + {file = "xmltodict-0.13.0.tar.gz", hash = "sha256:341595a488e3e01a85a9d8911d8912fd922ede5fecc4dce437eb4b6c8d037e56"}, +] + [[package]] name = "xxhash" -version = "3.4.1" +version = "3.5.0" description = "Python binding for xxHash" optional = false python-versions = ">=3.7" files = [ - {file = "xxhash-3.4.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:91dbfa55346ad3e18e738742236554531a621042e419b70ad8f3c1d9c7a16e7f"}, - {file = "xxhash-3.4.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:665a65c2a48a72068fcc4d21721510df5f51f1142541c890491afc80451636d2"}, - {file = "xxhash-3.4.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:bb11628470a6004dc71a09fe90c2f459ff03d611376c1debeec2d648f44cb693"}, - {file = "xxhash-3.4.1-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5bef2a7dc7b4f4beb45a1edbba9b9194c60a43a89598a87f1a0226d183764189"}, - {file = "xxhash-3.4.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9c0f7b2d547d72c7eda7aa817acf8791f0146b12b9eba1d4432c531fb0352228"}, - {file = "xxhash-3.4.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:00f2fdef6b41c9db3d2fc0e7f94cb3db86693e5c45d6de09625caad9a469635b"}, - {file = "xxhash-3.4.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:23cfd9ca09acaf07a43e5a695143d9a21bf00f5b49b15c07d5388cadf1f9ce11"}, - {file = "xxhash-3.4.1-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:6a9ff50a3cf88355ca4731682c168049af1ca222d1d2925ef7119c1a78e95b3b"}, - {file = "xxhash-3.4.1-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:f1d7c69a1e9ca5faa75546fdd267f214f63f52f12692f9b3a2f6467c9e67d5e7"}, - {file = "xxhash-3.4.1-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:672b273040d5d5a6864a36287f3514efcd1d4b1b6a7480f294c4b1d1ee1b8de0"}, - {file = "xxhash-3.4.1-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:4178f78d70e88f1c4a89ff1ffe9f43147185930bb962ee3979dba15f2b1cc799"}, - {file = "xxhash-3.4.1-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:9804b9eb254d4b8cc83ab5a2002128f7d631dd427aa873c8727dba7f1f0d1c2b"}, - {file = "xxhash-3.4.1-cp310-cp310-win32.whl", hash = "sha256:c09c49473212d9c87261d22c74370457cfff5db2ddfc7fd1e35c80c31a8c14ce"}, - {file = "xxhash-3.4.1-cp310-cp310-win_amd64.whl", hash = "sha256:ebbb1616435b4a194ce3466d7247df23499475c7ed4eb2681a1fa42ff766aff6"}, - {file = "xxhash-3.4.1-cp310-cp310-win_arm64.whl", hash = "sha256:25dc66be3db54f8a2d136f695b00cfe88018e59ccff0f3b8f545869f376a8a46"}, - {file = "xxhash-3.4.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:58c49083801885273e262c0f5bbeac23e520564b8357fbb18fb94ff09d3d3ea5"}, - {file = "xxhash-3.4.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:b526015a973bfbe81e804a586b703f163861da36d186627e27524f5427b0d520"}, - {file = "xxhash-3.4.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:36ad4457644c91a966f6fe137d7467636bdc51a6ce10a1d04f365c70d6a16d7e"}, - {file = "xxhash-3.4.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:248d3e83d119770f96003271fe41e049dd4ae52da2feb8f832b7a20e791d2920"}, - {file = "xxhash-3.4.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:2070b6d5bbef5ee031666cf21d4953c16e92c2f8a24a94b5c240f8995ba3b1d0"}, - {file = "xxhash-3.4.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:b2746035f518f0410915e247877f7df43ef3372bf36cfa52cc4bc33e85242641"}, - {file = "xxhash-3.4.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2a8ba6181514681c2591840d5632fcf7356ab287d4aff1c8dea20f3c78097088"}, - {file = "xxhash-3.4.1-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:0aac5010869240e95f740de43cd6a05eae180c59edd182ad93bf12ee289484fa"}, - {file = "xxhash-3.4.1-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:4cb11d8debab1626181633d184b2372aaa09825bde709bf927704ed72765bed1"}, - {file = "xxhash-3.4.1-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:b29728cff2c12f3d9f1d940528ee83918d803c0567866e062683f300d1d2eff3"}, - {file = "xxhash-3.4.1-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:a15cbf3a9c40672523bdb6ea97ff74b443406ba0ab9bca10ceccd9546414bd84"}, - {file = "xxhash-3.4.1-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:6e66df260fed01ed8ea790c2913271641c58481e807790d9fca8bfd5a3c13844"}, - {file = "xxhash-3.4.1-cp311-cp311-win32.whl", hash = "sha256:e867f68a8f381ea12858e6d67378c05359d3a53a888913b5f7d35fbf68939d5f"}, - {file = "xxhash-3.4.1-cp311-cp311-win_amd64.whl", hash = "sha256:200a5a3ad9c7c0c02ed1484a1d838b63edcf92ff538770ea07456a3732c577f4"}, - {file = "xxhash-3.4.1-cp311-cp311-win_arm64.whl", hash = "sha256:1d03f1c0d16d24ea032e99f61c552cb2b77d502e545187338bea461fde253583"}, - {file = "xxhash-3.4.1-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:c4bbba9b182697a52bc0c9f8ec0ba1acb914b4937cd4a877ad78a3b3eeabefb3"}, - {file = "xxhash-3.4.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:9fd28a9da300e64e434cfc96567a8387d9a96e824a9be1452a1e7248b7763b78"}, - {file = "xxhash-3.4.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6066d88c9329ab230e18998daec53d819daeee99d003955c8db6fc4971b45ca3"}, - {file = "xxhash-3.4.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:93805bc3233ad89abf51772f2ed3355097a5dc74e6080de19706fc447da99cd3"}, - {file = "xxhash-3.4.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:64da57d5ed586ebb2ecdde1e997fa37c27fe32fe61a656b77fabbc58e6fbff6e"}, - {file = "xxhash-3.4.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7a97322e9a7440bf3c9805cbaac090358b43f650516486746f7fa482672593df"}, - {file = "xxhash-3.4.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bbe750d512982ee7d831838a5dee9e9848f3fb440e4734cca3f298228cc957a6"}, - {file = "xxhash-3.4.1-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:fd79d4087727daf4d5b8afe594b37d611ab95dc8e29fe1a7517320794837eb7d"}, - {file = "xxhash-3.4.1-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:743612da4071ff9aa4d055f3f111ae5247342931dedb955268954ef7201a71ff"}, - {file = "xxhash-3.4.1-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:b41edaf05734092f24f48c0958b3c6cbaaa5b7e024880692078c6b1f8247e2fc"}, - {file = "xxhash-3.4.1-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:a90356ead70d715fe64c30cd0969072de1860e56b78adf7c69d954b43e29d9fa"}, - {file = "xxhash-3.4.1-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:ac56eebb364e44c85e1d9e9cc5f6031d78a34f0092fea7fc80478139369a8b4a"}, - {file = "xxhash-3.4.1-cp312-cp312-win32.whl", hash = "sha256:911035345932a153c427107397c1518f8ce456f93c618dd1c5b54ebb22e73747"}, - {file = "xxhash-3.4.1-cp312-cp312-win_amd64.whl", hash = "sha256:f31ce76489f8601cc7b8713201ce94b4bd7b7ce90ba3353dccce7e9e1fee71fa"}, - {file = "xxhash-3.4.1-cp312-cp312-win_arm64.whl", hash = "sha256:b5beb1c6a72fdc7584102f42c4d9df232ee018ddf806e8c90906547dfb43b2da"}, - {file = "xxhash-3.4.1-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:6d42b24d1496deb05dee5a24ed510b16de1d6c866c626c2beb11aebf3be278b9"}, - {file = "xxhash-3.4.1-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3b685fab18876b14a8f94813fa2ca80cfb5ab6a85d31d5539b7cd749ce9e3624"}, - {file = "xxhash-3.4.1-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:419ffe34c17ae2df019a4685e8d3934d46b2e0bbe46221ab40b7e04ed9f11137"}, - {file = "xxhash-3.4.1-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0e041ce5714f95251a88670c114b748bca3bf80cc72400e9f23e6d0d59cf2681"}, - {file = "xxhash-3.4.1-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fc860d887c5cb2f524899fb8338e1bb3d5789f75fac179101920d9afddef284b"}, - {file = "xxhash-3.4.1-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:312eba88ffe0a05e332e3a6f9788b73883752be63f8588a6dc1261a3eaaaf2b2"}, - {file = "xxhash-3.4.1-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:e01226b6b6a1ffe4e6bd6d08cfcb3ca708b16f02eb06dd44f3c6e53285f03e4f"}, - {file = "xxhash-3.4.1-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:9f3025a0d5d8cf406a9313cd0d5789c77433ba2004b1c75439b67678e5136537"}, - {file = "xxhash-3.4.1-cp37-cp37m-musllinux_1_1_ppc64le.whl", hash = "sha256:6d3472fd4afef2a567d5f14411d94060099901cd8ce9788b22b8c6f13c606a93"}, - {file = "xxhash-3.4.1-cp37-cp37m-musllinux_1_1_s390x.whl", hash = "sha256:43984c0a92f06cac434ad181f329a1445017c33807b7ae4f033878d860a4b0f2"}, - {file = "xxhash-3.4.1-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:a55e0506fdb09640a82ec4f44171273eeabf6f371a4ec605633adb2837b5d9d5"}, - {file = "xxhash-3.4.1-cp37-cp37m-win32.whl", hash = "sha256:faec30437919555b039a8bdbaba49c013043e8f76c999670aef146d33e05b3a0"}, - {file = "xxhash-3.4.1-cp37-cp37m-win_amd64.whl", hash = "sha256:c9e1b646af61f1fc7083bb7b40536be944f1ac67ef5e360bca2d73430186971a"}, - {file = "xxhash-3.4.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:961d948b7b1c1b6c08484bbce3d489cdf153e4122c3dfb07c2039621243d8795"}, - {file = "xxhash-3.4.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:719a378930504ab159f7b8e20fa2aa1896cde050011af838af7e7e3518dd82de"}, - {file = "xxhash-3.4.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:74fb5cb9406ccd7c4dd917f16630d2e5e8cbbb02fc2fca4e559b2a47a64f4940"}, - {file = "xxhash-3.4.1-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:5dab508ac39e0ab988039bc7f962c6ad021acd81fd29145962b068df4148c476"}, - {file = "xxhash-3.4.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:8c59f3e46e7daf4c589e8e853d700ef6607afa037bfad32c390175da28127e8c"}, - {file = "xxhash-3.4.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:8cc07256eff0795e0f642df74ad096f8c5d23fe66bc138b83970b50fc7f7f6c5"}, - {file = "xxhash-3.4.1-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:e9f749999ed80f3955a4af0eb18bb43993f04939350b07b8dd2f44edc98ffee9"}, - {file = "xxhash-3.4.1-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:7688d7c02149a90a3d46d55b341ab7ad1b4a3f767be2357e211b4e893efbaaf6"}, - {file = "xxhash-3.4.1-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:a8b4977963926f60b0d4f830941c864bed16aa151206c01ad5c531636da5708e"}, - {file = "xxhash-3.4.1-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:8106d88da330f6535a58a8195aa463ef5281a9aa23b04af1848ff715c4398fb4"}, - {file = "xxhash-3.4.1-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:4c76a77dbd169450b61c06fd2d5d436189fc8ab7c1571d39265d4822da16df22"}, - {file = "xxhash-3.4.1-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:11f11357c86d83e53719c592021fd524efa9cf024dc7cb1dfb57bbbd0d8713f2"}, - {file = "xxhash-3.4.1-cp38-cp38-win32.whl", hash = "sha256:0c786a6cd74e8765c6809892a0d45886e7c3dc54de4985b4a5eb8b630f3b8e3b"}, - {file = "xxhash-3.4.1-cp38-cp38-win_amd64.whl", hash = "sha256:aabf37fb8fa27430d50507deeab2ee7b1bcce89910dd10657c38e71fee835594"}, - {file = "xxhash-3.4.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:6127813abc1477f3a83529b6bbcfeddc23162cece76fa69aee8f6a8a97720562"}, - {file = "xxhash-3.4.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:ef2e194262f5db16075caea7b3f7f49392242c688412f386d3c7b07c7733a70a"}, - {file = "xxhash-3.4.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:71be94265b6c6590f0018bbf73759d21a41c6bda20409782d8117e76cd0dfa8b"}, - {file = "xxhash-3.4.1-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:10e0a619cdd1c0980e25eb04e30fe96cf8f4324758fa497080af9c21a6de573f"}, - {file = "xxhash-3.4.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:fa122124d2e3bd36581dd78c0efa5f429f5220313479fb1072858188bc2d5ff1"}, - {file = "xxhash-3.4.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e17032f5a4fea0a074717fe33477cb5ee723a5f428de7563e75af64bfc1b1e10"}, - {file = "xxhash-3.4.1-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ca7783b20e3e4f3f52f093538895863f21d18598f9a48211ad757680c3bd006f"}, - {file = "xxhash-3.4.1-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:d77d09a1113899fad5f354a1eb4f0a9afcf58cefff51082c8ad643ff890e30cf"}, - {file = "xxhash-3.4.1-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:21287bcdd299fdc3328cc0fbbdeaa46838a1c05391264e51ddb38a3f5b09611f"}, - {file = "xxhash-3.4.1-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:dfd7a6cc483e20b4ad90224aeb589e64ec0f31e5610ab9957ff4314270b2bf31"}, - {file = "xxhash-3.4.1-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:543c7fcbc02bbb4840ea9915134e14dc3dc15cbd5a30873a7a5bf66039db97ec"}, - {file = "xxhash-3.4.1-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:fe0a98d990e433013f41827b62be9ab43e3cf18e08b1483fcc343bda0d691182"}, - {file = "xxhash-3.4.1-cp39-cp39-win32.whl", hash = "sha256:b9097af00ebf429cc7c0e7d2fdf28384e4e2e91008130ccda8d5ae653db71e54"}, - {file = "xxhash-3.4.1-cp39-cp39-win_amd64.whl", hash = "sha256:d699b921af0dcde50ab18be76c0d832f803034d80470703700cb7df0fbec2832"}, - {file = "xxhash-3.4.1-cp39-cp39-win_arm64.whl", hash = "sha256:2be491723405e15cc099ade1280133ccfbf6322d2ef568494fb7d07d280e7eee"}, - {file = "xxhash-3.4.1-pp310-pypy310_pp73-macosx_10_9_x86_64.whl", hash = "sha256:431625fad7ab5649368c4849d2b49a83dc711b1f20e1f7f04955aab86cd307bc"}, - {file = "xxhash-3.4.1-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fc6dbd5fc3c9886a9e041848508b7fb65fd82f94cc793253990f81617b61fe49"}, - {file = "xxhash-3.4.1-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:f3ff8dbd0ec97aec842476cb8ccc3e17dd288cd6ce3c8ef38bff83d6eb927817"}, - {file = "xxhash-3.4.1-pp310-pypy310_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ef73a53fe90558a4096e3256752268a8bdc0322f4692ed928b6cd7ce06ad4fe3"}, - {file = "xxhash-3.4.1-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:450401f42bbd274b519d3d8dcf3c57166913381a3d2664d6609004685039f9d3"}, - {file = "xxhash-3.4.1-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:a162840cf4de8a7cd8720ff3b4417fbc10001eefdd2d21541a8226bb5556e3bb"}, - {file = "xxhash-3.4.1-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:b736a2a2728ba45017cb67785e03125a79d246462dfa892d023b827007412c52"}, - {file = "xxhash-3.4.1-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:1d0ae4c2e7698adef58710d6e7a32ff518b66b98854b1c68e70eee504ad061d8"}, - {file = "xxhash-3.4.1-pp37-pypy37_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d6322c4291c3ff174dcd104fae41500e75dad12be6f3085d119c2c8a80956c51"}, - {file = "xxhash-3.4.1-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:dd59ed668801c3fae282f8f4edadf6dc7784db6d18139b584b6d9677ddde1b6b"}, - {file = "xxhash-3.4.1-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:92693c487e39523a80474b0394645b393f0ae781d8db3474ccdcead0559ccf45"}, - {file = "xxhash-3.4.1-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4603a0f642a1e8d7f3ba5c4c25509aca6a9c1cc16f85091004a7028607ead663"}, - {file = "xxhash-3.4.1-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6fa45e8cbfbadb40a920fe9ca40c34b393e0b067082d94006f7f64e70c7490a6"}, - {file = "xxhash-3.4.1-pp38-pypy38_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:595b252943b3552de491ff51e5bb79660f84f033977f88f6ca1605846637b7c6"}, - {file = "xxhash-3.4.1-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:562d8b8f783c6af969806aaacf95b6c7b776929ae26c0cd941d54644ea7ef51e"}, - {file = "xxhash-3.4.1-pp39-pypy39_pp73-macosx_10_9_x86_64.whl", hash = "sha256:41ddeae47cf2828335d8d991f2d2b03b0bdc89289dc64349d712ff8ce59d0647"}, - {file = "xxhash-3.4.1-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:c44d584afdf3c4dbb3277e32321d1a7b01d6071c1992524b6543025fb8f4206f"}, - {file = "xxhash-3.4.1-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd7bddb3a5b86213cc3f2c61500c16945a1b80ecd572f3078ddbbe68f9dabdfb"}, - {file = "xxhash-3.4.1-pp39-pypy39_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9ecb6c987b62437c2f99c01e97caf8d25660bf541fe79a481d05732e5236719c"}, - {file = "xxhash-3.4.1-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:696b4e18b7023527d5c50ed0626ac0520edac45a50ec7cf3fc265cd08b1f4c03"}, - {file = "xxhash-3.4.1.tar.gz", hash = "sha256:0379d6cf1ff987cd421609a264ce025e74f346e3e145dd106c0cc2e3ec3f99a9"}, + {file = "xxhash-3.5.0-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:ece616532c499ee9afbb83078b1b952beffef121d989841f7f4b3dc5ac0fd212"}, + {file = "xxhash-3.5.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:3171f693dbc2cef6477054a665dc255d996646b4023fe56cb4db80e26f4cc520"}, + {file = "xxhash-3.5.0-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7c5d3e570ef46adaf93fc81b44aca6002b5a4d8ca11bd0580c07eac537f36680"}, + {file = "xxhash-3.5.0-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:7cb29a034301e2982df8b1fe6328a84f4b676106a13e9135a0d7e0c3e9f806da"}, + {file = "xxhash-3.5.0-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:5d0d307d27099bb0cbeea7260eb39ed4fdb99c5542e21e94bb6fd29e49c57a23"}, + {file = "xxhash-3.5.0-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:c0342aafd421795d740e514bc9858ebddfc705a75a8c5046ac56d85fe97bf196"}, + {file = "xxhash-3.5.0-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:3dbbd9892c5ebffeca1ed620cf0ade13eb55a0d8c84e0751a6653adc6ac40d0c"}, + {file = "xxhash-3.5.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:4cc2d67fdb4d057730c75a64c5923abfa17775ae234a71b0200346bfb0a7f482"}, + {file = "xxhash-3.5.0-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:ec28adb204b759306a3d64358a5e5c07d7b1dd0ccbce04aa76cb9377b7b70296"}, + {file = "xxhash-3.5.0-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:1328f6d8cca2b86acb14104e381225a3d7b42c92c4b86ceae814e5c400dbb415"}, + {file = "xxhash-3.5.0-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:8d47ebd9f5d9607fd039c1fbf4994e3b071ea23eff42f4ecef246ab2b7334198"}, + {file = "xxhash-3.5.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:b96d559e0fcddd3343c510a0fe2b127fbff16bf346dd76280b82292567523442"}, + {file = "xxhash-3.5.0-cp310-cp310-win32.whl", hash = "sha256:61c722ed8d49ac9bc26c7071eeaa1f6ff24053d553146d5df031802deffd03da"}, + {file = "xxhash-3.5.0-cp310-cp310-win_amd64.whl", hash = "sha256:9bed5144c6923cc902cd14bb8963f2d5e034def4486ab0bbe1f58f03f042f9a9"}, + {file = "xxhash-3.5.0-cp310-cp310-win_arm64.whl", hash = "sha256:893074d651cf25c1cc14e3bea4fceefd67f2921b1bb8e40fcfeba56820de80c6"}, + {file = "xxhash-3.5.0-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:02c2e816896dc6f85922ced60097bcf6f008dedfc5073dcba32f9c8dd786f3c1"}, + {file = "xxhash-3.5.0-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:6027dcd885e21581e46d3c7f682cfb2b870942feeed58a21c29583512c3f09f8"}, + {file = "xxhash-3.5.0-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:1308fa542bbdbf2fa85e9e66b1077eea3a88bef38ee8a06270b4298a7a62a166"}, + {file = "xxhash-3.5.0-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c28b2fdcee797e1c1961cd3bcd3d545cab22ad202c846235197935e1df2f8ef7"}, + {file = "xxhash-3.5.0-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:924361811732ddad75ff23e90efd9ccfda4f664132feecb90895bade6a1b4623"}, + {file = "xxhash-3.5.0-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:89997aa1c4b6a5b1e5b588979d1da048a3c6f15e55c11d117a56b75c84531f5a"}, + {file = "xxhash-3.5.0-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:685c4f4e8c59837de103344eb1c8a3851f670309eb5c361f746805c5471b8c88"}, + {file = "xxhash-3.5.0-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:dbd2ecfbfee70bc1a4acb7461fa6af7748ec2ab08ac0fa298f281c51518f982c"}, + {file = "xxhash-3.5.0-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:25b5a51dc3dfb20a10833c8eee25903fd2e14059e9afcd329c9da20609a307b2"}, + {file = "xxhash-3.5.0-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:a8fb786fb754ef6ff8c120cb96629fb518f8eb5a61a16aac3a979a9dbd40a084"}, + {file = "xxhash-3.5.0-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:a905ad00ad1e1c34fe4e9d7c1d949ab09c6fa90c919860c1534ff479f40fd12d"}, + {file = "xxhash-3.5.0-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:963be41bcd49f53af6d795f65c0da9b4cc518c0dd9c47145c98f61cb464f4839"}, + {file = "xxhash-3.5.0-cp311-cp311-win32.whl", hash = "sha256:109b436096d0a2dd039c355fa3414160ec4d843dfecc64a14077332a00aeb7da"}, + {file = "xxhash-3.5.0-cp311-cp311-win_amd64.whl", hash = "sha256:b702f806693201ad6c0a05ddbbe4c8f359626d0b3305f766077d51388a6bac58"}, + {file = "xxhash-3.5.0-cp311-cp311-win_arm64.whl", hash = "sha256:c4dcb4120d0cc3cc448624147dba64e9021b278c63e34a38789b688fd0da9bf3"}, + {file = "xxhash-3.5.0-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:14470ace8bd3b5d51318782cd94e6f94431974f16cb3b8dc15d52f3b69df8e00"}, + {file = "xxhash-3.5.0-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:59aa1203de1cb96dbeab595ded0ad0c0056bb2245ae11fac11c0ceea861382b9"}, + {file = "xxhash-3.5.0-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:08424f6648526076e28fae6ea2806c0a7d504b9ef05ae61d196d571e5c879c84"}, + {file = "xxhash-3.5.0-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:61a1ff00674879725b194695e17f23d3248998b843eb5e933007ca743310f793"}, + {file = "xxhash-3.5.0-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f2f2c61bee5844d41c3eb015ac652a0229e901074951ae48581d58bfb2ba01be"}, + {file = "xxhash-3.5.0-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9d32a592cac88d18cc09a89172e1c32d7f2a6e516c3dfde1b9adb90ab5df54a6"}, + {file = "xxhash-3.5.0-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:70dabf941dede727cca579e8c205e61121afc9b28516752fd65724be1355cc90"}, + {file = "xxhash-3.5.0-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:e5d0ddaca65ecca9c10dcf01730165fd858533d0be84c75c327487c37a906a27"}, + {file = "xxhash-3.5.0-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:3e5b5e16c5a480fe5f59f56c30abdeba09ffd75da8d13f6b9b6fd224d0b4d0a2"}, + {file = "xxhash-3.5.0-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:149b7914451eb154b3dfaa721315117ea1dac2cc55a01bfbd4df7c68c5dd683d"}, + {file = "xxhash-3.5.0-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:eade977f5c96c677035ff39c56ac74d851b1cca7d607ab3d8f23c6b859379cab"}, + {file = "xxhash-3.5.0-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:fa9f547bd98f5553d03160967866a71056a60960be00356a15ecc44efb40ba8e"}, + {file = "xxhash-3.5.0-cp312-cp312-win32.whl", hash = "sha256:f7b58d1fd3551b8c80a971199543379be1cee3d0d409e1f6d8b01c1a2eebf1f8"}, + {file = "xxhash-3.5.0-cp312-cp312-win_amd64.whl", hash = "sha256:fa0cafd3a2af231b4e113fba24a65d7922af91aeb23774a8b78228e6cd785e3e"}, + {file = "xxhash-3.5.0-cp312-cp312-win_arm64.whl", hash = "sha256:586886c7e89cb9828bcd8a5686b12e161368e0064d040e225e72607b43858ba2"}, + {file = "xxhash-3.5.0-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:37889a0d13b0b7d739cfc128b1c902f04e32de17b33d74b637ad42f1c55101f6"}, + {file = "xxhash-3.5.0-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:97a662338797c660178e682f3bc180277b9569a59abfb5925e8620fba00b9fc5"}, + {file = "xxhash-3.5.0-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7f85e0108d51092bdda90672476c7d909c04ada6923c14ff9d913c4f7dc8a3bc"}, + {file = "xxhash-3.5.0-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:cd2fd827b0ba763ac919440042302315c564fdb797294d86e8cdd4578e3bc7f3"}, + {file = "xxhash-3.5.0-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:82085c2abec437abebf457c1d12fccb30cc8b3774a0814872511f0f0562c768c"}, + {file = "xxhash-3.5.0-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:07fda5de378626e502b42b311b049848c2ef38784d0d67b6f30bb5008642f8eb"}, + {file = "xxhash-3.5.0-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:c279f0d2b34ef15f922b77966640ade58b4ccdfef1c4d94b20f2a364617a493f"}, + {file = "xxhash-3.5.0-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:89e66ceed67b213dec5a773e2f7a9e8c58f64daeb38c7859d8815d2c89f39ad7"}, + {file = "xxhash-3.5.0-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:bcd51708a633410737111e998ceb3b45d3dbc98c0931f743d9bb0a209033a326"}, + {file = "xxhash-3.5.0-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:3ff2c0a34eae7df88c868be53a8dd56fbdf592109e21d4bfa092a27b0bf4a7bf"}, + {file = "xxhash-3.5.0-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:4e28503dccc7d32e0b9817aa0cbfc1f45f563b2c995b7a66c4c8a0d232e840c7"}, + {file = "xxhash-3.5.0-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:a6c50017518329ed65a9e4829154626f008916d36295b6a3ba336e2458824c8c"}, + {file = "xxhash-3.5.0-cp313-cp313-win32.whl", hash = "sha256:53a068fe70301ec30d868ece566ac90d873e3bb059cf83c32e76012c889b8637"}, + {file = "xxhash-3.5.0-cp313-cp313-win_amd64.whl", hash = "sha256:80babcc30e7a1a484eab952d76a4f4673ff601f54d5142c26826502740e70b43"}, + {file = "xxhash-3.5.0-cp313-cp313-win_arm64.whl", hash = "sha256:4811336f1ce11cac89dcbd18f3a25c527c16311709a89313c3acaf771def2d4b"}, + {file = "xxhash-3.5.0-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:6e5f70f6dca1d3b09bccb7daf4e087075ff776e3da9ac870f86ca316736bb4aa"}, + {file = "xxhash-3.5.0-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2e76e83efc7b443052dd1e585a76201e40b3411fe3da7af4fe434ec51b2f163b"}, + {file = "xxhash-3.5.0-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:33eac61d0796ca0591f94548dcfe37bb193671e0c9bcf065789b5792f2eda644"}, + {file = "xxhash-3.5.0-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:0ec70a89be933ea49222fafc3999987d7899fc676f688dd12252509434636622"}, + {file = "xxhash-3.5.0-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:dd86b8e7f703ec6ff4f351cfdb9f428955859537125904aa8c963604f2e9d3e7"}, + {file = "xxhash-3.5.0-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:0adfbd36003d9f86c8c97110039f7539b379f28656a04097e7434d3eaf9aa131"}, + {file = "xxhash-3.5.0-cp37-cp37m-musllinux_1_2_aarch64.whl", hash = "sha256:63107013578c8a730419adc05608756c3fa640bdc6abe806c3123a49fb829f43"}, + {file = "xxhash-3.5.0-cp37-cp37m-musllinux_1_2_i686.whl", hash = "sha256:683b94dbd1ca67557850b86423318a2e323511648f9f3f7b1840408a02b9a48c"}, + {file = "xxhash-3.5.0-cp37-cp37m-musllinux_1_2_ppc64le.whl", hash = "sha256:5d2a01dcce81789cf4b12d478b5464632204f4c834dc2d064902ee27d2d1f0ee"}, + {file = "xxhash-3.5.0-cp37-cp37m-musllinux_1_2_s390x.whl", hash = "sha256:a9d360a792cbcce2fe7b66b8d51274ec297c53cbc423401480e53b26161a290d"}, + {file = "xxhash-3.5.0-cp37-cp37m-musllinux_1_2_x86_64.whl", hash = "sha256:f0b48edbebea1b7421a9c687c304f7b44d0677c46498a046079d445454504737"}, + {file = "xxhash-3.5.0-cp37-cp37m-win32.whl", hash = "sha256:7ccb800c9418e438b44b060a32adeb8393764da7441eb52aa2aa195448935306"}, + {file = "xxhash-3.5.0-cp37-cp37m-win_amd64.whl", hash = "sha256:c3bc7bf8cb8806f8d1c9bf149c18708cb1c406520097d6b0a73977460ea03602"}, + {file = "xxhash-3.5.0-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:74752ecaa544657d88b1d1c94ae68031e364a4d47005a90288f3bab3da3c970f"}, + {file = "xxhash-3.5.0-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:dee1316133c9b463aa81aca676bc506d3f80d8f65aeb0bba2b78d0b30c51d7bd"}, + {file = "xxhash-3.5.0-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:602d339548d35a8579c6b013339fb34aee2df9b4e105f985443d2860e4d7ffaa"}, + {file = "xxhash-3.5.0-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:695735deeddfb35da1677dbc16a083445360e37ff46d8ac5c6fcd64917ff9ade"}, + {file = "xxhash-3.5.0-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:1030a39ba01b0c519b1a82f80e8802630d16ab95dc3f2b2386a0b5c8ed5cbb10"}, + {file = "xxhash-3.5.0-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a5bc08f33c4966f4eb6590d6ff3ceae76151ad744576b5fc6c4ba8edd459fdec"}, + {file = "xxhash-3.5.0-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:160e0c19ee500482ddfb5d5570a0415f565d8ae2b3fd69c5dcfce8a58107b1c3"}, + {file = "xxhash-3.5.0-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:f1abffa122452481a61c3551ab3c89d72238e279e517705b8b03847b1d93d738"}, + {file = "xxhash-3.5.0-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:d5e9db7ef3ecbfc0b4733579cea45713a76852b002cf605420b12ef3ef1ec148"}, + {file = "xxhash-3.5.0-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:23241ff6423378a731d84864bf923a41649dc67b144debd1077f02e6249a0d54"}, + {file = "xxhash-3.5.0-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:82b833d5563fefd6fceafb1aed2f3f3ebe19f84760fdd289f8b926731c2e6e91"}, + {file = "xxhash-3.5.0-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:0a80ad0ffd78bef9509eee27b4a29e56f5414b87fb01a888353e3d5bda7038bd"}, + {file = "xxhash-3.5.0-cp38-cp38-win32.whl", hash = "sha256:50ac2184ffb1b999e11e27c7e3e70cc1139047e7ebc1aa95ed12f4269abe98d4"}, + {file = "xxhash-3.5.0-cp38-cp38-win_amd64.whl", hash = "sha256:392f52ebbb932db566973693de48f15ce787cabd15cf6334e855ed22ea0be5b3"}, + {file = "xxhash-3.5.0-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:bfc8cdd7f33d57f0468b0614ae634cc38ab9202c6957a60e31d285a71ebe0301"}, + {file = "xxhash-3.5.0-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:e0c48b6300cd0b0106bf49169c3e0536408dfbeb1ccb53180068a18b03c662ab"}, + {file = "xxhash-3.5.0-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fe1a92cfbaa0a1253e339ccec42dbe6db262615e52df591b68726ab10338003f"}, + {file = "xxhash-3.5.0-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:33513d6cc3ed3b559134fb307aae9bdd94d7e7c02907b37896a6c45ff9ce51bd"}, + {file = "xxhash-3.5.0-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:eefc37f6138f522e771ac6db71a6d4838ec7933939676f3753eafd7d3f4c40bc"}, + {file = "xxhash-3.5.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a606c8070ada8aa2a88e181773fa1ef17ba65ce5dd168b9d08038e2a61b33754"}, + {file = "xxhash-3.5.0-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:42eca420c8fa072cc1dd62597635d140e78e384a79bb4944f825fbef8bfeeef6"}, + {file = "xxhash-3.5.0-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:604253b2143e13218ff1ef0b59ce67f18b8bd1c4205d2ffda22b09b426386898"}, + {file = "xxhash-3.5.0-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:6e93a5ad22f434d7876665444a97e713a8f60b5b1a3521e8df11b98309bff833"}, + {file = "xxhash-3.5.0-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:7a46e1d6d2817ba8024de44c4fd79913a90e5f7265434cef97026215b7d30df6"}, + {file = "xxhash-3.5.0-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:30eb2efe6503c379b7ab99c81ba4a779748e3830241f032ab46bd182bf5873af"}, + {file = "xxhash-3.5.0-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:c8aa771ff2c13dd9cda8166d685d7333d389fae30a4d2bb39d63ab5775de8606"}, + {file = "xxhash-3.5.0-cp39-cp39-win32.whl", hash = "sha256:5ed9ebc46f24cf91034544b26b131241b699edbfc99ec5e7f8f3d02d6eb7fba4"}, + {file = "xxhash-3.5.0-cp39-cp39-win_amd64.whl", hash = "sha256:220f3f896c6b8d0316f63f16c077d52c412619e475f9372333474ee15133a558"}, + {file = "xxhash-3.5.0-cp39-cp39-win_arm64.whl", hash = "sha256:a7b1d8315d9b5e9f89eb2933b73afae6ec9597a258d52190944437158b49d38e"}, + {file = "xxhash-3.5.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:2014c5b3ff15e64feecb6b713af12093f75b7926049e26a580e94dcad3c73d8c"}, + {file = "xxhash-3.5.0-pp310-pypy310_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:fab81ef75003eda96239a23eda4e4543cedc22e34c373edcaf744e721a163986"}, + {file = "xxhash-3.5.0-pp310-pypy310_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4e2febf914ace002132aa09169cc572e0d8959d0f305f93d5828c4836f9bc5a6"}, + {file = "xxhash-3.5.0-pp310-pypy310_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:5d3a10609c51da2a1c0ea0293fc3968ca0a18bd73838455b5bca3069d7f8e32b"}, + {file = "xxhash-3.5.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:5a74f23335b9689b66eb6dbe2a931a88fcd7a4c2cc4b1cb0edba8ce381c7a1da"}, + {file = "xxhash-3.5.0-pp37-pypy37_pp73-macosx_10_9_x86_64.whl", hash = "sha256:2b4154c00eb22e4d543f472cfca430e7962a0f1d0f3778334f2e08a7ba59363c"}, + {file = "xxhash-3.5.0-pp37-pypy37_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d30bbc1644f726b825b3278764240f449d75f1a8bdda892e641d4a688b1494ae"}, + {file = "xxhash-3.5.0-pp37-pypy37_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:6fa0b72f2423e2aa53077e54a61c28e181d23effeaafd73fcb9c494e60930c8e"}, + {file = "xxhash-3.5.0-pp37-pypy37_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:13de2b76c1835399b2e419a296d5b38dc4855385d9e96916299170085ef72f57"}, + {file = "xxhash-3.5.0-pp37-pypy37_pp73-win_amd64.whl", hash = "sha256:0691bfcc4f9c656bcb96cc5db94b4d75980b9d5589f2e59de790091028580837"}, + {file = "xxhash-3.5.0-pp38-pypy38_pp73-macosx_10_9_x86_64.whl", hash = "sha256:297595fe6138d4da2c8ce9e72a04d73e58725bb60f3a19048bc96ab2ff31c692"}, + {file = "xxhash-3.5.0-pp38-pypy38_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:cc1276d369452040cbb943300dc8abeedab14245ea44056a2943183822513a18"}, + {file = "xxhash-3.5.0-pp38-pypy38_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:2061188a1ba352fc699c82bff722f4baacb4b4b8b2f0c745d2001e56d0dfb514"}, + {file = "xxhash-3.5.0-pp38-pypy38_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:38c384c434021e4f62b8d9ba0bc9467e14d394893077e2c66d826243025e1f81"}, + {file = "xxhash-3.5.0-pp38-pypy38_pp73-win_amd64.whl", hash = "sha256:e6a4dd644d72ab316b580a1c120b375890e4c52ec392d4aef3c63361ec4d77d1"}, + {file = "xxhash-3.5.0-pp39-pypy39_pp73-macosx_10_15_x86_64.whl", hash = "sha256:531af8845aaadcadf951b7e0c1345c6b9c68a990eeb74ff9acd8501a0ad6a1c9"}, + {file = "xxhash-3.5.0-pp39-pypy39_pp73-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:7ce379bcaa9fcc00f19affa7773084dd09f5b59947b3fb47a1ceb0179f91aaa1"}, + {file = "xxhash-3.5.0-pp39-pypy39_pp73-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:fd1b2281d01723f076df3c8188f43f2472248a6b63118b036e641243656b1b0f"}, + {file = "xxhash-3.5.0-pp39-pypy39_pp73-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:9c770750cc80e8694492244bca7251385188bc5597b6a39d98a9f30e8da984e0"}, + {file = "xxhash-3.5.0-pp39-pypy39_pp73-win_amd64.whl", hash = "sha256:b150b8467852e1bd844387459aa6fbe11d7f38b56e901f9f3b3e6aba0d660240"}, + {file = "xxhash-3.5.0.tar.gz", hash = "sha256:84f2caddf951c9cbf8dc2e22a89d4ccf5d86391ac6418fe81e3c67d0cf60b45f"}, ] [[package]] name = "yarl" -version = "1.9.4" +version = "1.12.1" description = "Yet another URL library" optional = false -python-versions = ">=3.7" +python-versions = ">=3.8" files = [ - {file = "yarl-1.9.4-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:a8c1df72eb746f4136fe9a2e72b0c9dc1da1cbd23b5372f94b5820ff8ae30e0e"}, - {file = "yarl-1.9.4-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:a3a6ed1d525bfb91b3fc9b690c5a21bb52de28c018530ad85093cc488bee2dd2"}, - {file = "yarl-1.9.4-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:c38c9ddb6103ceae4e4498f9c08fac9b590c5c71b0370f98714768e22ac6fa66"}, - {file = "yarl-1.9.4-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d9e09c9d74f4566e905a0b8fa668c58109f7624db96a2171f21747abc7524234"}, - {file = "yarl-1.9.4-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b8477c1ee4bd47c57d49621a062121c3023609f7a13b8a46953eb6c9716ca392"}, - {file = "yarl-1.9.4-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:d5ff2c858f5f6a42c2a8e751100f237c5e869cbde669a724f2062d4c4ef93551"}, - {file = "yarl-1.9.4-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:357495293086c5b6d34ca9616a43d329317feab7917518bc97a08f9e55648455"}, - {file = "yarl-1.9.4-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:54525ae423d7b7a8ee81ba189f131054defdb122cde31ff17477951464c1691c"}, - {file = "yarl-1.9.4-cp310-cp310-musllinux_1_1_aarch64.whl", hash = "sha256:801e9264d19643548651b9db361ce3287176671fb0117f96b5ac0ee1c3530d53"}, - {file = "yarl-1.9.4-cp310-cp310-musllinux_1_1_i686.whl", hash = "sha256:e516dc8baf7b380e6c1c26792610230f37147bb754d6426462ab115a02944385"}, - {file = "yarl-1.9.4-cp310-cp310-musllinux_1_1_ppc64le.whl", hash = "sha256:7d5aaac37d19b2904bb9dfe12cdb08c8443e7ba7d2852894ad448d4b8f442863"}, - {file = "yarl-1.9.4-cp310-cp310-musllinux_1_1_s390x.whl", hash = "sha256:54beabb809ffcacbd9d28ac57b0db46e42a6e341a030293fb3185c409e626b8b"}, - {file = "yarl-1.9.4-cp310-cp310-musllinux_1_1_x86_64.whl", hash = "sha256:bac8d525a8dbc2a1507ec731d2867025d11ceadcb4dd421423a5d42c56818541"}, - {file = "yarl-1.9.4-cp310-cp310-win32.whl", hash = "sha256:7855426dfbddac81896b6e533ebefc0af2f132d4a47340cee6d22cac7190022d"}, - {file = "yarl-1.9.4-cp310-cp310-win_amd64.whl", hash = "sha256:848cd2a1df56ddbffeb375535fb62c9d1645dde33ca4d51341378b3f5954429b"}, - {file = "yarl-1.9.4-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:35a2b9396879ce32754bd457d31a51ff0a9d426fd9e0e3c33394bf4b9036b099"}, - {file = "yarl-1.9.4-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:4c7d56b293cc071e82532f70adcbd8b61909eec973ae9d2d1f9b233f3d943f2c"}, - {file = "yarl-1.9.4-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:d8a1c6c0be645c745a081c192e747c5de06e944a0d21245f4cf7c05e457c36e0"}, - {file = "yarl-1.9.4-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:4b3c1ffe10069f655ea2d731808e76e0f452fc6c749bea04781daf18e6039525"}, - {file = "yarl-1.9.4-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:549d19c84c55d11687ddbd47eeb348a89df9cb30e1993f1b128f4685cd0ebbf8"}, - {file = "yarl-1.9.4-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a7409f968456111140c1c95301cadf071bd30a81cbd7ab829169fb9e3d72eae9"}, - {file = "yarl-1.9.4-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e23a6d84d9d1738dbc6e38167776107e63307dfc8ad108e580548d1f2c587f42"}, - {file = "yarl-1.9.4-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:d8b889777de69897406c9fb0b76cdf2fd0f31267861ae7501d93003d55f54fbe"}, - {file = "yarl-1.9.4-cp311-cp311-musllinux_1_1_aarch64.whl", hash = "sha256:03caa9507d3d3c83bca08650678e25364e1843b484f19986a527630ca376ecce"}, - {file = "yarl-1.9.4-cp311-cp311-musllinux_1_1_i686.whl", hash = "sha256:4e9035df8d0880b2f1c7f5031f33f69e071dfe72ee9310cfc76f7b605958ceb9"}, - {file = "yarl-1.9.4-cp311-cp311-musllinux_1_1_ppc64le.whl", hash = "sha256:c0ec0ed476f77db9fb29bca17f0a8fcc7bc97ad4c6c1d8959c507decb22e8572"}, - {file = "yarl-1.9.4-cp311-cp311-musllinux_1_1_s390x.whl", hash = "sha256:ee04010f26d5102399bd17f8df8bc38dc7ccd7701dc77f4a68c5b8d733406958"}, - {file = "yarl-1.9.4-cp311-cp311-musllinux_1_1_x86_64.whl", hash = "sha256:49a180c2e0743d5d6e0b4d1a9e5f633c62eca3f8a86ba5dd3c471060e352ca98"}, - {file = "yarl-1.9.4-cp311-cp311-win32.whl", hash = "sha256:81eb57278deb6098a5b62e88ad8281b2ba09f2f1147c4767522353eaa6260b31"}, - {file = "yarl-1.9.4-cp311-cp311-win_amd64.whl", hash = "sha256:d1d2532b340b692880261c15aee4dc94dd22ca5d61b9db9a8a361953d36410b1"}, - {file = "yarl-1.9.4-cp312-cp312-macosx_10_9_universal2.whl", hash = "sha256:0d2454f0aef65ea81037759be5ca9947539667eecebca092733b2eb43c965a81"}, - {file = "yarl-1.9.4-cp312-cp312-macosx_10_9_x86_64.whl", hash = "sha256:44d8ffbb9c06e5a7f529f38f53eda23e50d1ed33c6c869e01481d3fafa6b8142"}, - {file = "yarl-1.9.4-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:aaaea1e536f98754a6e5c56091baa1b6ce2f2700cc4a00b0d49eca8dea471074"}, - {file = "yarl-1.9.4-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:3777ce5536d17989c91696db1d459574e9a9bd37660ea7ee4d3344579bb6f129"}, - {file = "yarl-1.9.4-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:9fc5fc1eeb029757349ad26bbc5880557389a03fa6ada41703db5e068881e5f2"}, - {file = "yarl-1.9.4-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ea65804b5dc88dacd4a40279af0cdadcfe74b3e5b4c897aa0d81cf86927fee78"}, - {file = "yarl-1.9.4-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:aa102d6d280a5455ad6a0f9e6d769989638718e938a6a0a2ff3f4a7ff8c62cc4"}, - {file = "yarl-1.9.4-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:09efe4615ada057ba2d30df871d2f668af661e971dfeedf0c159927d48bbeff0"}, - {file = "yarl-1.9.4-cp312-cp312-musllinux_1_1_aarch64.whl", hash = "sha256:008d3e808d03ef28542372d01057fd09168419cdc8f848efe2804f894ae03e51"}, - {file = "yarl-1.9.4-cp312-cp312-musllinux_1_1_i686.whl", hash = "sha256:6f5cb257bc2ec58f437da2b37a8cd48f666db96d47b8a3115c29f316313654ff"}, - {file = "yarl-1.9.4-cp312-cp312-musllinux_1_1_ppc64le.whl", hash = "sha256:992f18e0ea248ee03b5a6e8b3b4738850ae7dbb172cc41c966462801cbf62cf7"}, - {file = "yarl-1.9.4-cp312-cp312-musllinux_1_1_s390x.whl", hash = "sha256:0e9d124c191d5b881060a9e5060627694c3bdd1fe24c5eecc8d5d7d0eb6faabc"}, - {file = "yarl-1.9.4-cp312-cp312-musllinux_1_1_x86_64.whl", hash = "sha256:3986b6f41ad22988e53d5778f91855dc0399b043fc8946d4f2e68af22ee9ff10"}, - {file = "yarl-1.9.4-cp312-cp312-win32.whl", hash = "sha256:4b21516d181cd77ebd06ce160ef8cc2a5e9ad35fb1c5930882baff5ac865eee7"}, - {file = "yarl-1.9.4-cp312-cp312-win_amd64.whl", hash = "sha256:a9bd00dc3bc395a662900f33f74feb3e757429e545d831eef5bb280252631984"}, - {file = "yarl-1.9.4-cp37-cp37m-macosx_10_9_x86_64.whl", hash = "sha256:63b20738b5aac74e239622d2fe30df4fca4942a86e31bf47a81a0e94c14df94f"}, - {file = "yarl-1.9.4-cp37-cp37m-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:d7d7f7de27b8944f1fee2c26a88b4dabc2409d2fea7a9ed3df79b67277644e17"}, - {file = "yarl-1.9.4-cp37-cp37m-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c74018551e31269d56fab81a728f683667e7c28c04e807ba08f8c9e3bba32f14"}, - {file = "yarl-1.9.4-cp37-cp37m-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:ca06675212f94e7a610e85ca36948bb8fc023e458dd6c63ef71abfd482481aa5"}, - {file = "yarl-1.9.4-cp37-cp37m-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:5aef935237d60a51a62b86249839b51345f47564208c6ee615ed2a40878dccdd"}, - {file = "yarl-1.9.4-cp37-cp37m-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:2b134fd795e2322b7684155b7855cc99409d10b2e408056db2b93b51a52accc7"}, - {file = "yarl-1.9.4-cp37-cp37m-musllinux_1_1_aarch64.whl", hash = "sha256:d25039a474c4c72a5ad4b52495056f843a7ff07b632c1b92ea9043a3d9950f6e"}, - {file = "yarl-1.9.4-cp37-cp37m-musllinux_1_1_i686.whl", hash = "sha256:f7d6b36dd2e029b6bcb8a13cf19664c7b8e19ab3a58e0fefbb5b8461447ed5ec"}, - {file = "yarl-1.9.4-cp37-cp37m-musllinux_1_1_ppc64le.whl", hash = "sha256:957b4774373cf6f709359e5c8c4a0af9f6d7875db657adb0feaf8d6cb3c3964c"}, - {file = "yarl-1.9.4-cp37-cp37m-musllinux_1_1_s390x.whl", hash = "sha256:d7eeb6d22331e2fd42fce928a81c697c9ee2d51400bd1a28803965883e13cead"}, - {file = "yarl-1.9.4-cp37-cp37m-musllinux_1_1_x86_64.whl", hash = "sha256:6a962e04b8f91f8c4e5917e518d17958e3bdee71fd1d8b88cdce74dd0ebbf434"}, - {file = "yarl-1.9.4-cp37-cp37m-win32.whl", hash = "sha256:f3bc6af6e2b8f92eced34ef6a96ffb248e863af20ef4fde9448cc8c9b858b749"}, - {file = "yarl-1.9.4-cp37-cp37m-win_amd64.whl", hash = "sha256:ad4d7a90a92e528aadf4965d685c17dacff3df282db1121136c382dc0b6014d2"}, - {file = "yarl-1.9.4-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:ec61d826d80fc293ed46c9dd26995921e3a82146feacd952ef0757236fc137be"}, - {file = "yarl-1.9.4-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:8be9e837ea9113676e5754b43b940b50cce76d9ed7d2461df1af39a8ee674d9f"}, - {file = "yarl-1.9.4-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:bef596fdaa8f26e3d66af846bbe77057237cb6e8efff8cd7cc8dff9a62278bbf"}, - {file = "yarl-1.9.4-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2d47552b6e52c3319fede1b60b3de120fe83bde9b7bddad11a69fb0af7db32f1"}, - {file = "yarl-1.9.4-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:84fc30f71689d7fc9168b92788abc977dc8cefa806909565fc2951d02f6b7d57"}, - {file = "yarl-1.9.4-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:4aa9741085f635934f3a2583e16fcf62ba835719a8b2b28fb2917bb0537c1dfa"}, - {file = "yarl-1.9.4-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:206a55215e6d05dbc6c98ce598a59e6fbd0c493e2de4ea6cc2f4934d5a18d130"}, - {file = "yarl-1.9.4-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:07574b007ee20e5c375a8fe4a0789fad26db905f9813be0f9fef5a68080de559"}, - {file = "yarl-1.9.4-cp38-cp38-musllinux_1_1_aarch64.whl", hash = "sha256:5a2e2433eb9344a163aced6a5f6c9222c0786e5a9e9cac2c89f0b28433f56e23"}, - {file = "yarl-1.9.4-cp38-cp38-musllinux_1_1_i686.whl", hash = "sha256:6ad6d10ed9b67a382b45f29ea028f92d25bc0bc1daf6c5b801b90b5aa70fb9ec"}, - {file = "yarl-1.9.4-cp38-cp38-musllinux_1_1_ppc64le.whl", hash = "sha256:6fe79f998a4052d79e1c30eeb7d6c1c1056ad33300f682465e1b4e9b5a188b78"}, - {file = "yarl-1.9.4-cp38-cp38-musllinux_1_1_s390x.whl", hash = "sha256:a825ec844298c791fd28ed14ed1bffc56a98d15b8c58a20e0e08c1f5f2bea1be"}, - {file = "yarl-1.9.4-cp38-cp38-musllinux_1_1_x86_64.whl", hash = "sha256:8619d6915b3b0b34420cf9b2bb6d81ef59d984cb0fde7544e9ece32b4b3043c3"}, - {file = "yarl-1.9.4-cp38-cp38-win32.whl", hash = "sha256:686a0c2f85f83463272ddffd4deb5e591c98aac1897d65e92319f729c320eece"}, - {file = "yarl-1.9.4-cp38-cp38-win_amd64.whl", hash = "sha256:a00862fb23195b6b8322f7d781b0dc1d82cb3bcac346d1e38689370cc1cc398b"}, - {file = "yarl-1.9.4-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:604f31d97fa493083ea21bd9b92c419012531c4e17ea6da0f65cacdcf5d0bd27"}, - {file = "yarl-1.9.4-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:8a854227cf581330ffa2c4824d96e52ee621dd571078a252c25e3a3b3d94a1b1"}, - {file = "yarl-1.9.4-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:ba6f52cbc7809cd8d74604cce9c14868306ae4aa0282016b641c661f981a6e91"}, - {file = "yarl-1.9.4-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a6327976c7c2f4ee6816eff196e25385ccc02cb81427952414a64811037bbc8b"}, - {file = "yarl-1.9.4-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8397a3817d7dcdd14bb266283cd1d6fc7264a48c186b986f32e86d86d35fbac5"}, - {file = "yarl-1.9.4-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:e0381b4ce23ff92f8170080c97678040fc5b08da85e9e292292aba67fdac6c34"}, - {file = "yarl-1.9.4-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:23d32a2594cb5d565d358a92e151315d1b2268bc10f4610d098f96b147370136"}, - {file = "yarl-1.9.4-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:ddb2a5c08a4eaaba605340fdee8fc08e406c56617566d9643ad8bf6852778fc7"}, - {file = "yarl-1.9.4-cp39-cp39-musllinux_1_1_aarch64.whl", hash = "sha256:26a1dc6285e03f3cc9e839a2da83bcbf31dcb0d004c72d0730e755b33466c30e"}, - {file = "yarl-1.9.4-cp39-cp39-musllinux_1_1_i686.whl", hash = "sha256:18580f672e44ce1238b82f7fb87d727c4a131f3a9d33a5e0e82b793362bf18b4"}, - {file = "yarl-1.9.4-cp39-cp39-musllinux_1_1_ppc64le.whl", hash = "sha256:29e0f83f37610f173eb7e7b5562dd71467993495e568e708d99e9d1944f561ec"}, - {file = "yarl-1.9.4-cp39-cp39-musllinux_1_1_s390x.whl", hash = "sha256:1f23e4fe1e8794f74b6027d7cf19dc25f8b63af1483d91d595d4a07eca1fb26c"}, - {file = "yarl-1.9.4-cp39-cp39-musllinux_1_1_x86_64.whl", hash = "sha256:db8e58b9d79200c76956cefd14d5c90af54416ff5353c5bfd7cbe58818e26ef0"}, - {file = "yarl-1.9.4-cp39-cp39-win32.whl", hash = "sha256:c7224cab95645c7ab53791022ae77a4509472613e839dab722a72abe5a684575"}, - {file = "yarl-1.9.4-cp39-cp39-win_amd64.whl", hash = "sha256:824d6c50492add5da9374875ce72db7a0733b29c2394890aef23d533106e2b15"}, - {file = "yarl-1.9.4-py3-none-any.whl", hash = "sha256:928cecb0ef9d5a7946eb6ff58417ad2fe9375762382f1bf5c55e61645f2c43ad"}, - {file = "yarl-1.9.4.tar.gz", hash = "sha256:566db86717cf8080b99b58b083b773a908ae40f06681e87e589a976faf8246bf"}, + {file = "yarl-1.12.1-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:64c5b0f2b937fe40d0967516eee5504b23cb247b8b7ffeba7213a467d9646fdc"}, + {file = "yarl-1.12.1-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:2e430ac432f969ef21770645743611c1618362309e3ad7cab45acd1ad1a540ff"}, + {file = "yarl-1.12.1-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:3e26e64f42bce5ddf9002092b2c37b13071c2e6413d5c05f9fa9de58ed2f7749"}, + {file = "yarl-1.12.1-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:0103c52f8dfe5d573c856322149ddcd6d28f51b4d4a3ee5c4b3c1b0a05c3d034"}, + {file = "yarl-1.12.1-cp310-cp310-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:b63465b53baeaf2122a337d4ab57d6bbdd09fcadceb17a974cfa8a0300ad9c67"}, + {file = "yarl-1.12.1-cp310-cp310-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:17d4dc4ff47893a06737b8788ed2ba2f5ac4e8bb40281c8603920f7d011d5bdd"}, + {file = "yarl-1.12.1-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:a8b54949267bd5704324397efe9fbb6aa306466dee067550964e994d309db5f1"}, + {file = "yarl-1.12.1-cp310-cp310-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:10b690cd78cbaca2f96a7462f303fdd2b596d3978b49892e4b05a7567c591572"}, + {file = "yarl-1.12.1-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:c85ab016e96a975afbdb9d49ca90f3bca9920ef27c64300843fe91c3d59d8d20"}, + {file = "yarl-1.12.1-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:c1caa5763d1770216596e0a71b5567f27aac28c95992110212c108ec74589a48"}, + {file = "yarl-1.12.1-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:595bbcdbfc4a9c6989d7489dca8510cba053ff46b16c84ffd95ac8e90711d419"}, + {file = "yarl-1.12.1-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:e64f0421892a207d3780903085c1b04efeb53b16803b23d947de5a7261b71355"}, + {file = "yarl-1.12.1-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:319c206e83e46ec2421b25b300c8482b6fe8a018baca246be308c736d9dab267"}, + {file = "yarl-1.12.1-cp310-cp310-win32.whl", hash = "sha256:da045bd1147d12bd43fb032296640a7cc17a7f2eaba67495988362e99db24fd2"}, + {file = "yarl-1.12.1-cp310-cp310-win_amd64.whl", hash = "sha256:aebbd47df77190ada603157f0b3670d578c110c31746ecc5875c394fdcc59a99"}, + {file = "yarl-1.12.1-cp311-cp311-macosx_10_9_universal2.whl", hash = "sha256:28389a68981676bf74e2e199fe42f35d1aa27a9c98e3a03e6f58d2d3d054afe1"}, + {file = "yarl-1.12.1-cp311-cp311-macosx_10_9_x86_64.whl", hash = "sha256:f736f54565f8dd7e3ab664fef2bc461d7593a389a7f28d4904af8d55a91bd55f"}, + {file = "yarl-1.12.1-cp311-cp311-macosx_11_0_arm64.whl", hash = "sha256:6dee0496d5f1a8f57f0f28a16f81a2033fc057a2cf9cd710742d11828f8c80e2"}, + {file = "yarl-1.12.1-cp311-cp311-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:f8981a94a27ac520a398302afb74ae2c0be1c3d2d215c75c582186a006c9e7b0"}, + {file = "yarl-1.12.1-cp311-cp311-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:ff54340fc1129e8e181827e2234af3ff659b4f17d9bbe77f43bc19e6577fadec"}, + {file = "yarl-1.12.1-cp311-cp311-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:54c8cee662b5f8c30ad7eedfc26123f845f007798e4ff1001d9528fe959fd23c"}, + {file = "yarl-1.12.1-cp311-cp311-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:e97a29b37830ba1262d8dfd48ddb5b28ad4d3ebecc5d93a9c7591d98641ec737"}, + {file = "yarl-1.12.1-cp311-cp311-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:6c89894cc6f6ddd993813e79244b36b215c14f65f9e4f1660b1f2ba9e5594b95"}, + {file = "yarl-1.12.1-cp311-cp311-musllinux_1_2_aarch64.whl", hash = "sha256:712ba8722c0699daf186de089ddc4677651eb9875ed7447b2ad50697522cbdd9"}, + {file = "yarl-1.12.1-cp311-cp311-musllinux_1_2_i686.whl", hash = "sha256:6e9a9f50892153bad5046c2a6df153224aa6f0573a5a8ab44fc54a1e886f6e21"}, + {file = "yarl-1.12.1-cp311-cp311-musllinux_1_2_ppc64le.whl", hash = "sha256:1d4017e78fb22bc797c089b746230ad78ecd3cdb215bc0bd61cb72b5867da57e"}, + {file = "yarl-1.12.1-cp311-cp311-musllinux_1_2_s390x.whl", hash = "sha256:f494c01b28645c431239863cb17af8b8d15b93b0d697a0320d5dd34cd9d7c2fa"}, + {file = "yarl-1.12.1-cp311-cp311-musllinux_1_2_x86_64.whl", hash = "sha256:de4544b1fb29cf14870c4e2b8a897c0242449f5dcebd3e0366aa0aa3cf58a23a"}, + {file = "yarl-1.12.1-cp311-cp311-win32.whl", hash = "sha256:7564525a4673fde53dee7d4c307a961c0951918f0b8c7f09b2c9e02067cf6504"}, + {file = "yarl-1.12.1-cp311-cp311-win_amd64.whl", hash = "sha256:f23bb1a7a6e8e8b612a164fdd08e683bcc16c76f928d6dbb7bdbee2374fbfee6"}, + {file = "yarl-1.12.1-cp312-cp312-macosx_10_13_universal2.whl", hash = "sha256:a3e2aff8b822ab0e0bdbed9f50494b3a35629c4b9488ae391659973a37a9f53f"}, + {file = "yarl-1.12.1-cp312-cp312-macosx_10_13_x86_64.whl", hash = "sha256:22dda2799c8d39041d731e02bf7690f0ef34f1691d9ac9dfcb98dd1e94c8b058"}, + {file = "yarl-1.12.1-cp312-cp312-macosx_11_0_arm64.whl", hash = "sha256:18c2a7757561f05439c243f517dbbb174cadfae3a72dee4ae7c693f5b336570f"}, + {file = "yarl-1.12.1-cp312-cp312-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:835010cc17d0020e7931d39e487d72c8e01c98e669b6896a8b8c9aa8ca69a949"}, + {file = "yarl-1.12.1-cp312-cp312-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:e2254fe137c4a360b0a13173a56444f756252c9283ba4d267ca8e9081cd140ea"}, + {file = "yarl-1.12.1-cp312-cp312-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:f6a071d2c3d39b4104f94fc08ab349e9b19b951ad4b8e3b6d7ea92d6ef7ccaf8"}, + {file = "yarl-1.12.1-cp312-cp312-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:73a183042ae0918c82ce2df38c3db2409b0eeae88e3afdfc80fb67471a95b33b"}, + {file = "yarl-1.12.1-cp312-cp312-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:326b8a079a9afcac0575971e56dabdf7abb2ea89a893e6949b77adfeb058b50e"}, + {file = "yarl-1.12.1-cp312-cp312-musllinux_1_2_aarch64.whl", hash = "sha256:126309c0f52a2219b3d1048aca00766429a1346596b186d51d9fa5d2070b7b13"}, + {file = "yarl-1.12.1-cp312-cp312-musllinux_1_2_i686.whl", hash = "sha256:ba1c779b45a399cc25f511c681016626f69e51e45b9d350d7581998722825af9"}, + {file = "yarl-1.12.1-cp312-cp312-musllinux_1_2_ppc64le.whl", hash = "sha256:af1107299cef049ad00a93df4809517be432283a0847bcae48343ebe5ea340dc"}, + {file = "yarl-1.12.1-cp312-cp312-musllinux_1_2_s390x.whl", hash = "sha256:20d817c0893191b2ab0ba30b45b77761e8dfec30a029b7c7063055ca71157f84"}, + {file = "yarl-1.12.1-cp312-cp312-musllinux_1_2_x86_64.whl", hash = "sha256:d4f818f6371970d6a5d1e42878389bbfb69dcde631e4bbac5ec1cb11158565ca"}, + {file = "yarl-1.12.1-cp312-cp312-win32.whl", hash = "sha256:0ac33d22b2604b020569a82d5f8a03ba637ba42cc1adf31f616af70baf81710b"}, + {file = "yarl-1.12.1-cp312-cp312-win_amd64.whl", hash = "sha256:fd24996e12e1ba7c397c44be75ca299da14cde34d74bc5508cce233676cc68d0"}, + {file = "yarl-1.12.1-cp313-cp313-macosx_10_13_universal2.whl", hash = "sha256:dea360778e0668a7ad25d7727d03364de8a45bfd5d808f81253516b9f2217765"}, + {file = "yarl-1.12.1-cp313-cp313-macosx_10_13_x86_64.whl", hash = "sha256:1f50a37aeeb5179d293465e522fd686080928c4d89e0ff215e1f963405ec4def"}, + {file = "yarl-1.12.1-cp313-cp313-macosx_11_0_arm64.whl", hash = "sha256:0274b1b7a9c9c32b7bf250583e673ff99fb9fccb389215841e2652d9982de740"}, + {file = "yarl-1.12.1-cp313-cp313-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:a4f3ab9eb8ab2d585ece959c48d234f7b39ac0ca1954a34d8b8e58a52064bdb3"}, + {file = "yarl-1.12.1-cp313-cp313-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:8d31dd0245d88cf7239e96e8f2a99f815b06e458a5854150f8e6f0e61618d41b"}, + {file = "yarl-1.12.1-cp313-cp313-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:a96198d5d26f40557d986c1253bfe0e02d18c9d9b93cf389daf1a3c9f7c755fa"}, + {file = "yarl-1.12.1-cp313-cp313-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:ddae504cfb556fe220efae65e35be63cd11e3c314b202723fc2119ce19f0ca2e"}, + {file = "yarl-1.12.1-cp313-cp313-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:bce00f3b1f7f644faae89677ca68645ed5365f1c7f874fdd5ebf730a69640d38"}, + {file = "yarl-1.12.1-cp313-cp313-musllinux_1_2_aarch64.whl", hash = "sha256:eee5ff934b0c9f4537ff9596169d56cab1890918004791a7a06b879b3ba2a7ef"}, + {file = "yarl-1.12.1-cp313-cp313-musllinux_1_2_i686.whl", hash = "sha256:4ea99e64b2ad2635e0f0597b63f5ea6c374791ff2fa81cdd4bad8ed9f047f56f"}, + {file = "yarl-1.12.1-cp313-cp313-musllinux_1_2_ppc64le.whl", hash = "sha256:5c667b383529520b8dd6bd496fc318678320cb2a6062fdfe6d3618da6b8790f6"}, + {file = "yarl-1.12.1-cp313-cp313-musllinux_1_2_s390x.whl", hash = "sha256:d920401941cb898ef089422e889759dd403309eb370d0e54f1bdf6ca07fef603"}, + {file = "yarl-1.12.1-cp313-cp313-musllinux_1_2_x86_64.whl", hash = "sha256:501a1576716032cc6d48c7c47bcdc42d682273415a8f2908e7e72cb4625801f3"}, + {file = "yarl-1.12.1-cp313-cp313-win32.whl", hash = "sha256:24416bb5e221e29ddf8aac5b97e94e635ca2c5be44a1617ad6fe32556df44294"}, + {file = "yarl-1.12.1-cp313-cp313-win_amd64.whl", hash = "sha256:71af3766bb46738d12cc288d9b8de7ef6f79c31fd62757e2b8a505fe3680b27f"}, + {file = "yarl-1.12.1-cp38-cp38-macosx_10_9_universal2.whl", hash = "sha256:c924deab8105f86980983eced740433fb7554a7f66db73991affa4eda99d5402"}, + {file = "yarl-1.12.1-cp38-cp38-macosx_10_9_x86_64.whl", hash = "sha256:5fb475a4cdde582c9528bb412b98f899680492daaba318231e96f1a0a1bb0d53"}, + {file = "yarl-1.12.1-cp38-cp38-macosx_11_0_arm64.whl", hash = "sha256:36ee0115b9edca904153a66bb74a9ff1ce38caff015de94eadfb9ba8e6ecd317"}, + {file = "yarl-1.12.1-cp38-cp38-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:2631c9d7386bd2d4ce24ecc6ebf9ae90b3efd713d588d90504eaa77fec4dba01"}, + {file = "yarl-1.12.1-cp38-cp38-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:2376d8cf506dffd0e5f2391025ae8675b09711016656590cb03b55894161fcfa"}, + {file = "yarl-1.12.1-cp38-cp38-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:24197ba3114cc85ddd4091e19b2ddc62650f2e4a899e51b074dfd52d56cf8c72"}, + {file = "yarl-1.12.1-cp38-cp38-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:bfdf419bf5d3644f94cd7052954fc233522f5a1b371fc0b00219ebd9c14d5798"}, + {file = "yarl-1.12.1-cp38-cp38-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:8112f640a4f7e7bf59f7cabf0d47a29b8977528c521d73a64d5cc9e99e48a174"}, + {file = "yarl-1.12.1-cp38-cp38-musllinux_1_2_aarch64.whl", hash = "sha256:607d12f0901f6419a8adceb139847c42c83864b85371f58270e42753f9780fa6"}, + {file = "yarl-1.12.1-cp38-cp38-musllinux_1_2_i686.whl", hash = "sha256:664380c7ed524a280b6a2d5d9126389c3e96cd6e88986cdb42ca72baa27421d6"}, + {file = "yarl-1.12.1-cp38-cp38-musllinux_1_2_ppc64le.whl", hash = "sha256:0d0a5e87bc48d76dfcfc16295201e9812d5f33d55b4a0b7cad1025b92bf8b91b"}, + {file = "yarl-1.12.1-cp38-cp38-musllinux_1_2_s390x.whl", hash = "sha256:eff6bac402719c14e17efe845d6b98593c56c843aca6def72080fbede755fd1f"}, + {file = "yarl-1.12.1-cp38-cp38-musllinux_1_2_x86_64.whl", hash = "sha256:22839d1d1eab9e4b427828a88a22beb86f67c14d8ff81175505f1cc8493f3500"}, + {file = "yarl-1.12.1-cp38-cp38-win32.whl", hash = "sha256:717f185086bb9d817d4537dd18d5df5d657598cd00e6fc22e4d54d84de266c1d"}, + {file = "yarl-1.12.1-cp38-cp38-win_amd64.whl", hash = "sha256:71978ba778948760cff528235c951ea0ef7a4f9c84ac5a49975f8540f76c3f73"}, + {file = "yarl-1.12.1-cp39-cp39-macosx_10_9_universal2.whl", hash = "sha256:30ffc046ebddccb3c4cac72c1a3e1bc343492336f3ca86d24672e90ccc5e788a"}, + {file = "yarl-1.12.1-cp39-cp39-macosx_10_9_x86_64.whl", hash = "sha256:f10954b233d4df5cc3137ffa5ced97f8894152df817e5d149bf05a0ef2ab8134"}, + {file = "yarl-1.12.1-cp39-cp39-macosx_11_0_arm64.whl", hash = "sha256:2e912b282466444023610e4498e3795c10e7cfd641744524876239fcf01d538d"}, + {file = "yarl-1.12.1-cp39-cp39-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:6af871f70cfd5b528bd322c65793b5fd5659858cdfaa35fbe563fb99b667ed1f"}, + {file = "yarl-1.12.1-cp39-cp39-manylinux_2_17_ppc64le.manylinux2014_ppc64le.whl", hash = "sha256:c3e4e1f7b08d1ec6b685ccd3e2d762219c550164fbf524498532e39f9413436e"}, + {file = "yarl-1.12.1-cp39-cp39-manylinux_2_17_s390x.manylinux2014_s390x.whl", hash = "sha256:9a7ee79183f0b17dcede8b6723e7da2ded529cf159a878214be9a5d3098f5b1e"}, + {file = "yarl-1.12.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:96c8ff1e1dd680e38af0887927cab407a4e51d84a5f02ae3d6eb87233036c763"}, + {file = "yarl-1.12.1-cp39-cp39-manylinux_2_5_i686.manylinux1_i686.manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:7e9905fc2dc1319e4c39837b906a024cf71b1261cc66b0cd89678f779c0c61f5"}, + {file = "yarl-1.12.1-cp39-cp39-musllinux_1_2_aarch64.whl", hash = "sha256:01549468858b87d36f967c97d02e6e54106f444aeb947ed76f8f71f85ed07cec"}, + {file = "yarl-1.12.1-cp39-cp39-musllinux_1_2_i686.whl", hash = "sha256:96b34830bd6825ca0220bf005ea99ac83eb9ce51301ddb882dcf613ae6cd95fb"}, + {file = "yarl-1.12.1-cp39-cp39-musllinux_1_2_ppc64le.whl", hash = "sha256:2aee7594d2c2221c717a8e394bbed4740029df4c0211ceb0f04815686e99c795"}, + {file = "yarl-1.12.1-cp39-cp39-musllinux_1_2_s390x.whl", hash = "sha256:15871130439ad10abb25a4631120d60391aa762b85fcab971411e556247210a0"}, + {file = "yarl-1.12.1-cp39-cp39-musllinux_1_2_x86_64.whl", hash = "sha256:838dde2cb570cfbb4cab8a876a0974e8b90973ea40b3ac27a79b8a74c8a2db15"}, + {file = "yarl-1.12.1-cp39-cp39-win32.whl", hash = "sha256:eacbcf30efaca7dc5cb264228ffecdb95fdb1e715b1ec937c0ce6b734161e0c8"}, + {file = "yarl-1.12.1-cp39-cp39-win_amd64.whl", hash = "sha256:76a59d1b63de859398bc7764c860a769499511463c1232155061fe0147f13e01"}, + {file = "yarl-1.12.1-py3-none-any.whl", hash = "sha256:dc3192a81ecd5ff954cecd690327badd5a84d00b877e1573f7c9097ce13e5bfb"}, + {file = "yarl-1.12.1.tar.gz", hash = "sha256:5b860055199aec8d6fe4dcee3c5196ce506ca198a50aab0059ffd26e8e815828"}, ] [package.dependencies] @@ -4536,20 +7373,20 @@ multidict = ">=4.0" [[package]] name = "zarr" -version = "2.18.2" +version = "2.18.3" description = "An implementation of chunked, compressed, N-dimensional arrays for Python" optional = false -python-versions = ">=3.9" +python-versions = ">=3.10" files = [ - {file = "zarr-2.18.2-py3-none-any.whl", hash = "sha256:a638754902f97efa99b406083fdc807a0e2ccf12a949117389d2a4ba9b05df38"}, - {file = "zarr-2.18.2.tar.gz", hash = "sha256:9bb393b8a0a38fb121dbb913b047d75db28de9890f6d644a217a73cf4ae74f47"}, + {file = "zarr-2.18.3-py3-none-any.whl", hash = "sha256:b1f7dfd2496f436745cdd4c7bcf8d3b4bc1dceef5fdd0d589c87130d842496dd"}, + {file = "zarr-2.18.3.tar.gz", hash = "sha256:2580d8cb6dd84621771a10d31c4d777dca8a27706a1a89b29f42d2d37e2df5ce"}, ] [package.dependencies] asciitree = "*" fasteners = {version = "*", markers = "sys_platform != \"emscripten\""} numcodecs = ">=0.10.0" -numpy = ">=1.23" +numpy = ">=1.24" [package.extras] docs = ["numcodecs[msgpack]", "numpydoc", "pydata-sphinx-theme", "sphinx", "sphinx-automodapi", "sphinx-copybutton", "sphinx-design", "sphinx-issues"] @@ -4557,18 +7394,22 @@ jupyter = ["ipytree (>=0.2.2)", "ipywidgets (>=8.0.0)", "notebook"] [[package]] name = "zipp" -version = "3.19.2" +version = "3.20.2" description = "Backport of pathlib-compatible object wrapper for zip files" optional = false python-versions = ">=3.8" files = [ - {file = "zipp-3.19.2-py3-none-any.whl", hash = "sha256:f091755f667055f2d02b32c53771a7a6c8b47e1fdbc4b72a8b9072b3eef8015c"}, - {file = "zipp-3.19.2.tar.gz", hash = "sha256:bf1dcf6450f873a13e952a29504887c89e6de7506209e5b1bcc3460135d4de19"}, + {file = "zipp-3.20.2-py3-none-any.whl", hash = "sha256:a817ac80d6cf4b23bf7f2828b7cabf326f15a001bea8b1f9b49631780ba28350"}, + {file = "zipp-3.20.2.tar.gz", hash = "sha256:bc9eb26f4506fda01b81bcde0ca78103b6e62f991b381fec825435c836edbc29"}, ] [package.extras] +check = ["pytest-checkdocs (>=2.4)", "pytest-ruff (>=0.2.1)"] +cover = ["pytest-cov"] doc = ["furo", "jaraco.packaging (>=9.3)", "jaraco.tidelift (>=1.4)", "rst.linker (>=1.9)", "sphinx (>=3.5)", "sphinx-lint"] -test = ["big-O", "importlib-resources", "jaraco.functools", "jaraco.itertools", "jaraco.test", "more-itertools", "pytest (>=6,!=8.1.*)", "pytest-checkdocs (>=2.4)", "pytest-cov", "pytest-enabler (>=2.2)", "pytest-ignore-flaky", "pytest-mypy", "pytest-ruff (>=0.2.1)"] +enabler = ["pytest-enabler (>=2.2)"] +test = ["big-O", "importlib-resources", "jaraco.functools", "jaraco.itertools", "jaraco.test", "more-itertools", "pytest (>=6,!=8.1.*)", "pytest-ignore-flaky"] +type = ["pytest-mypy"] [extras] aloha = ["gym-aloha"] @@ -4577,6 +7418,7 @@ dora = ["gym-dora"] dynamixel = ["dynamixel-sdk", "pynput"] intelrealsense = ["pyrealsense2"] pusht = ["gym-pusht"] +stretch = ["hello-robot-stretch-body", "pynput", "pyrealsense2", "pyrender"] test = ["pyserial", "pytest", "pytest-cov"] umi = ["imagecodecs"] video-benchmark = ["pandas", "scikit-image"] @@ -4585,4 +7427,4 @@ xarm = ["gym-xarm"] [metadata] lock-version = "2.0" python-versions = ">=3.10,<3.13" -content-hash = "5e4f6b9727d67a37d1c6d94af7661bb688a0866afd30878c5e523b8e768deac6" +content-hash = "78f31561a7e4b6f0a97e27a65ec00c2c1826f420d2587396762bb5485d12f676" diff --git a/pyproject.toml b/pyproject.toml index 119244419..47e982d1b 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -64,9 +64,10 @@ pandas = {version = ">=2.2.2", optional = true} scikit-image = {version = ">=0.23.2", optional = true} dynamixel-sdk = {version = ">=3.7.31", optional = true} pynput = {version = ">=1.7.7", optional = true} -# TODO(rcadene, salibert): 71.0.1 has a bug -setuptools = {version = "!=71.0.1", optional = true} -pyrealsense2 = {version = ">=2.55.1.6486", markers = "sys_platform != 'darwin'", optional = true} +setuptools = {version = "!=71.0.1", optional = true} # TODO(rcadene, aliberts): 71.0.1 has a bug +pyrealsense2 = {version = ">=2.55.1.6486", markers = "sys_platform != 'darwin'", optional = true} # TODO(rcadene, aliberts): Fix on Mac +pyrender = {git = "https://github.com/mmatl/pyrender.git", markers = "sys_platform == 'linux'", optional = true} +hello-robot-stretch-body = {version = ">=0.7.27", markers = "sys_platform == 'linux'", optional = true} pyserial = {version = ">=3.5", optional = true} @@ -81,6 +82,7 @@ umi = ["imagecodecs"] video_benchmark = ["scikit-image", "pandas"] dynamixel = ["dynamixel-sdk", "pynput"] intelrealsense = ["pyrealsense2"] +stretch = ["hello-robot-stretch-body", "pyrender", "pyrealsense2", "pynput"] [tool.ruff] line-length = 110 diff --git a/tests/mock_cv2.py b/tests/mock_cv2.py index a3e19e550..3f3f9e343 100644 --- a/tests/mock_cv2.py +++ b/tests/mock_cv2.py @@ -8,6 +8,10 @@ COLOR_RGB2BGR = 4 COLOR_BGR2RGB = 4 +ROTATE_90_COUNTERCLOCKWISE = 2 +ROTATE_90_CLOCKWISE = 0 +ROTATE_180 = 1 + @cache def _generate_image(width: int, height: int): @@ -21,6 +25,19 @@ def cvtColor(color_image, color_convertion): # noqa: N802 raise NotImplementedError(color_convertion) +def rotate(color_image, rotation): + if rotation is None: + return color_image + elif rotation == ROTATE_90_CLOCKWISE: + return np.rot90(color_image, k=1) + elif rotation == ROTATE_180: + return np.rot90(color_image, k=2) + elif rotation == ROTATE_90_COUNTERCLOCKWISE: + return np.rot90(color_image, k=3) + else: + raise NotImplementedError(rotation) + + class VideoCapture: def __init__(self, *args, **kwargs): self._mock_dict = { diff --git a/tests/mock_pyrealsense2.py b/tests/mock_pyrealsense2.py index b9c6ccf96..5a39fc2bf 100644 --- a/tests/mock_pyrealsense2.py +++ b/tests/mock_pyrealsense2.py @@ -3,33 +3,31 @@ import numpy as np -class RSStream(enum.Enum): +class stream(enum.Enum): # noqa: N801 color = 0 depth = 1 -class RSFormat(enum.Enum): +class format(enum.Enum): # noqa: N801 rgb8 = 0 z16 = 1 -class RSConfig: +class config: # noqa: N801 def enable_device(self, device_id: str): self.device_enabled = device_id - def enable_stream( - self, stream_type: RSStream, width=None, height=None, color_format: RSFormat = None, fps=None - ): + def enable_stream(self, stream_type: stream, width=None, height=None, color_format=None, fps=None): self.stream_type = stream_type # Overwrite default values when possible self.width = 848 if width is None else width self.height = 480 if height is None else height - self.color_format = RSFormat.rgb8 if color_format is None else color_format + self.color_format = format.rgb8 if color_format is None else color_format self.fps = 30 if fps is None else fps class RSColorProfile: - def __init__(self, config: RSConfig): + def __init__(self, config): self.config = config def fps(self): @@ -43,7 +41,7 @@ def height(self): class RSColorStream: - def __init__(self, config: RSConfig): + def __init__(self, config): self.config = config def as_video_stream_profile(self): @@ -51,20 +49,20 @@ def as_video_stream_profile(self): class RSProfile: - def __init__(self, config: RSConfig): + def __init__(self, config): self.config = config - def get_stream(self, color_format: RSFormat): + def get_stream(self, color_format): del color_format # unused return RSColorStream(self.config) -class RSPipeline: +class pipeline: # noqa: N801 def __init__(self): self.started = False self.config = None - def start(self, config: RSConfig): + def start(self, config): self.started = True self.config = config return RSProfile(self.config) @@ -81,7 +79,7 @@ def wait_for_frames(self, timeout_ms=50000): class RSFrames: - def __init__(self, config: RSConfig): + def __init__(self, config): self.config = config def get_color_frame(self): @@ -92,7 +90,7 @@ def get_depth_frame(self): class RSColorFrame: - def __init__(self, config: RSConfig): + def __init__(self, config): self.config = config def get_data(self): @@ -103,7 +101,7 @@ def get_data(self): class RSDepthFrame: - def __init__(self, config: RSConfig): + def __init__(self, config): self.config = config def get_data(self): @@ -120,7 +118,7 @@ def get_info(self, camera_info) -> str: return "123456789" -class RSContext: +class context: # noqa: N801 def __init__(self): pass @@ -128,7 +126,10 @@ def query_devices(self): return [RSDevice()] -class RSCameraInfo: +class camera_info: # noqa: N801 + # fake name + name = "Intel RealSense D435I" + def __init__(self, serial_number): del serial_number pass diff --git a/tests/test_cameras.py b/tests/test_cameras.py index 72da248d6..67512779a 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -120,6 +120,41 @@ def test_camera(request, camera_type, mock): ) del camera + # Test acquiring a rotated image + camera = make_camera(camera_type, mock=mock) + camera.connect() + ori_color_image = camera.read() + del camera + + for rotation in [None, 90, 180, -90]: + camera = make_camera(camera_type, rotation=rotation, mock=mock) + camera.connect() + + if mock: + import tests.mock_cv2 as cv2 + else: + import cv2 + + if rotation is None: + manual_rot_img = ori_color_image + assert camera.rotation is None + elif rotation == 90: + manual_rot_img = np.rot90(color_image, k=1) + assert camera.rotation == cv2.ROTATE_90_CLOCKWISE + elif rotation == 180: + manual_rot_img = np.rot90(color_image, k=2) + assert camera.rotation == cv2.ROTATE_180 + elif rotation == -90: + manual_rot_img = np.rot90(color_image, k=3) + assert camera.rotation == cv2.ROTATE_90_COUNTERCLOCKWISE + + rot_color_image = camera.read() + + np.testing.assert_allclose( + rot_color_image, manual_rot_img, rtol=1e-5, atol=MAX_PIXEL_DIFFERENCE, err_msg=error_msg + ) + del camera + # TODO(rcadene): Add a test for a camera that doesnt support fps=60 and raises an OSError # TODO(rcadene): Add a test for a camera that supports fps=60 @@ -152,4 +187,5 @@ def test_save_images_from_cameras(tmpdir, request, camera_type, mock): elif camera_type == "intelrealsense": from lerobot.common.robot_devices.cameras.intelrealsense import save_images_from_cameras - save_images_from_cameras(tmpdir, record_time_s=1, mock=mock) + # Small `record_time_s` to speedup unit tests + save_images_from_cameras(tmpdir, record_time_s=0.02, mock=mock) From d5b669634ae71e5a76679b976d9cc8031dcea0b5 Mon Sep 17 00:00:00 2001 From: Remi Date: Mon, 7 Oct 2024 11:35:35 +0200 Subject: [PATCH 03/29] Fix nightly by updating .cache in dockerignore (#464) --- .dockerignore | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/.dockerignore b/.dockerignore index 701807953..b8c1be153 100644 --- a/.dockerignore +++ b/.dockerignore @@ -65,7 +65,6 @@ htmlcov/ .nox/ .coverage .coverage.* -.cache nosetests.xml coverage.xml *.cover @@ -73,6 +72,11 @@ coverage.xml .hypothesis/ .pytest_cache/ +# Ignore .cache except calibration +.cache/* +!.cache/calibration/ +!.cache/calibration/** + # Translations *.mo *.pot From c29e70e5a17d61f150e33779dab01e2d4f2e0534 Mon Sep 17 00:00:00 2001 From: Eugene Mironov Date: Wed, 9 Oct 2024 16:35:19 +0700 Subject: [PATCH 04/29] Fix issue with wrong using index instead of camera_index in opencv (#466) --- lerobot/common/robot_devices/cameras/opencv.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/robot_devices/cameras/opencv.py index 7de4bc4e0..2d8b12c91 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/robot_devices/cameras/opencv.py @@ -156,7 +156,7 @@ def save_images_from_cameras( executor.submit( save_image, image, - camera.index, + camera.camera_index, frame_index, images_dir, ) From 97b1feb0b3c5f28c148dde8a9baf0a175be29d05 Mon Sep 17 00:00:00 2001 From: Remi Date: Thu, 10 Oct 2024 17:12:45 +0200 Subject: [PATCH 05/29] Add policy/act_aloha_real.yaml + env/act_real.yaml (#429) Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- examples/9_use_aloha.md | 179 ++++++++++++++ lerobot/__init__.py | 4 +- .../robot_devices/robots/manipulator.py | 1 + lerobot/configs/env/aloha_real.yaml | 10 + .../{act_real.yaml => act_aloha_real.yaml} | 31 ++- lerobot/configs/policy/act_real_no_state.yaml | 110 --------- lerobot/scripts/control_robot.py | 222 +++++++++++++++--- poetry.lock | 2 +- tests/conftest.py | 9 +- .../actions.safetensors | 0 .../grad_stats.safetensors | 0 .../output_dict.safetensors | 0 .../param_stats.safetensors | 0 .../actions.safetensors | 3 - .../grad_stats.safetensors | 3 - .../output_dict.safetensors | 3 - .../param_stats.safetensors | 3 - tests/test_control_robot.py | 64 ++++- tests/test_datasets.py | 5 +- tests/test_policies.py | 3 +- 20 files changed, 464 insertions(+), 188 deletions(-) create mode 100644 examples/9_use_aloha.md create mode 100644 lerobot/configs/env/aloha_real.yaml rename lerobot/configs/policy/{act_real.yaml => act_aloha_real.yaml} (75%) delete mode 100644 lerobot/configs/policy/act_real_no_state.yaml rename tests/data/save_policy_to_safetensors/{dora_aloha_real_act_real => dora_aloha_real_act_aloha_real}/actions.safetensors (100%) rename tests/data/save_policy_to_safetensors/{dora_aloha_real_act_real => dora_aloha_real_act_aloha_real}/grad_stats.safetensors (100%) rename tests/data/save_policy_to_safetensors/{dora_aloha_real_act_real => dora_aloha_real_act_aloha_real}/output_dict.safetensors (100%) rename tests/data/save_policy_to_safetensors/{dora_aloha_real_act_real => dora_aloha_real_act_aloha_real}/param_stats.safetensors (100%) delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/actions.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/grad_stats.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/output_dict.safetensors delete mode 100644 tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/param_stats.safetensors diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md new file mode 100644 index 000000000..9859e3641 --- /dev/null +++ b/examples/9_use_aloha.md @@ -0,0 +1,179 @@ +This tutorial explains how to use [Aloha and Aloha 2 stationary](https://www.trossenrobotics.com/aloha-stationary) with LeRobot. + +## 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. + + +## Install LeRobot + +On your computer: + +1. [Install Miniconda](https://docs.anaconda.com/miniconda/#quick-command-line-install): +```bash +mkdir -p ~/miniconda3 +wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh +bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3 +rm ~/miniconda3/miniconda.sh +~/miniconda3/bin/conda init bash +``` + +2. Restart shell or `source ~/.bashrc` + +3. Create and activate a fresh conda environment for lerobot +```bash +conda create -y -n lerobot python=3.10 && conda activate lerobot +``` + +4. Clone LeRobot: +```bash +git clone https://github.com/huggingface/lerobot.git ~/lerobot +``` + +5. Install LeRobot with dependencies for the Aloha motors (dynamixel) and cameras (intelrealsense): +```bash +cd ~/lerobot && pip install -e ".[dynamixel intelrealsense]" +``` + +And install extra dependencies for recording datasets on Linux: +```bash +conda install -y -c conda-forge ffmpeg +pip uninstall -y opencv-python +conda install -y -c conda-forge "opencv>=4.10.0" +``` + +## Teleoperate + +**/!\ FOR SAFETY, READ THIS /!\** +Teleoperation consists in manually operating the leader arms to move the follower arms. Importantly: +1. Make sure your leader arms are in the same position as the follower arms, so that the follower arms don't move too fast to match the leader arms, +2. Our code assumes that your robot has been assembled following Trossen Robotics instructions. This allows us to skip calibration, as we use the pre-defined calibration files in `.cache/calibration/aloha_default`. If you replace a motor, make sure you follow the exact instructions from Trossen Robotics. + +By running the following code, you can start your first **SAFE** teleoperation: +```bash +python lerobot/scripts/control_robot.py teleoperate \ + --robot-path lerobot/configs/robot/aloha.yaml \ + --robot-overrides max_relative_target=5 +``` + +By adding `--robot-overrides max_relative_target=5`, we override the default value for `max_relative_target` defined in `lerobot/configs/robot/aloha.yaml`. It is expected to be `5` to limit the magnitude of the movement for more safety, but the teloperation won't be smooth. When you feel confident, you can disable this limit by adding `--robot-overrides max_relative_target=null` to the command line: +```bash +python lerobot/scripts/control_robot.py teleoperate \ + --robot-path lerobot/configs/robot/aloha.yaml \ + --robot-overrides max_relative_target=null +``` + +## Record a dataset + +Once you're familiar with teleoperation, you can record your first dataset with Aloha. + +If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens): +```bash +huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential +``` + +Store your Hugging Face repository name in a variable to run these commands: +```bash +HF_USER=$(huggingface-cli whoami | head -n 1) +echo $HF_USER +``` + +Record 2 episodes and upload your dataset to the hub: +```bash +python lerobot/scripts/control_robot.py record \ + --robot-path lerobot/configs/robot/aloha.yaml \ + --robot-overrides max_relative_target=null \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/aloha_test \ + --tags aloha tutorial \ + --warmup-time-s 5 \ + --episode-time-s 40 \ + --reset-time-s 10 \ + --num-episodes 2 \ + --push-to-hub 1 +``` + +## Visualize a dataset + +If you uploaded your dataset to the hub with `--push-to-hub 1`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by: +```bash +echo ${HF_USER}/aloha_test +``` + +If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with: +```bash +python lerobot/scripts/visualize_dataset_html.py \ + --root data \ + --repo-id ${HF_USER}/aloha_test +``` + +## Replay an episode + +**/!\ FOR SAFETY, READ THIS /!\** +Replay consists in automatically replaying the sequence of actions (i.e. goal positions for your motors) recorded in a given dataset episode. Make sure the current initial position of your robot is similar to the one in your episode, so that your follower arms don't move too fast to go to the first goal positions. For safety, you might want to add `--robot-overrides max_relative_target=5` to your command line as explained above. + +Now try to replay the first episode on your robot: +```bash +python lerobot/scripts/control_robot.py replay \ + --robot-path lerobot/configs/robot/aloha.yaml \ + --robot-overrides max_relative_target=null \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/aloha_test \ + --episode 0 +``` + +## 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: +```bash +DATA_DIR=data python lerobot/scripts/train.py \ + dataset_repo_id=${HF_USER}/aloha_test \ + policy=act_aloha_real \ + env=aloha_real \ + hydra.run.dir=outputs/train/act_aloha_test \ + hydra.job.name=act_aloha_test \ + device=cuda \ + wandb.enable=true +``` + +Let's explain it: +1. We provided the dataset as argument with `dataset_repo_id=${HF_USER}/aloha_test`. +2. We provided the policy with `policy=act_aloha_real`. This loads configurations from [`lerobot/configs/policy/act_aloha_real.yaml`](../lerobot/configs/policy/act_aloha_real.yaml). Importantly, this policy uses 4 cameras as input `cam_right_wrist`, `cam_left_wrist`, `cam_high`, and `cam_low`. +3. We provided an environment as argument with `env=aloha_real`. This loads configurations from [`lerobot/configs/env/aloha_real.yaml`](../lerobot/configs/env/aloha_real.yaml). Note: this yaml defines 18 dimensions for the `state_dim` and `action_dim`, corresponding to 18 motors, not 14 motors as used in previous Aloha work. This is because, we include the `shoulder_shadow` and `elbow_shadow` motors for simplicity. +4. We provided `device=cuda` since we are training on a Nvidia GPU. +5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`. +6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync. + +Training should take several hours. You will find checkpoints in `outputs/train/act_aloha_test/checkpoints`. + +## Evaluate your policy + +You can use the `record` function from [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) but with a policy checkpoint as input. For instance, run this command to record 10 evaluation episodes: +```bash +python lerobot/scripts/control_robot.py record \ + --robot-path lerobot/configs/robot/aloha.yaml \ + --robot-overrides max_relative_target=null \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/eval_act_aloha_test \ + --tags aloha tutorial eval \ + --warmup-time-s 5 \ + --episode-time-s 40 \ + --reset-time-s 10 \ + --num-episodes 10 \ + --num-image-writer-processes 1 \ + -p outputs/train/act_aloha_test/checkpoints/last/pretrained_model +``` + +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 `-p` argument which indicates the path to your policy checkpoint with (e.g. `-p outputs/train/eval_aloha_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `-p ${HF_USER}/act_aloha_test`). +2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `--repo-id ${HF_USER}/eval_act_aloha_test`). +3. We use `--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 `--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. + +If you have any question or need help, please reach out on Discord in the channel `#aloha-arm`. diff --git a/lerobot/__init__.py b/lerobot/__init__.py index 851383dd9..5acd8aaad 100644 --- a/lerobot/__init__.py +++ b/lerobot/__init__.py @@ -216,7 +216,9 @@ "aloha": ["act"], "pusht": ["diffusion", "vqbet"], "xarm": ["tdmpc"], - "dora_aloha_real": ["act_real"], + "koch_real": ["act_koch_real"], + "aloha_real": ["act_aloha_real"], + "dora_aloha_real": ["act_aloha_real"], } env_task_pairs = [(env, task) for env, tasks in available_tasks_per_env.items() for task in tasks] diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index 98ae691a0..6ab900fb9 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -364,6 +364,7 @@ def connect(self): for name in self.follower_arms: print(f"Connecting {name} follower arm.") self.follower_arms[name].connect() + for name in self.leader_arms: print(f"Connecting {name} leader arm.") self.leader_arms[name].connect() diff --git a/lerobot/configs/env/aloha_real.yaml b/lerobot/configs/env/aloha_real.yaml new file mode 100644 index 000000000..57af4be20 --- /dev/null +++ b/lerobot/configs/env/aloha_real.yaml @@ -0,0 +1,10 @@ +# @package _global_ + +fps: 30 + +env: + name: real_world + task: null + state_dim: 18 + action_dim: 18 + fps: ${fps} diff --git a/lerobot/configs/policy/act_real.yaml b/lerobot/configs/policy/act_aloha_real.yaml similarity index 75% rename from lerobot/configs/policy/act_real.yaml rename to lerobot/configs/policy/act_aloha_real.yaml index 058104f4d..70da3c561 100644 --- a/lerobot/configs/policy/act_real.yaml +++ b/lerobot/configs/policy/act_aloha_real.yaml @@ -1,16 +1,22 @@ # @package _global_ -# Use `act_real.yaml` to train on real-world Aloha/Aloha2 datasets. -# Compared to `act.yaml`, it contains 4 cameras (i.e. cam_right_wrist, cam_left_wrist, images, -# cam_low) instead of 1 camera (i.e. top). Also, `training.eval_freq` is set to -1. This config is used -# to evaluate checkpoints at a certain frequency of training steps. When it is set to -1, it deactivates evaluation. -# This is because real-world evaluation is done through [dora-lerobot](https://github.com/dora-rs/dora-lerobot). -# Look at its README for more information on how to evaluate a checkpoint in the real-world. +# Use `act_aloha_real.yaml` to train on real-world datasets collected on Aloha or Aloha-2 robots. +# Compared to `act.yaml`, it contains 4 cameras (i.e. cam_right_wrist, cam_left_wrist, cam_high, cam_low) instead of 1 camera (i.e. top). +# Also, `training.eval_freq` is set to -1. This config is used to evaluate checkpoints at a certain frequency of training steps. +# When it is set to -1, it deactivates evaluation. This is because real-world evaluation is done through our `control_robot.py` script. +# Look at the documentation in header of `control_robot.py` for more information on how to collect data , train and evaluate a policy. # -# Example of usage for training: +# Example of usage for training and inference with `control_robot.py`: # ```bash # python lerobot/scripts/train.py \ -# policy=act_real \ +# policy=act_aloha_real \ +# env=aloha_real +# ``` +# +# Example of usage for training and inference with [Dora-rs](https://github.com/dora-rs/dora-lerobot): +# ```bash +# python lerobot/scripts/train.py \ +# policy=act_aloha_real \ # env=dora_aloha_real # ``` @@ -36,10 +42,11 @@ override_dataset_stats: std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) training: - offline_steps: 100000 + offline_steps: 80000 online_steps: 0 eval_freq: -1 - save_freq: 20000 + save_freq: 10000 + log_freq: 100 save_checkpoint: true batch_size: 8 @@ -62,7 +69,7 @@ policy: # Input / output structure. n_obs_steps: 1 - chunk_size: 100 # chunk_size + chunk_size: 100 n_action_steps: 100 input_shapes: @@ -107,7 +114,7 @@ policy: n_vae_encoder_layers: 4 # Inference. - temporal_ensemble_coeff: null + temporal_ensemble_momentum: null # Training and loss computation. dropout: 0.1 diff --git a/lerobot/configs/policy/act_real_no_state.yaml b/lerobot/configs/policy/act_real_no_state.yaml deleted file mode 100644 index 082610503..000000000 --- a/lerobot/configs/policy/act_real_no_state.yaml +++ /dev/null @@ -1,110 +0,0 @@ -# @package _global_ - -# Use `act_real_no_state.yaml` to train on real-world Aloha/Aloha2 datasets when cameras are moving (e.g. wrist cameras) -# Compared to `act_real.yaml`, it is camera only and does not use the state as input which is vector of robot joint positions. -# We validated experimentaly that not using state reaches better success rate. Our hypothesis is that `act_real.yaml` might -# overfits to the state, because the images are more complex to learn from since they are moving. -# -# Example of usage for training: -# ```bash -# python lerobot/scripts/train.py \ -# policy=act_real_no_state \ -# env=dora_aloha_real -# ``` - -seed: 1000 -dataset_repo_id: lerobot/aloha_static_vinh_cup - -override_dataset_stats: - observation.images.cam_right_wrist: - # stats from imagenet, since we use a pretrained vision model - mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) - std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) - observation.images.cam_left_wrist: - # stats from imagenet, since we use a pretrained vision model - mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) - std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) - observation.images.cam_high: - # stats from imagenet, since we use a pretrained vision model - mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) - std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) - observation.images.cam_low: - # stats from imagenet, since we use a pretrained vision model - mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) - std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) - -training: - offline_steps: 100000 - online_steps: 0 - eval_freq: -1 - save_freq: 20000 - save_checkpoint: true - - batch_size: 8 - lr: 1e-5 - lr_backbone: 1e-5 - weight_decay: 1e-4 - grad_clip_norm: 10 - online_steps_between_rollouts: 1 - - delta_timestamps: - action: "[i / ${fps} for i in range(${policy.chunk_size})]" - -eval: - n_episodes: 50 - batch_size: 50 - -# See `configuration_act.py` for more details. -policy: - name: act - - # Input / output structure. - n_obs_steps: 1 - chunk_size: 100 # chunk_size - n_action_steps: 100 - - input_shapes: - # TODO(rcadene, alexander-soare): add variables for height and width from the dataset/env? - observation.images.cam_right_wrist: [3, 480, 640] - observation.images.cam_left_wrist: [3, 480, 640] - observation.images.cam_high: [3, 480, 640] - observation.images.cam_low: [3, 480, 640] - output_shapes: - action: ["${env.action_dim}"] - - # Normalization / Unnormalization - input_normalization_modes: - observation.images.cam_right_wrist: mean_std - observation.images.cam_left_wrist: mean_std - observation.images.cam_high: mean_std - observation.images.cam_low: mean_std - output_normalization_modes: - action: mean_std - - # Architecture. - # Vision backbone. - vision_backbone: resnet18 - pretrained_backbone_weights: ResNet18_Weights.IMAGENET1K_V1 - replace_final_stride_with_dilation: false - # Transformer layers. - pre_norm: false - dim_model: 512 - n_heads: 8 - dim_feedforward: 3200 - feedforward_activation: relu - n_encoder_layers: 4 - # Note: Although the original ACT implementation has 7 for `n_decoder_layers`, there is a bug in the code - # that means only the first layer is used. Here we match the original implementation by setting this to 1. - # See this issue https://github.com/tonyzhaozh/act/issues/25#issue-2258740521. - n_decoder_layers: 1 - # VAE. - use_vae: true - latent_dim: 32 - n_vae_encoder_layers: 4 - - # Inference. - temporal_ensemble_coeff: null - - # Training and loss computation. - dropout: 0.1 - kl_weight: 10.0 diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 742dd8bca..3b6345b42 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -102,6 +102,7 @@ import concurrent.futures import json import logging +import multiprocessing import os import platform import shutil @@ -163,9 +164,9 @@ def say(text, blocking=False): os.system(cmd) -def save_image(img_tensor, key, frame_index, episode_index, videos_dir): +def save_image(img_tensor, key, frame_index, episode_index, videos_dir: str): img = Image.fromarray(img_tensor.numpy()) - path = videos_dir / f"{key}_episode_{episode_index:06d}" / f"frame_{frame_index:06d}.png" + path = Path(videos_dir) / f"{key}_episode_{episode_index:06d}" / f"frame_{frame_index:06d}.png" path.parent.mkdir(parents=True, exist_ok=True) img.save(str(path), quality=100) @@ -255,6 +256,129 @@ def get_available_arms(robot): return available_arms +######################################################################################## +# Asynchrounous saving of images on disk +######################################################################################## + + +def loop_to_save_images_in_threads(image_queue, num_threads): + if num_threads < 1: + raise NotImplementedError(f"Only `num_threads>=1` is supported for now, but {num_threads=} given.") + + with concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) as executor: + futures = [] + while True: + # Blocks until a frame is available + frame_data = image_queue.get() + + # As usually done, exit loop when receiving None to stop the worker + if frame_data is None: + break + + image, key, frame_index, episode_index, videos_dir = frame_data + futures.append(executor.submit(save_image, image, key, frame_index, episode_index, videos_dir)) + + # Before exiting function, wait for all threads to complete + with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: + concurrent.futures.wait(futures) + progress_bar.update(len(futures)) + + +def start_image_writer_processes(image_queue, num_processes, num_threads_per_process): + if num_processes < 1: + raise ValueError(f"Only `num_processes>=1` is supported, but {num_processes=} given.") + + if num_threads_per_process < 1: + raise NotImplementedError( + "Only `num_threads_per_process>=1` is supported for now, but {num_threads_per_process=} given." + ) + + processes = [] + for _ in range(num_processes): + process = multiprocessing.Process( + target=loop_to_save_images_in_threads, + args=(image_queue, num_threads_per_process), + ) + process.start() + processes.append(process) + return processes + + +def stop_processes(processes, queue, timeout): + # Send None to each process to signal them to stop + for _ in processes: + queue.put(None) + + # Close the queue, no more items can be put in the queue + queue.close() + + # Wait maximum 20 seconds for all processes to terminate + for process in processes: + process.join(timeout=timeout) + + # If not terminated after 20 seconds, force termination + if process.is_alive(): + process.terminate() + + # Ensure all background queue threads have finished + queue.join_thread() + + +def start_image_writer(num_processes, num_threads): + """This function abstract away the initialisation of processes or/and threads to + save images on disk asynchrounously, which is critical to control a robot and record data + at a high frame rate. + + When `num_processes=0`, it returns a dictionary containing a threads pool of size `num_threads`. + When `num_processes>0`, it returns a dictionary containing a processes pool of size `num_processes`, + where each subprocess starts their own threads pool of size `num_threads`. + + The optimal number of processes and threads depends on your computer capabilities. + We advise to use 4 threads per camera with 0 processes. If the fps is not stable, try to increase or lower + the number of threads. If it is still not stable, try to use 1 subprocess, or more. + """ + image_writer = {} + + if num_processes == 0: + futures = [] + threads_pool = concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) + image_writer["threads_pool"], image_writer["futures"] = threads_pool, futures + else: + # TODO(rcadene): When using num_processes>1, `multiprocessing.Manager().Queue()` + # might be better than `multiprocessing.Queue()`. Source: https://www.geeksforgeeks.org/python-multiprocessing-queue-vs-multiprocessing-manager-queue + image_queue = multiprocessing.Queue() + processes_pool = start_image_writer_processes( + image_queue, num_processes=num_processes, num_threads_per_process=num_threads + ) + image_writer["processes_pool"], image_writer["image_queue"] = processes_pool, image_queue + + return image_writer + + +def async_save_image(image_writer, image, key, frame_index, episode_index, videos_dir): + """This function abstract away the saving of an image on disk asynchrounously. It uses a dictionary + called image writer which contains either a pool of processes or a pool of threads. + """ + if "threads_pool" in image_writer: + threads_pool, futures = image_writer["threads_pool"], image_writer["futures"] + futures.append(threads_pool.submit(save_image, image, key, frame_index, episode_index, videos_dir)) + else: + image_queue = image_writer["image_queue"] + image_queue.put((image, key, frame_index, episode_index, videos_dir)) + + +def stop_image_writer(image_writer, timeout): + if "threads_pool" in image_writer: + futures = image_writer["futures"] + # Before exiting function, wait for all threads to complete + with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: + concurrent.futures.wait(futures, timeout=timeout) + progress_bar.update(len(futures)) + else: + processes_pool, image_queue = image_writer["processes_pool"], image_writer["image_queue"] + stop_processes(processes_pool, image_queue, timeout=timeout) + + ######################################################################################## # Control modes ######################################################################################## @@ -342,9 +466,11 @@ def record( run_compute_stats=True, push_to_hub=True, tags=None, - num_image_writers_per_camera=4, + num_image_writer_processes=0, + num_image_writer_threads_per_camera=4, force_override=False, display_cameras=True, + play_sounds=True, ): # TODO(rcadene): Add option to record logs # TODO(rcadene): Clean this function via decomposition in higher level functions @@ -436,7 +562,8 @@ def on_press(key): while timestamp < warmup_time_s: if not is_warmup_print: logging.info("Warming up (no data recording)") - say("Warming up") + if play_sounds: + say("Warming up") is_warmup_print = True start_loop_t = time.perf_counter() @@ -463,16 +590,22 @@ def on_press(key): if has_method(robot, "teleop_safety_stop"): robot.teleop_safety_stop() - # Save images using threads to reach high fps (30 and more) - # Using `with` to exist smoothly if an execption is raised. - futures = [] - num_image_writers = num_image_writers_per_camera * len(robot.cameras) - num_image_writers = max(num_image_writers, 1) - with concurrent.futures.ThreadPoolExecutor(max_workers=num_image_writers) as executor: + has_camera = len(robot.cameras) > 0 + if has_camera: + # Initialize processes or/and threads dedicated to save images on disk asynchronously, + # which is critical to control a robot and record data at a high frame rate. + image_writer = start_image_writer( + num_processes=num_image_writer_processes, + num_threads=num_image_writer_threads_per_camera * len(robot.cameras), + ) + + # Using `try` to exist smoothly if an exception is raised + try: # Start recording all episodes while episode_index < num_episodes: logging.info(f"Recording episode {episode_index}") - say(f"Recording episode {episode_index}") + if play_sounds: + say(f"Recording episode {episode_index}") ep_dict = {} frame_index = 0 timestamp = 0 @@ -488,12 +621,16 @@ def on_press(key): image_keys = [key for key in observation if "image" in key] not_image_keys = [key for key in observation if "image" not in key] - for key in image_keys: - futures += [ - executor.submit( - save_image, observation[key], key, frame_index, episode_index, videos_dir + if has_camera > 0: + for key in image_keys: + async_save_image( + image_writer, + image=observation[key], + key=key, + frame_index=frame_index, + episode_index=episode_index, + videos_dir=str(videos_dir), ) - ] if display_cameras and not is_headless(): image_keys = [key for key in observation if "image" in key] @@ -563,7 +700,8 @@ def on_press(key): if not stop_recording: # Start resetting env while the executor are finishing logging.info("Reset the environment") - say("Reset the environment") + if play_sounds: + say("Reset the environment") timestamp = 0 start_vencod_t = time.perf_counter() @@ -635,18 +773,23 @@ def on_press(key): if is_last_episode: logging.info("Done recording") - say("Done recording", blocking=True) + if play_sounds: + say("Done recording", blocking=True) if not is_headless(): listener.stop() - logging.info("Waiting for threads writing the images on disk to terminate...") - for _ in tqdm.tqdm( - concurrent.futures.as_completed(futures), total=len(futures), desc="Writting images" - ): - pass - break + if has_camera > 0: + logging.info("Waiting for image writer to terminate...") + stop_image_writer(image_writer, timeout=20) + + except Exception as e: + if has_camera > 0: + logging.info("Waiting for image writer to terminate...") + stop_image_writer(image_writer, timeout=20) + raise e robot.disconnect() + if display_cameras and not is_headless(): cv2.destroyAllWindows() @@ -654,7 +797,8 @@ def on_press(key): if video: logging.info("Encoding videos") - say("Encoding videos") + if play_sounds: + say("Encoding videos") # Use ffmpeg to convert frames stored as png into mp4 videos for episode_index in tqdm.tqdm(range(num_episodes)): for key in image_keys: @@ -699,7 +843,8 @@ def on_press(key): ) if run_compute_stats: logging.info("Computing dataset statistics") - say("Computing dataset statistics") + if play_sounds: + say("Computing dataset statistics") stats = compute_stats(lerobot_dataset) lerobot_dataset.stats = stats else: @@ -721,11 +866,14 @@ def on_press(key): create_branch(repo_id, repo_type="dataset", branch=CODEBASE_VERSION) logging.info("Exiting") - say("Exiting") + if play_sounds: + say("Exiting") return lerobot_dataset -def replay(robot: Robot, episode: int, fps: int | None = None, root="data", repo_id="lerobot/debug"): +def replay( + robot: Robot, episode: int, fps: int | None = None, root="data", repo_id="lerobot/debug", play_sounds=True +): # TODO(rcadene): Add option to record logs local_dir = Path(root) / repo_id if not local_dir.exists(): @@ -740,7 +888,8 @@ def replay(robot: Robot, episode: int, fps: int | None = None, root="data", repo robot.connect() logging.info("Replaying episode") - say("Replaying episode", blocking=True) + if play_sounds: + say("Replaying episode", blocking=True) for idx in range(from_idx, to_idx): start_episode_t = time.perf_counter() @@ -840,12 +989,23 @@ def replay(robot: Robot, episode: int, fps: int | None = None, root="data", repo help="Add tags to your dataset on the hub.", ) parser_record.add_argument( - "--num-image-writers-per-camera", + "--num-image-writer-processes", + type=int, + default=0, + help=( + "Number of subprocesses handling the saving of frames as PNGs. 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." + ), + ) + parser_record.add_argument( + "--num-image-writer-threads-per-camera", type=int, default=4, help=( "Number of threads writing the frames as png images on disk, per camera. " - "Too much threads might cause unstable teleoperation fps due to main thread being blocked. " + "Too many threads might cause unstable teleoperation fps due to main thread being blocked. " "Not enough threads might cause low camera fps." ), ) diff --git a/poetry.lock b/poetry.lock index 43089048d..f0e50dcda 100644 --- a/poetry.lock +++ b/poetry.lock @@ -5245,7 +5245,7 @@ docs = ["sphinx", "sphinx-automodapi", "sphinx-rtd-theme"] name = "pyserial" version = "3.5" description = "Python Serial Port Extension" -optional = true +optional = false python-versions = "*" files = [ {file = "pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0"}, diff --git a/tests/conftest.py b/tests/conftest.py index 386441e5d..949a25357 100644 --- a/tests/conftest.py +++ b/tests/conftest.py @@ -52,8 +52,9 @@ def is_robot_available(robot_type): print(f"\nInstall module '{e.name}'") elif isinstance(e, SerialException): print("\nNo physical motors bus detected.") + else: + traceback.print_exc() - traceback.print_exc() return False @@ -77,8 +78,9 @@ def is_camera_available(camera_type): print(f"\nInstall module '{e.name}'") elif isinstance(e, ValueError) and "camera_index" in e.args[0]: print("\nNo physical camera detected.") + else: + traceback.print_exc() - traceback.print_exc() return False @@ -102,8 +104,9 @@ def is_motor_available(motor_type): print(f"\nInstall module '{e.name}'") elif isinstance(e, SerialException): print("\nNo physical motors bus detected.") + else: + traceback.print_exc() - traceback.print_exc() return False diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/actions.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/actions.safetensors similarity index 100% rename from tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/actions.safetensors rename to tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/actions.safetensors diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/grad_stats.safetensors similarity index 100% rename from tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/grad_stats.safetensors rename to tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/grad_stats.safetensors diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/output_dict.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/output_dict.safetensors similarity index 100% rename from tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/output_dict.safetensors rename to tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/output_dict.safetensors diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/param_stats.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/param_stats.safetensors similarity index 100% rename from tests/data/save_policy_to_safetensors/dora_aloha_real_act_real/param_stats.safetensors rename to tests/data/save_policy_to_safetensors/dora_aloha_real_act_aloha_real/param_stats.safetensors diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/actions.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/actions.safetensors deleted file mode 100644 index 2e26ef270..000000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/actions.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:b5a9f73a2356aff9c717cdfd0d37a6da08b0cf2cc09c98edbc9492501b7f64a5 -size 5104 diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/grad_stats.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/grad_stats.safetensors deleted file mode 100644 index b959bc6e0..000000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/grad_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:28738b3cfad17af0ac5181effdd796acdf7953cd5bcca3f421a11ddfd6b0076f -size 30800 diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/output_dict.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/output_dict.safetensors deleted file mode 100644 index 455834aa8..000000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/output_dict.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:4bb8a197a40456fdbc16029126268e6bcef3eca1837d88235165dc7e14618bea -size 68 diff --git a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/param_stats.safetensors b/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/param_stats.safetensors deleted file mode 100644 index d50fb31d9..000000000 --- a/tests/data/save_policy_to_safetensors/dora_aloha_real_act_real_no_state/param_stats.safetensors +++ /dev/null @@ -1,3 +0,0 @@ -version https://git-lfs.github.com/spec/v1 -oid sha256:bea60cce42d324f539dd3bca1e66b5ba6391838fdcadb00efc25f3240edb529a -size 33600 diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index f554c2511..770b3489b 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -23,6 +23,7 @@ ``` """ +import multiprocessing from pathlib import Path import pytest @@ -37,7 +38,7 @@ @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot def test_teleoperate(tmpdir, request, robot_type, mock): - if mock: + if mock and robot_type != "aloha": request.getfixturevalue("patch_builtins_input") # Create an empty calibration directory to trigger manual calibration @@ -78,7 +79,7 @@ def test_record_without_cameras(tmpdir, request, robot_type, mock): # Avoid using cameras overrides = ["~cameras"] - if mock: + if mock and robot_type != "aloha": request.getfixturevalue("patch_builtins_input") # Create an empty calibration directory to trigger manual calibration @@ -101,13 +102,14 @@ def test_record_without_cameras(tmpdir, request, robot_type, mock): run_compute_stats=False, push_to_hub=False, video=False, + play_sounds=False, ) @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @require_robot def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): - if mock: + if mock and robot_type != "aloha": request.getfixturevalue("patch_builtins_input") # Create an empty calibration directory to trigger manual calibration @@ -115,12 +117,9 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): calibration_dir = Path(tmpdir) / robot_type overrides = [f"calibration_dir={calibration_dir}"] else: - # Use the default .cache/calibration folder when mock=False + # Use the default .cache/calibration folder when mock=False or for aloha overrides = None - if robot_type == "aloha": - pytest.skip("TODO(rcadene): enable test once aloha_real and act_aloha_real are merged") - env_name = "koch_real" policy_name = "act_koch_real" @@ -141,21 +140,58 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): video=False, # TODO(rcadene): display cameras through cv2 sometimes crashes on mac display_cameras=False, + play_sounds=False, ) - replay(robot, episode=0, fps=30, root=root, repo_id=repo_id) + replay(robot, episode=0, fps=30, root=root, repo_id=repo_id, play_sounds=False) + + # TODO(rcadene, aliberts): rethink this design + if robot_type == "aloha": + env_name = "aloha_real" + policy_name = "act_aloha_real" + elif robot_type in ["koch", "koch_bimanual"]: + env_name = "koch_real" + policy_name = "act_koch_real" + else: + raise NotImplementedError(robot_type) + + overrides = [ + f"env={env_name}", + f"policy={policy_name}", + f"device={DEVICE}", + ] + + if robot_type == "koch_bimanual": + overrides += ["env.state_dim=12", "env.action_dim=12"] cfg = init_hydra_config( DEFAULT_CONFIG_PATH, - overrides=[ - f"env={env_name}", - f"policy={policy_name}", - f"device={DEVICE}", - ], + overrides=overrides, ) policy = make_policy(hydra_cfg=cfg, dataset_stats=dataset.stats) + # 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. + if robot_type == "aloha": + num_image_writer_processes = 1 + + # `multiprocessing.set_start_method("spawn", force=True)` avoids a hanging issue + # before exiting pytest. However, it outputs the following error in the log: + # Traceback (most recent call last): + # File "", line 1, in + # File "/Users/rcadene/miniconda3/envs/lerobot/lib/python3.10/multiprocessing/spawn.py", line 116, in spawn_main + # exitcode = _main(fd, parent_sentinel) + # File "/Users/rcadene/miniconda3/envs/lerobot/lib/python3.10/multiprocessing/spawn.py", line 126, in _main + # self = reduction.pickle.load(from_parent) + # File "/Users/rcadene/miniconda3/envs/lerobot/lib/python3.10/multiprocessing/synchronize.py", line 110, in __setstate__ + # self._semlock = _multiprocessing.SemLock._rebuild(*state) + # FileNotFoundError: [Errno 2] No such file or directory + # TODO(rcadene, aliberts): fix FileNotFoundError in multiprocessing + multiprocessing.set_start_method("spawn", force=True) + else: + num_image_writer_processes = 0 + record( robot, policy, @@ -167,6 +203,8 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): push_to_hub=False, video=False, display_cameras=False, + play_sounds=False, + num_image_writer_processes=num_image_writer_processes, ) del robot diff --git a/tests/test_datasets.py b/tests/test_datasets.py index 7fe84bc57..1316df786 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -308,12 +308,11 @@ def test_flatten_unflatten_dict(): # "lerobot/cmu_stretch", ], ) +# TODO(rcadene, aliberts): all these tests fail locally on Mac M1, but not on Linux def test_backward_compatibility(repo_id): """The artifacts for this test have been generated by `tests/scripts/save_dataset_to_safetensors.py`.""" - dataset = LeRobotDataset( - repo_id, - ) + dataset = LeRobotDataset(repo_id) test_dir = Path("tests/data/save_dataset_to_safetensors") / repo_id diff --git a/tests/test_policies.py b/tests/test_policies.py index d90f00716..f358170d1 100644 --- a/tests/test_policies.py +++ b/tests/test_policies.py @@ -367,8 +367,7 @@ def test_normalize(insert_temporal_dim): ), ("aloha", "act", ["policy.n_action_steps=10"], ""), ("aloha", "act", ["policy.n_action_steps=1000", "policy.chunk_size=1000"], "_1000_steps"), - ("dora_aloha_real", "act_real", ["policy.n_action_steps=10"], ""), - ("dora_aloha_real", "act_real_no_state", ["policy.n_action_steps=10"], ""), + ("dora_aloha_real", "act_aloha_real", ["policy.n_action_steps=10"], ""), ], ) # As artifacts have been generated on an x86_64 kernel, this test won't From 77478d50e5d5642112d1bad6f1657f08eb1c3378 Mon Sep 17 00:00:00 2001 From: Remi Date: Wed, 16 Oct 2024 20:51:35 +0200 Subject: [PATCH 06/29] Refactor `record` with `add_frame` (#468) Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- .github/workflows/test.yml | 2 + lerobot/common/datasets/populate_dataset.py | 468 ++++++++++ lerobot/common/logger.py | 2 +- lerobot/common/robot_devices/control_utils.py | 330 +++++++ .../robot_devices/robots/manipulator.py | 19 + lerobot/common/utils/utils.py | 34 + lerobot/scripts/control_robot.py | 825 +++--------------- lerobot/scripts/train.py | 2 +- .../templates/visualize_dataset_template.html | 2 +- tests/test_control_robot.py | 260 +++++- tests/test_robots.py | 1 + 11 files changed, 1236 insertions(+), 709 deletions(-) create mode 100644 lerobot/common/datasets/populate_dataset.py create mode 100644 lerobot/common/robot_devices/control_utils.py diff --git a/.github/workflows/test.yml b/.github/workflows/test.yml index 10c90f841..9d51def4d 100644 --- a/.github/workflows/test.yml +++ b/.github/workflows/test.yml @@ -47,6 +47,7 @@ jobs: pipx install poetry && poetry config virtualenvs.in-project true echo "${{ github.workspace }}/.venv/bin" >> $GITHUB_PATH + # TODO(rcadene, aliberts): python 3.12 seems to be used in the tests, not python 3.10 - name: Set up Python 3.10 uses: actions/setup-python@v5 with: @@ -84,6 +85,7 @@ jobs: pipx install poetry && poetry config virtualenvs.in-project true echo "${{ github.workspace }}/.venv/bin" >> $GITHUB_PATH + # TODO(rcadene, aliberts): python 3.12 seems to be used in the tests, not python 3.10 - name: Set up Python 3.10 uses: actions/setup-python@v5 with: diff --git a/lerobot/common/datasets/populate_dataset.py b/lerobot/common/datasets/populate_dataset.py new file mode 100644 index 000000000..df5d20e56 --- /dev/null +++ b/lerobot/common/datasets/populate_dataset.py @@ -0,0 +1,468 @@ +"""Functions to create an empty dataset, and populate it with frames.""" +# TODO(rcadene, aliberts): to adapt as class methods of next version of LeRobotDataset + +import concurrent +import json +import logging +import multiprocessing +import shutil +from pathlib import Path + +import torch +import tqdm +from PIL import Image + +from lerobot.common.datasets.compute_stats import compute_stats +from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION, LeRobotDataset +from lerobot.common.datasets.push_dataset_to_hub.aloha_hdf5_format import to_hf_dataset +from lerobot.common.datasets.push_dataset_to_hub.utils import concatenate_episodes, get_default_encoding +from lerobot.common.datasets.utils import calculate_episode_data_index, create_branch +from lerobot.common.datasets.video_utils import encode_video_frames +from lerobot.common.utils.utils import log_say +from lerobot.scripts.push_dataset_to_hub import ( + push_dataset_card_to_hub, + push_meta_data_to_hub, + push_videos_to_hub, + save_meta_data, +) + +######################################################################################## +# Asynchrounous saving of images on disk +######################################################################################## + + +def safe_stop_image_writer(func): + # TODO(aliberts): Allow to pass custom exceptions + # (e.g. ThreadServiceExit, KeyboardInterrupt, SystemExit, UnpluggedError, DynamixelCommError) + def wrapper(*args, **kwargs): + try: + return func(*args, **kwargs) + except Exception as e: + image_writer = kwargs.get("dataset", {}).get("image_writer") + if image_writer is not None: + print("Waiting for image writer to terminate...") + stop_image_writer(image_writer, timeout=20) + raise e + + return wrapper + + +def save_image(img_tensor, key, frame_index, episode_index, videos_dir: str): + img = Image.fromarray(img_tensor.numpy()) + path = Path(videos_dir) / f"{key}_episode_{episode_index:06d}" / f"frame_{frame_index:06d}.png" + path.parent.mkdir(parents=True, exist_ok=True) + img.save(str(path), quality=100) + + +def loop_to_save_images_in_threads(image_queue, num_threads): + if num_threads < 1: + raise NotImplementedError(f"Only `num_threads>=1` is supported for now, but {num_threads=} given.") + + with concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) as executor: + futures = [] + while True: + # Blocks until a frame is available + frame_data = image_queue.get() + + # As usually done, exit loop when receiving None to stop the worker + if frame_data is None: + break + + image, key, frame_index, episode_index, videos_dir = frame_data + futures.append(executor.submit(save_image, image, key, frame_index, episode_index, videos_dir)) + + # Before exiting function, wait for all threads to complete + with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: + concurrent.futures.wait(futures) + progress_bar.update(len(futures)) + + +def start_image_writer_processes(image_queue, num_processes, num_threads_per_process): + if num_processes < 1: + raise ValueError(f"Only `num_processes>=1` is supported, but {num_processes=} given.") + + if num_threads_per_process < 1: + raise NotImplementedError( + "Only `num_threads_per_process>=1` is supported for now, but {num_threads_per_process=} given." + ) + + processes = [] + for _ in range(num_processes): + process = multiprocessing.Process( + target=loop_to_save_images_in_threads, + args=(image_queue, num_threads_per_process), + ) + process.start() + processes.append(process) + return processes + + +def stop_processes(processes, queue, timeout): + # Send None to each process to signal them to stop + for _ in processes: + queue.put(None) + + # Wait maximum 20 seconds for all processes to terminate + for process in processes: + process.join(timeout=timeout) + + # If not terminated after 20 seconds, force termination + if process.is_alive(): + process.terminate() + + # Close the queue, no more items can be put in the queue + queue.close() + + # Ensure all background queue threads have finished + queue.join_thread() + + +def start_image_writer(num_processes, num_threads): + """This function abstract away the initialisation of processes or/and threads to + save images on disk asynchrounously, which is critical to control a robot and record data + at a high frame rate. + + When `num_processes=0`, it returns a dictionary containing a threads pool of size `num_threads`. + When `num_processes>0`, it returns a dictionary containing a processes pool of size `num_processes`, + where each subprocess starts their own threads pool of size `num_threads`. + + The optimal number of processes and threads depends on your computer capabilities. + We advise to use 4 threads per camera with 0 processes. If the fps is not stable, try to increase or lower + the number of threads. If it is still not stable, try to use 1 subprocess, or more. + """ + image_writer = {} + + if num_processes == 0: + futures = [] + threads_pool = concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) + image_writer["threads_pool"], image_writer["futures"] = threads_pool, futures + else: + # TODO(rcadene): When using num_processes>1, `multiprocessing.Manager().Queue()` + # might be better than `multiprocessing.Queue()`. Source: https://www.geeksforgeeks.org/python-multiprocessing-queue-vs-multiprocessing-manager-queue + image_queue = multiprocessing.Queue() + processes_pool = start_image_writer_processes( + image_queue, num_processes=num_processes, num_threads_per_process=num_threads + ) + image_writer["processes_pool"], image_writer["image_queue"] = processes_pool, image_queue + + return image_writer + + +def async_save_image(image_writer, image, key, frame_index, episode_index, videos_dir): + """This function abstract away the saving of an image on disk asynchrounously. It uses a dictionary + called image writer which contains either a pool of processes or a pool of threads. + """ + if "threads_pool" in image_writer: + threads_pool, futures = image_writer["threads_pool"], image_writer["futures"] + futures.append(threads_pool.submit(save_image, image, key, frame_index, episode_index, videos_dir)) + else: + image_queue = image_writer["image_queue"] + image_queue.put((image, key, frame_index, episode_index, videos_dir)) + + +def stop_image_writer(image_writer, timeout): + if "threads_pool" in image_writer: + futures = image_writer["futures"] + # Before exiting function, wait for all threads to complete + with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: + concurrent.futures.wait(futures, timeout=timeout) + progress_bar.update(len(futures)) + else: + processes_pool, image_queue = image_writer["processes_pool"], image_writer["image_queue"] + stop_processes(processes_pool, image_queue, timeout=timeout) + + +######################################################################################## +# Functions to initialize, resume and populate a dataset +######################################################################################## + + +def init_dataset( + repo_id, + root, + force_override, + fps, + video, + write_images, + num_image_writer_processes, + num_image_writer_threads, +): + local_dir = Path(root) / repo_id + if local_dir.exists() and force_override: + shutil.rmtree(local_dir) + + episodes_dir = local_dir / "episodes" + episodes_dir.mkdir(parents=True, exist_ok=True) + + videos_dir = local_dir / "videos" + videos_dir.mkdir(parents=True, exist_ok=True) + + # Logic to resume data recording + rec_info_path = episodes_dir / "data_recording_info.json" + if rec_info_path.exists(): + with open(rec_info_path) as f: + rec_info = json.load(f) + num_episodes = rec_info["last_episode_index"] + 1 + else: + num_episodes = 0 + + dataset = { + "repo_id": repo_id, + "local_dir": local_dir, + "videos_dir": videos_dir, + "episodes_dir": episodes_dir, + "fps": fps, + "video": video, + "rec_info_path": rec_info_path, + "num_episodes": num_episodes, + } + + if write_images: + # Initialize processes or/and threads dedicated to save images on disk asynchronously, + # which is critical to control a robot and record data at a high frame rate. + image_writer = start_image_writer( + num_processes=num_image_writer_processes, + num_threads=num_image_writer_threads, + ) + dataset["image_writer"] = image_writer + + return dataset + + +def add_frame(dataset, observation, action): + if "current_episode" not in dataset: + # initialize episode dictionary + ep_dict = {} + for key in observation: + if key not in ep_dict: + ep_dict[key] = [] + for key in action: + if key not in ep_dict: + ep_dict[key] = [] + + ep_dict["episode_index"] = [] + ep_dict["frame_index"] = [] + ep_dict["timestamp"] = [] + ep_dict["next.done"] = [] + + dataset["current_episode"] = ep_dict + dataset["current_frame_index"] = 0 + + ep_dict = dataset["current_episode"] + episode_index = dataset["num_episodes"] + frame_index = dataset["current_frame_index"] + videos_dir = dataset["videos_dir"] + video = dataset["video"] + fps = dataset["fps"] + + ep_dict["episode_index"].append(episode_index) + ep_dict["frame_index"].append(frame_index) + ep_dict["timestamp"].append(frame_index / fps) + ep_dict["next.done"].append(False) + + img_keys = [key for key in observation if "image" in key] + non_img_keys = [key for key in observation if "image" not in key] + + # Save all observed modalities except images + for key in non_img_keys: + ep_dict[key].append(observation[key]) + + # Save actions + for key in action: + ep_dict[key].append(action[key]) + + if "image_writer" not in dataset: + dataset["current_frame_index"] += 1 + return + + # Save images + image_writer = dataset["image_writer"] + for key in img_keys: + imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" + async_save_image( + image_writer, + image=observation[key], + key=key, + frame_index=frame_index, + episode_index=episode_index, + videos_dir=str(videos_dir), + ) + + if video: + fname = f"{key}_episode_{episode_index:06d}.mp4" + frame_info = {"path": f"videos/{fname}", "timestamp": frame_index / fps} + else: + frame_info = str(imgs_dir / f"frame_{frame_index:06d}.png") + + ep_dict[key].append(frame_info) + + dataset["current_frame_index"] += 1 + + +def delete_current_episode(dataset): + del dataset["current_episode"] + del dataset["current_frame_index"] + + # delete temporary images + episode_index = dataset["num_episodes"] + videos_dir = dataset["videos_dir"] + for tmp_imgs_dir in videos_dir.glob(f"*_episode_{episode_index:06d}"): + shutil.rmtree(tmp_imgs_dir) + + +def save_current_episode(dataset): + episode_index = dataset["num_episodes"] + ep_dict = dataset["current_episode"] + episodes_dir = dataset["episodes_dir"] + rec_info_path = dataset["rec_info_path"] + + ep_dict["next.done"][-1] = True + + for key in ep_dict: + if "observation" in key and "image" not in key: + ep_dict[key] = torch.stack(ep_dict[key]) + + ep_dict["action"] = torch.stack(ep_dict["action"]) + ep_dict["episode_index"] = torch.tensor(ep_dict["episode_index"]) + ep_dict["frame_index"] = torch.tensor(ep_dict["frame_index"]) + ep_dict["timestamp"] = torch.tensor(ep_dict["timestamp"]) + ep_dict["next.done"] = torch.tensor(ep_dict["next.done"]) + + ep_path = episodes_dir / f"episode_{episode_index}.pth" + torch.save(ep_dict, ep_path) + + rec_info = { + "last_episode_index": episode_index, + } + with open(rec_info_path, "w") as f: + json.dump(rec_info, f) + + # force re-initialization of episode dictionnary during add_frame + del dataset["current_episode"] + + dataset["num_episodes"] += 1 + + +def encode_videos(dataset, image_keys, play_sounds): + log_say("Encoding videos", play_sounds) + + num_episodes = dataset["num_episodes"] + videos_dir = dataset["videos_dir"] + local_dir = dataset["local_dir"] + fps = dataset["fps"] + + # Use ffmpeg to convert frames stored as png into mp4 videos + for episode_index in tqdm.tqdm(range(num_episodes)): + for key in image_keys: + # key = f"observation.images.{name}" + tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" + fname = f"{key}_episode_{episode_index:06d}.mp4" + video_path = local_dir / "videos" / fname + if video_path.exists(): + # Skip if video is already encoded. Could be the case when resuming data recording. + continue + # note: `encode_video_frames` is a blocking call. Making it asynchronous shouldn't speedup encoding, + # since video encoding with ffmpeg is already using multithreading. + encode_video_frames(tmp_imgs_dir, video_path, fps, overwrite=True) + shutil.rmtree(tmp_imgs_dir) + + +def from_dataset_to_lerobot_dataset(dataset, play_sounds): + log_say("Consolidate episodes", play_sounds) + + num_episodes = dataset["num_episodes"] + episodes_dir = dataset["episodes_dir"] + videos_dir = dataset["videos_dir"] + video = dataset["video"] + fps = dataset["fps"] + repo_id = dataset["repo_id"] + + ep_dicts = [] + for episode_index in tqdm.tqdm(range(num_episodes)): + ep_path = episodes_dir / f"episode_{episode_index}.pth" + ep_dict = torch.load(ep_path) + ep_dicts.append(ep_dict) + data_dict = concatenate_episodes(ep_dicts) + + if video: + image_keys = [key for key in data_dict if "image" in key] + encode_videos(dataset, image_keys, play_sounds) + + hf_dataset = to_hf_dataset(data_dict, video) + episode_data_index = calculate_episode_data_index(hf_dataset) + + info = { + "codebase_version": CODEBASE_VERSION, + "fps": fps, + "video": video, + } + if video: + info["encoding"] = get_default_encoding() + + lerobot_dataset = LeRobotDataset.from_preloaded( + repo_id=repo_id, + hf_dataset=hf_dataset, + episode_data_index=episode_data_index, + info=info, + videos_dir=videos_dir, + ) + + return lerobot_dataset + + +def save_lerobot_dataset_on_disk(lerobot_dataset): + hf_dataset = lerobot_dataset.hf_dataset + info = lerobot_dataset.info + stats = lerobot_dataset.stats + episode_data_index = lerobot_dataset.episode_data_index + local_dir = lerobot_dataset.videos_dir.parent + meta_data_dir = local_dir / "meta_data" + + hf_dataset = hf_dataset.with_format(None) # to remove transforms that cant be saved + hf_dataset.save_to_disk(str(local_dir / "train")) + + save_meta_data(info, stats, episode_data_index, meta_data_dir) + + +def push_lerobot_dataset_to_hub(lerobot_dataset, tags): + hf_dataset = lerobot_dataset.hf_dataset + local_dir = lerobot_dataset.videos_dir.parent + videos_dir = lerobot_dataset.videos_dir + repo_id = lerobot_dataset.repo_id + video = lerobot_dataset.video + meta_data_dir = local_dir / "meta_data" + + if not (local_dir / "train").exists(): + raise ValueError( + "You need to run `save_lerobot_dataset_on_disk(lerobot_dataset)` before pushing to the hub." + ) + + hf_dataset.push_to_hub(repo_id, revision="main") + push_meta_data_to_hub(repo_id, meta_data_dir, revision="main") + push_dataset_card_to_hub(repo_id, revision="main", tags=tags) + if video: + push_videos_to_hub(repo_id, videos_dir, revision="main") + create_branch(repo_id, repo_type="dataset", branch=CODEBASE_VERSION) + + +def create_lerobot_dataset(dataset, run_compute_stats, push_to_hub, tags, play_sounds): + if "image_writer" in dataset: + logging.info("Waiting for image writer to terminate...") + image_writer = dataset["image_writer"] + stop_image_writer(image_writer, timeout=20) + + lerobot_dataset = from_dataset_to_lerobot_dataset(dataset, play_sounds) + + if run_compute_stats: + log_say("Computing dataset statistics", play_sounds) + lerobot_dataset.stats = compute_stats(lerobot_dataset) + else: + logging.info("Skipping computation of the dataset statistics") + lerobot_dataset.stats = {} + + save_lerobot_dataset_on_disk(lerobot_dataset) + + if push_to_hub: + push_lerobot_dataset_to_hub(lerobot_dataset, tags) + + return lerobot_dataset diff --git a/lerobot/common/logger.py b/lerobot/common/logger.py index bf578fcc5..3bd2df89a 100644 --- a/lerobot/common/logger.py +++ b/lerobot/common/logger.py @@ -189,7 +189,7 @@ def save_training_state( training_state["scheduler"] = scheduler.state_dict() torch.save(training_state, save_dir / self.training_state_file_name) - def save_checkpont( + def save_checkpoint( self, train_step: int, policy: Policy, diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/robot_devices/control_utils.py new file mode 100644 index 000000000..08bcec2e6 --- /dev/null +++ b/lerobot/common/robot_devices/control_utils.py @@ -0,0 +1,330 @@ +######################################################################################## +# Utilities +######################################################################################## + + +import logging +import time +import traceback +from contextlib import nullcontext +from copy import copy +from functools import cache + +import cv2 +import torch +import tqdm +from termcolor import colored + +from lerobot.common.datasets.populate_dataset import add_frame, safe_stop_image_writer +from lerobot.common.policies.factory import make_policy +from lerobot.common.robot_devices.robots.utils import Robot +from lerobot.common.robot_devices.utils import busy_wait +from lerobot.common.utils.utils import get_safe_torch_device, init_hydra_config, set_global_seed +from lerobot.scripts.eval import get_pretrained_policy_path + + +def log_control_info(robot: Robot, dt_s, episode_index=None, frame_index=None, fps=None): + log_items = [] + if episode_index is not None: + log_items.append(f"ep:{episode_index}") + if frame_index is not None: + log_items.append(f"frame:{frame_index}") + + def log_dt(shortname, dt_val_s): + nonlocal log_items, fps + info_str = f"{shortname}:{dt_val_s * 1000:5.2f} ({1/ dt_val_s:3.1f}hz)" + if fps is not None: + actual_fps = 1 / dt_val_s + if actual_fps < fps - 1: + info_str = colored(info_str, "yellow") + log_items.append(info_str) + + # total step time displayed in milliseconds and its frequency + log_dt("dt", dt_s) + + # TODO(aliberts): move robot-specific logs logic in robot.print_logs() + if not robot.robot_type.startswith("stretch"): + for name in robot.leader_arms: + key = f"read_leader_{name}_pos_dt_s" + if key in robot.logs: + log_dt("dtRlead", robot.logs[key]) + + for name in robot.follower_arms: + key = f"write_follower_{name}_goal_pos_dt_s" + if key in robot.logs: + log_dt("dtWfoll", robot.logs[key]) + + key = f"read_follower_{name}_pos_dt_s" + if key in robot.logs: + log_dt("dtRfoll", robot.logs[key]) + + for name in robot.cameras: + key = f"read_camera_{name}_dt_s" + if key in robot.logs: + log_dt(f"dtR{name}", robot.logs[key]) + + info_str = " ".join(log_items) + logging.info(info_str) + + +@cache +def is_headless(): + """Detects if python is running without a monitor.""" + try: + import pynput # noqa + + return False + except Exception: + print( + "Error trying to import pynput. Switching to headless mode. " + "As a result, the video stream from the cameras won't be shown, " + "and you won't be able to change the control flow with keyboards. " + "For more info, see traceback below.\n" + ) + traceback.print_exc() + print() + return True + + +def has_method(_object: object, method_name: str): + return hasattr(_object, method_name) and callable(getattr(_object, method_name)) + + +def predict_action(observation, policy, device, use_amp): + observation = copy(observation) + with ( + torch.inference_mode(), + torch.autocast(device_type=device.type) if device.type == "cuda" and use_amp else nullcontext(), + ): + # Convert to pytorch format: channel first and float32 in [0,1] with batch dimension + for name in observation: + if "image" in name: + observation[name] = observation[name].type(torch.float32) / 255 + observation[name] = observation[name].permute(2, 0, 1).contiguous() + observation[name] = observation[name].unsqueeze(0) + observation[name] = observation[name].to(device) + + # Compute the next action with the policy + # based on the current observation + action = policy.select_action(observation) + + # Remove batch dimension + action = action.squeeze(0) + + # Move to cpu, if not already the case + action = action.to("cpu") + + return action + + +def init_keyboard_listener(): + # Allow to exit early while recording an episode or resetting the environment, + # by tapping the right arrow key '->'. This might require a sudo permission + # to allow your terminal to monitor keyboard events. + events = {} + events["exit_early"] = False + events["rerecord_episode"] = False + events["stop_recording"] = False + + if is_headless(): + logging.warning( + "Headless environment detected. On-screen cameras display and keyboard inputs will not be available." + ) + listener = None + return listener, events + + # Only import pynput if not in a headless environment + from pynput import keyboard + + def on_press(key): + try: + if key == keyboard.Key.right: + print("Right arrow key pressed. Exiting loop...") + events["exit_early"] = True + elif key == keyboard.Key.left: + print("Left arrow key pressed. Exiting loop and rerecord the last episode...") + events["rerecord_episode"] = True + events["exit_early"] = True + elif key == keyboard.Key.esc: + print("Escape key pressed. Stopping data recording...") + events["stop_recording"] = True + events["exit_early"] = True + except Exception as e: + print(f"Error handling key press: {e}") + + listener = keyboard.Listener(on_press=on_press) + listener.start() + + return listener, events + + +def init_policy(pretrained_policy_name_or_path, policy_overrides): + """Instantiate the policy and load fps, device and use_amp from config yaml""" + pretrained_policy_path = get_pretrained_policy_path(pretrained_policy_name_or_path) + hydra_cfg = init_hydra_config(pretrained_policy_path / "config.yaml", policy_overrides) + policy = make_policy(hydra_cfg=hydra_cfg, pretrained_policy_name_or_path=pretrained_policy_path) + + # Check device is available + device = get_safe_torch_device(hydra_cfg.device, log=True) + use_amp = hydra_cfg.use_amp + policy_fps = hydra_cfg.env.fps + + policy.eval() + policy.to(device) + + torch.backends.cudnn.benchmark = True + torch.backends.cuda.matmul.allow_tf32 = True + set_global_seed(hydra_cfg.seed) + return policy, policy_fps, device, use_amp + + +def warmup_record( + robot, + events, + enable_teloperation, + warmup_time_s, + display_cameras, + fps, +): + control_loop( + robot=robot, + control_time_s=warmup_time_s, + display_cameras=display_cameras, + events=events, + fps=fps, + teleoperate=enable_teloperation, + ) + + +def record_episode( + robot, + dataset, + events, + episode_time_s, + display_cameras, + policy, + device, + use_amp, + fps, +): + control_loop( + robot=robot, + control_time_s=episode_time_s, + display_cameras=display_cameras, + dataset=dataset, + events=events, + policy=policy, + device=device, + use_amp=use_amp, + fps=fps, + teleoperate=policy is None, + ) + + +@safe_stop_image_writer +def control_loop( + robot, + control_time_s=None, + teleoperate=False, + display_cameras=False, + dataset=None, + events=None, + policy=None, + device=None, + use_amp=None, + fps=None, +): + # TODO(rcadene): Add option to record logs + if not robot.is_connected: + robot.connect() + + if events is None: + events = {"exit_early": False} + + if control_time_s is None: + control_time_s = float("inf") + + if teleoperate and policy is not None: + raise ValueError("When `teleoperate` is True, `policy` should be None.") + + 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}).") + + timestamp = 0 + start_episode_t = time.perf_counter() + while timestamp < control_time_s: + start_loop_t = time.perf_counter() + + if teleoperate: + observation, action = robot.teleop_step(record_data=True) + else: + observation = robot.capture_observation() + + if policy is not None: + pred_action = predict_action(observation, policy, device, use_amp) + # Action can eventually be clipped using `max_relative_target`, + # so action actually sent is saved in the dataset. + action = robot.send_action(pred_action) + action = {"action": action} + + if dataset is not None: + add_frame(dataset, observation, action) + + if display_cameras and not is_headless(): + image_keys = [key for key in observation if "image" in key] + for key in image_keys: + cv2.imshow(key, cv2.cvtColor(observation[key].numpy(), cv2.COLOR_RGB2BGR)) + cv2.waitKey(1) + + if fps is not None: + dt_s = time.perf_counter() - start_loop_t + busy_wait(1 / fps - dt_s) + + dt_s = time.perf_counter() - start_loop_t + log_control_info(robot, dt_s, fps=fps) + + timestamp = time.perf_counter() - start_episode_t + if events["exit_early"]: + events["exit_early"] = False + break + + +def reset_environment(robot, events, reset_time_s): + # 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 + + +def stop_recording(robot, listener, display_cameras): + robot.disconnect() + + if not is_headless(): + if listener is not None: + listener.stop() + + if display_cameras: + cv2.destroyAllWindows() + + +def sanity_check_dataset_name(repo_id, policy): + _, dataset_name = repo_id.split("/") + # either repo_id doesnt start with "eval_" and there is no policy + # or repo_id starts with "eval_" and there is a policy + if dataset_name.startswith("eval_") == (policy is None): + raise ValueError( + f"Your dataset name begins by 'eval_' ({dataset_name}) but no policy is provided ({policy})." + ) diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index 6ab900fb9..20969c30c 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -349,6 +349,25 @@ def __init__( self.is_connected = False self.logs = {} + @property + def has_camera(self): + return len(self.cameras) > 0 + + @property + def num_cameras(self): + return len(self.cameras) + + @property + def available_arms(self): + available_arms = [] + for name in self.follower_arms: + arm_id = get_arm_id(name, "follower") + available_arms.append(arm_id) + for name in self.leader_arms: + arm_id = get_arm_id(name, "leader") + available_arms.append(arm_id) + return available_arms + def connect(self): if self.is_connected: raise RobotDeviceAlreadyConnectedError( diff --git a/lerobot/common/utils/utils.py b/lerobot/common/utils/utils.py index 1aa0bc2d4..554e054e8 100644 --- a/lerobot/common/utils/utils.py +++ b/lerobot/common/utils/utils.py @@ -16,6 +16,7 @@ import logging import os import os.path as osp +import platform import random from contextlib import contextmanager from datetime import datetime, timezone @@ -28,6 +29,12 @@ from omegaconf import DictConfig +def none_or_int(value): + if value == "None": + return None + return int(value) + + def inside_slurm(): """Check whether the python process was launched through slurm""" # TODO(rcadene): return False for interactive mode `--pty bash` @@ -183,3 +190,30 @@ def print_cuda_memory_usage(): def capture_timestamp_utc(): return datetime.now(timezone.utc) + + +def say(text, blocking=False): + # Check if mac, linux, or windows. + if platform.system() == "Darwin": + cmd = f'say "{text}"' + elif platform.system() == "Linux": + cmd = f'spd-say "{text}"' + elif platform.system() == "Windows": + cmd = ( + 'PowerShell -Command "Add-Type -AssemblyName System.Speech; ' + f"(New-Object System.Speech.Synthesis.SpeechSynthesizer).Speak('{text}')\"" + ) + + if not blocking and platform.system() in ["Darwin", "Linux"]: + # TODO(rcadene): Make it work for Windows + # Use the ampersand to run command in the background + cmd += " &" + + os.system(cmd) + + +def log_say(text, play_sounds, blocking=False): + logging.info(text) + + if play_sounds: + say(text, blocking) diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 3b6345b42..425247e65 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -99,285 +99,35 @@ """ import argparse -import concurrent.futures -import json import logging -import multiprocessing -import os -import platform -import shutil import time -import traceback -from contextlib import nullcontext -from functools import cache from pathlib import Path - -import cv2 -import torch -import tqdm -from omegaconf import DictConfig -from PIL import Image -from termcolor import colored +from typing import List # from safetensors.torch import load_file, save_file -from lerobot.common.datasets.compute_stats import compute_stats -from lerobot.common.datasets.lerobot_dataset import CODEBASE_VERSION, LeRobotDataset -from lerobot.common.datasets.push_dataset_to_hub.aloha_hdf5_format import to_hf_dataset -from lerobot.common.datasets.push_dataset_to_hub.utils import concatenate_episodes, get_default_encoding -from lerobot.common.datasets.utils import calculate_episode_data_index, create_branch -from lerobot.common.datasets.video_utils import encode_video_frames -from lerobot.common.policies.factory import make_policy +from lerobot.common.datasets.lerobot_dataset import LeRobotDataset +from lerobot.common.datasets.populate_dataset import ( + create_lerobot_dataset, + delete_current_episode, + init_dataset, + save_current_episode, +) +from lerobot.common.robot_devices.control_utils import ( + control_loop, + has_method, + init_keyboard_listener, + init_policy, + log_control_info, + record_episode, + reset_environment, + sanity_check_dataset_name, + stop_recording, + warmup_record, +) from lerobot.common.robot_devices.robots.factory import make_robot -from lerobot.common.robot_devices.robots.utils import Robot, get_arm_id +from lerobot.common.robot_devices.robots.utils import Robot from lerobot.common.robot_devices.utils import busy_wait, safe_disconnect -from lerobot.common.utils.utils import get_safe_torch_device, init_hydra_config, init_logging, set_global_seed -from lerobot.scripts.eval import get_pretrained_policy_path -from lerobot.scripts.push_dataset_to_hub import ( - push_dataset_card_to_hub, - push_meta_data_to_hub, - push_videos_to_hub, - save_meta_data, -) - -######################################################################################## -# Utilities -######################################################################################## - - -def say(text, blocking=False): - # Check if mac, linux, or windows. - if platform.system() == "Darwin": - cmd = f'say "{text}"' - elif platform.system() == "Linux": - cmd = f'spd-say "{text}"' - elif platform.system() == "Windows": - cmd = ( - 'PowerShell -Command "Add-Type -AssemblyName System.Speech; ' - f"(New-Object System.Speech.Synthesis.SpeechSynthesizer).Speak('{text}')\"" - ) - - if not blocking and platform.system() in ["Darwin", "Linux"]: - # TODO(rcadene): Make it work for Windows - # Use the ampersand to run command in the background - cmd += " &" - - os.system(cmd) - - -def save_image(img_tensor, key, frame_index, episode_index, videos_dir: str): - img = Image.fromarray(img_tensor.numpy()) - path = Path(videos_dir) / f"{key}_episode_{episode_index:06d}" / f"frame_{frame_index:06d}.png" - path.parent.mkdir(parents=True, exist_ok=True) - img.save(str(path), quality=100) - - -def none_or_int(value): - if value == "None": - return None - return int(value) - - -def log_control_info(robot: Robot, dt_s, episode_index=None, frame_index=None, fps=None): - log_items = [] - if episode_index is not None: - log_items.append(f"ep:{episode_index}") - if frame_index is not None: - log_items.append(f"frame:{frame_index}") - - def log_dt(shortname, dt_val_s): - nonlocal log_items, fps - info_str = f"{shortname}:{dt_val_s * 1000:5.2f} ({1/ dt_val_s:3.1f}hz)" - if fps is not None: - actual_fps = 1 / dt_val_s - if actual_fps < fps - 1: - info_str = colored(info_str, "yellow") - log_items.append(info_str) - - # total step time displayed in milliseconds and its frequency - log_dt("dt", dt_s) - - # TODO(aliberts): move robot-specific logs logic in robot.print_logs() - if not robot.robot_type.startswith("stretch"): - for name in robot.leader_arms: - key = f"read_leader_{name}_pos_dt_s" - if key in robot.logs: - log_dt("dtRlead", robot.logs[key]) - - for name in robot.follower_arms: - key = f"write_follower_{name}_goal_pos_dt_s" - if key in robot.logs: - log_dt("dtWfoll", robot.logs[key]) - - key = f"read_follower_{name}_pos_dt_s" - if key in robot.logs: - log_dt("dtRfoll", robot.logs[key]) - - for name in robot.cameras: - key = f"read_camera_{name}_dt_s" - if key in robot.logs: - log_dt(f"dtR{name}", robot.logs[key]) - - info_str = " ".join(log_items) - logging.info(info_str) - - -@cache -def is_headless(): - """Detects if python is running without a monitor.""" - try: - import pynput # noqa - - return False - except Exception: - print( - "Error trying to import pynput. Switching to headless mode. " - "As a result, the video stream from the cameras won't be shown, " - "and you won't be able to change the control flow with keyboards. " - "For more info, see traceback below.\n" - ) - traceback.print_exc() - print() - return True - - -def has_method(_object: object, method_name: str): - return hasattr(_object, method_name) and callable(getattr(_object, method_name)) - - -def get_available_arms(robot): - # TODO(rcadene): moves this function in manipulator class? - available_arms = [] - for name in robot.follower_arms: - arm_id = get_arm_id(name, "follower") - available_arms.append(arm_id) - for name in robot.leader_arms: - arm_id = get_arm_id(name, "leader") - available_arms.append(arm_id) - return available_arms - - -######################################################################################## -# Asynchrounous saving of images on disk -######################################################################################## - - -def loop_to_save_images_in_threads(image_queue, num_threads): - if num_threads < 1: - raise NotImplementedError(f"Only `num_threads>=1` is supported for now, but {num_threads=} given.") - - with concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) as executor: - futures = [] - while True: - # Blocks until a frame is available - frame_data = image_queue.get() - - # As usually done, exit loop when receiving None to stop the worker - if frame_data is None: - break - - image, key, frame_index, episode_index, videos_dir = frame_data - futures.append(executor.submit(save_image, image, key, frame_index, episode_index, videos_dir)) - - # Before exiting function, wait for all threads to complete - with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: - concurrent.futures.wait(futures) - progress_bar.update(len(futures)) - - -def start_image_writer_processes(image_queue, num_processes, num_threads_per_process): - if num_processes < 1: - raise ValueError(f"Only `num_processes>=1` is supported, but {num_processes=} given.") - - if num_threads_per_process < 1: - raise NotImplementedError( - "Only `num_threads_per_process>=1` is supported for now, but {num_threads_per_process=} given." - ) - - processes = [] - for _ in range(num_processes): - process = multiprocessing.Process( - target=loop_to_save_images_in_threads, - args=(image_queue, num_threads_per_process), - ) - process.start() - processes.append(process) - return processes - - -def stop_processes(processes, queue, timeout): - # Send None to each process to signal them to stop - for _ in processes: - queue.put(None) - - # Close the queue, no more items can be put in the queue - queue.close() - - # Wait maximum 20 seconds for all processes to terminate - for process in processes: - process.join(timeout=timeout) - - # If not terminated after 20 seconds, force termination - if process.is_alive(): - process.terminate() - - # Ensure all background queue threads have finished - queue.join_thread() - - -def start_image_writer(num_processes, num_threads): - """This function abstract away the initialisation of processes or/and threads to - save images on disk asynchrounously, which is critical to control a robot and record data - at a high frame rate. - - When `num_processes=0`, it returns a dictionary containing a threads pool of size `num_threads`. - When `num_processes>0`, it returns a dictionary containing a processes pool of size `num_processes`, - where each subprocess starts their own threads pool of size `num_threads`. - - The optimal number of processes and threads depends on your computer capabilities. - We advise to use 4 threads per camera with 0 processes. If the fps is not stable, try to increase or lower - the number of threads. If it is still not stable, try to use 1 subprocess, or more. - """ - image_writer = {} - - if num_processes == 0: - futures = [] - threads_pool = concurrent.futures.ThreadPoolExecutor(max_workers=num_threads) - image_writer["threads_pool"], image_writer["futures"] = threads_pool, futures - else: - # TODO(rcadene): When using num_processes>1, `multiprocessing.Manager().Queue()` - # might be better than `multiprocessing.Queue()`. Source: https://www.geeksforgeeks.org/python-multiprocessing-queue-vs-multiprocessing-manager-queue - image_queue = multiprocessing.Queue() - processes_pool = start_image_writer_processes( - image_queue, num_processes=num_processes, num_threads_per_process=num_threads - ) - image_writer["processes_pool"], image_writer["image_queue"] = processes_pool, image_queue - - return image_writer - - -def async_save_image(image_writer, image, key, frame_index, episode_index, videos_dir): - """This function abstract away the saving of an image on disk asynchrounously. It uses a dictionary - called image writer which contains either a pool of processes or a pool of threads. - """ - if "threads_pool" in image_writer: - threads_pool, futures = image_writer["threads_pool"], image_writer["futures"] - futures.append(threads_pool.submit(save_image, image, key, frame_index, episode_index, videos_dir)) - else: - image_queue = image_writer["image_queue"] - image_queue.put((image, key, frame_index, episode_index, videos_dir)) - - -def stop_image_writer(image_writer, timeout): - if "threads_pool" in image_writer: - futures = image_writer["futures"] - # Before exiting function, wait for all threads to complete - with tqdm.tqdm(total=len(futures), desc="Writing images") as progress_bar: - concurrent.futures.wait(futures, timeout=timeout) - progress_bar.update(len(futures)) - else: - processes_pool, image_queue = image_writer["processes_pool"], image_writer["image_queue"] - stop_processes(processes_pool, image_queue, timeout=timeout) - +from lerobot.common.utils.utils import init_hydra_config, init_logging, log_say, none_or_int ######################################################################################## # Control modes @@ -394,9 +144,8 @@ def calibrate(robot: Robot, arms: list[str] | None): robot.home() return - available_arms = get_available_arms(robot) - unknown_arms = [arm_id for arm_id in arms if arm_id not in available_arms] - available_arms_str = " ".join(available_arms) + unknown_arms = [arm_id for arm_id in arms if arm_id not in robot.available_arms] + available_arms_str = " ".join(robot.available_arms) unknown_arms_str = " ".join(unknown_arms) if arms is None or len(arms) == 0: @@ -429,35 +178,26 @@ def calibrate(robot: Robot, arms: list[str] | None): @safe_disconnect -def teleoperate(robot: Robot, fps: int | None = None, teleop_time_s: float | None = None): - # TODO(rcadene): Add option to record logs - if not robot.is_connected: - robot.connect() - - start_teleop_t = time.perf_counter() - while True: - start_loop_t = time.perf_counter() - robot.teleop_step() - - if fps is not None: - dt_s = time.perf_counter() - start_loop_t - busy_wait(1 / fps - dt_s) - - dt_s = time.perf_counter() - start_loop_t - log_control_info(robot, dt_s, fps=fps) - - if teleop_time_s is not None and time.perf_counter() - start_teleop_t > teleop_time_s: - break +def teleoperate( + robot: Robot, fps: int | None = None, teleop_time_s: float | None = None, display_cameras: bool = False +): + control_loop( + robot, + control_time_s=teleop_time_s, + fps=fps, + teleoperate=True, + display_cameras=display_cameras, + ) @safe_disconnect def record( robot: Robot, - policy: torch.nn.Module | None = None, - hydra_cfg: DictConfig | None = None, + root: str, + repo_id: str, + pretrained_policy_name_or_path: str | None = None, + policy_overrides: List[str] | None = None, fps: int | None = None, - root="data", - repo_id="lerobot/debug", warmup_time_s=2, episode_time_s=10, reset_time_s=5, @@ -473,407 +213,108 @@ def record( play_sounds=True, ): # TODO(rcadene): Add option to record logs - # TODO(rcadene): Clean this function via decomposition in higher level functions - - _, dataset_name = repo_id.split("/") - if dataset_name.startswith("eval_") and policy is None: - raise ValueError( - f"Your dataset name begins by 'eval_' ({dataset_name}) but no policy is provided ({policy})." - ) + listener = None + events = None + policy = None + device = None + use_amp = None + + # Load pretrained policy + if pretrained_policy_name_or_path is not None: + policy, policy_fps, device, use_amp = init_policy(pretrained_policy_name_or_path, policy_overrides) + + if fps is None: + fps = policy_fps + logging.warning(f"No fps provided, so using the fps from policy config ({policy_fps}).") + elif fps != policy_fps: + logging.warning( + f"There is a mismatch between the provided fps ({fps}) and the one from policy config ({policy_fps})." + ) + + # Create empty dataset or load existing saved episodes + sanity_check_dataset_name(repo_id, policy) + dataset = init_dataset( + repo_id, + root, + force_override, + fps, + video, + write_images=robot.has_camera, + num_image_writer_processes=num_image_writer_processes, + num_image_writer_threads=num_image_writer_threads_per_camera * robot.num_cameras, + ) if not robot.is_connected: robot.connect() - local_dir = Path(root) / repo_id - if local_dir.exists() and force_override: - shutil.rmtree(local_dir) - - episodes_dir = local_dir / "episodes" - episodes_dir.mkdir(parents=True, exist_ok=True) - - videos_dir = local_dir / "videos" - videos_dir.mkdir(parents=True, exist_ok=True) - - # Logic to resume data recording - rec_info_path = episodes_dir / "data_recording_info.json" - if rec_info_path.exists(): - with open(rec_info_path) as f: - rec_info = json.load(f) - episode_index = rec_info["last_episode_index"] + 1 - else: - episode_index = 0 - - if is_headless(): - logging.warning( - "Headless environment detected. On-screen cameras display and keyboard inputs will not be available." - ) - - # Allow to exit early while recording an episode or resetting the environment, - # by tapping the right arrow key '->'. This might require a sudo permission - # to allow your terminal to monitor keyboard events. - exit_early = False - rerecord_episode = False - stop_recording = False - - # Only import pynput if not in a headless environment - if not is_headless(): - from pynput import keyboard - - def on_press(key): - nonlocal exit_early, rerecord_episode, stop_recording - try: - if key == keyboard.Key.right: - print("Right arrow key pressed. Exiting loop...") - exit_early = True - elif key == keyboard.Key.left: - print("Left arrow key pressed. Exiting loop and rerecord the last episode...") - rerecord_episode = True - exit_early = True - elif key == keyboard.Key.esc: - print("Escape key pressed. Stopping data recording...") - stop_recording = True - exit_early = True - except Exception as e: - print(f"Error handling key press: {e}") - - listener = keyboard.Listener(on_press=on_press) - listener.start() - - # Load policy if any - if policy is not None: - # Check device is available - device = get_safe_torch_device(hydra_cfg.device, log=True) - - policy.eval() - policy.to(device) - - torch.backends.cudnn.benchmark = True - torch.backends.cuda.matmul.allow_tf32 = True - set_global_seed(hydra_cfg.seed) - - # override fps using policy fps - fps = hydra_cfg.env.fps - - # Execute a few seconds without recording data, to give times - # to the robot devices to connect and start synchronizing. - timestamp = 0 - start_warmup_t = time.perf_counter() - is_warmup_print = False - while timestamp < warmup_time_s: - if not is_warmup_print: - logging.info("Warming up (no data recording)") - if play_sounds: - say("Warming up") - is_warmup_print = True - - start_loop_t = time.perf_counter() - - if policy is None: - observation, action = robot.teleop_step(record_data=True) - else: - observation = robot.capture_observation() - - if display_cameras and not is_headless(): - image_keys = [key for key in observation if "image" in key] - for key in image_keys: - cv2.imshow(key, cv2.cvtColor(observation[key].numpy(), cv2.COLOR_RGB2BGR)) - cv2.waitKey(1) - - dt_s = time.perf_counter() - start_loop_t - busy_wait(1 / fps - dt_s) - - dt_s = time.perf_counter() - start_loop_t - log_control_info(robot, dt_s, fps=fps) + listener, events = init_keyboard_listener() - timestamp = time.perf_counter() - start_warmup_t + # Execute a few seconds without recording to: + # 1. teleoperate the robot to move it in starting position if no policy provided, + # 2. give times to the robot devices to connect and start synchronizing, + # 3. place the cameras windows on screen + enable_teleoperation = policy is None + log_say("Warmup record", play_sounds) + warmup_record(robot, events, enable_teleoperation, warmup_time_s, display_cameras, fps) if has_method(robot, "teleop_safety_stop"): robot.teleop_safety_stop() - has_camera = len(robot.cameras) > 0 - if has_camera: - # Initialize processes or/and threads dedicated to save images on disk asynchronously, - # which is critical to control a robot and record data at a high frame rate. - image_writer = start_image_writer( - num_processes=num_image_writer_processes, - num_threads=num_image_writer_threads_per_camera * len(robot.cameras), + while True: + if dataset["num_episodes"] >= num_episodes: + break + + episode_index = dataset["num_episodes"] + log_say(f"Recording episode {episode_index}", play_sounds) + record_episode( + dataset=dataset, + robot=robot, + events=events, + episode_time_s=episode_time_s, + display_cameras=display_cameras, + policy=policy, + device=device, + use_amp=use_amp, + fps=fps, ) - # Using `try` to exist smoothly if an exception is raised - try: - # Start recording all episodes - while episode_index < num_episodes: - logging.info(f"Recording episode {episode_index}") - if play_sounds: - say(f"Recording episode {episode_index}") - ep_dict = {} - frame_index = 0 - timestamp = 0 - start_episode_t = time.perf_counter() - while timestamp < episode_time_s: - start_loop_t = time.perf_counter() - - if policy is None: - observation, action = robot.teleop_step(record_data=True) - else: - observation = robot.capture_observation() - - image_keys = [key for key in observation if "image" in key] - not_image_keys = [key for key in observation if "image" not in key] - - if has_camera > 0: - for key in image_keys: - async_save_image( - image_writer, - image=observation[key], - key=key, - frame_index=frame_index, - episode_index=episode_index, - videos_dir=str(videos_dir), - ) - - if display_cameras and not is_headless(): - image_keys = [key for key in observation if "image" in key] - for key in image_keys: - cv2.imshow(key, cv2.cvtColor(observation[key].numpy(), cv2.COLOR_RGB2BGR)) - cv2.waitKey(1) - - for key in not_image_keys: - if key not in ep_dict: - ep_dict[key] = [] - ep_dict[key].append(observation[key]) - - if policy is not None: - with ( - torch.inference_mode(), - torch.autocast(device_type=device.type) - if device.type == "cuda" and hydra_cfg.use_amp - else nullcontext(), - ): - # Convert to pytorch format: channel first and float32 in [0,1] with batch dimension - for name in observation: - if "image" in name: - observation[name] = observation[name].type(torch.float32) / 255 - observation[name] = observation[name].permute(2, 0, 1).contiguous() - observation[name] = observation[name].unsqueeze(0) - observation[name] = observation[name].to(device) - - # Compute the next action with the policy - # based on the current observation - action = policy.select_action(observation) - - # Remove batch dimension - action = action.squeeze(0) - - # Move to cpu, if not already the case - action = action.to("cpu") - - # Order the robot to move - action_sent = robot.send_action(action) - - # Action can eventually be clipped using `max_relative_target`, - # so action actually sent is saved in the dataset. - action = {"action": action_sent} - - for key in action: - if key not in ep_dict: - ep_dict[key] = [] - ep_dict[key].append(action[key]) - - frame_index += 1 - - dt_s = time.perf_counter() - start_loop_t - busy_wait(1 / fps - dt_s) - - dt_s = time.perf_counter() - start_loop_t - log_control_info(robot, dt_s, fps=fps) - - timestamp = time.perf_counter() - start_episode_t - if exit_early: - exit_early = False - break - - # TODO(alibets): allow for teleop during reset - if has_method(robot, "teleop_safety_stop"): - robot.teleop_safety_stop() - - if not stop_recording: - # Start resetting env while the executor are finishing - logging.info("Reset the environment") - if play_sounds: - say("Reset the environment") - - timestamp = 0 - start_vencod_t = time.perf_counter() - - # During env reset we save the data and encode the videos - num_frames = frame_index - - for key in image_keys: - if video: - tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" - fname = f"{key}_episode_{episode_index:06d}.mp4" - video_path = local_dir / "videos" / fname - if video_path.exists(): - video_path.unlink() - # Store the reference to the video frame, even tho the videos are not yet encoded - ep_dict[key] = [] - for i in range(num_frames): - ep_dict[key].append({"path": f"videos/{fname}", "timestamp": i / fps}) - - else: - imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" - ep_dict[key] = [] - for i in range(num_frames): - img_path = imgs_dir / f"frame_{i:06d}.png" - ep_dict[key].append({"path": str(img_path)}) - - for key in not_image_keys: - ep_dict[key] = torch.stack(ep_dict[key]) - - for key in action: - ep_dict[key] = torch.stack(ep_dict[key]) - - ep_dict["episode_index"] = torch.tensor([episode_index] * num_frames) - ep_dict["frame_index"] = torch.arange(0, num_frames, 1) - ep_dict["timestamp"] = torch.arange(0, num_frames, 1) / fps - - done = torch.zeros(num_frames, dtype=torch.bool) - done[-1] = True - ep_dict["next.done"] = done - - ep_path = episodes_dir / f"episode_{episode_index}.pth" - print("Saving episode dictionary...") - torch.save(ep_dict, ep_path) - - rec_info = { - "last_episode_index": episode_index, - } - with open(rec_info_path, "w") as f: - json.dump(rec_info, f) - - is_last_episode = stop_recording or (episode_index == (num_episodes - 1)) - - # Wait if necessary - with tqdm.tqdm(total=reset_time_s, desc="Waiting") as pbar: - while timestamp < reset_time_s and not is_last_episode: - time.sleep(1) - timestamp = time.perf_counter() - start_vencod_t - pbar.update(1) - if exit_early: - exit_early = False - break - - # Skip updating episode index which forces re-recording episode - if rerecord_episode: - rerecord_episode = False - continue - - episode_index += 1 - - if is_last_episode: - logging.info("Done recording") - if play_sounds: - say("Done recording", blocking=True) - if not is_headless(): - listener.stop() - - if has_camera > 0: - logging.info("Waiting for image writer to terminate...") - stop_image_writer(image_writer, timeout=20) - - except Exception as e: - if has_camera > 0: - logging.info("Waiting for image writer to terminate...") - stop_image_writer(image_writer, timeout=20) - raise e + # Execute a few seconds without recording to give time to manually reset the environment + # Current code logic doesn't allow to teleoperate during this time. + # TODO(rcadene): add an option to enable teleoperation during reset + # Skip reset for the last episode to be recorded + if not events["stop_recording"] and ( + (episode_index < num_episodes - 1) or events["rerecord_episode"] + ): + log_say("Reset the environment", play_sounds) + reset_environment(robot, events, reset_time_s) + + if events["rerecord_episode"]: + log_say("Re-record episode", play_sounds) + events["rerecord_episode"] = False + events["exit_early"] = False + delete_current_episode(dataset) + continue + + # Increment by one dataset["current_episode_index"] + save_current_episode(dataset) + + if events["stop_recording"]: + break - robot.disconnect() + log_say("Stop recording", play_sounds, blocking=True) + stop_recording(robot, listener, display_cameras) - if display_cameras and not is_headless(): - cv2.destroyAllWindows() - - num_episodes = episode_index - - if video: - logging.info("Encoding videos") - if play_sounds: - say("Encoding videos") - # Use ffmpeg to convert frames stored as png into mp4 videos - for episode_index in tqdm.tqdm(range(num_episodes)): - for key in image_keys: - tmp_imgs_dir = videos_dir / f"{key}_episode_{episode_index:06d}" - fname = f"{key}_episode_{episode_index:06d}.mp4" - video_path = local_dir / "videos" / fname - if video_path.exists(): - # Skip if video is already encoded. Could be the case when resuming data recording. - continue - # note: `encode_video_frames` is a blocking call. Making it asynchronous shouldn't speedup encoding, - # since video encoding with ffmpeg is already using multithreading. - encode_video_frames(tmp_imgs_dir, video_path, fps, overwrite=True) - shutil.rmtree(tmp_imgs_dir) - - logging.info("Concatenating episodes") - ep_dicts = [] - for episode_index in tqdm.tqdm(range(num_episodes)): - ep_path = episodes_dir / f"episode_{episode_index}.pth" - ep_dict = torch.load(ep_path) - ep_dicts.append(ep_dict) - data_dict = concatenate_episodes(ep_dicts) - - total_frames = data_dict["frame_index"].shape[0] - data_dict["index"] = torch.arange(0, total_frames, 1) - - hf_dataset = to_hf_dataset(data_dict, video) - episode_data_index = calculate_episode_data_index(hf_dataset) - info = { - "codebase_version": CODEBASE_VERSION, - "fps": fps, - "video": video, - } - if video: - info["encoding"] = get_default_encoding() - - lerobot_dataset = LeRobotDataset.from_preloaded( - repo_id=repo_id, - hf_dataset=hf_dataset, - episode_data_index=episode_data_index, - info=info, - videos_dir=videos_dir, - ) - if run_compute_stats: - logging.info("Computing dataset statistics") - if play_sounds: - say("Computing dataset statistics") - stats = compute_stats(lerobot_dataset) - lerobot_dataset.stats = stats - else: - stats = {} - logging.info("Skipping computation of the dataset statistics") - - hf_dataset = hf_dataset.with_format(None) # to remove transforms that cant be saved - hf_dataset.save_to_disk(str(local_dir / "train")) - - meta_data_dir = local_dir / "meta_data" - save_meta_data(info, stats, episode_data_index, meta_data_dir) - - if push_to_hub: - hf_dataset.push_to_hub(repo_id, revision="main") - push_meta_data_to_hub(repo_id, meta_data_dir, revision="main") - push_dataset_card_to_hub(repo_id, revision="main", tags=tags) - if video: - push_videos_to_hub(repo_id, videos_dir, revision="main") - create_branch(repo_id, repo_type="dataset", branch=CODEBASE_VERSION) - - logging.info("Exiting") - if play_sounds: - say("Exiting") + lerobot_dataset = create_lerobot_dataset(dataset, run_compute_stats, push_to_hub, tags, play_sounds) + + log_say("Exiting", play_sounds) return lerobot_dataset +@safe_disconnect def replay( robot: Robot, episode: int, fps: int | None = None, root="data", repo_id="lerobot/debug", play_sounds=True ): + # TODO(rcadene, aliberts): refactor with control_loop, once `dataset` is an instance of LeRobotDataset # TODO(rcadene): Add option to record logs local_dir = Path(root) / repo_id if not local_dir.exists(): @@ -887,9 +328,7 @@ def replay( if not robot.is_connected: robot.connect() - logging.info("Replaying episode") - if play_sounds: - say("Replaying episode", blocking=True) + log_say("Replaying episode", play_sounds, blocking=True) for idx in range(from_idx, to_idx): start_episode_t = time.perf_counter() @@ -934,6 +373,12 @@ def replay( parser_teleop.add_argument( "--fps", type=none_or_int, default=None, help="Frames per second (set to None to disable)" ) + parser_teleop.add_argument( + "--display-cameras", + type=int, + default=1, + help="Display all cameras on screen (set to 1 to display or 0).", + ) parser_record = subparsers.add_parser("record", parents=[base_parser]) parser_record.add_argument( @@ -1071,19 +516,7 @@ def replay( teleoperate(robot, **kwargs) elif control_mode == "record": - pretrained_policy_name_or_path = args.pretrained_policy_name_or_path - policy_overrides = args.policy_overrides - del kwargs["pretrained_policy_name_or_path"] - del kwargs["policy_overrides"] - - policy_cfg = None - if pretrained_policy_name_or_path is not None: - pretrained_policy_path = get_pretrained_policy_path(pretrained_policy_name_or_path) - policy_cfg = init_hydra_config(pretrained_policy_path / "config.yaml", policy_overrides) - policy = make_policy(hydra_cfg=policy_cfg, pretrained_policy_name_or_path=pretrained_policy_path) - record(robot, policy, policy_cfg, **kwargs) - else: - record(robot, **kwargs) + record(robot, **kwargs) elif control_mode == "replay": replay(robot, **kwargs) diff --git a/lerobot/scripts/train.py b/lerobot/scripts/train.py index 45807503f..f60f904eb 100644 --- a/lerobot/scripts/train.py +++ b/lerobot/scripts/train.py @@ -383,7 +383,7 @@ def evaluate_and_checkpoint_if_needed(step, is_online): logging.info(f"Checkpoint policy after step {step}") # Note: Save with step as the identifier, and format it to have at least 6 digits but more if # needed (choose 6 as a minimum for consistency without being overkill). - logger.save_checkpont( + logger.save_checkpoint( step, policy, optimizer, diff --git a/lerobot/templates/visualize_dataset_template.html b/lerobot/templates/visualize_dataset_template.html index 4f0bd343e..658d6ba6c 100644 --- a/lerobot/templates/visualize_dataset_template.html +++ b/lerobot/templates/visualize_dataset_template.html @@ -250,7 +250,7 @@

if(!canPlayVideos){ this.videoCodecError = true; } - + // process CSV data this.videos = document.querySelectorAll('video'); this.video = this.videos[0]; diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 770b3489b..2c0bca9b6 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -25,12 +25,16 @@ import multiprocessing from pathlib import Path +from unittest.mock import patch import pytest +from lerobot.common.datasets.populate_dataset import add_frame, init_dataset +from lerobot.common.logger import Logger from lerobot.common.policies.factory import make_policy from lerobot.common.utils.utils import init_hydra_config -from lerobot.scripts.control_robot import calibrate, get_available_arms, record, replay, teleoperate +from lerobot.scripts.control_robot import calibrate, record, replay, teleoperate +from lerobot.scripts.train import make_optimizer_and_scheduler from tests.test_robots import make_robot from tests.utils import DEFAULT_CONFIG_PATH, DEVICE, TEST_ROBOT_TYPES, require_robot @@ -69,7 +73,7 @@ def test_calibrate(tmpdir, request, robot_type, mock): overrides_calibration_dir = [f"calibration_dir={calibration_dir}"] robot = make_robot(robot_type, overrides=overrides_calibration_dir, mock=mock) - calibrate(robot, arms=get_available_arms(robot)) + calibrate(robot, arms=robot.available_arms) del robot @@ -109,12 +113,14 @@ 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) + if mock and robot_type != "aloha": request.getfixturevalue("patch_builtins_input") # 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 = tmpdir / robot_type overrides = [f"calibration_dir={calibration_dir}"] else: # Use the default .cache/calibration folder when mock=False or for aloha @@ -123,17 +129,19 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): env_name = "koch_real" policy_name = "act_koch_real" - root = Path(tmpdir) / "data" + root = tmpdir / "data" repo_id = "lerobot/debug" + eval_repo_id = "lerobot/eval_debug" robot = make_robot(robot_type, overrides=overrides, mock=mock) dataset = record( robot, - fps=30, - root=root, - repo_id=repo_id, + root, + repo_id, + fps=1, warmup_time_s=1, episode_time_s=1, + reset_time_s=1, num_episodes=2, push_to_hub=False, # TODO(rcadene, aliberts): test video=True @@ -142,8 +150,10 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): display_cameras=False, play_sounds=False, ) + assert dataset.num_episodes == 2 + assert len(dataset) == 2 - replay(robot, episode=0, fps=30, root=root, repo_id=repo_id, play_sounds=False) + replay(robot, episode=0, fps=1, root=root, repo_id=repo_id, play_sounds=False) # TODO(rcadene, aliberts): rethink this design if robot_type == "aloha": @@ -164,12 +174,26 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): if robot_type == "koch_bimanual": overrides += ["env.state_dim=12", "env.action_dim=12"] + overrides += ["wandb.enable=false"] + overrides += ["env.fps=1"] + cfg = init_hydra_config( DEFAULT_CONFIG_PATH, overrides=overrides, ) policy = make_policy(hydra_cfg=cfg, dataset_stats=dataset.stats) + optimizer, lr_scheduler = make_optimizer_and_scheduler(cfg, policy) + out_dir = tmpdir / "logger" + logger = Logger(cfg, out_dir, wandb_job_name="debug") + logger.save_checkpoint( + 0, + policy, + optimizer, + lr_scheduler, + identifier=0, + ) + pretrained_policy_name_or_path = out_dir / "checkpoints/last/pretrained_model" # 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. @@ -194,10 +218,12 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): record( robot, - policy, - cfg, + root, + eval_repo_id, + pretrained_policy_name_or_path, warmup_time_s=1, episode_time_s=1, + reset_time_s=1, num_episodes=2, run_compute_stats=False, push_to_hub=False, @@ -207,4 +233,218 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): num_image_writer_processes=num_image_writer_processes, ) + assert dataset.num_episodes == 2 + assert len(dataset) == 2 + del robot + + +@pytest.mark.parametrize("robot_type, mock", [("koch", True)]) +@require_robot +def test_resume_record(tmpdir, request, robot_type, mock): + if mock and robot_type != "aloha": + request.getfixturevalue("patch_builtins_input") + + # Create an empty calibration directory to trigger manual calibration + # and avoid writing calibration files in user .cache/calibration folder + calibration_dir = tmpdir / robot_type + overrides = [f"calibration_dir={calibration_dir}"] + else: + # Use the default .cache/calibration folder when mock=False or for aloha + overrides = [] + + robot = make_robot(robot_type, overrides=overrides, mock=mock) + + root = Path(tmpdir) / "data" + repo_id = "lerobot/debug" + + dataset = record( + robot, + root, + repo_id, + fps=1, + warmup_time_s=0, + episode_time_s=1, + num_episodes=1, + push_to_hub=False, + video=False, + display_cameras=False, + play_sounds=False, + run_compute_stats=False, + ) + assert len(dataset) == 1, "`dataset` should contain only 1 frame" + + init_dataset_return_value = {} + + def wrapped_init_dataset(*args, **kwargs): + nonlocal init_dataset_return_value + init_dataset_return_value = init_dataset(*args, **kwargs) + return init_dataset_return_value + + with patch("lerobot.scripts.control_robot.init_dataset", wraps=wrapped_init_dataset): + dataset = record( + robot, + root, + repo_id, + fps=1, + warmup_time_s=0, + episode_time_s=1, + num_episodes=2, + push_to_hub=False, + video=False, + display_cameras=False, + play_sounds=False, + run_compute_stats=False, + ) + assert len(dataset) == 2, "`dataset` should contain only 1 frame" + assert ( + init_dataset_return_value["num_episodes"] == 2 + ), "`init_dataset` should load the previous episode" + + +@pytest.mark.parametrize("robot_type, mock", [("koch", True)]) +@require_robot +def test_record_with_event_rerecord_episode(tmpdir, request, robot_type, mock): + if mock and robot_type != "aloha": + request.getfixturevalue("patch_builtins_input") + + # Create an empty calibration directory to trigger manual calibration + # and avoid writing calibration files in user .cache/calibration folder + calibration_dir = tmpdir / robot_type + overrides = [f"calibration_dir={calibration_dir}"] + else: + # Use the default .cache/calibration folder when mock=False or for aloha + overrides = [] + + robot = make_robot(robot_type, overrides=overrides, mock=mock) + with ( + patch("lerobot.scripts.control_robot.init_keyboard_listener") as mock_listener, + patch("lerobot.common.robot_devices.control_utils.add_frame", wraps=add_frame) as mock_add_frame, + ): + mock_events = {} + mock_events["exit_early"] = True + mock_events["rerecord_episode"] = True + mock_events["stop_recording"] = False + mock_listener.return_value = (None, mock_events) + + root = Path(tmpdir) / "data" + repo_id = "lerobot/debug" + + dataset = record( + robot, + root, + repo_id, + fps=1, + warmup_time_s=0, + episode_time_s=1, + num_episodes=1, + push_to_hub=False, + video=False, + display_cameras=False, + play_sounds=False, + run_compute_stats=False, + ) + + assert not mock_events["rerecord_episode"], "`rerecord_episode` wasn't properly reset to False" + assert not mock_events["exit_early"], "`exit_early` wasn't properly reset to False" + assert mock_add_frame.call_count == 2, "`add_frame` should have been called 2 times" + assert len(dataset) == 1, "`dataset` should contain only 1 frame" + + +@pytest.mark.parametrize("robot_type, mock", [("koch", True)]) +@require_robot +def test_record_with_event_exit_early(tmpdir, request, robot_type, mock): + if mock: + request.getfixturevalue("patch_builtins_input") + + # Create an empty calibration directory to trigger manual calibration + # and avoid writing calibration files in user .cache/calibration folder + calibration_dir = tmpdir / robot_type + overrides = [f"calibration_dir={calibration_dir}"] + else: + # Use the default .cache/calibration folder when mock=False or for aloha + overrides = [] + + robot = make_robot(robot_type, overrides=overrides, mock=mock) + with ( + patch("lerobot.scripts.control_robot.init_keyboard_listener") as mock_listener, + patch("lerobot.common.robot_devices.control_utils.add_frame", wraps=add_frame) as mock_add_frame, + ): + mock_events = {} + mock_events["exit_early"] = True + mock_events["rerecord_episode"] = False + mock_events["stop_recording"] = False + mock_listener.return_value = (None, mock_events) + + root = Path(tmpdir) / "data" + repo_id = "lerobot/debug" + + dataset = record( + robot, + fps=2, + root=root, + repo_id=repo_id, + warmup_time_s=0, + episode_time_s=1, + num_episodes=1, + push_to_hub=False, + video=False, + display_cameras=False, + play_sounds=False, + run_compute_stats=False, + ) + + assert not mock_events["exit_early"], "`exit_early` wasn't properly reset to False" + assert mock_add_frame.call_count == 1, "`add_frame` should have been called 1 time" + assert len(dataset) == 1, "`dataset` should contain only 1 frame" + + +@pytest.mark.parametrize( + "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): + if mock: + request.getfixturevalue("patch_builtins_input") + + # Create an empty calibration directory to trigger manual calibration + # and avoid writing calibration files in user .cache/calibration folder + calibration_dir = tmpdir / robot_type + overrides = [f"calibration_dir={calibration_dir}"] + else: + # Use the default .cache/calibration folder when mock=False or for aloha + overrides = [] + + robot = make_robot(robot_type, overrides=overrides, mock=mock) + with ( + patch("lerobot.scripts.control_robot.init_keyboard_listener") as mock_listener, + patch("lerobot.common.robot_devices.control_utils.add_frame", wraps=add_frame) as mock_add_frame, + ): + mock_events = {} + mock_events["exit_early"] = True + mock_events["rerecord_episode"] = False + mock_events["stop_recording"] = True + mock_listener.return_value = (None, mock_events) + + root = Path(tmpdir) / "data" + repo_id = "lerobot/debug" + + dataset = record( + robot, + root, + repo_id, + fps=1, + warmup_time_s=0, + episode_time_s=1, + num_episodes=2, + push_to_hub=False, + video=False, + display_cameras=False, + play_sounds=False, + run_compute_stats=False, + num_image_writer_processes=num_image_writer_processes, + ) + + assert not mock_events["exit_early"], "`exit_early` wasn't properly reset to False" + assert mock_add_frame.call_count == 1, "`add_frame` should have been called 1 time" + assert len(dataset) == 1, "`dataset` should contain only 1 frame" diff --git a/tests/test_robots.py b/tests/test_robots.py index 72f0c9444..13ad8c450 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -127,6 +127,7 @@ def test_robot(tmpdir, request, robot_type, mock): # 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) + assert captured_observation[name].shape == observation[name].shape # Test send_action can run robot.send_action(action["action"]) From cd0fc261c051f4fabf352844f6bed6c3db74d688 Mon Sep 17 00:00:00 2001 From: Alexander Soare Date: Thu, 17 Oct 2024 15:22:21 +0100 Subject: [PATCH 07/29] Make `say(blocking=True)` work for Linux (#460) --- lerobot/common/utils/utils.py | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/lerobot/common/utils/utils.py b/lerobot/common/utils/utils.py index 554e054e8..4e276e169 100644 --- a/lerobot/common/utils/utils.py +++ b/lerobot/common/utils/utils.py @@ -196,19 +196,19 @@ def say(text, blocking=False): # Check if mac, linux, or windows. if platform.system() == "Darwin": cmd = f'say "{text}"' + if not blocking: + cmd += " &" elif platform.system() == "Linux": cmd = f'spd-say "{text}"' + if blocking: + cmd += " --wait" elif platform.system() == "Windows": + # TODO(rcadene): Make blocking option work for Windows cmd = ( 'PowerShell -Command "Add-Type -AssemblyName System.Speech; ' f"(New-Object System.Speech.Synthesis.SpeechSynthesizer).Speak('{text}')\"" ) - if not blocking and platform.system() in ["Darwin", "Linux"]: - # TODO(rcadene): Make it work for Windows - # Use the ampersand to run command in the background - cmd += " &" - os.system(cmd) From c351e1fff92ed276ef668f188f645bdfdf42f6b3 Mon Sep 17 00:00:00 2001 From: Boris Zimka <4560910+zimka@users.noreply.github.com> Date: Fri, 18 Oct 2024 10:23:27 +0200 Subject: [PATCH 08/29] Fix gymnasium version as pre-1.0.0 (#471) Co-authored-by: Remi Co-authored-by: Remi --- poetry.lock | 10 +++++++--- pyproject.toml | 3 ++- 2 files changed, 9 insertions(+), 4 deletions(-) diff --git a/poetry.lock b/poetry.lock index f0e50dcda..fbf0431bc 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry 1.8.2 and should not be changed by hand. +# This file is automatically @generated by Poetry 1.8.4 and should not be changed by hand. [[package]] name = "absl-py" @@ -1292,6 +1292,10 @@ files = [ {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:78656d3ae1282a142a5fed410ec3a6f725fdf8d9f9192ed673e336ea3b083e12"}, {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:681e22c8ecb3b48d11cb9019f8a32d4ae1e353e20d4ce3a0f0eedd0ccbd95e5f"}, {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4598572bab6f726ec41fabb43bf0f7e3cf8082ea0f6f8f4e57845a6c919f31b3"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:157fc1fed50946646f09df75c6d52198735a5973e53d252199bbb1c65e1594d2"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_armv7l.whl", hash = "sha256:7ae2724c181be10692c24fb8d9ce2a99a9afc57237332c3658e2ea6f4f33c091"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_i686.whl", hash = "sha256:3d324835f292edd81b962f8c0df44f7f47c0a6f8fe6f7d081951aeb1f5ba57d2"}, + {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:474c087b5e584293685a7d4837165b2ead96dc74fb435ae50d5fa0ac168a0de0"}, {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:297350f05f5f87a0bf647a1e5b4446728e5f800788c6bb28b462bcd167f1de7f"}, {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:b1870a8e30f0ac298d17fd546224348d13a648bcfa0cbc51dba7e5136c1af928"}, {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:182a189212d41be0c960fd3299bf6731af2e771f8858cfb1be7ebcc17d60a254"}, @@ -5245,7 +5249,7 @@ docs = ["sphinx", "sphinx-automodapi", "sphinx-rtd-theme"] name = "pyserial" version = "3.5" description = "Python Serial Port Extension" -optional = false +optional = true python-versions = "*" files = [ {file = "pyserial-3.5-py2.py3-none-any.whl", hash = "sha256:c4451db6ba391ca6ca299fb3ec7bae67a5c55dde170964c7a14ceefec02f2cf0"}, @@ -7427,4 +7431,4 @@ xarm = ["gym-xarm"] [metadata] lock-version = "2.0" python-versions = ">=3.10,<3.13" -content-hash = "78f31561a7e4b6f0a97e27a65ec00c2c1826f420d2587396762bb5485d12f676" +content-hash = "cd59da219818a9906018a25462e76e15c5d2c0e6419531e8ddbdc2ae998854c1" diff --git a/pyproject.toml b/pyproject.toml index 47e982d1b..ee898db80 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -44,7 +44,8 @@ diffusers = ">=0.27.2" torchvision = ">=0.17.1" h5py = ">=3.10.0" huggingface-hub = {extras = ["hf-transfer", "cli"], version = ">=0.25.0"} -gymnasium = ">=0.29.1" +# TODO(rcadene, aliberts): Make gym 1.0.0 work +gymnasium = "==0.29.1" cmake = ">=3.29.0.1" gym-dora = { git = "https://github.com/dora-rs/dora-lerobot.git", subdirectory = "gym_dora", optional = true } gym-pusht = { version = ">=0.1.5", optional = true} From 2efee45ef13bf1b323cf2031f8b36f38dea36aa9 Mon Sep 17 00:00:00 2001 From: Bastian Krohg <98895859+bastiankrohg@users.noreply.github.com> Date: Wed, 23 Oct 2024 16:13:26 +0200 Subject: [PATCH 09/29] Update 9_use_aloha.md, missing comma (#479) --- 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 9859e3641..d161978fd 100644 --- a/examples/9_use_aloha.md +++ b/examples/9_use_aloha.md @@ -32,7 +32,7 @@ git clone https://github.com/huggingface/lerobot.git ~/lerobot 5. Install LeRobot with dependencies for the Aloha motors (dynamixel) and cameras (intelrealsense): ```bash -cd ~/lerobot && pip install -e ".[dynamixel intelrealsense]" +cd ~/lerobot && pip install -e ".[dynamixel, intelrealsense]" ``` And install extra dependencies for recording datasets on Linux: From 114870d703fa6835b0b8731ab11b9bf6f468db96 Mon Sep 17 00:00:00 2001 From: Arsen Ohanyan Date: Wed, 23 Oct 2024 07:24:06 -0700 Subject: [PATCH 10/29] Fix link (#482) Co-authored-by: Remi --- examples/7_get_started_with_real_robot.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index 58bfc66c3..266e4f0da 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -11,7 +11,7 @@ This tutorial will guide you through the process of setting up and training a ne By following these steps, you'll be able to replicate tasks like picking up a Lego block and placing it in a bin with a high success rate, as demonstrated in [this video](https://x.com/RemiCadene/status/1814680760592572934). -This tutorial is specifically made for the affordable [Koch v1.1](https://github.com/jess-moss/koch-v1-1) robot, but it contains additional information to be easily adapted to various types of robots like [Aloha bimanual robot](aloha-2.github.io) by changing some configurations. The Koch v1.1 consists of a leader arm and a follower arm, each with 6 motors. It can work with one or several cameras to record the scene, which serve as visual sensors for the robot. +This tutorial is specifically made for the affordable [Koch v1.1](https://github.com/jess-moss/koch-v1-1) robot, but it contains additional information to be easily adapted to various types of robots like [Aloha bimanual robot](https://aloha-2.github.io) by changing some configurations. The Koch v1.1 consists of a leader arm and a follower arm, each with 6 motors. It can work with one or several cameras to record the scene, which serve as visual sensors for the robot. During the data collection phase, you will control the follower arm by moving the leader arm. This process is known as "teleoperation." This technique is used to collect robot trajectories. Afterward, you'll train a neural network to imitate these trajectories and deploy the network to enable your robot to operate autonomously. From 07e8716315244c2dea8e38c0e7a48bb73a9cabf6 Mon Sep 17 00:00:00 2001 From: Remi Date: Fri, 25 Oct 2024 11:23:55 +0200 Subject: [PATCH 11/29] Add FeetechMotorsBus, SO-100, Moss-v1 (#419) Co-authored-by: jess-moss Co-authored-by: Simon Alibert <75076266+aliberts@users.noreply.github.com> --- README.md | 8 +- examples/10_use_so100.md | 280 ++++++ examples/11_use_moss.md | 280 ++++++ examples/7_get_started_with_real_robot.md | 6 +- examples/8_use_stretch.md | 2 +- examples/9_use_aloha.md | 2 +- lerobot/__init__.py | 3 + .../robot_devices/cameras/intelrealsense.py | 2 +- .../common/robot_devices/motors/dynamixel.py | 181 +--- .../common/robot_devices/motors/feetech.py | 887 ++++++++++++++++++ .../robots/dynamixel_calibration.py | 130 +++ .../robots/feetech_calibration.py | 485 ++++++++++ .../robot_devices/robots/manipulator.py | 206 ++-- lerobot/configs/env/moss_real.yaml | 10 + lerobot/configs/env/so100_real.yaml | 10 + lerobot/configs/policy/act_moss_real.yaml | 102 ++ lerobot/configs/policy/act_so100_real.yaml | 102 ++ lerobot/configs/robot/aloha.yaml | 6 +- lerobot/configs/robot/koch_bimanual.yaml | 2 +- lerobot/configs/robot/moss.yaml | 56 ++ lerobot/configs/robot/so100.yaml | 56 ++ lerobot/configs/robot/stretch.yaml | 9 + lerobot/scripts/configure_motor.py | 145 +++ lerobot/scripts/control_robot.py | 3 + lerobot/scripts/find_motors_bus_port.py | 36 + media/moss/follower_initial.webp | Bin 0 -> 118620 bytes media/moss/leader_rest.webp | Bin 0 -> 88928 bytes media/moss/leader_rotated.webp | Bin 0 -> 117078 bytes media/moss/leader_zero.webp | Bin 0 -> 158308 bytes media/so100/follower_initial.webp | Bin 0 -> 198594 bytes media/so100/leader_follower.webp | Bin 0 -> 120188 bytes media/so100/leader_rest.webp | Bin 0 -> 89600 bytes media/so100/leader_rotated.webp | Bin 0 -> 94970 bytes media/so100/leader_zero.webp | Bin 0 -> 87888 bytes poetry.lock | 22 +- pyproject.toml | 2 + tests/mock_dynamixel_sdk.py | 29 +- tests/mock_scservo_sdk.py | 103 ++ tests/test_control_robot.py | 15 +- tests/test_motors.py | 18 +- tests/test_robots.py | 4 +- tests/utils.py | 49 +- 42 files changed, 2911 insertions(+), 340 deletions(-) create mode 100644 examples/10_use_so100.md create mode 100644 examples/11_use_moss.md create mode 100644 lerobot/common/robot_devices/motors/feetech.py create mode 100644 lerobot/common/robot_devices/robots/dynamixel_calibration.py create mode 100644 lerobot/common/robot_devices/robots/feetech_calibration.py create mode 100644 lerobot/configs/env/moss_real.yaml create mode 100644 lerobot/configs/env/so100_real.yaml create mode 100644 lerobot/configs/policy/act_moss_real.yaml create mode 100644 lerobot/configs/policy/act_so100_real.yaml create mode 100644 lerobot/configs/robot/moss.yaml create mode 100644 lerobot/configs/robot/so100.yaml create mode 100644 lerobot/scripts/configure_motor.py create mode 100644 lerobot/scripts/find_motors_bus_port.py create mode 100644 media/moss/follower_initial.webp create mode 100644 media/moss/leader_rest.webp create mode 100644 media/moss/leader_rotated.webp create mode 100644 media/moss/leader_zero.webp create mode 100644 media/so100/follower_initial.webp create mode 100644 media/so100/leader_follower.webp create mode 100644 media/so100/leader_rest.webp create mode 100644 media/so100/leader_rotated.webp create mode 100644 media/so100/leader_zero.webp create mode 100644 tests/mock_scservo_sdk.py diff --git a/README.md b/README.md index 703e64881..b505c545d 100644 --- a/README.md +++ b/README.md @@ -23,15 +23,15 @@

-

Hot new tutorial: Getting started with real-world robots

+

New robot in town: SO-100

- Koch v1.1 leader and follower arms -

We just dropped an in-depth tutorial on how to build your own robot!

+ SO-100 leader and follower arms +

We just added a new tutorial on how to build a more affordable robot, at the price of $110 per arm!

Teach it new skills by showing it a few moves with just a laptop.

Then watch your homemade robot act autonomously 🤯

-

For more info, see our thread on X or our tutorial page.

+

Follow the link to the full tutorial for SO-100.


diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md new file mode 100644 index 000000000..ffadb1f3e --- /dev/null +++ b/examples/10_use_so100.md @@ -0,0 +1,280 @@ +This tutorial explains how to use [SO-100](https://github.com/TheRobotStudio/SO-ARM100) with LeRobot. + +## Source the parts + +Follow this [README](https://github.com/TheRobotStudio/SO-ARM100). 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. + +**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. + +## Install LeRobot + +On your computer: + +1. [Install Miniconda](https://docs.anaconda.com/miniconda/#quick-command-line-install): +```bash +mkdir -p ~/miniconda3 +wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh +bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3 +rm ~/miniconda3/miniconda.sh +~/miniconda3/bin/conda init bash +``` + +2. Restart shell or `source ~/.bashrc` + +3. Create and activate a fresh conda environment for lerobot +```bash +conda create -y -n lerobot python=3.10 && conda activate lerobot +``` + +4. Clone LeRobot: +```bash +git clone https://github.com/huggingface/lerobot.git ~/lerobot +``` + +5. Install LeRobot with dependencies for the feetech motors: +```bash +cd ~/lerobot && pip install -e ".[feetech]" +``` + +For Linux only (not Mac), install extra dependencies for recording datasets: +```bash +conda install -y -c conda-forge ffmpeg +pip uninstall -y opencv-python +conda install -y -c conda-forge "opencv>=4.10.0" +``` + +## Configure the motors + +Follow steps 1 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the use of our scripts below. + +**Find USB ports associated to your arms** +To find the correct ports for each arm, run the utility script twice: +```bash +python lerobot/scripts/find_motors_bus_port.py +``` + +Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem575E0031751` on Mac, or possibly `/dev/ttyACM0` on Linux): +``` +Finding all available ports for the MotorBus. +['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] +Remove the usb cable from your DynamixelMotorsBus and press Enter when done. + +[...Disconnect leader arm and press Enter...] + +The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751 +Reconnect the usb cable. +``` + +Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux): +``` +Finding all available ports for the MotorBus. +['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] +Remove the usb cable from your DynamixelMotorsBus and press Enter when done. + +[...Disconnect follower arm and press Enter...] + +The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0032081 +Reconnect the usb cable. +``` + +Troubleshooting: On Linux, you might need to give access to the USB ports by running: +```bash +sudo chmod 666 /dev/ttyACM0 +sudo chmod 666 /dev/ttyACM1 +``` + +**Configure your motors** +Plug your first motor and run this script to set its ID to 1. It will also set its present position to 2048, so expect your motor to rotate: +```bash +python lerobot/scripts/configure_motor.py \ + --port /dev/tty.usbmodem58760432961 \ + --brand feetech \ + --model sts3215 \ + --baudrate 1000000 \ + --ID 1 +``` + +Note: These motors are currently limitated. They can take values between 0 and 4096 only, which corresponds to a full turn. They can't turn more than that. 2048 is at the middle of this range, so we can take -2048 steps (180 degrees anticlockwise) and reach the maximum range, or take +2048 steps (180 degrees clockwise) and reach the maximum range. The configuration step also sets the homing offset to 0, so that if you misassembled the arm, you can always update the homing offset to account for a shift up to ± 2048 steps (± 180 degrees). + +Then unplug your motor and plug the second motor and set its ID to 2. +```bash +python lerobot/scripts/configure_motor.py \ + --port /dev/tty.usbmodem58760432961 \ + --brand feetech \ + --model sts3215 \ + --baudrate 1000000 \ + --ID 2 +``` + +Redo the process for all your motors until ID 6. Do the same for the 6 motors of the leader arm. + +**Remove the gears of the 6 leader motors** +Follow step 2 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I). 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. + +**Add motor horn to the motors** +Follow step 3 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I). 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. + +## Assemble the arms + +Follow step 4 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I). The first arm should take a bit more than 1 hour to assemble, but once you get use to it, you can do it under 1 hour for the second arm. + +## Calibrate + +Next, you'll need to calibrate your SO-100 robot to ensure that the leader and follower arms have the same position values when they are in the same physical position. This calibration is essential because it allows a neural network trained on one SO-100 robot to work on another. + +**Auto-calibration of follower arm** +Follow step 5 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the auto-calibration of the follower arm. You first need to manually move your follower arm to this initial position: + +
+ SO-100 follower arm initial position +
+ +Then run this script to launch auto-calibration: +```bash +python lerobot/scripts/control_robot.py calibrate \ + --robot-path lerobot/configs/robot/so100.yaml \ + --robot-overrides '~cameras' --arms main_follower +``` + +Note: You can't run auto-calibration for the leader arm, since we removed the gears. Thus, you will need to manually calibrate the leader arm. It's less precise than auto-calibration, but precision is not as critical for the leader arm. + +**Manual calibration of leader arm** +Follow step 6 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the manual calibration. You will need to move the leader arm to these positions sequentially: + +| 1. Zero position | 2. Rotated position | 3. Rest position | +|---|---|---| +| SO-100 leader arm zero position | SO-100 leader arm rotated position | SO-100 leader arm rest position | + +Run this script to launch manual calibration: +```bash +python lerobot/scripts/control_robot.py calibrate \ + --robot-path lerobot/configs/robot/so100.yaml \ + --robot-overrides '~cameras' --arms main_leader +``` + +## Teleoperate + +**Simple teleop** +Then you are ready to teleoperate your robot! Run this simple script (it won't connect and display the cameras): +```bash +python lerobot/scripts/control_robot.py teleoperate \ + --robot-path lerobot/configs/robot/so100.yaml \ + --robot-overrides '~cameras' \ + --display-cameras 0 +``` + + +**Teleop with displaying cameras** +Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset. +```bash +python lerobot/scripts/control_robot.py teleoperate \ + --robot-path lerobot/configs/robot/so100.yaml +``` + +## Record a dataset + +Once you're familiar with teleoperation, you can record your first dataset with SO-100. + +If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens): +```bash +huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential +``` + +Store your Hugging Face repository name in a variable to run these commands: +```bash +HF_USER=$(huggingface-cli whoami | head -n 1) +echo $HF_USER +``` + +Record 2 episodes and upload your dataset to the hub: +```bash +python lerobot/scripts/control_robot.py record \ + --robot-path lerobot/configs/robot/so100.yaml \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/so100_test \ + --tags so100 tutorial \ + --warmup-time-s 5 \ + --episode-time-s 40 \ + --reset-time-s 10 \ + --num-episodes 2 \ + --push-to-hub 1 +``` + +## Visualize a dataset + +If you uploaded your dataset to the hub with `--push-to-hub 1`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by: +```bash +echo ${HF_USER}/so100_test +``` + +If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with: +```bash +python lerobot/scripts/visualize_dataset_html.py \ + --root data \ + --repo-id ${HF_USER}/so100_test +``` + +## Replay an episode + +Now try to replay the first episode on your robot: +```bash +DATA_DIR=data python lerobot/scripts/control_robot.py replay \ + --robot-path lerobot/configs/robot/so100.yaml \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/so100_test \ + --episode 0 +``` + +## 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: +```bash +DATA_DIR=data python lerobot/scripts/train.py \ + dataset_repo_id=${HF_USER}/so100_test \ + policy=act_so100_real \ + env=so100_real \ + hydra.run.dir=outputs/train/act_so100_test \ + hydra.job.name=act_so100_test \ + device=cuda \ + wandb.enable=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=act_so100_real`. This loads configurations from [`lerobot/configs/policy/act_so100_real.yaml`](../lerobot/configs/policy/act_so100_real.yaml). Importantly, this policy uses 2 cameras as input `laptop`, `phone`. +3. We provided an environment as argument with `env=so100_real`. This loads configurations from [`lerobot/configs/env/so100_real.yaml`](../lerobot/configs/env/so100_real.yaml). +4. We provided `device=cuda` since we are training on a Nvidia GPU, but you can also use `device=mps` if you are using a Mac with Apple silicon, or `device=cpu` otherwise. +5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`. +6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync. + +Training should take several hours. You will find checkpoints in `outputs/train/act_so100_test/checkpoints`. + +## Evaluate your policy + +You can use the `record` function from [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) but with a policy checkpoint as input. For instance, run this command to record 10 evaluation episodes: +```bash +python lerobot/scripts/control_robot.py record \ + --robot-path lerobot/configs/robot/so100.yaml \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/eval_act_so100_test \ + --tags so100 tutorial eval \ + --warmup-time-s 5 \ + --episode-time-s 40 \ + --reset-time-s 10 \ + --num-episodes 10 \ + -p outputs/train/act_so100_test/checkpoints/last/pretrained_model +``` + +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 `-p` argument which indicates the path to your policy checkpoint with (e.g. `-p outputs/train/eval_so100_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `-p ${HF_USER}/act_so100_test`). +2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `--repo-id ${HF_USER}/eval_act_so100_test`). + +## 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 tutorial on controlling real robots with LeRobot. + +If you have any question or need help, please reach out on Discord in the channel [`#so100-arm`](https://discord.com/channels/1216765309076115607/1237741463832363039). diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md new file mode 100644 index 000000000..4286fb8bc --- /dev/null +++ b/examples/11_use_moss.md @@ -0,0 +1,280 @@ +This tutorial explains how to use [Moss v1](https://github.com/jess-moss/moss-robot-arms) with LeRobot. + +## 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. + +**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. + +## Install LeRobot + +On your computer: + +1. [Install Miniconda](https://docs.anaconda.com/miniconda/#quick-command-line-install): +```bash +mkdir -p ~/miniconda3 +wget https://repo.anaconda.com/miniconda/Miniconda3-latest-Linux-x86_64.sh -O ~/miniconda3/miniconda.sh +bash ~/miniconda3/miniconda.sh -b -u -p ~/miniconda3 +rm ~/miniconda3/miniconda.sh +~/miniconda3/bin/conda init bash +``` + +2. Restart shell or `source ~/.bashrc` + +3. Create and activate a fresh conda environment for lerobot +```bash +conda create -y -n lerobot python=3.10 && conda activate lerobot +``` + +4. Clone LeRobot: +```bash +git clone https://github.com/huggingface/lerobot.git ~/lerobot +``` + +5. Install LeRobot with dependencies for the feetech motors: +```bash +cd ~/lerobot && pip install -e ".[feetech]" +``` + +For Linux only (not Mac), install extra dependencies for recording datasets: +```bash +conda install -y -c conda-forge ffmpeg +pip uninstall -y opencv-python +conda install -y -c conda-forge "opencv>=4.10.0" +``` + +## Configure the motors + +Follow steps 1 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the use of our scripts below. + +**Find USB ports associated to your arms** +To find the correct ports for each arm, run the utility script twice: +```bash +python lerobot/scripts/find_motors_bus_port.py +``` + +Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem575E0031751` on Mac, or possibly `/dev/ttyACM0` on Linux): +``` +Finding all available ports for the MotorBus. +['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] +Remove the usb cable from your DynamixelMotorsBus and press Enter when done. + +[...Disconnect leader arm and press Enter...] + +The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751 +Reconnect the usb cable. +``` + +Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux): +``` +Finding all available ports for the MotorBus. +['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] +Remove the usb cable from your DynamixelMotorsBus and press Enter when done. + +[...Disconnect follower arm and press Enter...] + +The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0032081 +Reconnect the usb cable. +``` + +Troubleshooting: On Linux, you might need to give access to the USB ports by running: +```bash +sudo chmod 666 /dev/ttyACM0 +sudo chmod 666 /dev/ttyACM1 +``` + +**Configure your motors** +Plug your first motor and run this script to set its ID to 1. It will also set its present position to 2048, so expect your motor to rotate: +```bash +python lerobot/scripts/configure_motor.py \ + --port /dev/tty.usbmodem58760432961 \ + --brand feetech \ + --model sts3215 \ + --baudrate 1000000 \ + --ID 1 +``` + +Note: These motors are currently limitated. They can take values between 0 and 4096 only, which corresponds to a full turn. They can't turn more than that. 2048 is at the middle of this range, so we can take -2048 steps (180 degrees anticlockwise) and reach the maximum range, or take +2048 steps (180 degrees clockwise) and reach the maximum range. The configuration step also sets the homing offset to 0, so that if you misassembled the arm, you can always update the homing offset to account for a shift up to ± 2048 steps (± 180 degrees). + +Then unplug your motor and plug the second motor and set its ID to 2. +```bash +python lerobot/scripts/configure_motor.py \ + --port /dev/tty.usbmodem58760432961 \ + --brand feetech \ + --model sts3215 \ + --baudrate 1000000 \ + --ID 2 +``` + +Redo the process for all your motors until ID 6. Do the same for the 6 motors of the leader arm. + +**Remove the gears of the 6 leader motors** +Follow step 2 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic). 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. + +**Add motor horn to the motors** +Follow step 3 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic). For Moss v1, you need to align the holes on the motor horn to the motor spline to be approximately 3, 6, 9 and 12 o'clock. +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. + +## Assemble the arms + +Follow step 4 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic). The first arm should take a bit more than 1 hour to assemble, but once you get use to it, you can do it under 1 hour for the second arm. + +## Calibrate + +Next, you'll need to calibrate your Moss v1 robot to ensure that the leader and follower arms have the same position values when they are in the same physical position. This calibration is essential because it allows a neural network trained on one Moss v1 robot to work on another. + +**Auto-calibration of follower arm** +Follow step 5 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the auto-calibration of the follower arm. You first need to manually move your follower arm to this initial position: + +
+ Moss v1 follower arm initial position +
+ +Then run this script to launch auto-calibration: +```bash +python lerobot/scripts/control_robot.py calibrate \ + --robot-path lerobot/configs/robot/moss.yaml \ + --robot-overrides '~cameras' --arms main_follower +``` + +Note: You can't run auto-calibration for the leader arm, since we removed the gears. Thus, you will need to manually calibrate the leader arm. It's less precise than auto-calibration, but precision is not as critical for the leader arm. + +**Manual calibration of leader arm** +Follow step 6 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the manual calibration. You will need to move the leader arm to these positions sequentially: + +| 1. Zero position | 2. Rotated position | 3. Rest position | +|---|---|---| +| Moss v1 leader arm zero position | Moss v1 leader arm rotated position | Moss v1 leader arm rest position | + +Run this script to launch manual calibration: +```bash +python lerobot/scripts/control_robot.py calibrate \ + --robot-path lerobot/configs/robot/moss.yaml \ + --robot-overrides '~cameras' --arms main_leader +``` + +## Teleoperate + +**Simple teleop** +Then you are ready to teleoperate your robot! Run this simple script (it won't connect and display the cameras): +```bash +python lerobot/scripts/control_robot.py teleoperate \ + --robot-path lerobot/configs/robot/moss.yaml \ + --robot-overrides '~cameras' \ + --display-cameras 0 +``` + + +**Teleop with displaying cameras** +Follow [this guide to setup your cameras](https://github.com/huggingface/lerobot/blob/main/examples/7_get_started_with_real_robot.md#c-add-your-cameras-with-opencvcamera). Then you will be able to display the cameras on your computer while you are teleoperating by running the following code. This is useful to prepare your setup before recording your first dataset. +```bash +python lerobot/scripts/control_robot.py teleoperate \ + --robot-path lerobot/configs/robot/moss.yaml +``` + +## Record a dataset + +Once you're familiar with teleoperation, you can record your first dataset with Moss v1. + +If you want to use the Hugging Face hub features for uploading your dataset and you haven't previously done it, make sure you've logged in using a write-access token, which can be generated from the [Hugging Face settings](https://huggingface.co/settings/tokens): +```bash +huggingface-cli login --token ${HUGGINGFACE_TOKEN} --add-to-git-credential +``` + +Store your Hugging Face repository name in a variable to run these commands: +```bash +HF_USER=$(huggingface-cli whoami | head -n 1) +echo $HF_USER +``` + +Record 2 episodes and upload your dataset to the hub: +```bash +python lerobot/scripts/control_robot.py record \ + --robot-path lerobot/configs/robot/moss.yaml \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/moss_test \ + --tags moss tutorial \ + --warmup-time-s 5 \ + --episode-time-s 40 \ + --reset-time-s 10 \ + --num-episodes 2 \ + --push-to-hub 1 +``` + +## Visualize a dataset + +If you uploaded your dataset to the hub with `--push-to-hub 1`, you can [visualize your dataset online](https://huggingface.co/spaces/lerobot/visualize_dataset) by copy pasting your repo id given by: +```bash +echo ${HF_USER}/moss_test +``` + +If you didn't upload with `--push-to-hub 0`, you can also visualize it locally with: +```bash +python lerobot/scripts/visualize_dataset_html.py \ + --root data \ + --repo-id ${HF_USER}/moss_test +``` + +## Replay an episode + +Now try to replay the first episode on your robot: +```bash +DATA_DIR=data python lerobot/scripts/control_robot.py replay \ + --robot-path lerobot/configs/robot/moss.yaml \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/moss_test \ + --episode 0 +``` + +## 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: +```bash +DATA_DIR=data python lerobot/scripts/train.py \ + dataset_repo_id=${HF_USER}/moss_test \ + policy=act_moss_real \ + env=moss_real \ + hydra.run.dir=outputs/train/act_moss_test \ + hydra.job.name=act_moss_test \ + device=cuda \ + wandb.enable=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=act_moss_real`. This loads configurations from [`lerobot/configs/policy/act_moss_real.yaml`](../lerobot/configs/policy/act_moss_real.yaml). Importantly, this policy uses 2 cameras as input `laptop`, `phone`. +3. We provided an environment as argument with `env=moss_real`. This loads configurations from [`lerobot/configs/env/moss_real.yaml`](../lerobot/configs/env/moss_real.yaml). +4. We provided `device=cuda` since we are training on a Nvidia GPU, but you can also use `device=mps` if you are using a Mac with Apple silicon, or `device=cpu` otherwise. +5. We provided `wandb.enable=true` to use [Weights and Biases](https://docs.wandb.ai/quickstart) for visualizing training plots. This is optional but if you use it, make sure you are logged in by running `wandb login`. +6. We added `DATA_DIR=data` to access your dataset stored in your local `data` directory. If you dont provide `DATA_DIR`, your dataset will be downloaded from Hugging Face hub to your cache folder `$HOME/.cache/hugginface`. In future versions of `lerobot`, both directories will be in sync. + +Training should take several hours. You will find checkpoints in `outputs/train/act_moss_test/checkpoints`. + +## Evaluate your policy + +You can use the `record` function from [`lerobot/scripts/control_robot.py`](../lerobot/scripts/control_robot.py) but with a policy checkpoint as input. For instance, run this command to record 10 evaluation episodes: +```bash +python lerobot/scripts/control_robot.py record \ + --robot-path lerobot/configs/robot/moss.yaml \ + --fps 30 \ + --root data \ + --repo-id ${HF_USER}/eval_act_moss_test \ + --tags moss tutorial eval \ + --warmup-time-s 5 \ + --episode-time-s 40 \ + --reset-time-s 10 \ + --num-episodes 10 \ + -p outputs/train/act_moss_test/checkpoints/last/pretrained_model +``` + +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 `-p` argument which indicates the path to your policy checkpoint with (e.g. `-p outputs/train/eval_moss_test/checkpoints/last/pretrained_model`). You can also use the model repository if you uploaded a model checkpoint to the hub (e.g. `-p ${HF_USER}/act_moss_test`). +2. The name of dataset begins by `eval` to reflect that you are running inference (e.g. `--repo-id ${HF_USER}/eval_act_moss_test`). + +## 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 tutorial on controlling real robots with LeRobot. + +If you have any question or need help, please reach out on Discord in the channel [`#moss-arm`](https://discord.com/channels/1216765309076115607/1275374638985252925). diff --git a/examples/7_get_started_with_real_robot.md b/examples/7_get_started_with_real_robot.md index 266e4f0da..9db7e2521 100644 --- a/examples/7_get_started_with_real_robot.md +++ b/examples/7_get_started_with_real_robot.md @@ -78,12 +78,12 @@ To begin, create two instances of the [`DynamixelMotorsBus`](../lerobot/common/ To find the correct ports for each arm, run the utility script twice: ```bash -python lerobot/common/robot_devices/motors/dynamixel.py +python lerobot/scripts/find_motors_bus_port.py ``` Example output when identifying the leader arm's port (e.g., `/dev/tty.usbmodem575E0031751` on Mac, or possibly `/dev/ttyACM0` on Linux): ``` -Finding all available ports for the DynamixelMotorsBus. +Finding all available ports for the MotorBus. ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] Remove the usb cable from your DynamixelMotorsBus and press Enter when done. @@ -95,7 +95,7 @@ Reconnect the usb cable. Example output when identifying the follower arm's port (e.g., `/dev/tty.usbmodem575E0032081`, or possibly `/dev/ttyACM1` on Linux): ``` -Finding all available ports for the DynamixelMotorsBus. +Finding all available ports for the MotorBus. ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] Remove the usb cable from your DynamixelMotorsBus and press Enter when done. diff --git a/examples/8_use_stretch.md b/examples/8_use_stretch.md index fcd1cacee..97caf2ba8 100644 --- a/examples/8_use_stretch.md +++ b/examples/8_use_stretch.md @@ -50,7 +50,7 @@ cd ~/lerobot && pip install -e ".[stretch]" > **Note:** If you get this message, you can ignore it: `ERROR: pip's dependency resolver does not currently take into account all the packages that are installed.` -And install extra dependencies for recording datasets on Linux: +For Linux only (not Mac), install extra dependencies for recording datasets: ```bash conda install -y -c conda-forge ffmpeg pip uninstall -y opencv-python diff --git a/examples/9_use_aloha.md b/examples/9_use_aloha.md index d161978fd..cf5e1ceca 100644 --- a/examples/9_use_aloha.md +++ b/examples/9_use_aloha.md @@ -35,7 +35,7 @@ git clone https://github.com/huggingface/lerobot.git ~/lerobot cd ~/lerobot && pip install -e ".[dynamixel, intelrealsense]" ``` -And install extra dependencies for recording datasets on Linux: +For Linux only (not Mac), install extra dependencies for recording datasets: ```bash conda install -y -c conda-forge ffmpeg pip uninstall -y opencv-python diff --git a/lerobot/__init__.py b/lerobot/__init__.py index 5acd8aaad..d462c7337 100644 --- a/lerobot/__init__.py +++ b/lerobot/__init__.py @@ -198,6 +198,8 @@ "koch", "koch_bimanual", "aloha", + "so100", + "moss", ] # lists all available cameras from `lerobot/common/robot_devices/cameras` @@ -209,6 +211,7 @@ # lists all available motors from `lerobot/common/robot_devices/motors` available_motors = [ "dynamixel", + "feetech", ] # keys and values refer to yaml files diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/robot_devices/cameras/intelrealsense.py index 66c7fe5cb..479694277 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/robot_devices/cameras/intelrealsense.py @@ -21,9 +21,9 @@ from lerobot.common.robot_devices.utils import ( RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError, + busy_wait, ) from lerobot.common.utils.utils import capture_timestamp_utc -from lerobot.scripts.control_robot import busy_wait SERIAL_NUMBER_INDEX = 1 diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/robot_devices/motors/dynamixel.py index 815b4986a..1e1396f76 100644 --- a/lerobot/common/robot_devices/motors/dynamixel.py +++ b/lerobot/common/robot_devices/motors/dynamixel.py @@ -4,7 +4,6 @@ import time import traceback from copy import deepcopy -from pathlib import Path import numpy as np import tqdm @@ -229,35 +228,6 @@ def assert_same_address(model_ctrl_table, motor_models, data_name): ) -def find_available_ports(): - ports = [] - for path in Path("/dev").glob("tty*"): - ports.append(str(path)) - return ports - - -def find_port(): - print("Finding all available ports for the DynamixelMotorsBus.") - ports_before = find_available_ports() - print(ports_before) - - print("Remove the usb cable from your DynamixelMotorsBus and press Enter when done.") - input() - - time.sleep(0.5) - ports_after = find_available_ports() - ports_diff = list(set(ports_before) - set(ports_after)) - - if len(ports_diff) == 1: - port = ports_diff[0] - print(f"The port of this DynamixelMotorsBus is '{port}'") - print("Reconnect the usb cable.") - elif len(ports_diff) == 0: - raise OSError(f"Could not detect the port. No difference was found ({ports_diff}).") - else: - raise OSError(f"Could not detect the port. More than one port was found ({ports_diff}).") - - class TorqueMode(enum.Enum): ENABLED = 1 DISABLED = 0 @@ -290,8 +260,8 @@ class DynamixelMotorsBus: A DynamixelMotorsBus instance requires a port (e.g. `DynamixelMotorsBus(port="/dev/tty.usbmodem575E0031751"`)). To find the port, you can run our utility script: ```bash - python lerobot/common/robot_devices/motors/dynamixel.py - >>> Finding all available ports for the DynamixelMotorsBus. + python lerobot/scripts/find_motors_bus_port.py + >>> Finding all available ports for the MotorBus. >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] >>> Remove the usb cable from your DynamixelMotorsBus and press Enter when done. >>> The port of this DynamixelMotorsBus is /dev/tty.usbmodem575E0031751. @@ -369,7 +339,7 @@ def connect(self): except Exception: traceback.print_exc() print( - "\nTry running `python lerobot/common/robot_devices/motors/dynamixel.py` to make sure you are using the correct port.\n" + "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n" ) raise @@ -378,20 +348,6 @@ def connect(self): self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS) - # Set expected baudrate for the bus - self.set_bus_baudrate(BAUDRATE) - - if not self.are_motors_configured(): - input( - "\n/!\\ A configuration issue has been detected with your motors: \n" - "If it's the first time that you use these motors, press enter to configure your motors... but before " - "verify that all the cables are connected the proper way. If you find an issue, before making a modification, " - "kill the python process, unplug the power cord to not damage the motors, rewire correctly, then plug the power " - "again and relaunch the script.\n" - ) - print() - self.configure_motors() - def reconnect(self): if self.mock: import tests.mock_dynamixel_sdk as dxl @@ -415,120 +371,14 @@ def are_motors_configured(self): print(e) return False - def configure_motors(self): - # TODO(rcadene): This script assumes motors follow the X_SERIES baudrates - # TODO(rcadene): Refactor this function with intermediate high-level functions - - print("Scanning all baudrates and motor indices") - all_baudrates = set(X_SERIES_BAUDRATE_TABLE.values()) - ids_per_baudrate = {} - for baudrate in all_baudrates: - self.set_bus_baudrate(baudrate) - present_ids = self.find_motor_indices() - if len(present_ids) > 0: - ids_per_baudrate[baudrate] = present_ids - print(f"Motor indices detected: {ids_per_baudrate}") - print() - - possible_baudrates = list(ids_per_baudrate.keys()) - possible_ids = list({idx for sublist in ids_per_baudrate.values() for idx in sublist}) - untaken_ids = list(set(range(MAX_ID_RANGE)) - set(possible_ids) - set(self.motor_indices)) - - # Connect successively one motor to the chain and write a unique random index for each - for i in range(len(self.motors)): - self.disconnect() - input( - "1. Unplug the power cord\n" - "2. Plug/unplug minimal number of cables to only have the first " - f"{i+1} motor(s) ({self.motor_names[:i+1]}) connected.\n" - "3. Re-plug the power cord\n" - "Press Enter to continue..." - ) - print() - self.reconnect() - - if i > 0: - try: - self._read_with_motor_ids(self.motor_models, untaken_ids[:i], "ID") - except ConnectionError: - print(f"Failed to read from {untaken_ids[:i+1]}. Make sure the power cord is plugged in.") - input("Press Enter to continue...") - print() - self.reconnect() - - print("Scanning possible baudrates and motor indices") - motor_found = False - for baudrate in possible_baudrates: - self.set_bus_baudrate(baudrate) - present_ids = self.find_motor_indices(possible_ids) - if len(present_ids) == 1: - present_idx = present_ids[0] - print(f"Detected motor with index {present_idx}") - - if baudrate != BAUDRATE: - print(f"Setting its baudrate to {BAUDRATE}") - baudrate_idx = list(X_SERIES_BAUDRATE_TABLE.values()).index(BAUDRATE) - - # The write can fail, so we allow retries - for _ in range(NUM_WRITE_RETRY): - self._write_with_motor_ids( - self.motor_models, present_idx, "Baud_Rate", baudrate_idx - ) - time.sleep(0.5) - self.set_bus_baudrate(BAUDRATE) - try: - present_baudrate_idx = self._read_with_motor_ids( - self.motor_models, present_idx, "Baud_Rate" - ) - except ConnectionError: - print("Failed to write baudrate. Retrying.") - self.set_bus_baudrate(baudrate) - continue - break - else: - raise - - if present_baudrate_idx != baudrate_idx: - raise OSError("Failed to write baudrate.") - - print(f"Setting its index to a temporary untaken index ({untaken_ids[i]})") - self._write_with_motor_ids(self.motor_models, present_idx, "ID", untaken_ids[i]) - - present_idx = self._read_with_motor_ids(self.motor_models, untaken_ids[i], "ID") - if present_idx != untaken_ids[i]: - raise OSError("Failed to write index.") - - motor_found = True - break - elif len(present_ids) > 1: - raise OSError(f"More than one motor detected ({present_ids}), but only one was expected.") - - if not motor_found: - raise OSError( - "No motor found, but one new motor expected. Verify power cord is plugged in and retry." - ) - print() - - print(f"Setting expected motor indices: {self.motor_indices}") - self.set_bus_baudrate(BAUDRATE) - self._write_with_motor_ids( - self.motor_models, untaken_ids[: len(self.motors)], "ID", self.motor_indices - ) - print() - - if (self.read("ID") != self.motor_indices).any(): - raise OSError("Failed to write motors indices.") - - print("Configuration is done!") - - def find_motor_indices(self, possible_ids=None): + def find_motor_indices(self, possible_ids=None, num_retry=2): if possible_ids is None: possible_ids = range(MAX_ID_RANGE) indices = [] for idx in tqdm.tqdm(possible_ids): try: - present_idx = self._read_with_motor_ids(self.motor_models, [idx], "ID")[0] + present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0] except ConnectionError: continue @@ -788,7 +638,7 @@ def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | values = np.round(values).astype(np.int32) return values - def _read_with_motor_ids(self, motor_models, motor_ids, data_name): + def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY): if self.mock: import tests.mock_dynamixel_sdk as dxl else: @@ -805,7 +655,11 @@ def _read_with_motor_ids(self, motor_models, motor_ids, data_name): for idx in motor_ids: group.addParam(idx) - comm = group.txRxPacket() + for _ in range(num_retry): + comm = group.txRxPacket() + if comm == dxl.COMM_SUCCESS: + break + if comm != dxl.COMM_SUCCESS: raise ConnectionError( f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: " @@ -895,7 +749,7 @@ def read(self, data_name, motor_names: str | list[str] | None = None): return values - def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values): + def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY): if self.mock: import tests.mock_dynamixel_sdk as dxl else: @@ -913,7 +767,11 @@ def _write_with_motor_ids(self, motor_models, motor_ids, data_name, values): data = convert_to_bytes(value, bytes, self.mock) group.addParam(idx, data) - comm = group.txPacket() + for _ in range(num_retry): + comm = group.txPacket() + if comm == dxl.COMM_SUCCESS: + break + if comm != dxl.COMM_SUCCESS: raise ConnectionError( f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: " @@ -1007,8 +865,3 @@ def disconnect(self): def __del__(self): if getattr(self, "is_connected", False): self.disconnect() - - -if __name__ == "__main__": - # Helper to find the usb port associated to all your DynamixelMotorsBus. - find_port() diff --git a/lerobot/common/robot_devices/motors/feetech.py b/lerobot/common/robot_devices/motors/feetech.py new file mode 100644 index 000000000..0d5480f7a --- /dev/null +++ b/lerobot/common/robot_devices/motors/feetech.py @@ -0,0 +1,887 @@ +import enum +import logging +import math +import time +import traceback +from copy import deepcopy + +import numpy as np +import tqdm + +from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.utils.utils import capture_timestamp_utc + +PROTOCOL_VERSION = 0 +BAUDRATE = 1_000_000 +TIMEOUT_MS = 1000 + +MAX_ID_RANGE = 252 + +# The following bounds define the lower and upper joints range (after calibration). +# For joints in degree (i.e. revolute joints), their nominal range is [-180, 180] degrees +# which corresponds to a half rotation on the left and half rotation on the right. +# Some joints might require higher range, so we allow up to [-270, 270] degrees until +# an error is raised. +LOWER_BOUND_DEGREE = -270 +UPPER_BOUND_DEGREE = 270 +# For joints in percentage (i.e. joints that move linearly like the prismatic joint of a gripper), +# their nominal range is [0, 100] %. For instance, for Aloha gripper, 0% is fully +# closed, and 100% is fully open. To account for slight calibration issue, we allow up to +# [-10, 110] until an error is raised. +LOWER_BOUND_LINEAR = -10 +UPPER_BOUND_LINEAR = 110 + +HALF_TURN_DEGREE = 180 + + +# See this link for STS3215 Memory Table: +# https://docs.google.com/spreadsheets/d/1GVs7W1VS1PqdhA1nW-abeyAHhTUxKUdR/edit?usp=sharing&ouid=116566590112741600240&rtpof=true&sd=true +# data_name: (address, size_byte) +SCS_SERIES_CONTROL_TABLE = { + "Model": (3, 2), + "ID": (5, 1), + "Baud_Rate": (6, 1), + "Return_Delay": (7, 1), + "Response_Status_Level": (8, 1), + "Min_Angle_Limit": (9, 2), + "Max_Angle_Limit": (11, 2), + "Max_Temperature_Limit": (13, 1), + "Max_Voltage_Limit": (14, 1), + "Min_Voltage_Limit": (15, 1), + "Max_Torque_Limit": (16, 2), + "Phase": (18, 1), + "Unloading_Condition": (19, 1), + "LED_Alarm_Condition": (20, 1), + "P_Coefficient": (21, 1), + "D_Coefficient": (22, 1), + "I_Coefficient": (23, 1), + "Minimum_Startup_Force": (24, 2), + "CW_Dead_Zone": (26, 1), + "CCW_Dead_Zone": (27, 1), + "Protection_Current": (28, 2), + "Angular_Resolution": (30, 1), + "Offset": (31, 2), + "Mode": (33, 1), + "Protective_Torque": (34, 1), + "Protection_Time": (35, 1), + "Overload_Torque": (36, 1), + "Speed_closed_loop_P_proportional_coefficient": (37, 1), + "Over_Current_Protection_Time": (38, 1), + "Velocity_closed_loop_I_integral_coefficient": (39, 1), + "Torque_Enable": (40, 1), + "Acceleration": (41, 1), + "Goal_Position": (42, 2), + "Goal_Time": (44, 2), + "Goal_Speed": (46, 2), + "Torque_Limit": (48, 2), + "Lock": (55, 1), + "Present_Position": (56, 2), + "Present_Speed": (58, 2), + "Present_Load": (60, 2), + "Present_Voltage": (62, 1), + "Present_Temperature": (63, 1), + "Status": (65, 1), + "Moving": (66, 1), + "Present_Current": (69, 2), + # Not in the Memory Table + "Maximum_Acceleration": (85, 2), +} + +SCS_SERIES_BAUDRATE_TABLE = { + 0: 1_000_000, + 1: 500_000, + 2: 250_000, + 3: 128_000, + 4: 115_200, + 5: 57_600, + 6: 38_400, + 7: 19_200, +} + +CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"] +CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"] + + +MODEL_CONTROL_TABLE = { + "scs_series": SCS_SERIES_CONTROL_TABLE, + "sts3215": SCS_SERIES_CONTROL_TABLE, +} + +MODEL_RESOLUTION = { + "scs_series": 4096, + "sts3215": 4096, +} + +MODEL_BAUDRATE_TABLE = { + "scs_series": SCS_SERIES_BAUDRATE_TABLE, + "sts3215": SCS_SERIES_BAUDRATE_TABLE, +} + +# High number of retries is needed for feetech compared to dynamixel motors. +NUM_READ_RETRY = 20 +NUM_WRITE_RETRY = 20 + + +def convert_degrees_to_steps(degrees: float | np.ndarray, models: str | list[str]) -> np.ndarray: + """This function converts the degree range to the step range for indicating motors rotation. + It assumes a motor achieves a full rotation by going from -180 degree position to +180. + The motor resolution (e.g. 4096) corresponds to the number of steps needed to achieve a full rotation. + """ + resolutions = [MODEL_RESOLUTION[model] for model in models] + steps = degrees / 180 * np.array(resolutions) / 2 + steps = steps.astype(int) + return steps + + +def convert_to_bytes(value, bytes, mock=False): + if mock: + return value + + import scservo_sdk as scs + + # Note: No need to convert back into unsigned int, since this byte preprocessing + # already handles it for us. + if bytes == 1: + data = [ + scs.SCS_LOBYTE(scs.SCS_LOWORD(value)), + ] + elif bytes == 2: + data = [ + scs.SCS_LOBYTE(scs.SCS_LOWORD(value)), + scs.SCS_HIBYTE(scs.SCS_LOWORD(value)), + ] + elif bytes == 4: + data = [ + scs.SCS_LOBYTE(scs.SCS_LOWORD(value)), + scs.SCS_HIBYTE(scs.SCS_LOWORD(value)), + scs.SCS_LOBYTE(scs.SCS_HIWORD(value)), + scs.SCS_HIBYTE(scs.SCS_HIWORD(value)), + ] + else: + raise NotImplementedError( + f"Value of the number of bytes to be sent is expected to be in [1, 2, 4], but " + f"{bytes} is provided instead." + ) + return data + + +def get_group_sync_key(data_name, motor_names): + group_key = f"{data_name}_" + "_".join(motor_names) + return group_key + + +def get_result_name(fn_name, data_name, motor_names): + group_key = get_group_sync_key(data_name, motor_names) + rslt_name = f"{fn_name}_{group_key}" + return rslt_name + + +def get_queue_name(fn_name, data_name, motor_names): + group_key = get_group_sync_key(data_name, motor_names) + queue_name = f"{fn_name}_{group_key}" + return queue_name + + +def get_log_name(var_name, fn_name, data_name, motor_names): + group_key = get_group_sync_key(data_name, motor_names) + log_name = f"{var_name}_{fn_name}_{group_key}" + return log_name + + +def assert_same_address(model_ctrl_table, motor_models, data_name): + all_addr = [] + all_bytes = [] + for model in motor_models: + addr, bytes = model_ctrl_table[model][data_name] + all_addr.append(addr) + all_bytes.append(bytes) + + if len(set(all_addr)) != 1: + raise NotImplementedError( + f"At least two motor models use a different address for `data_name`='{data_name}' ({list(zip(motor_models, all_addr, strict=False))}). Contact a LeRobot maintainer." + ) + + if len(set(all_bytes)) != 1: + raise NotImplementedError( + f"At least two motor models use a different bytes representation for `data_name`='{data_name}' ({list(zip(motor_models, all_bytes, strict=False))}). Contact a LeRobot maintainer." + ) + + +class TorqueMode(enum.Enum): + ENABLED = 1 + DISABLED = 0 + + +class DriveMode(enum.Enum): + NON_INVERTED = 0 + INVERTED = 1 + + +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] + LINEAR = 1 + + +class JointOutOfRangeError(Exception): + def __init__(self, message="Joint is out of range"): + self.message = message + super().__init__(self.message) + + +class FeetechMotorsBus: + """ + The FeetechMotorsBus class allows to efficiently read and write to the attached motors. It relies on + the python feetech sdk to communicate with the motors. For more info, see the [feetech SDK Documentation](https://emanual.robotis.com/docs/en/software/feetech/feetech_sdk/sample_code/python_read_write_protocol_2_0/#python-read-write-protocol-20). + + A FeetechMotorsBus instance requires a port (e.g. `FeetechMotorsBus(port="/dev/tty.usbmodem575E0031751"`)). + To find the port, you can run our utility script: + ```bash + python lerobot/scripts/find_motors_bus_port.py + >>> Finding all available ports for the MotorsBus. + >>> ['/dev/tty.usbmodem575E0032081', '/dev/tty.usbmodem575E0031751'] + >>> Remove the usb cable from your FeetechMotorsBus and press Enter when done. + >>> The port of this FeetechMotorsBus is /dev/tty.usbmodem575E0031751. + >>> Reconnect the usb cable. + ``` + + Example of usage for 1 motor connected to the bus: + ```python + motor_name = "gripper" + motor_index = 6 + motor_model = "sts3215" + + motors_bus = FeetechMotorsBus( + port="/dev/tty.usbmodem575E0031751", + motors={motor_name: (motor_index, motor_model)}, + ) + motors_bus.connect() + + position = motors_bus.read("Present_Position") + + # move from a few motor steps as an example + few_steps = 30 + motors_bus.write("Goal_Position", position + few_steps) + + # when done, consider disconnecting + motors_bus.disconnect() + ``` + """ + + def __init__( + self, + port: str, + motors: dict[str, tuple[int, str]], + extra_model_control_table: dict[str, list[tuple]] | None = None, + extra_model_resolution: dict[str, int] | None = None, + mock=False, + ): + self.port = port + self.motors = motors + self.mock = mock + + self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE) + if extra_model_control_table: + self.model_ctrl_table.update(extra_model_control_table) + + self.model_resolution = deepcopy(MODEL_RESOLUTION) + if extra_model_resolution: + self.model_resolution.update(extra_model_resolution) + + self.port_handler = None + self.packet_handler = None + self.calibration = None + self.is_connected = False + self.group_readers = {} + self.group_writers = {} + self.logs = {} + + self.track_positions = {} + + def connect(self): + if self.is_connected: + raise RobotDeviceAlreadyConnectedError( + f"FeetechMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice." + ) + + if self.mock: + import tests.mock_scservo_sdk as scs + else: + import scservo_sdk as scs + + self.port_handler = scs.PortHandler(self.port) + self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION) + + try: + if not self.port_handler.openPort(): + raise OSError(f"Failed to open port '{self.port}'.") + except Exception: + traceback.print_exc() + print( + "\nTry running `python lerobot/scripts/find_motors_bus_port.py` to make sure you are using the correct port.\n" + ) + raise + + # Allow to read and write + self.is_connected = True + + self.port_handler.setPacketTimeoutMillis(TIMEOUT_MS) + + def reconnect(self): + if self.mock: + import tests.mock_scservo_sdk as scs + else: + import scservo_sdk as scs + + self.port_handler = scs.PortHandler(self.port) + self.packet_handler = scs.PacketHandler(PROTOCOL_VERSION) + + if not self.port_handler.openPort(): + raise OSError(f"Failed to open port '{self.port}'.") + + self.is_connected = True + + def are_motors_configured(self): + # Only check the motor indices and not baudrate, since if the motor baudrates are incorrect, + # a ConnectionError will be raised anyway. + try: + return (self.motor_indices == self.read("ID")).all() + except ConnectionError as e: + print(e) + return False + + def find_motor_indices(self, possible_ids=None, num_retry=2): + if possible_ids is None: + possible_ids = range(MAX_ID_RANGE) + + indices = [] + for idx in tqdm.tqdm(possible_ids): + try: + present_idx = self.read_with_motor_ids(self.motor_models, [idx], "ID", num_retry=num_retry)[0] + except ConnectionError: + continue + + if idx != present_idx: + # sanity check + raise OSError( + "Motor index used to communicate through the bus is not the same as the one present in the motor memory. The motor memory might be damaged." + ) + indices.append(idx) + + return indices + + def set_bus_baudrate(self, baudrate): + present_bus_baudrate = self.port_handler.getBaudRate() + if present_bus_baudrate != baudrate: + print(f"Setting bus baud rate to {baudrate}. Previously {present_bus_baudrate}.") + self.port_handler.setBaudRate(baudrate) + + if self.port_handler.getBaudRate() != baudrate: + raise OSError("Failed to write bus baud rate.") + + @property + def motor_names(self) -> list[str]: + return list(self.motors.keys()) + + @property + def motor_models(self) -> list[str]: + return [model for _, model in self.motors.values()] + + @property + def motor_indices(self) -> list[int]: + return [idx for idx, _ in self.motors.values()] + + def set_calibration(self, calibration: dict[str, list]): + self.calibration = calibration + + def apply_calibration_autocorrect(self, values: np.ndarray | list, motor_names: list[str] | None): + """This function apply the calibration, automatically detects out of range errors for motors values and attempt to correct. + + For more info, see docstring of `apply_calibration` and `autocorrect_calibration`. + """ + try: + values = self.apply_calibration(values, motor_names) + except JointOutOfRangeError as e: + print(e) + self.autocorrect_calibration(values, motor_names) + values = self.apply_calibration(values, motor_names) + return values + + def apply_calibration(self, values: np.ndarray | list, motor_names: list[str] | None): + """Convert from unsigned int32 joint position range [0, 2**32[ to the universal float32 nominal degree range ]-180.0, 180.0[ with + a "zero position" at 0 degree. + + Note: We say "nominal degree range" since the motors can take values outside this range. For instance, 190 degrees, if the motor + rotate more than a half a turn from the zero position. However, most motors can't rotate more than 180 degrees and will stay in this range. + + Joints values are original in [0, 2**32[ (unsigned int32). Each motor are expected to complete a full rotation + when given a goal position that is + or - their resolution. For instance, feetech xl330-m077 have a resolution of 4096, and + at any position in their original range, let's say the position 56734, they complete a full rotation clockwise by moving to 60830, + or anticlockwise by moving to 52638. The position in the original range is arbitrary and might change a lot between each motor. + To harmonize between motors of the same model, different robots, or even models of different brands, we propose to work + in the centered nominal degree range ]-180, 180[. + """ + if motor_names is None: + motor_names = self.motor_names + + # Convert from unsigned int32 original range [0, 2**32] to signed float32 range + values = values.astype(np.float32) + + for i, name in enumerate(motor_names): + calib_idx = self.calibration["motor_names"].index(name) + calib_mode = self.calibration["calib_mode"][calib_idx] + + if CalibrationMode[calib_mode] == CalibrationMode.DEGREE: + drive_mode = self.calibration["drive_mode"][calib_idx] + homing_offset = self.calibration["homing_offset"][calib_idx] + _, model = self.motors[name] + resolution = self.model_resolution[model] + + # Update direction of rotation of the motor to match between leader and follower. + # In fact, the motor of the leader for a given joint can be assembled in an + # opposite direction in term of rotation than the motor of the follower on the same joint. + if drive_mode: + values[i] *= -1 + + # Convert from range [-2**31, 2**31[ to + # nominal range ]-resolution, resolution[ (e.g. ]-2048, 2048[) + values[i] += homing_offset + + # Convert from range ]-resolution, resolution[ to + # universal float32 centered degree range ]-180, 180[ + values[i] = values[i] / (resolution // 2) * HALF_TURN_DEGREE + + if (values[i] < LOWER_BOUND_DEGREE) or (values[i] > UPPER_BOUND_DEGREE): + raise JointOutOfRangeError( + f"Wrong motor position range detected for {name}. " + f"Expected to be in nominal range of [-{HALF_TURN_DEGREE}, {HALF_TURN_DEGREE}] degrees (a full rotation), " + f"with a maximum range of [{LOWER_BOUND_DEGREE}, {UPPER_BOUND_DEGREE}] degrees to account for joints that can rotate a bit more, " + f"but present value is {values[i]} degree. " + "This might be due to a cable connection issue creating an artificial 360 degrees jump in motor values. " + "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`" + ) + + elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR: + start_pos = self.calibration["start_pos"][calib_idx] + end_pos = self.calibration["end_pos"][calib_idx] + + # Rescale the present position to a nominal range [0, 100] %, + # useful for joints with linear motions like Aloha gripper + values[i] = (values[i] - start_pos) / (end_pos - start_pos) * 100 + + if (values[i] < LOWER_BOUND_LINEAR) or (values[i] > UPPER_BOUND_LINEAR): + raise JointOutOfRangeError( + f"Wrong motor position range detected for {name}. " + f"Expected to be in nominal range of [0, 100] % (a full linear translation), " + f"with a maximum range of [{LOWER_BOUND_LINEAR}, {UPPER_BOUND_LINEAR}] % to account for some imprecision during calibration, " + f"but present value is {values[i]} %. " + "This might be due to a cable connection issue creating an artificial jump in motor values. " + "You need to recalibrate by running: `python lerobot/scripts/control_robot.py calibrate`" + ) + + return values + + def autocorrect_calibration(self, values: np.ndarray | list, motor_names: list[str] | None): + """This function automatically detects issues with values of motors after calibration, and correct for these issues. + + Some motors might have values outside of expected maximum bounds after calibration. + For instance, for a joint in degree, its value can be outside [-270, 270] degrees, which is totally unexpected given + a nominal range of [-180, 180] degrees, which represents half a turn to the left or right starting from zero position. + + Known issues: + #1: Motor value randomly shifts of a full turn, caused by hardware/connection errors. + #2: Motor internal homing offset is shifted of a full turn, caused by using default calibration (e.g Aloha). + #3: motor internal homing offset is shifted of less or more than a full turn, caused by using default calibration + or by human error during manual calibration. + + Issues #1 and #2 can be solved by shifting the calibration homing offset by a full turn. + Issue #3 will be visually detected by user and potentially captured by the safety feature `max_relative_target`, + that will slow down the motor, raise an error asking to recalibrate. Manual recalibrating will solve the issue. + + Note: A full turn corresponds to 360 degrees but also to 4096 steps for a motor resolution of 4096. + """ + if motor_names is None: + motor_names = self.motor_names + + # Convert from unsigned int32 original range [0, 2**32] to signed float32 range + values = values.astype(np.float32) + + for i, name in enumerate(motor_names): + calib_idx = self.calibration["motor_names"].index(name) + calib_mode = self.calibration["calib_mode"][calib_idx] + + if CalibrationMode[calib_mode] == CalibrationMode.DEGREE: + drive_mode = self.calibration["drive_mode"][calib_idx] + homing_offset = self.calibration["homing_offset"][calib_idx] + _, model = self.motors[name] + resolution = self.model_resolution[model] + + if drive_mode: + values[i] *= -1 + + # Convert from initial range to range [-180, 180] degrees + calib_val = (values[i] + homing_offset) / (resolution // 2) * HALF_TURN_DEGREE + in_range = (calib_val > LOWER_BOUND_DEGREE) and (calib_val < UPPER_BOUND_DEGREE) + + # Solve this inequality to find the factor to shift the range into [-180, 180] degrees + # values[i] = (values[i] + homing_offset + resolution * factor) / (resolution // 2) * HALF_TURN_DEGREE + # - HALF_TURN_DEGREE <= (values[i] + homing_offset + resolution * factor) / (resolution // 2) * HALF_TURN_DEGREE <= HALF_TURN_DEGREE + # (- HALF_TURN_DEGREE / HALF_TURN_DEGREE * (resolution // 2) - values[i] - homing_offset) / resolution <= factor <= (HALF_TURN_DEGREE / 180 * (resolution // 2) - values[i] - homing_offset) / resolution + low_factor = ( + -HALF_TURN_DEGREE / HALF_TURN_DEGREE * (resolution // 2) - values[i] - homing_offset + ) / resolution + upp_factor = ( + HALF_TURN_DEGREE / HALF_TURN_DEGREE * (resolution // 2) - values[i] - homing_offset + ) / resolution + + elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR: + start_pos = self.calibration["start_pos"][calib_idx] + end_pos = self.calibration["end_pos"][calib_idx] + + # Convert from initial range to range [0, 100] in % + calib_val = (values[i] - start_pos) / (end_pos - start_pos) * 100 + in_range = (calib_val > LOWER_BOUND_LINEAR) and (calib_val < UPPER_BOUND_LINEAR) + + # Solve this inequality to find the factor to shift the range into [0, 100] % + # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos + resolution * factor - start_pos - resolution * factor) * 100 + # values[i] = (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100 + # 0 <= (values[i] - start_pos + resolution * factor) / (end_pos - start_pos) * 100 <= 100 + # (start_pos - values[i]) / resolution <= factor <= (end_pos - values[i]) / resolution + low_factor = (start_pos - values[i]) / resolution + upp_factor = (end_pos - values[i]) / resolution + + if not in_range: + # Get first integer between the two bounds + if low_factor < upp_factor: + factor = math.ceil(low_factor) + + if factor > upp_factor: + raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]") + else: + factor = math.ceil(upp_factor) + + if factor > low_factor: + raise ValueError(f"No integer found between bounds [{low_factor=}, {upp_factor=}]") + + if CalibrationMode[calib_mode] == CalibrationMode.DEGREE: + out_of_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees" + in_range_str = f"{LOWER_BOUND_DEGREE} < {calib_val} < {UPPER_BOUND_DEGREE} degrees" + elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR: + out_of_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %" + in_range_str = f"{LOWER_BOUND_LINEAR} < {calib_val} < {UPPER_BOUND_LINEAR} %" + + logging.warning( + f"Auto-correct calibration of motor '{name}' by shifting value by {abs(factor)} full turns, " + f"from '{out_of_range_str}' to '{in_range_str}'." + ) + + # A full turn corresponds to 360 degrees but also to 4096 steps for a motor resolution of 4096. + self.calibration["homing_offset"][calib_idx] += resolution * factor + + def revert_calibration(self, values: np.ndarray | list, motor_names: list[str] | None): + """Inverse of `apply_calibration`.""" + if motor_names is None: + motor_names = self.motor_names + + for i, name in enumerate(motor_names): + calib_idx = self.calibration["motor_names"].index(name) + calib_mode = self.calibration["calib_mode"][calib_idx] + + if CalibrationMode[calib_mode] == CalibrationMode.DEGREE: + drive_mode = self.calibration["drive_mode"][calib_idx] + homing_offset = self.calibration["homing_offset"][calib_idx] + _, model = self.motors[name] + resolution = self.model_resolution[model] + + # Convert from nominal 0-centered degree range [-180, 180] to + # 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 + # which can be arbitrary. + values[i] -= homing_offset + + # Remove drive mode, which is the rotation direction of the motor, to come back to + # actual motor rotation direction which can be arbitrary. + if drive_mode: + values[i] *= -1 + + elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR: + start_pos = self.calibration["start_pos"][calib_idx] + end_pos = self.calibration["end_pos"][calib_idx] + + # Convert from nominal lnear range of [0, 100] % to + # actual motor range of values which can be arbitrary. + values[i] = values[i] / 100 * (end_pos - start_pos) + start_pos + + values = np.round(values).astype(np.int32) + return values + + def avoid_rotation_reset(self, values, motor_names, data_name): + if data_name not in self.track_positions: + self.track_positions[data_name] = { + "prev": [None] * len(self.motor_names), + # Assume False at initialization + "below_zero": [False] * len(self.motor_names), + "above_max": [False] * len(self.motor_names), + } + + track = self.track_positions[data_name] + + if motor_names is None: + motor_names = self.motor_names + + for i, name in enumerate(motor_names): + idx = self.motor_names.index(name) + + if track["prev"][idx] is None: + track["prev"][idx] = values[i] + continue + + # Detect a full rotation occured + if abs(track["prev"][idx] - values[i]) > 2048: + # Position went below 0 and got reset to 4095 + if track["prev"][idx] < values[i]: + # So we set negative value by adding a full rotation + values[i] -= 4096 + + # Position went above 4095 and got reset to 0 + elif track["prev"][idx] > values[i]: + # So we add a full rotation + values[i] += 4096 + + track["prev"][idx] = values[i] + + return values + + def read_with_motor_ids(self, motor_models, motor_ids, data_name, num_retry=NUM_READ_RETRY): + if self.mock: + import tests.mock_scservo_sdk as scs + else: + import scservo_sdk as scs + + return_list = True + if not isinstance(motor_ids, list): + return_list = False + motor_ids = [motor_ids] + + assert_same_address(self.model_ctrl_table, self.motor_models, data_name) + addr, bytes = self.model_ctrl_table[motor_models[0]][data_name] + group = scs.GroupSyncRead(self.port_handler, self.packet_handler, addr, bytes) + for idx in motor_ids: + group.addParam(idx) + + for _ in range(num_retry): + comm = group.txRxPacket() + if comm == scs.COMM_SUCCESS: + break + + if comm != scs.COMM_SUCCESS: + raise ConnectionError( + f"Read failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: " + f"{self.packet_handler.getTxRxResult(comm)}" + ) + + values = [] + for idx in motor_ids: + value = group.getData(idx, addr, bytes) + values.append(value) + + if return_list: + return values + else: + return values[0] + + def read(self, data_name, motor_names: str | list[str] | None = None): + if self.mock: + import tests.mock_scservo_sdk as scs + else: + import scservo_sdk as scs + + if not self.is_connected: + raise RobotDeviceNotConnectedError( + f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`." + ) + + start_time = time.perf_counter() + + if motor_names is None: + motor_names = self.motor_names + + if isinstance(motor_names, str): + motor_names = [motor_names] + + motor_ids = [] + models = [] + for name in motor_names: + motor_idx, model = self.motors[name] + motor_ids.append(motor_idx) + models.append(model) + + assert_same_address(self.model_ctrl_table, models, data_name) + addr, bytes = self.model_ctrl_table[model][data_name] + group_key = get_group_sync_key(data_name, motor_names) + + if data_name not in self.group_readers: + # create new group reader + self.group_readers[group_key] = scs.GroupSyncRead( + self.port_handler, self.packet_handler, addr, bytes + ) + for idx in motor_ids: + self.group_readers[group_key].addParam(idx) + + for _ in range(NUM_READ_RETRY): + comm = self.group_readers[group_key].txRxPacket() + if comm == scs.COMM_SUCCESS: + break + + if comm != scs.COMM_SUCCESS: + raise ConnectionError( + f"Read failed due to communication error on port {self.port} for group_key {group_key}: " + f"{self.packet_handler.getTxRxResult(comm)}" + ) + + values = [] + for idx in motor_ids: + value = self.group_readers[group_key].getData(idx, addr, bytes) + values.append(value) + + values = np.array(values) + + # Convert to signed int to use range [-2048, 2048] for our motor positions. + if data_name in CONVERT_UINT32_TO_INT32_REQUIRED: + values = values.astype(np.int32) + + if data_name in CALIBRATION_REQUIRED: + values = self.avoid_rotation_reset(values, motor_names, data_name) + + if data_name in CALIBRATION_REQUIRED and self.calibration is not None: + values = self.apply_calibration_autocorrect(values, motor_names) + + # log the number of seconds it took to read the data from the motors + delta_ts_name = get_log_name("delta_timestamp_s", "read", data_name, motor_names) + self.logs[delta_ts_name] = time.perf_counter() - start_time + + # log the utc time at which the data was received + ts_utc_name = get_log_name("timestamp_utc", "read", data_name, motor_names) + self.logs[ts_utc_name] = capture_timestamp_utc() + + return values + + def write_with_motor_ids(self, motor_models, motor_ids, data_name, values, num_retry=NUM_WRITE_RETRY): + if self.mock: + import tests.mock_scservo_sdk as scs + else: + import scservo_sdk as scs + + if not isinstance(motor_ids, list): + motor_ids = [motor_ids] + if not isinstance(values, list): + values = [values] + + assert_same_address(self.model_ctrl_table, motor_models, data_name) + addr, bytes = self.model_ctrl_table[motor_models[0]][data_name] + group = scs.GroupSyncWrite(self.port_handler, self.packet_handler, addr, bytes) + for idx, value in zip(motor_ids, values, strict=True): + data = convert_to_bytes(value, bytes, self.mock) + group.addParam(idx, data) + + for _ in range(num_retry): + comm = group.txPacket() + if comm == scs.COMM_SUCCESS: + break + + if comm != scs.COMM_SUCCESS: + raise ConnectionError( + f"Write failed due to communication error on port {self.port_handler.port_name} for indices {motor_ids}: " + f"{self.packet_handler.getTxRxResult(comm)}" + ) + + def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None): + if not self.is_connected: + raise RobotDeviceNotConnectedError( + f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`." + ) + + start_time = time.perf_counter() + + if self.mock: + import tests.mock_scservo_sdk as scs + else: + import scservo_sdk as scs + + if motor_names is None: + motor_names = self.motor_names + + if isinstance(motor_names, str): + motor_names = [motor_names] + + if isinstance(values, (int, float, np.integer)): + values = [int(values)] * len(motor_names) + + values = np.array(values) + + motor_ids = [] + models = [] + for name in motor_names: + motor_idx, model = self.motors[name] + motor_ids.append(motor_idx) + models.append(model) + + if data_name in CALIBRATION_REQUIRED and self.calibration is not None: + values = self.revert_calibration(values, motor_names) + + values = values.tolist() + + assert_same_address(self.model_ctrl_table, models, data_name) + addr, bytes = self.model_ctrl_table[model][data_name] + group_key = get_group_sync_key(data_name, motor_names) + + init_group = data_name not in self.group_readers + if init_group: + self.group_writers[group_key] = scs.GroupSyncWrite( + self.port_handler, self.packet_handler, addr, bytes + ) + + for idx, value in zip(motor_ids, values, strict=True): + data = convert_to_bytes(value, bytes, self.mock) + if init_group: + self.group_writers[group_key].addParam(idx, data) + else: + self.group_writers[group_key].changeParam(idx, data) + + comm = self.group_writers[group_key].txPacket() + if comm != scs.COMM_SUCCESS: + raise ConnectionError( + f"Write failed due to communication error on port {self.port} for group_key {group_key}: " + f"{self.packet_handler.getTxRxResult(comm)}" + ) + + # log the number of seconds it took to write the data to the motors + delta_ts_name = get_log_name("delta_timestamp_s", "write", data_name, motor_names) + self.logs[delta_ts_name] = time.perf_counter() - start_time + + # TODO(rcadene): should we log the time before sending the write command? + # log the utc time when the write has been completed + ts_utc_name = get_log_name("timestamp_utc", "write", data_name, motor_names) + self.logs[ts_utc_name] = capture_timestamp_utc() + + def disconnect(self): + if not self.is_connected: + raise RobotDeviceNotConnectedError( + f"FeetechMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first." + ) + + if self.port_handler is not None: + self.port_handler.closePort() + self.port_handler = None + + self.packet_handler = None + self.group_readers = {} + self.group_writers = {} + self.is_connected = False + + def __del__(self): + if getattr(self, "is_connected", False): + self.disconnect() diff --git a/lerobot/common/robot_devices/robots/dynamixel_calibration.py b/lerobot/common/robot_devices/robots/dynamixel_calibration.py new file mode 100644 index 000000000..5c4932d2e --- /dev/null +++ b/lerobot/common/robot_devices/robots/dynamixel_calibration.py @@ -0,0 +1,130 @@ +"""Logic to calibrate a robot arm built with dynamixel motors""" +# TODO(rcadene, aliberts): move this logic into the robot code when refactoring + +import numpy as np + +from lerobot.common.robot_devices.motors.dynamixel import ( + CalibrationMode, + TorqueMode, + convert_degrees_to_steps, +) +from lerobot.common.robot_devices.motors.utils import MotorsBus + +URL_TEMPLATE = ( + "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp" +) + +# The following positions are provided in nominal degree range ]-180, +180[ +# For more info on these constants, see comments in the code where they get used. +ZERO_POSITION_DEGREE = 0 +ROTATED_POSITION_DEGREE = 90 + + +def assert_drive_mode(drive_mode): + # `drive_mode` is in [0,1] with 0 means original rotation direction for the motor, and 1 means inverted. + if not np.all(np.isin(drive_mode, [0, 1])): + raise ValueError(f"`drive_mode` contains values other than 0 or 1: ({drive_mode})") + + +def apply_drive_mode(position, drive_mode): + assert_drive_mode(drive_mode) + # Convert `drive_mode` from [0, 1] with 0 indicates original rotation direction and 1 inverted, + # to [-1, 1] with 1 indicates original rotation direction and -1 inverted. + signed_drive_mode = -(drive_mode * 2 - 1) + position *= signed_drive_mode + return position + + +def compute_nearest_rounded_position(position, models): + delta_turn = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, models) + nearest_pos = np.round(position.astype(float) / delta_turn) * delta_turn + return nearest_pos.astype(position.dtype) + + +def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): + """This function ensures that a neural network trained on data collected on a given robot + can work on another robot. For instance before calibration, setting a same goal position + for each motor of two different robots will get two very different positions. But after calibration, + the two robots will move to the same position.To this end, this function computes the homing offset + and the drive mode for each motor of a given robot. + + Homing offset is used to shift the motor position to a ]-2048, +2048[ nominal range (when the motor uses 2048 steps + to complete a half a turn). This range is set around an arbitrary "zero position" corresponding to all motor positions + being 0. During the calibration process, you will need to manually move the robot to this "zero position". + + Drive mode is used to invert the rotation direction of the motor. This is useful when some motors have been assembled + in the opposite orientation for some robots. During the calibration process, you will need to manually move the robot + to the "rotated position". + + After calibration, the homing offsets and drive modes are stored in a cache. + + Example of usage: + ```python + run_arm_calibration(arm, "koch", "left", "follower") + ``` + """ + if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any(): + raise ValueError("To run calibration, the torque must be disabled on all motors.") + + print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...") + + print("\nMove arm to zero position") + print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero")) + input("Press Enter to continue...") + + # We arbitrarily chose our zero target position to be a straight horizontal position with gripper upwards and closed. + # It is easy to identify and all motors are in a "quarter turn" position. Once calibration is done, this position will + # correspond to every motor angle being 0. If you set all 0 as Goal Position, the arm will move in this position. + zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.motor_models) + + # Compute homing offset so that `present_position + homing_offset ~= target_position`. + zero_pos = arm.read("Present_Position") + zero_nearest_pos = compute_nearest_rounded_position(zero_pos, arm.motor_models) + homing_offset = zero_target_pos - zero_nearest_pos + + # The rotated target position corresponds to a rotation of a quarter turn from the zero position. + # This allows to identify the rotation direction of each motor. + # 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 + # 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")) + input("Press Enter to continue...") + + rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models) + + # Find drive mode by rotating each motor by a quarter of a turn. + # Drive mode indicates if the motor rotation direction should be inverted (=1) or not (=0). + rotated_pos = arm.read("Present_Position") + drive_mode = (rotated_pos < zero_pos).astype(np.int32) + + # Re-compute homing offset to take into account drive mode + rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode) + rotated_nearest_pos = compute_nearest_rounded_position(rotated_drived_pos, arm.motor_models) + homing_offset = rotated_target_pos - rotated_nearest_pos + + print("\nMove arm to rest position") + print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rest")) + input("Press Enter to continue...") + print() + + # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180] + calib_mode = [CalibrationMode.DEGREE.name] * len(arm.motor_names) + + # 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] + calib_idx = arm.motor_names.index("gripper") + calib_mode[calib_idx] = CalibrationMode.LINEAR.name + + calib_data = { + "homing_offset": homing_offset.tolist(), + "drive_mode": drive_mode.tolist(), + "start_pos": zero_pos.tolist(), + "end_pos": rotated_pos.tolist(), + "calib_mode": calib_mode, + "motor_names": arm.motor_names, + } + return calib_data diff --git a/lerobot/common/robot_devices/robots/feetech_calibration.py b/lerobot/common/robot_devices/robots/feetech_calibration.py new file mode 100644 index 000000000..1fca07f43 --- /dev/null +++ b/lerobot/common/robot_devices/robots/feetech_calibration.py @@ -0,0 +1,485 @@ +"""Logic to calibrate a robot arm built with feetech motors""" +# TODO(rcadene, aliberts): move this logic into the robot code when refactoring + +import time + +import numpy as np + +from lerobot.common.robot_devices.motors.feetech import ( + CalibrationMode, + TorqueMode, + convert_degrees_to_steps, +) +from lerobot.common.robot_devices.motors.utils import MotorsBus + +URL_TEMPLATE = ( + "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp" +) + +# The following positions are provided in nominal degree range ]-180, +180[ +# For more info on these constants, see comments in the code where they get used. +ZERO_POSITION_DEGREE = 0 +ROTATED_POSITION_DEGREE = 90 + + +def assert_drive_mode(drive_mode): + # `drive_mode` is in [0,1] with 0 means original rotation direction for the motor, and 1 means inverted. + if not np.all(np.isin(drive_mode, [0, 1])): + raise ValueError(f"`drive_mode` contains values other than 0 or 1: ({drive_mode})") + + +def apply_drive_mode(position, drive_mode): + assert_drive_mode(drive_mode) + # Convert `drive_mode` from [0, 1] with 0 indicates original rotation direction and 1 inverted, + # to [-1, 1] with 1 indicates original rotation direction and -1 inverted. + signed_drive_mode = -(drive_mode * 2 - 1) + position *= signed_drive_mode + return position + + +def move_until_block(arm, motor_name, positive_direction=True, while_move_hook=None): + count = 0 + while True: + present_pos = arm.read("Present_Position", motor_name) + if positive_direction: + # Move +100 steps every time. Lower the steps to lower the speed at which the arm moves. + arm.write("Goal_Position", present_pos + 100, motor_name) + else: + arm.write("Goal_Position", present_pos - 100, motor_name) + + if while_move_hook is not None: + while_move_hook() + + present_pos = arm.read("Present_Position", motor_name).item() + present_speed = arm.read("Present_Speed", motor_name).item() + present_current = arm.read("Present_Current", motor_name).item() + # present_load = arm.read("Present_Load", motor_name).item() + # present_voltage = arm.read("Present_Voltage", motor_name).item() + # present_temperature = arm.read("Present_Temperature", motor_name).item() + + # print(f"{present_pos=}") + # print(f"{present_speed=}") + # print(f"{present_current=}") + # print(f"{present_load=}") + # print(f"{present_voltage=}") + # print(f"{present_temperature=}") + + if present_speed == 0 and present_current > 50: + count += 1 + if count > 100 or present_current > 300: + return present_pos + else: + count = 0 + + +def move_to_calibrate( + arm, + motor_name, + invert_drive_mode=False, + positive_first=True, + in_between_move_hook=None, + while_move_hook=None, +): + initial_pos = arm.read("Present_Position", motor_name) + + if positive_first: + p_present_pos = move_until_block( + arm, motor_name, positive_direction=True, while_move_hook=while_move_hook + ) + else: + n_present_pos = move_until_block( + arm, motor_name, positive_direction=False, while_move_hook=while_move_hook + ) + + if in_between_move_hook is not None: + in_between_move_hook() + + if positive_first: + n_present_pos = move_until_block( + arm, motor_name, positive_direction=False, while_move_hook=while_move_hook + ) + else: + p_present_pos = move_until_block( + arm, motor_name, positive_direction=True, while_move_hook=while_move_hook + ) + + zero_pos = (n_present_pos + p_present_pos) / 2 + + calib_data = { + "initial_pos": initial_pos, + "homing_offset": zero_pos if invert_drive_mode else -zero_pos, + "invert_drive_mode": invert_drive_mode, + "drive_mode": -1 if invert_drive_mode else 0, + "zero_pos": zero_pos, + "start_pos": n_present_pos if invert_drive_mode else p_present_pos, + "end_pos": p_present_pos if invert_drive_mode else n_present_pos, + } + return calib_data + + +def apply_offset(calib, offset): + calib["zero_pos"] += offset + if calib["drive_mode"]: + calib["homing_offset"] += offset + else: + calib["homing_offset"] -= offset + return calib + + +def run_arm_auto_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): + if robot_type == "so100": + return run_arm_auto_calibration_so100(arm, robot_type, arm_name, arm_type) + elif robot_type == "moss": + return run_arm_auto_calibration_moss(arm, robot_type, arm_name, arm_type) + else: + raise ValueError(robot_type) + + +def run_arm_auto_calibration_so100(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): + """All the offsets and magic numbers are hand tuned, and are unique to SO-100 follower arms""" + if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any(): + raise ValueError("To run calibration, the torque must be disabled on all motors.") + + if not (robot_type == "so100" and arm_type == "follower"): + raise NotImplementedError("Auto calibration only supports the follower of so100 arms for now.") + + print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...") + + print("\nMove arm to initial position") + print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="initial")) + input("Press Enter to continue...") + + # Lower the acceleration of the motors (in [0,254]) + initial_acceleration = arm.read("Acceleration") + arm.write("Lock", 0) + arm.write("Acceleration", 10) + time.sleep(1) + + arm.write("Torque_Enable", TorqueMode.ENABLED.value) + + print(f'{arm.read("Present_Position", "elbow_flex")=}') + + calib = {} + + init_wf_pos = arm.read("Present_Position", "wrist_flex") + init_sl_pos = arm.read("Present_Position", "shoulder_lift") + init_ef_pos = arm.read("Present_Position", "elbow_flex") + arm.write("Goal_Position", init_wf_pos - 800, "wrist_flex") + arm.write("Goal_Position", init_sl_pos + 150 + 1024, "shoulder_lift") + arm.write("Goal_Position", init_ef_pos - 2048, "elbow_flex") + time.sleep(2) + + print("Calibrate shoulder_pan") + calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan") + arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan") + time.sleep(1) + + print("Calibrate gripper") + calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True) + time.sleep(1) + + print("Calibrate wrist_flex") + calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex") + calib["wrist_flex"] = apply_offset(calib["wrist_flex"], offset=80) + + def in_between_move_hook(): + nonlocal arm, calib + time.sleep(2) + ef_pos = arm.read("Present_Position", "elbow_flex") + sl_pos = arm.read("Present_Position", "shoulder_lift") + arm.write("Goal_Position", ef_pos + 1024, "elbow_flex") + arm.write("Goal_Position", sl_pos - 1024, "shoulder_lift") + time.sleep(2) + + print("Calibrate elbow_flex") + calib["elbow_flex"] = move_to_calibrate( + arm, "elbow_flex", positive_first=False, in_between_move_hook=in_between_move_hook + ) + calib["elbow_flex"] = apply_offset(calib["elbow_flex"], offset=80 - 1024) + + arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] + 1024 + 512, "elbow_flex") + time.sleep(1) + + def in_between_move_hook(): + nonlocal arm, calib + arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"], "elbow_flex") + + print("Calibrate shoulder_lift") + calib["shoulder_lift"] = move_to_calibrate( + arm, + "shoulder_lift", + invert_drive_mode=True, + positive_first=False, + in_between_move_hook=in_between_move_hook, + ) + # add an 30 steps as offset to align with body + calib["shoulder_lift"] = apply_offset(calib["shoulder_lift"], offset=1024 - 50) + + def while_move_hook(): + nonlocal arm, calib + positions = { + "shoulder_lift": round(calib["shoulder_lift"]["zero_pos"] - 1600), + "elbow_flex": round(calib["elbow_flex"]["zero_pos"] + 1700), + "wrist_flex": round(calib["wrist_flex"]["zero_pos"] + 800), + "gripper": round(calib["gripper"]["end_pos"]), + } + arm.write("Goal_Position", list(positions.values()), list(positions.keys())) + + arm.write("Goal_Position", round(calib["shoulder_lift"]["zero_pos"] - 1600), "shoulder_lift") + time.sleep(2) + arm.write("Goal_Position", round(calib["elbow_flex"]["zero_pos"] + 1700), "elbow_flex") + time.sleep(2) + arm.write("Goal_Position", round(calib["wrist_flex"]["zero_pos"] + 800), "wrist_flex") + time.sleep(2) + arm.write("Goal_Position", round(calib["gripper"]["end_pos"]), "gripper") + time.sleep(2) + + print("Calibrate wrist_roll") + calib["wrist_roll"] = move_to_calibrate( + arm, "wrist_roll", invert_drive_mode=True, positive_first=False, while_move_hook=while_move_hook + ) + + arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"], "wrist_roll") + time.sleep(1) + arm.write("Goal_Position", calib["gripper"]["start_pos"], "gripper") + time.sleep(1) + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"], "wrist_flex") + time.sleep(1) + arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] + 2048, "elbow_flex") + arm.write("Goal_Position", calib["shoulder_lift"]["zero_pos"] - 2048, "shoulder_lift") + time.sleep(1) + arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan") + time.sleep(1) + + calib_modes = [] + for name in arm.motor_names: + if name == "gripper": + calib_modes.append(CalibrationMode.LINEAR.name) + else: + calib_modes.append(CalibrationMode.DEGREE.name) + + calib_dict = { + "homing_offset": [calib[name]["homing_offset"] for name in arm.motor_names], + "drive_mode": [calib[name]["drive_mode"] for name in arm.motor_names], + "start_pos": [calib[name]["start_pos"] for name in arm.motor_names], + "end_pos": [calib[name]["end_pos"] for name in arm.motor_names], + "calib_mode": calib_modes, + "motor_names": arm.motor_names, + } + + # Re-enable original accerlation + arm.write("Lock", 0) + arm.write("Acceleration", initial_acceleration) + time.sleep(1) + + return calib_dict + + +def run_arm_auto_calibration_moss(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): + """All the offsets and magic numbers are hand tuned, and are unique to SO-100 follower arms""" + if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any(): + raise ValueError("To run calibration, the torque must be disabled on all motors.") + + if not (robot_type == "moss" and arm_type == "follower"): + raise NotImplementedError("Auto calibration only supports the follower of moss arms for now.") + + print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...") + + print("\nMove arm to initial position") + print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="initial")) + input("Press Enter to continue...") + + # Lower the acceleration of the motors (in [0,254]) + initial_acceleration = arm.read("Acceleration") + arm.write("Lock", 0) + arm.write("Acceleration", 10) + time.sleep(1) + + arm.write("Torque_Enable", TorqueMode.ENABLED.value) + + sl_pos = arm.read("Present_Position", "shoulder_lift") + arm.write("Goal_Position", sl_pos - 1024 - 450, "shoulder_lift") + ef_pos = arm.read("Present_Position", "elbow_flex") + arm.write("Goal_Position", ef_pos + 1024 + 450, "elbow_flex") + time.sleep(2) + + calib = {} + + print("Calibrate shoulder_pan") + calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan", load_threshold=350, count_threshold=200) + arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan") + time.sleep(1) + + print("Calibrate gripper") + calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True, count_threshold=200) + time.sleep(1) + + print("Calibrate wrist_flex") + calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex", invert_drive_mode=True, count_threshold=200) + calib["wrist_flex"] = apply_offset(calib["wrist_flex"], offset=-210 + 1024) + + wr_pos = arm.read("Present_Position", "wrist_roll") + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex") + time.sleep(1) + arm.write("Goal_Position", wr_pos - 1024, "wrist_roll") + time.sleep(1) + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 2048, "wrist_flex") + time.sleep(1) + arm.write("Goal_Position", calib["gripper"]["end_pos"], "gripper") + time.sleep(1) + + print("Calibrate wrist_roll") + calib["wrist_roll"] = move_to_calibrate(arm, "wrist_roll", invert_drive_mode=True, count_threshold=200) + calib["wrist_roll"] = apply_offset(calib["wrist_roll"], offset=790) + + arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"] - 1024, "wrist_roll") + arm.write("Goal_Position", calib["gripper"]["start_pos"], "gripper") + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex") + time.sleep(1) + arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"], "wrist_roll") + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 2048, "wrist_flex") + + def in_between_move_elbow_flex_hook(): + nonlocal arm, calib + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"], "wrist_flex") + + print("Calibrate elbow_flex") + calib["elbow_flex"] = move_to_calibrate( + arm, + "elbow_flex", + invert_drive_mode=True, + count_threshold=200, + in_between_move_hook=in_between_move_elbow_flex_hook, + ) + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex") + + def in_between_move_shoulder_lift_hook(): + nonlocal arm, calib + sl = arm.read("Present_Position", "shoulder_lift") + arm.write("Goal_Position", sl - 1500, "shoulder_lift") + time.sleep(1) + arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] + 1536, "elbow_flex") + time.sleep(1) + arm.write("Goal_Position", calib["wrist_flex"]["start_pos"], "wrist_flex") + time.sleep(1) + + print("Calibrate shoulder_lift") + calib["shoulder_lift"] = move_to_calibrate( + arm, "shoulder_lift", in_between_move_hook=in_between_move_shoulder_lift_hook + ) + calib["shoulder_lift"] = apply_offset(calib["shoulder_lift"], offset=-1024) + + arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex") + time.sleep(1) + arm.write("Goal_Position", calib["shoulder_lift"]["zero_pos"] + 2048, "shoulder_lift") + arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] - 1024 - 400, "elbow_flex") + time.sleep(2) + + calib_modes = [] + for name in arm.motor_names: + if name == "gripper": + calib_modes.append(CalibrationMode.LINEAR.name) + else: + calib_modes.append(CalibrationMode.DEGREE.name) + + calib_dict = { + "homing_offset": [calib[name]["homing_offset"] for name in arm.motor_names], + "drive_mode": [calib[name]["drive_mode"] for name in arm.motor_names], + "start_pos": [calib[name]["start_pos"] for name in arm.motor_names], + "end_pos": [calib[name]["end_pos"] for name in arm.motor_names], + "calib_mode": calib_modes, + "motor_names": arm.motor_names, + } + + # Re-enable original accerlation + arm.write("Lock", 0) + arm.write("Acceleration", initial_acceleration) + time.sleep(1) + + return calib_dict + + +def run_arm_manual_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): + """This function ensures that a neural network trained on data collected on a given robot + can work on another robot. For instance before calibration, setting a same goal position + for each motor of two different robots will get two very different positions. But after calibration, + the two robots will move to the same position.To this end, this function computes the homing offset + and the drive mode for each motor of a given robot. + + Homing offset is used to shift the motor position to a ]-2048, +2048[ nominal range (when the motor uses 2048 steps + to complete a half a turn). This range is set around an arbitrary "zero position" corresponding to all motor positions + being 0. During the calibration process, you will need to manually move the robot to this "zero position". + + Drive mode is used to invert the rotation direction of the motor. This is useful when some motors have been assembled + in the opposite orientation for some robots. During the calibration process, you will need to manually move the robot + to the "rotated position". + + After calibration, the homing offsets and drive modes are stored in a cache. + + Example of usage: + ```python + run_arm_calibration(arm, "so100", "left", "follower") + ``` + """ + if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any(): + raise ValueError("To run calibration, the torque must be disabled on all motors.") + + print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...") + + print("\nMove arm to zero position") + print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero")) + input("Press Enter to continue...") + + # We arbitrarily chose our zero target position to be a straight horizontal position with gripper upwards and closed. + # It is easy to identify and all motors are in a "quarter turn" position. Once calibration is done, this position will + # correspond to every motor angle being 0. If you set all 0 as Goal Position, the arm will move in this position. + zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.motor_models) + + # Compute homing offset so that `present_position + homing_offset ~= target_position`. + zero_pos = arm.read("Present_Position") + homing_offset = zero_target_pos - zero_pos + + # The rotated target position corresponds to a rotation of a quarter turn from the zero position. + # This allows to identify the rotation direction of each motor. + # 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 + # 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")) + input("Press Enter to continue...") + + rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models) + + # Find drive mode by rotating each motor by a quarter of a turn. + # Drive mode indicates if the motor rotation direction should be inverted (=1) or not (=0). + rotated_pos = arm.read("Present_Position") + drive_mode = (rotated_pos < zero_pos).astype(np.int32) + + # Re-compute homing offset to take into account drive mode + rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode) + homing_offset = rotated_target_pos - rotated_drived_pos + + print("\nMove arm to rest position") + print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rest")) + input("Press Enter to continue...") + print() + + # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180] + calib_modes = [] + for name in arm.motor_names: + if name == "gripper": + calib_modes.append(CalibrationMode.LINEAR.name) + else: + calib_modes.append(CalibrationMode.DEGREE.name) + + calib_dict = { + "homing_offset": homing_offset.tolist(), + "drive_mode": drive_mode.tolist(), + "start_pos": zero_pos.tolist(), + "end_pos": rotated_pos.tolist(), + "calib_mode": calib_modes, + "motor_names": arm.motor_names, + } + return calib_dict diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index 20969c30c..2c358cb92 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -1,3 +1,9 @@ +"""Contains logic to instantiate a robot, read information from its motors and cameras, +and send orders to its motors. +""" +# TODO(rcadene, aliberts): reorganize the codebase into one file per robot, with the associated +# calibration procedure, to make it easy for people to add their own robot. + import json import logging import time @@ -10,138 +16,10 @@ import torch from lerobot.common.robot_devices.cameras.utils import Camera -from lerobot.common.robot_devices.motors.dynamixel import ( - CalibrationMode, - TorqueMode, - convert_degrees_to_steps, -) from lerobot.common.robot_devices.motors.utils import MotorsBus from lerobot.common.robot_devices.robots.utils import get_arm_id from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError -######################################################################## -# Calibration logic -######################################################################## - -URL_TEMPLATE = ( - "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp" -) - -# The following positions are provided in nominal degree range ]-180, +180[ -# For more info on these constants, see comments in the code where they get used. -ZERO_POSITION_DEGREE = 0 -ROTATED_POSITION_DEGREE = 90 - - -def assert_drive_mode(drive_mode): - # `drive_mode` is in [0,1] with 0 means original rotation direction for the motor, and 1 means inverted. - if not np.all(np.isin(drive_mode, [0, 1])): - raise ValueError(f"`drive_mode` contains values other than 0 or 1: ({drive_mode})") - - -def apply_drive_mode(position, drive_mode): - assert_drive_mode(drive_mode) - # Convert `drive_mode` from [0, 1] with 0 indicates original rotation direction and 1 inverted, - # to [-1, 1] with 1 indicates original rotation direction and -1 inverted. - signed_drive_mode = -(drive_mode * 2 - 1) - position *= signed_drive_mode - return position - - -def compute_nearest_rounded_position(position, models): - delta_turn = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, models) - nearest_pos = np.round(position.astype(float) / delta_turn) * delta_turn - return nearest_pos.astype(position.dtype) - - -def run_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): - """This function ensures that a neural network trained on data collected on a given robot - can work on another robot. For instance before calibration, setting a same goal position - for each motor of two different robots will get two very different positions. But after calibration, - the two robots will move to the same position.To this end, this function computes the homing offset - and the drive mode for each motor of a given robot. - - Homing offset is used to shift the motor position to a ]-2048, +2048[ nominal range (when the motor uses 2048 steps - to complete a half a turn). This range is set around an arbitrary "zero position" corresponding to all motor positions - being 0. During the calibration process, you will need to manually move the robot to this "zero position". - - Drive mode is used to invert the rotation direction of the motor. This is useful when some motors have been assembled - in the opposite orientation for some robots. During the calibration process, you will need to manually move the robot - to the "rotated position". - - After calibration, the homing offsets and drive modes are stored in a cache. - - Example of usage: - ```python - run_arm_calibration(arm, "koch", "left", "follower") - ``` - """ - if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any(): - raise ValueError("To run calibration, the torque must be disabled on all motors.") - - print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...") - - print("\nMove arm to zero position") - print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero")) - input("Press Enter to continue...") - - # We arbitrarily chose our zero target position to be a straight horizontal position with gripper upwards and closed. - # It is easy to identify and all motors are in a "quarter turn" position. Once calibration is done, this position will - # correspond to every motor angle being 0. If you set all 0 as Goal Position, the arm will move in this position. - zero_target_pos = convert_degrees_to_steps(ZERO_POSITION_DEGREE, arm.motor_models) - - # Compute homing offset so that `present_position + homing_offset ~= target_position`. - zero_pos = arm.read("Present_Position") - zero_nearest_pos = compute_nearest_rounded_position(zero_pos, arm.motor_models) - homing_offset = zero_target_pos - zero_nearest_pos - - # The rotated target position corresponds to a rotation of a quarter turn from the zero position. - # This allows to identify the rotation direction of each motor. - # 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 - # 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")) - input("Press Enter to continue...") - - rotated_target_pos = convert_degrees_to_steps(ROTATED_POSITION_DEGREE, arm.motor_models) - - # Find drive mode by rotating each motor by a quarter of a turn. - # Drive mode indicates if the motor rotation direction should be inverted (=1) or not (=0). - rotated_pos = arm.read("Present_Position") - drive_mode = (rotated_pos < zero_pos).astype(np.int32) - - # Re-compute homing offset to take into account drive mode - rotated_drived_pos = apply_drive_mode(rotated_pos, drive_mode) - rotated_nearest_pos = compute_nearest_rounded_position(rotated_drived_pos, arm.motor_models) - homing_offset = rotated_target_pos - rotated_nearest_pos - - print("\nMove arm to rest position") - print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rest")) - input("Press Enter to continue...") - print() - - # Joints with rotational motions are expressed in degrees in nominal range of [-180, 180] - calib_mode = [CalibrationMode.DEGREE.name] * len(arm.motor_names) - - # TODO(rcadene): make type of joints (DEGREE or LINEAR) configurable from yaml? - if robot_type == "aloha" and "gripper" in arm.motor_names: - # Joints with linear motions (like gripper of Aloha) are experessed in nominal range of [0, 100] - calib_idx = arm.motor_names.index("gripper") - calib_mode[calib_idx] = CalibrationMode.LINEAR.name - - calib_data = { - "homing_offset": homing_offset.tolist(), - "drive_mode": drive_mode.tolist(), - "start_pos": zero_pos.tolist(), - "end_pos": rotated_pos.tolist(), - "calib_mode": calib_mode, - "motor_names": arm.motor_names, - } - return calib_data - def ensure_safe_goal_position( goal_pos: torch.Tensor, present_pos: torch.Tensor, max_relative_target: float | list[float] @@ -163,11 +41,6 @@ def ensure_safe_goal_position( return safe_goal_pos -######################################################################## -# Manipulator robot -######################################################################## - - @dataclass class ManipulatorRobotConfig: """ @@ -178,7 +51,7 @@ class ManipulatorRobotConfig: """ # Define all components of the robot - robot_type: str | None = None + robot_type: str = "koch" leader_arms: dict[str, MotorsBus] = field(default_factory=lambda: {}) follower_arms: dict[str, MotorsBus] = field(default_factory=lambda: {}) cameras: dict[str, Camera] = field(default_factory=lambda: {}) @@ -207,6 +80,10 @@ def __setattr__(self, prop: str, val): ) super().__setattr__(prop, val) + def __post_init__(self): + if self.robot_type not in ["koch", "koch_bimanual", "aloha", "so100", "moss"]: + raise ValueError(f"Provided robot type ({self.robot_type}) is not supported.") + class ManipulatorRobot: # TODO(rcadene): Implement force feedback @@ -387,6 +264,11 @@ def connect(self): print(f"Connecting {name} leader arm.") self.leader_arms[name].connect() + if self.robot_type in ["koch", "koch_bimanual", "aloha"]: + from lerobot.common.robot_devices.motors.dynamixel import TorqueMode + elif self.robot_type in ["so100", "moss"]: + from lerobot.common.robot_devices.motors.feetech import TorqueMode + # We assume that at connection time, arms are in a rest position, and torque can # be safely disabled to run calibration and/or set robot preset configurations. for name in self.follower_arms: @@ -397,12 +279,12 @@ def connect(self): self.activate_calibration() # Set robot preset (e.g. torque in leader gripper for Koch v1.1) - if self.robot_type == "koch": + if self.robot_type in ["koch", "koch_bimanual"]: self.set_koch_robot_preset() elif self.robot_type == "aloha": self.set_aloha_robot_preset() - else: - warnings.warn(f"No preset found for robot type: {self.robot_type}", stacklevel=1) + elif self.robot_type in ["so100", "moss"]: + self.set_so100_robot_preset() # Enable torque on all motors of the follower arms for name in self.follower_arms: @@ -410,12 +292,22 @@ def connect(self): self.follower_arms[name].write("Torque_Enable", 1) if self.config.gripper_open_degree is not None: + if self.robot_type not in ["koch", "koch_bimanual"]: + raise NotImplementedError( + f"{self.robot_type} does not support position AND current control in the handle, which is require to set the gripper open." + ) # Set the leader arm in torque mode with the gripper motor set to an angle. This makes it possible # to squeeze the gripper and have it spring back to an open position on its own. for name in self.leader_arms: self.leader_arms[name].write("Torque_Enable", 1, "gripper") self.leader_arms[name].write("Goal_Position", self.config.gripper_open_degree, "gripper") + # Check both arms can be read + for name in self.follower_arms: + self.follower_arms[name].read("Present_Position") + for name in self.leader_arms: + self.leader_arms[name].read("Present_Position") + # Connect the cameras for name in self.cameras: self.cameras[name].connect() @@ -436,8 +328,27 @@ def load_or_run_calibration_(name, arm, arm_type): with open(arm_calib_path) as f: calibration = json.load(f) else: + # TODO(rcadene): display a warning in __init__ if calibration file not available print(f"Missing calibration file '{arm_calib_path}'") - calibration = run_arm_calibration(arm, self.robot_type, name, arm_type) + + if self.robot_type in ["koch", "koch_bimanual", "aloha"]: + from lerobot.common.robot_devices.robots.dynamixel_calibration import run_arm_calibration + + calibration = run_arm_calibration(arm, self.robot_type, name, arm_type) + + elif self.robot_type in ["so100", "moss"]: + from lerobot.common.robot_devices.robots.feetech_calibration import ( + run_arm_auto_calibration, + run_arm_manual_calibration, + ) + + # TODO(rcadene): better way to handle mocking + test run_arm_auto_calibration + if arm_type == "leader" or arm.mock: + calibration = run_arm_manual_calibration(arm, self.robot_type, name, arm_type) + elif arm_type == "follower": + calibration = run_arm_auto_calibration(arm, self.robot_type, name, arm_type) + else: + raise ValueError(arm_type) print(f"Calibration is done! Saving calibration file '{arm_calib_path}'") arm_calib_path.parent.mkdir(parents=True, exist_ok=True) @@ -455,6 +366,8 @@ def load_or_run_calibration_(name, arm, arm_type): def set_koch_robot_preset(self): def set_operating_mode_(arm): + from lerobot.common.robot_devices.motors.dynamixel import TorqueMode + if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any(): raise ValueError("To run set robot preset, the torque must be disabled on all motors.") @@ -542,6 +455,23 @@ def set_shadow_(arm): stacklevel=1, ) + def set_so100_robot_preset(self): + for name in self.follower_arms: + # Mode=0 for Position Control + self.follower_arms[name].write("Mode", 0) + # Set P_Coefficient to lower value to avoid shakiness (Default is 32) + self.follower_arms[name].write("P_Coefficient", 16) + # Set I_Coefficient and D_Coefficient to default value 0 and 32 + self.follower_arms[name].write("I_Coefficient", 0) + self.follower_arms[name].write("D_Coefficient", 32) + # Close the write lock so that Maximum_Acceleration gets written to EPROM address, + # which is mandatory for Maximum_Acceleration to take effect after rebooting. + self.follower_arms[name].write("Lock", 0) + # Set Maximum_Acceleration to 254 to speedup acceleration and deceleration of + # the motors. Note: this configuration is not in the official STS3215 Memory Table + self.follower_arms[name].write("Maximum_Acceleration", 254) + self.follower_arms[name].write("Acceleration", 254) + def teleop_step( self, record_data=False ) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]: diff --git a/lerobot/configs/env/moss_real.yaml b/lerobot/configs/env/moss_real.yaml new file mode 100644 index 000000000..8e65d72f4 --- /dev/null +++ b/lerobot/configs/env/moss_real.yaml @@ -0,0 +1,10 @@ +# @package _global_ + +fps: 30 + +env: + name: real_world + task: null + state_dim: 6 + action_dim: 6 + fps: ${fps} diff --git a/lerobot/configs/env/so100_real.yaml b/lerobot/configs/env/so100_real.yaml new file mode 100644 index 000000000..8e65d72f4 --- /dev/null +++ b/lerobot/configs/env/so100_real.yaml @@ -0,0 +1,10 @@ +# @package _global_ + +fps: 30 + +env: + name: real_world + task: null + state_dim: 6 + action_dim: 6 + fps: ${fps} diff --git a/lerobot/configs/policy/act_moss_real.yaml b/lerobot/configs/policy/act_moss_real.yaml new file mode 100644 index 000000000..840a64e14 --- /dev/null +++ b/lerobot/configs/policy/act_moss_real.yaml @@ -0,0 +1,102 @@ +# @package _global_ + +# Use `act_koch_real.yaml` to train on real-world datasets collected on Alexander Koch's robots. +# Compared to `act.yaml`, it contains 2 cameras (i.e. laptop, phone) instead of 1 camera (i.e. top). +# Also, `training.eval_freq` is set to -1. This config is used to evaluate checkpoints at a certain frequency of training steps. +# When it is set to -1, it deactivates evaluation. This is because real-world evaluation is done through our `control_robot.py` script. +# Look at the documentation in header of `control_robot.py` for more information on how to collect data , train and evaluate a policy. +# +# Example of usage for training: +# ```bash +# python lerobot/scripts/train.py \ +# policy=act_koch_real \ +# env=koch_real +# ``` + +seed: 1000 +dataset_repo_id: lerobot/moss_pick_place_lego + +override_dataset_stats: + observation.images.laptop: + # stats from imagenet, since we use a pretrained vision model + mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) + std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) + observation.images.phone: + # stats from imagenet, since we use a pretrained vision model + mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) + std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) + +training: + offline_steps: 80000 + online_steps: 0 + eval_freq: -1 + save_freq: 10000 + log_freq: 100 + save_checkpoint: true + + batch_size: 8 + lr: 1e-5 + lr_backbone: 1e-5 + weight_decay: 1e-4 + grad_clip_norm: 10 + online_steps_between_rollouts: 1 + + delta_timestamps: + action: "[i / ${fps} for i in range(${policy.chunk_size})]" + +eval: + n_episodes: 50 + batch_size: 50 + +# See `configuration_act.py` for more details. +policy: + name: act + + # Input / output structure. + n_obs_steps: 1 + chunk_size: 100 + n_action_steps: 100 + + input_shapes: + # TODO(rcadene, alexander-soare): add variables for height and width from the dataset/env? + observation.images.laptop: [3, 480, 640] + observation.images.phone: [3, 480, 640] + observation.state: ["${env.state_dim}"] + output_shapes: + action: ["${env.action_dim}"] + + # Normalization / Unnormalization + input_normalization_modes: + observation.images.laptop: mean_std + observation.images.phone: mean_std + observation.state: mean_std + output_normalization_modes: + action: mean_std + + # Architecture. + # Vision backbone. + vision_backbone: resnet18 + pretrained_backbone_weights: ResNet18_Weights.IMAGENET1K_V1 + replace_final_stride_with_dilation: false + # Transformer layers. + pre_norm: false + dim_model: 512 + n_heads: 8 + dim_feedforward: 3200 + feedforward_activation: relu + n_encoder_layers: 4 + # Note: Although the original ACT implementation has 7 for `n_decoder_layers`, there is a bug in the code + # that means only the first layer is used. Here we match the original implementation by setting this to 1. + # See this issue https://github.com/tonyzhaozh/act/issues/25#issue-2258740521. + n_decoder_layers: 1 + # VAE. + use_vae: true + latent_dim: 32 + n_vae_encoder_layers: 4 + + # Inference. + temporal_ensemble_momentum: null + + # Training and loss computation. + dropout: 0.1 + kl_weight: 10.0 diff --git a/lerobot/configs/policy/act_so100_real.yaml b/lerobot/configs/policy/act_so100_real.yaml new file mode 100644 index 000000000..3a0975b65 --- /dev/null +++ b/lerobot/configs/policy/act_so100_real.yaml @@ -0,0 +1,102 @@ +# @package _global_ + +# Use `act_koch_real.yaml` to train on real-world datasets collected on Alexander Koch's robots. +# Compared to `act.yaml`, it contains 2 cameras (i.e. laptop, phone) instead of 1 camera (i.e. top). +# Also, `training.eval_freq` is set to -1. This config is used to evaluate checkpoints at a certain frequency of training steps. +# When it is set to -1, it deactivates evaluation. This is because real-world evaluation is done through our `control_robot.py` script. +# Look at the documentation in header of `control_robot.py` for more information on how to collect data , train and evaluate a policy. +# +# Example of usage for training: +# ```bash +# python lerobot/scripts/train.py \ +# policy=act_koch_real \ +# env=koch_real +# ``` + +seed: 1000 +dataset_repo_id: lerobot/so100_pick_place_lego + +override_dataset_stats: + observation.images.laptop: + # stats from imagenet, since we use a pretrained vision model + mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) + std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) + observation.images.phone: + # stats from imagenet, since we use a pretrained vision model + mean: [[[0.485]], [[0.456]], [[0.406]]] # (c,1,1) + std: [[[0.229]], [[0.224]], [[0.225]]] # (c,1,1) + +training: + offline_steps: 80000 + online_steps: 0 + eval_freq: -1 + save_freq: 10000 + log_freq: 100 + save_checkpoint: true + + batch_size: 8 + lr: 1e-5 + lr_backbone: 1e-5 + weight_decay: 1e-4 + grad_clip_norm: 10 + online_steps_between_rollouts: 1 + + delta_timestamps: + action: "[i / ${fps} for i in range(${policy.chunk_size})]" + +eval: + n_episodes: 50 + batch_size: 50 + +# See `configuration_act.py` for more details. +policy: + name: act + + # Input / output structure. + n_obs_steps: 1 + chunk_size: 100 + n_action_steps: 100 + + input_shapes: + # TODO(rcadene, alexander-soare): add variables for height and width from the dataset/env? + observation.images.laptop: [3, 480, 640] + observation.images.phone: [3, 480, 640] + observation.state: ["${env.state_dim}"] + output_shapes: + action: ["${env.action_dim}"] + + # Normalization / Unnormalization + input_normalization_modes: + observation.images.laptop: mean_std + observation.images.phone: mean_std + observation.state: mean_std + output_normalization_modes: + action: mean_std + + # Architecture. + # Vision backbone. + vision_backbone: resnet18 + pretrained_backbone_weights: ResNet18_Weights.IMAGENET1K_V1 + replace_final_stride_with_dilation: false + # Transformer layers. + pre_norm: false + dim_model: 512 + n_heads: 8 + dim_feedforward: 3200 + feedforward_activation: relu + n_encoder_layers: 4 + # Note: Although the original ACT implementation has 7 for `n_decoder_layers`, there is a bug in the code + # that means only the first layer is used. Here we match the original implementation by setting this to 1. + # See this issue https://github.com/tonyzhaozh/act/issues/25#issue-2258740521. + n_decoder_layers: 1 + # VAE. + use_vae: true + latent_dim: 32 + n_vae_encoder_layers: 4 + + # Inference. + temporal_ensemble_momentum: null + + # Training and loss computation. + dropout: 0.1 + kl_weight: 10.0 diff --git a/lerobot/configs/robot/aloha.yaml b/lerobot/configs/robot/aloha.yaml index 51cde6a69..d8bca515f 100644 --- a/lerobot/configs/robot/aloha.yaml +++ b/lerobot/configs/robot/aloha.yaml @@ -1,11 +1,13 @@ -# Aloha: A Low-Cost Hardware for Bimanual Teleoperation +# [Aloha: A Low-Cost Hardware for Bimanual Teleoperation](https://www.trossenrobotics.com/aloha-stationary) # https://aloha-2.github.io -# https://www.trossenrobotics.com/aloha-stationary # Requires installing extras packages # With pip: `pip install -e ".[dynamixel intelrealsense]"` # With poetry: `poetry install --sync --extras "dynamixel intelrealsense"` +# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/9_use_aloha.md) + + _target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot robot_type: aloha # Specific to Aloha, LeRobot comes with default calibration files. Assuming the motors have been diff --git a/lerobot/configs/robot/koch_bimanual.yaml b/lerobot/configs/robot/koch_bimanual.yaml index 7f8138675..b551d15de 100644 --- a/lerobot/configs/robot/koch_bimanual.yaml +++ b/lerobot/configs/robot/koch_bimanual.yaml @@ -1,5 +1,5 @@ _target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot -robot_type: koch +robot_type: koch_bimanual calibration_dir: .cache/calibration/koch_bimanual # `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes. diff --git a/lerobot/configs/robot/moss.yaml b/lerobot/configs/robot/moss.yaml new file mode 100644 index 000000000..8a9019851 --- /dev/null +++ b/lerobot/configs/robot/moss.yaml @@ -0,0 +1,56 @@ +# [Moss v1 robot arm](https://github.com/jess-moss/moss-robot-arms) + +# Requires installing extras packages +# With pip: `pip install -e ".[feetech]"` +# With poetry: `poetry install --sync --extras "feetech"` + +# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/11_use_moss.md) + +_target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot +robot_type: moss +calibration_dir: .cache/calibration/moss + +# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes. +# Set this to a positive scalar to have the same value for all motors, or a list that is the same length as +# the number of motors in your follower arms. +max_relative_target: null + +leader_arms: + main: + _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus + port: /dev/tty.usbmodem58760431091 + motors: + # name: (index, model) + shoulder_pan: [1, "sts3215"] + shoulder_lift: [2, "sts3215"] + elbow_flex: [3, "sts3215"] + wrist_flex: [4, "sts3215"] + wrist_roll: [5, "sts3215"] + gripper: [6, "sts3215"] + +follower_arms: + main: + _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus + port: /dev/tty.usbmodem58760431191 + motors: + # name: (index, model) + shoulder_pan: [1, "sts3215"] + shoulder_lift: [2, "sts3215"] + elbow_flex: [3, "sts3215"] + wrist_flex: [4, "sts3215"] + wrist_roll: [5, "sts3215"] + gripper: [6, "sts3215"] + +cameras: + laptop: + _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera + camera_index: 0 + fps: 30 + width: 640 + height: 480 + phone: + _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera + camera_index: 1 + fps: 30 + width: 640 + height: 480 diff --git a/lerobot/configs/robot/so100.yaml b/lerobot/configs/robot/so100.yaml new file mode 100644 index 000000000..ec6f3e3fe --- /dev/null +++ b/lerobot/configs/robot/so100.yaml @@ -0,0 +1,56 @@ +# [SO-100 robot arm](https://github.com/TheRobotStudio/SO-ARM100) + +# Requires installing extras packages +# With pip: `pip install -e ".[feetech]"` +# With poetry: `poetry install --sync --extras "feetech"` + +# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/10_use_so100.md) + +_target_: lerobot.common.robot_devices.robots.manipulator.ManipulatorRobot +robot_type: so100 +calibration_dir: .cache/calibration/so100 + +# `max_relative_target` limits the magnitude of the relative positional target vector for safety purposes. +# Set this to a positive scalar to have the same value for all motors, or a list that is the same length as +# the number of motors in your follower arms. +max_relative_target: null + +leader_arms: + main: + _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus + port: /dev/tty.usbmodem585A0077581 + motors: + # name: (index, model) + shoulder_pan: [1, "sts3215"] + shoulder_lift: [2, "sts3215"] + elbow_flex: [3, "sts3215"] + wrist_flex: [4, "sts3215"] + wrist_roll: [5, "sts3215"] + gripper: [6, "sts3215"] + +follower_arms: + main: + _target_: lerobot.common.robot_devices.motors.feetech.FeetechMotorsBus + port: /dev/tty.usbmodem585A0080971 + motors: + # name: (index, model) + shoulder_pan: [1, "sts3215"] + shoulder_lift: [2, "sts3215"] + elbow_flex: [3, "sts3215"] + wrist_flex: [4, "sts3215"] + wrist_roll: [5, "sts3215"] + gripper: [6, "sts3215"] + +cameras: + laptop: + _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera + camera_index: 0 + fps: 30 + width: 640 + height: 480 + phone: + _target_: lerobot.common.robot_devices.cameras.opencv.OpenCVCamera + camera_index: 1 + fps: 30 + width: 640 + height: 480 diff --git a/lerobot/configs/robot/stretch.yaml b/lerobot/configs/robot/stretch.yaml index 6d9f0be85..e29966b6f 100644 --- a/lerobot/configs/robot/stretch.yaml +++ b/lerobot/configs/robot/stretch.yaml @@ -1,3 +1,12 @@ +# [Stretch3 from Hello Robot](https://hello-robot.com/stretch-3-product) + +# Requires installing extras packages +# With pip: `pip install -e ".[stretch]"` +# With poetry: `poetry install --sync --extras "stretch"` + +# See [tutorial](https://github.com/huggingface/lerobot/blob/main/examples/8_use_stretch.md) + + _target_: lerobot.common.robot_devices.robots.stretch.StretchRobot robot_type: stretch3 diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py new file mode 100644 index 000000000..18707397f --- /dev/null +++ b/lerobot/scripts/configure_motor.py @@ -0,0 +1,145 @@ +""" +This script configure a single motor at a time to a given ID and baudrate. + +Example of usage: +```bash +python lerobot/scripts/configure_motor.py \ + --port /dev/tty.usbmodem585A0080521 \ + --brand feetech \ + --model sts3215 \ + --baudrate 1000000 \ + --ID 1 +``` +""" + +import argparse +import time + + +def configure_motor(port, brand, model, motor_idx_des, baudrate_des): + if brand == "feetech": + from lerobot.common.robot_devices.motors.feetech import MODEL_BAUDRATE_TABLE + from lerobot.common.robot_devices.motors.feetech import ( + SCS_SERIES_BAUDRATE_TABLE as SERIES_BAUDRATE_TABLE, + ) + from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus as MotorsBusClass + elif brand == "dynamixel": + from lerobot.common.robot_devices.motors.dynamixel import MODEL_BAUDRATE_TABLE + from lerobot.common.robot_devices.motors.dynamixel import ( + X_SERIES_BAUDRATE_TABLE as SERIES_BAUDRATE_TABLE, + ) + from lerobot.common.robot_devices.motors.dynamixel import DynamixelMotorsBus as MotorsBusClass + else: + raise ValueError( + f"Currently we do not support this motor brand: {brand}. We currently support feetech and dynamixel motors." + ) + + # Check if the provided model exists in the model_baud_rate_table + if model not in MODEL_BAUDRATE_TABLE: + raise ValueError( + f"Invalid model '{model}' for brand '{brand}'. Supported models: {list(MODEL_BAUDRATE_TABLE.keys())}" + ) + + # Setup motor names, indices, and models + motor_name = "motor" + motor_index_arbitrary = motor_idx_des # Use the motor ID passed via argument + motor_model = model # Use the motor model passed via argument + + # Initialize the MotorBus with the correct port and motor configurations + motor_bus = MotorsBusClass(port=port, motors={motor_name: (motor_index_arbitrary, motor_model)}) + + # Try to connect to the motor bus and handle any connection-specific errors + try: + motor_bus.connect() + print(f"Connected on port {motor_bus.port}") + except OSError as e: + print(f"Error occurred when connecting to the motor bus: {e}") + return + + # Motor bus is connected, proceed with the rest of the operations + try: + print("Scanning all baudrates and motor indices") + all_baudrates = set(SERIES_BAUDRATE_TABLE.values()) + motor_index = -1 # Set the motor index to an out-of-range value. + + for baudrate in all_baudrates: + motor_bus.set_bus_baudrate(baudrate) + present_ids = motor_bus.find_motor_indices(list(range(1, 10))) + if len(present_ids) > 1: + raise ValueError( + "Error: More than one motor ID detected. This script is designed to only handle one motor at a time. Please disconnect all but one motor." + ) + + if len(present_ids) == 1: + if motor_index != -1: + raise ValueError( + "Error: More than one motor ID detected. This script is designed to only handle one motor at a time. Please disconnect all but one motor." + ) + motor_index = present_ids[0] + + if motor_index == -1: + raise ValueError("No motors detected. Please ensure you have one motor connected.") + + print(f"Motor index found at: {motor_index}") + + if brand == "feetech": + # Allows ID and BAUDRATE to be written in memory + motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Lock", 0) + + if baudrate != baudrate_des: + print(f"Setting its baudrate to {baudrate_des}") + baudrate_idx = list(SERIES_BAUDRATE_TABLE.values()).index(baudrate_des) + + # The write can fail, so we allow retries + motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Baud_Rate", baudrate_idx) + time.sleep(0.5) + motor_bus.set_bus_baudrate(baudrate_des) + present_baudrate_idx = motor_bus.read_with_motor_ids( + motor_bus.motor_models, motor_index, "Baud_Rate", num_retry=2 + ) + + if present_baudrate_idx != baudrate_idx: + raise OSError("Failed to write baudrate.") + + print(f"Setting its index to desired index {motor_idx_des}") + motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "Lock", 0) + motor_bus.write_with_motor_ids(motor_bus.motor_models, motor_index, "ID", motor_idx_des) + + present_idx = motor_bus.read_with_motor_ids(motor_bus.motor_models, motor_idx_des, "ID", num_retry=2) + if present_idx != motor_idx_des: + raise OSError("Failed to write index.") + + if brand == "feetech": + # Set Maximum_Acceleration to 254 to speedup acceleration and deceleration of + # the motors. Note: this configuration is not in the official STS3215 Memory Table + motor_bus.write("Lock", 0) + motor_bus.write("Maximum_Acceleration", 254) + + motor_bus.write("Goal_Position", 2048) + time.sleep(4) + print("Present Position", motor_bus.read("Present_Position")) + + motor_bus.write("Offset", 0) + time.sleep(4) + print("Offset", motor_bus.read("Offset")) + + except Exception as e: + print(f"Error occurred during motor configuration: {e}") + + finally: + motor_bus.disconnect() + print("Disconnected from motor bus.") + + +if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument("--port", type=str, required=True, help="Motors bus port (e.g. dynamixel,feetech)") + parser.add_argument("--brand", type=str, required=True, help="Motor brand (e.g. dynamixel,feetech)") + parser.add_argument("--model", type=str, required=True, help="Motor model (e.g. xl330-m077,sts3215)") + parser.add_argument("--ID", type=int, required=True, help="Desired ID of the current motor (e.g. 1,2,3)") + parser.add_argument( + "--baudrate", type=int, default=1000000, help="Desired baudrate for the motor (default: 1000000)" + ) + args = parser.parse_args() + + configure_motor(args.port, args.brand, args.model, args.ID, args.baudrate) diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 425247e65..031e608e7 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -144,6 +144,9 @@ def calibrate(robot: Robot, arms: list[str] | None): robot.home() return + if arms is None: + arms = robot.available_arms + unknown_arms = [arm_id for arm_id in arms if arm_id not in robot.available_arms] available_arms_str = " ".join(robot.available_arms) unknown_arms_str = " ".join(unknown_arms) diff --git a/lerobot/scripts/find_motors_bus_port.py b/lerobot/scripts/find_motors_bus_port.py new file mode 100644 index 000000000..51ef6d41c --- /dev/null +++ b/lerobot/scripts/find_motors_bus_port.py @@ -0,0 +1,36 @@ +import time +from pathlib import Path + + +def find_available_ports(): + ports = [] + for path in Path("/dev").glob("tty*"): + ports.append(str(path)) + return ports + + +def find_port(): + print("Finding all available ports for the MotorsBus.") + ports_before = find_available_ports() + print(ports_before) + + print("Remove the usb cable from your MotorsBus and press Enter when done.") + input() + + time.sleep(0.5) + ports_after = find_available_ports() + ports_diff = list(set(ports_before) - set(ports_after)) + + if len(ports_diff) == 1: + port = ports_diff[0] + print(f"The port of this MotorsBus is '{port}'") + print("Reconnect the usb cable.") + elif len(ports_diff) == 0: + raise OSError(f"Could not detect the port. No difference was found ({ports_diff}).") + else: + raise OSError(f"Could not detect the port. More than one port was found ({ports_diff}).") + + +if __name__ == "__main__": + # Helper to find the usb port associated to all your MotorsBus. + find_port() diff --git a/media/moss/follower_initial.webp b/media/moss/follower_initial.webp new file mode 100644 index 0000000000000000000000000000000000000000..e7ded16bdac7a6442199edc6da730789cdd361b8 GIT binary patch literal 118620 zcmZ^~1ymf{7A@MiYjB6)PS6B*C%C&?a3@G`w?J@rPjGh&?vUUFcXxROIp^N{{vWRy z-My)<>gv7svbok=ijrbt%41+4HBljXRe3ITcn}Cg4LrvXKRiGVCXjvzabHOK(u4k7``gINC`=d-<@FATB;&UObm0N0s;%t21T zHG;sAmv1lu#*!c#kP(OxL=TMLftZ2kyO(tat_2=fGykj~{eO@7uYf?j?a$B8&Hp_n z)eZvv-~@r-8~=NZnhOL%LjZvW8tn`m3|_wu0(b>CH3fmr3PB(w4G`$fIB<=YqbcjV z*U!Nag+L&v<>%*fN)QOjDEY|HMiMqa8=+ zK;aMV`DMz_-`<{s-q?M@0%u|K?6xa+@qBKCVTNa^jg*L@c}r*8^MT)-nC1B+>jV4b z^TOpe=SSXA1dHdV=g!S%jE_3IJAQ8EKE4hnMj097xorrr9m!ZrzM%1SO}!5`^@7(Y+1*r@~%gXj4Iju0HRuY6(68#-!Gf&3QK;U*Y58*Zf z>cLoMv!y=4K*{hOMhExEV|O)QAT#Q+5_nC$tX=?Td_R)z{;AVed8cS9um5Jc*+Yu) zFDu!mI)tFH8^PM{YBaU)zt;IueAUa0w}^pTz}o)L41w=II^dtpw$aa&e4X(6I9S}o zhES3(!!Qll>6O_3ECX<1^*q zdmY@`(%nGW9wA*KY1?^$W_IQ7kRW}^1g4?9>fxd^{_jQY(6rR*91bfRmnm?UsiyHA zm?7MHu4BSxM&X}aMn3nkI~dD;S)e7TN+_{CEyZ;XgTyHvcP4mj?s~!Nn!NZ?ofUjH z+l4o*gxZ!-w%dZKgBfrwURj|B(U-c?BY3O2(}9(K-h#(}cggFGE6}D&AN-)vU2s<@b7lNY^~p%6E*_|*H?VzhF+Ph=t<$nW6u7!IIsei z)jyorV{%=-7SQSh{{m*<`?H8IuZLIst9-@=~djT*y=*d?awts1b`7y~}5ug2tnknsV@l?OIB*4_Za(jwd7oKj}wR~EhZklAgfbaR|(PkL{ion=Qe1y#GUSgVm;^9>_5E8QJ@8zhBRogs5zEbI3OC>TE7shSMqa zJxGztOHc6QsKcE48suZbD8_U zDYySILqxPl({-Vg{>}_VwEbF1kJ=;NwyA<6q&TKy&1ZNp)649aWjVS82`y#^cBeby z69hy7A&ZY^3$xm@N}yxTYg1fNYYcL*I5}fh#Ac(z_i*eH3D0@V(_I%nzZt@eAQ+zV zw!oI{ejxv^fq50hNs>E@FPbJ#N=z41U>FqT{$(w)LQ9|CB1<7jwY7lf_6FGzd*w8c zd6PlR^jQ98v5P4PUW#V^koBrDMv!So;eQ|#>4W6jw*o0E|enBUuEIftY#L} z3O(uuB^aqR`u5{@_H@0MbOgdg=fYq5=|XWlF_h$HTc(*-<^*VxoM_@(EUfk7BZZ+Y-3+d`)1UCJR50C0SDkjRx*LRMT$$_knBH}bVhrsb*#sf z*0v2~KoPB+KxiS%r(wIJ3Fk{o_znSvc!D1Af&VNLonf+E`*K1^jb@(ea~%qiZua$y zN(oc^=Zt^#7!i`9wVn6y_K~e`ycm&V>B1+q@>(pE3isaMcdgJYbT#wZq!xuLNUi=S ztX%3|F){PHvr5GOxH>=*7q6qZ*p`y&Q|DDjw&&}zE znQ3NTG&*+*!b?JuE z$2`{`5vFqe8()a=zdF4|?te4@ovu(0FOPYKG-z_D;}e~Gs8eSl+*QP!kh_4RnTm3t zDb0+@2ny@A?lpO%KMxSMtdIY-BN;ZKp*G~)?0g$>hz(@yQauts-v4#LiG$uyPixQr zNB&5N_DBwrZaK60#PYAmhtHZDPtQ;J3)*56?N6H1+$qxB8^G5%M>{+hO! zPF}M=(zKYQJxnUi&bqKCLHHP&h!%wBd{c&A8|~`$`ht9Wd@v-U8Y>c;F+{i?gZxA| zMEuQR;gT;-+9nzZ%ijC-Poc|d?>{TxV*E1{aHmr@V?!c58D_*aPvJpX*dU;PWIttZ97x)pY)6Mc&{1hW7emSn6cI z35Szs<)4k6_#*+R|S{5iwh{0N%Pg@NMYG}&xi7BcDf#izPR1 zZ4(>6YOH+~=e3|!L#)=rQ!XHBr_mnIEO3=b>y>@u%{9!-cg$VBu7l%Ec;+j&a2=%I zsRtlqO0q=P9~O}NtLApnHQhoBsvj5Q_#_%zkGCXk($MVLl}BD2LdFQP;P)3>HM2KxMGUl^WUq#uvkNEe>LrPFnJf*{z= z6`Cgl!@K+MrmYb-)=%T&__#)g&iEO~eMfXozbz+DK2DZ#bApw3yn415my6Fdp*Kp} zfT`heh4P}cE&qxe=QTP*ue}YY=J{2e6<($Dt-sxT#G_A#izTLbvWuySriCiMYK1nm z1&$*UG3+EOm(|gr7Cvg^_T}hGgTm=G+4f^?#l;R@ zcm`lqecZ?kZ2kc^FS|>w`po~y{ZafC?LeG4ArHDBvRbPA&}J%SOpqpQ^AZ*Jb6lA< z)gt^NaqsNM7xZV6(8WKz=~&WB2=hTmDEFRo;D+|Mr4Iv3SCLC<9UOD<8DRwpDvE$G z2WKYc^XVWsuqbzXI}W+2hK0L;ey_f!qrS1FTTL=htFM^n^Aq$78_rdr)bVB7*}|U4&sRO zWhi)$fR(|6$vx zp2Zpgsizwv{KhN*UqNNJtYKI9z`0saFq3_uqIv|SYEJnYPY3!jWxhCMr!CWO;|Ei> zkCJF567eJ=rX~HX38d_pD_5n?tFYB|d6ASaWwQMkZrp(yXLMc5Htp=Nk?>g05ni zCS6N_Rv{tIcsctf?aE^BV_zZ*)xf&`4z;dh&W+ z*>Woo++2U5^0Cr=F%*7p*UNWkvN75E#Qn0MO;-{a}g>6c*}a-w}4UW?xM zq`2#NBAVRj)%N_))ZU0|o3^`go*`;R%W6;qu^6K^w>6=zZAi6(MPFSqI76W?Y0%PI zziaVhrVjFiqTN8qWc)=;W9ooYzmOf{B4d?=kLkqPMPz5D(=E8B|GZ@G%`Z|?!9Qu6 zeiFApv`4mIq_g`>)p(x*V&)6>ZI3KOy*mb<#kn_kv2jhb)2L+DVtEsmQrJ`*P;v~yKp{qT`W5GANxO+_MRMkjEGZoRH9lGzo?MDR%6 za!c9@)>YoN_KwM;^eFBpJc4(TZF-UHFuIrfWts{fb&4Te_HO_SQ@{XN_NV+6`YzEh^4j+9#*7Mizvsf1^EUrw7rwEhEoc; z!agcj`Xg{tghgp%<32?9{JWRc$L{$Yu>U(n0ALULraZRENReoXU>>QcitxzoPMmkx z?NA&Gf!pLrzjm%-!Sl0W*N|Oyi2*nCD*OEh1qKn=5Z8q6(|4*%xj4aTXwCO=xAf5Nz15j~x_ramA%b~o7h_X+|50FV*7#NHxE&iai}advQDk7> zKh$zump#-@G}Mm37KnTJA3C@n-GLD1H!&xWYXU%6Cf#hL+5-Kbm_<&Uc06fZ0laUk z^UicvxRG8${Nco|u5K0KCM;d3Pag&Qu`-`BK>Be=lhn8-dn3)$IiC=kdznV-N&ePklcjx%eNL5aIKhrfY(i%(xCCSA&#dvneHPuKv8BOFnqNDIo1H zuOS02bji|PxAy_bE{m~aQj2;B3?2J4qqJ;uRAy@;*VqBjLuBJpr3mgS$&jDW;>mWb z)X=>V-0^In`*EGOP*x##3#o72r)j-HYz!|!N(;S?c01&#MG{|SVj|EA>9&~WQQ zX2``p1!<#M-seo6YZn(FJNuE{gRwgqp}UC=iK&)@WHoD5xIM{{)oAw?eEo+ z!AbY9Tnog@DArGC_z8mDF|-wGk}HMi>7?`q&j^{{7Q;0SY36{R0y`W zVnWjhe1_Q5nB4Z`^)JOtDr{7s(c-G` zR?D1(b+mx4C%_1j7=_x_KKX2{>98jeo6s`+st(Pw1wsYYk~R-W;`En4c0I%8wZzF%ZZ=9eIrk;@MonHa=R~ydWmDJ4-yb@SB#qF1WaGMcF&Z~g6M6EDj!IiYi&%HA7c z*9$1xsD+2o<~KQFUCA`qumj^fl!r;0Z0O!ohd@H7*!l@ALIx1n-RtbO>>ZnBQ9QL5^0lk$VJKM9P>vhkj*(fnJ^PcPptD0TClz{w0 zSipNawff$EkR)YA{jyhw`)%Pak1*#$K=oSS^Ic#j>rX1WBaUxduce`FJUKJ5iEF3p zh#7|`!X5eBC2U4?g@Bl*wr(?$0WXYi$jzB0R*a5s=&!H-z&ZJT9b?Lpt>J; zIXB4Ef!)ZuxEZ@Mkl#}8d80K%(C?#1C#a%fK=hlTSCCq)nvheYtf0GM2;(o^X96UT ziGkOt9gmwarrCe2>RC+QK|L7kFeqA4A344NWNjNDO%G%vI`@cELiQiYa@F4Md1^!K zY{hj4!!XjN#2$~@fa?{H@WOn`Jq7i~kCDV-43N2&3)Svc<$;EiInY}tZoVyn)LawB z*tM= zNI2W_FX?Uu2H3qi6`_!xnp&5l7gC5Ar?c3H$3~b(jth zj0j89V&tVvK-Qz6j{|@RCb348qHz>mpY149-y?wDze_)_wSs8z0Iin zaiT1jP9ST>mRJnq>G;7Wy5lpSUVz6Wv}Rzh+CAp?rPYfX6(V2AlrQ?LI@KdTX^rh{ z$_*wihfFmEy_YbdTvlJg$>(~e2A|TpwrtrZ4nv`LUl(bVQKbUCHd|DZ$bM1|#KXEu ziwc!z24hJ4yyQ(Gnvqo^Wi#`8@)}^lH@Np4wjM&WB=`SQff4rBRyhpZZcT*%otJ~+ z_&B*K$^~y_r-PbTI5|a2UgzH9`8IcoUcSt%adDEu=205WEa{Mo51Jxnisj?A8v4g@ zKFXCG;R?b66a*k+i0IY!r`jOMcw6+nPLD^(ni5?S1uC>sWDd5-p!t^meu8O}J0>k2 z`VZX4?1ueV!J-I{tx9eL!bkmfiUpnysx8^6n}vp?ip@72h7eP^1c%#mUyEmA@lrca z+G`lHKWU4aW4wiwpA?WC6T3Ul&kiw2(0{K&805zI79Dp)O0-18d+7eE`l3=<{}TCA zh7EK&=HOUgt_XmlwbGm{?n8$5ly^61RBg4lU=nalh}mHKvrpr&S|w_G)QL0AHn=#V zOFTamS%oTOp4uXxTC(;CC7%$_%sTYRu4DVgw)Sb(L^68gXv_Lkx&}xcb^Jiy+Ej-l zU(1%ros<@viS7)I-w7@-J;3K$wDQtAorlFZ({EfyQXSIN$bj+c{0gbpn|RaAl3 z=d=73hruvPpHG7ItH0#7QIa%z_*}gH^By=vlS5mFgN~EpGu`ax>hCC+P;$}rU#NpD zZX5$k-ZEQGWq3ZmOPj%n%~PZU<2yz+o`(_2)5PK;OX6^+PPzEjWgV?1Skmui9gB?A z9xz?)f|*f48M{=WVehAPrN&B$tdLafuu`=@vG>e0-jmKFz+xhyAKrUy;!=tt5K|Mt zdc}YLAat%HLnu?p`QwN~T+Sy`f~||-h;)E7aO7vMw7E<0h#i8{ykzK8GnjPN#7%Iv zNDp^u^l7auSpC-2^ex2tmEbTt|M$b=jR)+Y1Ge>+w&*8A6ciE}{NDbu=cJWjO!aWm zn~1aS^7jN1DAtU~qn!p+=MGj)(Knui?fwsmR^HyfU(!i${Z8fR^NH=-1=oXgVrsP< zyDF!6jaVmol##|hl;ia*|CvdCESpUUUcH?aKF8DD@rQUkeK)QYg0wN=@jt_3!N9N zX>^)`ZNJgI5B%a#t}MmLDz5d%$H0!SH*j(^gMT>M7mlI=V~MMtEY)phVH>_Fhk3|m zD-!T40OcrRk!74@w&-`t%J^6`b=f0#-uqHiCObLJxz81x2xFc6^4aI#gr@v-b{>+n z%liwUO&LQ1F^QF7a#4he( zG~aS6svFjCFerv+@aM6*{M6=^l;)RRNBKd6&ob4iD_|3u?<{0*W<>|Y(zHZMDjB^51WR_-9#J>#HUp3*#@7eje`n`JzNK+UUI5a3V(H8 zhBa~@&fexY@g@YF9?1J{?BV1*d14#<)-f*Hu2P8Di_oX z;6EPiH8!%|#?^4@xw}|?_AGdy)WFf2GGwm1Gc*uG65_LrZ5reeQ!9A7Bv-mMBX6~u z*p~DdqKN}?;@CxPLSWL#__9*e^Jg{cv$k}$+u~Rtao0z9cU|4xK4Z*qp2ZX&balHi zNJkF!TqQ81+lR_(l+-JO{48y$@3YjK^f1K@10^H;30`8XY*AQPvw6OXZ`Y!r8zgfWFC>AA>n~>-Kn1_Cb~y&X&yxqc>;v0S$qJsY2RiWAf<+0+j?> z?!Ms%@`$PPn*@g0S*_BDJX*Y`=FbtTn!nW#LiM94o5lj!Y)o(wS82)dWn;#9O=c_N zCW(YTF69s{C$%9WiszF48QdQOmz+N22(8i4p!B_Utw)hxl4iX$nZe;Dw%(W{b*EFe zBefG~Kw@3oo$3a3@W?OD?CjeX=8#n!?R^r=1SfAG#a9x+gPHn5zOtlx(o=y)GK#C8 z(^kH|`B5Sih>;KIULVjn`#Bf5V+B=AxVgU9M|G{NXQqghZS!0-q%$W@A~i2e68Q&x z%d0{bP?dx{($vuMuQ_o05NqAvgia-z!)Ijdn{m3e;-Q49)0gvGdJr_regTubLMJG? z8tsIOJ3#fT(YX<=<;Rk?tUxGA*b;)&Vu!H1l7=Z>lA?~bfPzg^7^IuJ^y*3JXh+?U zfKrVge*Am8F|g7_tFt@OFDkxcqDIX<2^Ve=4;I6*ld(Il_cOBNO_L}E-!6w15aRGq zdane+BZf-@y)GYr_PgU+Pj~my36)C)3#?^;9g$EoipR)lE5=){bu2xWtgk&kOyfHm z1rxt-KN0Tkw3iP+Gzk z3-g!>c}%=9?hZySCW$lWmbqm8NggtGH~xsE`_ZU1?c zuBAtov;X}N?$d=fPCyZPr?x>>+$suRR%k#2FQR>by-IG5xqCz@auhOq8+99+4YkrH zC1r`3jBZ9pg*b^{20op{|FK z8JBZc#Fx|2UMrF-RERPQUk^v@B9YJp;cejp8_=-%YBc*8P-*Tp7KtS9kTm|pQa1i3 zSvo34OuO!uN)9ij%IAUJVXqcGj`??y)(3AUNX-U&9Ll;%a&H;Lqat zeD>EK>Gb9{QdQ9HZ}VNS5)!KU29o50fb8tmMwYsHZSJzfU+f zA>~(jxK{o*+XWviYTg~BlVzr^U=(3%ZMafoz#Vv` zFpl`-74SaAe(v9i4vI?G#X(-k4cg)pJJ-08UTp`TUp0fA^!P>p5p*P}(XN#2^f^^MTh9mYmH6-*aCNoDPlB-HgFuRo7OKJRn^oGo}QkRCg~GaGrL z1Gq4$_g|CHZE4}{667EUS}%^PYIKU_yzQF7NQJ+EQ5sE+N7$6#1qZN}5&0!Le0~?#!IA8 z5CfXHBeJgN9h%ga$+HvD()iP{gAj{|XZh`E1!&KuS&M7)JQBw(ATj^SV=!$07*@>H z=Hi+>RuvkC2rr;Al~%DQp*d{rZ0fZ>&gdZIwF(Ed+vHgvzaU5^leG2oJ$eH@DIr+t z$ACD1lc;k4;X=>l^}oJCVMOCciEa)8bjYdq`mLnF6;B9OLSC~ zaWN+Jt`Z;Y44aLFfP^_+zBSAEQN|C{rNNLkf!)nut^N#KG!bhA-{LK)bN2fjS%Bpr zy|(<5A&gGYmjIp*_I%vTW9LpJI7Ee`G3P8RTF3Be3A~5}dcBnKP(RcFS-72Q56?X+#P?)5C48wG&SD+8d{4pUfRs7?{zsXd^7{FeKI|8ImAa@4c?`!eS39|CGabu{4w0Eof@XtOvZ8l?}u+zh!5b-FZ(pe!|Mp9HTFW!^rZ_9ApzhH&~wI3ay$CC<_COkG=JUVV>H)!zuN?G^yXOb^-qw|2<*d7r9 z6`{{hThEyJJpjymWgXi5&`UnQPL{g(`9zUU6o?HmA@+lzv!iPbuRcHZ35q=~O+EH- zl}>y%aXUfGYl)mpA*YmeeFm5jB#fzPD|zfNbRNFBapjjT8~8!Yk_ ztgZ-;J&fQ|F=LQg`Nds{=x5fk2x2qIr_xeSe~>F^b3Mi8%BtpDLv8K4uD(6B8|T?17FmAlqnJN^1tLCr(hPMbir7)~~3 zd=Wk=I)C|PPhB3V|5RH5I@HRBgi7Yeb&2q>gxOdJh*npU*o%C3w~>K2eam0vASq>% zlBSQ&o3iHydRPN0_l-@?*LJMBC-l2ynSx^#WByTCOro-za*%%0spldC* zkDHs?b&;mg{n@U~@>RB-$NP9js_+D(KE^z|VqXJe>)$E~R~GtV2oJYSgjVVhs7JiW z`hf~yEM8eQ!ds`BuPUd)7syqa2&t8WIIfk~BsW3U^pNS_n{bve$9}%_HQPhuR6-&Z za~N+&O6bihtr5Iu5!{@AS+wp!gFL{YV`%gNa}-(MyNHD)X}wMoa;?$a_<~^nZE@ zLNTY3QvjOiiB&1U@H)TWEgGwU-}+*-gb917pJ__Q$(Ar|2kJc&eb2liql=ruW4hAz zE7wNUg$>0J;bTv4HhU$?Q03}`PP9kB?bR!kpuv8+8CMg%5R7KTiXM4#Oj6iVkcr6_sYL( z;(Jk{Jgylbw8KxglVu!$HK{s8r%iX9(o9s3nvqN}io_oq?s%|0V)9=csCU+DOEkuP zN7KiQyKtpIB(-_j6EIi5Mory}soD-O0Mhm4@|F5LTJC%>eBY!boYDjc^&Q?PhUg(N zZPglJGl+%jZ-%{ivlmqW3~Mg&3zZpY*!UZe{iVm?HphG-`dwx`{aWX_l|G)TUwP*v zvhnK!M&tx&^Z3ruN?Ls4c&L=A;ieipg(Z2RjAMw+HsdQjs!ubX|C&7*e``AsoZl zT-j>nu`x^-n#V#kJ--2)mkEU1iFe+3RfFvUPp3boz?;QhQekRPKus%7isR1)@8M<2?f+8=JmT10tqHC)5)77 zG;n_C>>xFg$ReNT4*|oM0UbXZqj6(g-Z35&rsJY782sOth-e>GBXYwKxP>LWz9M1- zDu5X>3HKs6{#Akd-ksp*G!3iq$-3=9tuzf8h$bihmQ|eh`dC{S$=vgqOvobqQ)=sd zc_kRFxm2GB>y^eY^W&ma)P8BWUxr5u6#8MAX>V`Y{7_ib4(~>i{&T^p*&FYE@g6KI z;`52)jwNqc_ltk>z_7wA*OxKI5m37_;;%)r|BPlI_0^FP{9mDarMGpw`(qq>xGAgW z-|{c>R)SMCp9JB+&GXnXsM0N}HTi+v_LtbU1hI&-Y@#`{$|2&ty&gg)A3S|L(- zyzls;^^-pvBYexf-JLS1{3+~%1K?*qU6dTJQB1_4W~EP_<$x!>Xvfr~OcU>yJA~6*dqq_sNnAhP}s(!a@cU(_Kt3T0j;# z9>__N7QT<8k-^UVHQqg1`$Jq|muhjBCX;`P1FDBw*r8a1AM-!*_1eT zHKg7vJ9`NdrR{u3gG~SY7uCRT4L3xAP%(fxy%R$tPC*3EbnqtBq6%znp$F+sup)4E zf(IO{G0Lj-;11S+hW}2RppkV?s6Xge{n)9FH-ktwQsD28m^-}Co7sFHhPaOr_w28863vfvw;4_iZ6X>uO>O|(W=1}85IC3cmpya z;f`Q$&4pD=r4=PSruNqBZ||ketz7$K`Amd!U98E#vI(YImHWBR9hA73_$haYASUn) z=Ie^D+1Z{-9c<>`Z_#lb=&R{;j`26g&H8ZU8hbuH8Qqd9Sc^j zN%Q^Y!^^7#OJO-D>d9P@^>lvqUui(^MIEt=LqF)%SpWqLpjuEx^3(yegEV~?ol;U# zI3D>u=CL?Uf!hL2eB^f{f~mk6d9<)*t5$2WLBbYX+;Sit(kZSwA9r6~+wRk+ikR#d z#bNj}MT|(+JVwA+$k+jPVJgmfWSmf8cw~gy;+p_FbaU6x!9qixW zo~+$RfoD6?IAun53B%|c#CdXnL!3BpN#`zIqCc^+RK~PCbXZ+(wf&m9W(a}K7uX~s zoz|c=7}qSXd45;Vj<NYa)b2;kj#Zoa4_iaWOfN<)eko*(fQ zi}o3_t9|DyJjDE0R`ta@`Phx~00G{#aqoQT^m`@Q>V6Y?e&zE5G|=77SIWcq)JwW* z`yD`QOKH2Y-R;1M*NappnFWh?i~BI{gfrrjloYG<(gGu-Akp<_Kou^doq?XyD!+ME zFKYs*>J=W)>YVBf(giW{Q1RFJ{fvY-B6N_kdz_ayjy-%*R-67wqLPs>5bhB3uVuW$ z(~z%yi4^F35_1S$uK`xej#;?PhiO{T{g3stNAKtKU_6J+)VuJZ0X2p%~YA$_t z06})R0?~P_U78I7G4JF2hjX03Ze78*6l1b~{)}^ZmD$KYegCk5VOH1p)w`n=S=2~i zE`#MqzDjh|v^V?5Cs1vz%r(#cMA1KbGV}32jTIKEumJpvCD2LNZrB3cTu<`_Aq$j$ei%eMPfzk6iMt{ zb{MhtoRk+D`?O?T1;0dwC!59K6YX_XM;%fixyn7Z{85W^6V||C$3L%pf}+bMg6N0D zi53bJKUiqyW0IC!Q;(pA%mjTzx~PE z$5R$uX&xGX)C4~DRRMhi|17`@O;`CK^2vMBZETV5u((J4+p+}k;kZgl*a0;!s`pT; z@(!{nv<3A{qHPBT8ymO%Sfe)T<&kYAq%y_b)YvBNPdzZ+v&pC^E}CnovQS9&k6CEkgLQiaXM z*na{rx^^N}z$KKz|C3bICvBN5LrYwI)+IMBylrG$j`@C{EqwBMzXXLHLA0_6?Z3`NzFw(1F;B?$l*g+~YP8H7IfeYNP)>caR#i!l0g+f5Y;N$+lBN^&iHi+Bi$Z(s?P6;(9D%Nc7C}RU);(` zjn^5RM%t=I>3QM1){vwaLAqsL-9v^8t(YZG@w$iwikUg~?-tHT<3cQO-R1$w?6=~^XIGTB@9wIYvgsc}T7m zyY~AJpli-})1zkEeXMWZtL+9&_y=qO*T2AFs5(sSwife;Je6jo)>Sl*pnd>NZJ$$C z@Z_yW3;P8>^?zlUn<&8XbU`EwnE&`w1Jea9es>c2;-f7)&icar{*GES+a&2j42IMv zMaijDEgg!)-2H*CB0viI#qPaQ#End`wm?P3sfK$4ndACVGsY6{`3ZCeN9K9L-@NPn za=QS=eC1AV1_jjqI+2~Uh2DJ#>+VFe>p)EeNQV@2AQ&(|WL=@eMrs|Ol_tuJW*^^c zygPZnj`|f%qf#xt{Z*OG8|>(-IA!jzRl+^GYYYSgwK3cq2a+V2)jC?CO2N{-n$^A~wu03<=Hf zn{wS)>q1!aVfO19%^3GpgqL2=JMNz)lKeXRm7;-T&404(pi@-~laHsjAU4Zq(i`l< zzbJQGK(1jqVrC8l8$;0R zkA02L#>>h5BoxDJeo<9D+xrLpzRE@~4vSG2UHp*EDaf=WA}y4cJ;{hki=Kn{L2yxP zXqCl_;5!s};c#yFY-9L97vpzyT}(^f^l&=jpS7Ys!;k98w-0`Vx;IMM+?_*$wB#Y4 z+8O2s&Lw_t`~0uw%&_zMCua1nr`Mu6EL{afO;22NHodARuME0BHq8GBu8!Z)rl-l9 zrfa@#5V#MvTl?GhGPc=?_3O3c)Q$yuAxG9Gy9$DoU?7684ozLv&*1=mk2*dL`Lv6oAj}W}VH8#hAZt0kd#99OyoIdcV7%ZM zv`Lr=tK7johpB%xP|INc0Y5f=rKRi~GHrB-Yn#ro12qf5=R72cXsvRG267&|3l*_L zLGUSty_EGB_ktboE&s+;!j+Tw$WfU}l$N3+&XQ_glr`8Z{CX)A0ocnCu;XP#$#?3Q z1^l>lV&W8y~fFA;gh?S%=$+Jdsi^GaYK5%1$Tz5R^pa-auMMFN|jrO$lN zbnA%;%dB1q&CL?AGvA0ay%JS)klsT**a!O*q|*c9jK!_pF>SSe3u8UW%Z1|{t^DxF zuzCW%^Ww9UV0_<`O^2E0t05zL_Ntv;zSZ}_hp6k{sG_5RY=nUPpvlNHnvPyv8y`Jd zch}*D`vs1C`?Gf~6FpIbgfo{voa3LH-vsWHA|`&bbMaF7DXPruo@3F+On*k@MwrjX^WmR^gV*iCmAL$U;4muG$8frFD073BraaI6}MNx z039!?B!x~4wKHUcc3OHB@=tqMkEg0%k*4FCxrA>NBULlY^jo=}jJf)t)(hVVhQ~78 zA+lpF6vhP1O(8?zxeO?O?}s!f`59MygZ%KT5~JhCd?p?m!?84}`Ym|qXOrj-Fwm~m z0ET_o`+OFfy4`^(W$VjQp%dL9d}#f70v17uuTYli583&xkS6j*+3H&#Uoc1i(|7?# zjhJ7ni`FkUq)&EQ{fj^c6iTjGsoU!efG)*|5}@EgNOH{iKolmk^#ty|>$T)HCsk!L z4?i${#aJl{-U~%BpHZKXf#>D&kbg|8n;~I2uc}8$StRuJ|M2t<+?h398*Oacwrx8d zr{i?&bZpzUZQHi(j&0jH_w#<|oL{iV-ec^lRkhZfS4g6G!Z5#Y>IZWzp5DsM71t(M zDzwye=2c(Fw>BtI9u8+*=xYQLM_5h}(@O%y>BYxKM)y+zs~2iM0^L^kuYY->xpUFK z+Wwo{MjFCh=Ej071hk$=Bi3|_#j_|-|o~tfh3(pBoawkAZ2DX@N<8gLQo(N9q!p4dx z>eNbIi#k6KJ%M1&5VWBX2$vvhc}~_FINjxh#k(^Z9KH)AgD%FeuZ6Yft4;t44xOOgQy_t4a`=ni2~UPbG{T@%5^)7b|%5tKma@}cueocUjabR65| zeOs5az#Ebbf`V!qOXHC{|8RByl$D@H?M;5#NH}3b$~DC}Nboiowq<?36wusY$qNb#>E!=D85Urs`MIB>LzCPQSFP>#>3o;{otndx>}~DeH5UA z1|UuD|4BbK|7U-IQHA{<+T~|jZnRv^h2W$drbz{ZzNQCLEJAjmQ05`(4>fsiw+Rcs zvrKV_vIqo!psXBhFA62g#+(as0`n}&K*yE%Isqs9c_?muB!zy}8qcuX)C_A6yh*wz z{qY`nL$*L3&pW6vD-J#J(AfGR=?|qyp-x~`gbJb5KI!^QFLvvAFTb3jX-DF#-exLatCwc`aK+pgeXlkiw=INj1MChWb4+1w67)*bB`XdO z#}s2%Kvf%kSke;D8=hvWcm6X5hJ5hTA)d?S$9KX5A73;y8?U14p(yAMS{b|IPyU(1 zlBQa)oO|y}`g@{~-h@<;*8)GGA7%Eixz|pU(GScDNR2AHMBgtGhE#PPn?GKtOIroU z)>EMU^#Hd^^A;4nj0L!I!~I8%{3umrSHB-tuBQIa}dJ%-CN)zIV`M zKB#eTp&13rUc^i4P_uYtpRvX6dAd=d1)RzT&cDGx+o;7pVQ6yFdVcf#c=cJ~eS+M~ zRtFwC`yg#w3d}Rj7~5GYHEJbQOrwl=!T-*0-R+CIrZOqXq_qq^JR9JP3_}B zu05cVQYG~iFD3vw6~vz={1k1%e|k0u3OA7RWa;mVdcLz}ZhnWY^1?Lb!H(inI`^s*^TVlOz=Ehw zBTcNu8pKAoQVW2UtzlXK+6GYnf%edYaFI-=K}N&~1F+68on#om_4b!A3_=GI_Y}^K zEs364`~}Ongx#fVt~8Z5)53R%(JyeK4&8K2QiRUQ!$(^b#M2Qc^4KCWWec^IZ1~?o z{U|0r36*=au1iqy?b3n>NjW^>^=I@r!i{4b%_};@%-CdS4Ov)?Yo* z;LuVL+Nfaxy6uy+ac#$6`NT4c1+_YJEFw7%U`UW8{vYKeL~Ls)yrSbAfR1H6I_7y` z(;<1XOYGdKd`5HqWwhs@AHxm@6h=AjV$le&N)u`t@I040p^|W<1IJiu$Ujl}eIF4i zpa_LscI!?DMfMXKg~t#x3w1U7$}Kxmc6yGw*lt2IEpNFm@!ossa zNslGW`z+&I>`D)(y8;banVn$w6hik|0$SqC-P5Cp2n3QHuPA`BBY6u=Nc&3=g2 z)-E*}s_0rw)jplvLj4+mvOqXxZQZBktpSXjE*Tg@^wvj75I8hy4IHAIv0#{>UZe99n#KL zTUc%>nc~vW)KFZ|7*1Tw!}NO?_&8XiU?xiL>~H?7_nz1hzA&v-dy@8_5bhip4k7XD zD}z_Kr(KH~LlrUFW@Y4Iin}K|&q;nwBXPdqglYCyf$00{`bI8CE5@IYsE*`t#6aSu zqxcfJrwrWI^kD`XD@b6+h0XvTe`1KQJ-orLz^G1v#UgU6v=BkWFb&AW1ObeDOENG=NbG0snr ziCM)1_e798;%;y%h9C#22V9d^_%B^C=B#QZ>ENJa#H>eMj+DwG>T0|Ec1X`KJl;YT zlvJ+^I?;8(BsJ;VZ54B$egZbmcuQnwgDPo%?C^*xkK0uzUjd808QU{02(i-qZ@dzI zP*nrfXUJT-x2vApRLd#Fxi`+~Ml!<6!pa5xT*+#fQ6g>>tUA(VAY|oz6JcTW-Jb~{ z`FBv&Ki1|61_49p*!H1R&55F<0leU_X>YA%XaO@VA?eG{y}ik)S6>G?KJN*VAX6K3 zDr|Y>omy~3ZE!LKHFT}b< z{o?_Gf}T{;QHFuHe@;6S?Q*}%^128zDa}rUJ|d=qcqsQPLY}gl?Q3~(JB|#X%~-kI z7k<{w)W}GtIk`b$q}oyjK2k`Lf7j|A`&z>4`mA3Er2H&BT3$N3qxl0J_RzXqWLQhr zXB`DLR{@dl;#`sM4dU{%hro}{w#C1D^L|K@*Z_7RX*eaCU(QLD-a)XqaVX$+zH!ji(EhR!^^9) zxZJPCW*U5yKAXSOKRnXQAs9(!^@CnnRZ{doV2 z7!*+=2#sf+^r4*Ar93_BtJ8*x!yHej+`C7~T3oU%%ZJn7==s&GEgl+BlviY1)THmU zeF#(uY`P&~OzT&)m^nK}oq4o^bKNs~*b5eEJK6R!t!RyA2D?LdzYj8Y3-p723usDWQQiN8K?}7G@P^Z0A%Lv^RGriwnst z&Xd+>Mg-w&?xxVHydIFUgwgfAL2Z)=i~SYAP$e;+{T`fi4Es08OR4p0Z52;+pMz@b zIO$J&j#*F^0d7n!nL3tMR9eTwGF@_M?D629o8D6EcN*O7!BaCC@2(24xa7VxDc;8P-?53>-3M`tQUFE z;W9fBDpgp%g%03EgsHsWe=QJrO3lLJH^NJ$G^11|h%i0HHR(AtbaDO37o=L+EgzJ# zIJfcGuOj3$5U8Oo>qY9O&XsGuw3v$UcYU615%IW)C`!=6jkyqe>}RWUxN$>*Uan%pkq-Nwe`%k})6Q#eMR)GY6`DG@H@JY!<(0iwY z4>r&X#8h7Arz5sFx<(X|WR z5F!b));|rZPf2j$RDGEITQBqU6NCN-`Ms5PLm{NAc?-5}C+uZ@EN>%6uu>H1vDF@tH6*9nciS^0`mEx}~iHV=x+{o)2jjt$w9wV%QwLdAo zZT4;b$nkQBlsoxcW9RNx>QV+F<$L`!@hM<*o6SEPynfD>cs)G|{6uWxxr?Hs!=X_{ znG#dkxIk)?(^-GWcf`V;o>x;2*eZ>YzQ5q}VCS+M4qtw}KAm>9U_g{WO8D5ie;>Q> zSL{y^*d_kcmo}K}jvFKMjjIKpNf=cTS1VKE@yMB2A6te1Y4+3G5)mQn&S6QWp01gn;1*1UbJKmOglNtdF7U32?$>OIpM1n-x|Ntboa=pVxg@xTc|ZWaEhtlX)5!wr=0`O4M?V^l?$zOtf@7P)C5Md?K)zn zWg_T72~8P8iNss?^uPv>A{h(T%1Q;U)b=d!m{y_|^epa$kHA-IE-bMm)^3X|8^{EX zEGHYImhoaG;FdYC-u0S>vb)^U-rXM$&s7JPSFkYZJVA}ZV|cAuw%MFJkubIxGJ0il zjb7E@oE$pg*zX#J!TPNjSCqu8n$xgMBWbQT*UO9=^E}DF73cOYdVH5FzvAz%D zGY`-0AmBM0&nP3H1j)0JVz>NI^Sd>=`1gEzXnF*yNQ1lqX=Dh(1m|xM=@B4x9P0`c zG|$y_Mn;XJS!Wgpl*h_bsI+JWdQUjSkoBT#Czq>*D%o7GWAKza#-2SedYTKG;|>`u z1i+m(zzd}52xRtl#r24gd%!Rq12W<&49RN1;eoH88s@@VkgRF6qgeK7we1z zx?D=&V^M=y$AqWe=S!lDWjIf^EOY!S+7MYrAb!B_`P&d)=?b>F2whrdG6|hKDF68G zC=Qb3d0C3ItU%xVIbbm}ApSA0{X3nQbjf@c^I+cQ#+_!;&yYBh6y-e)iEM?n?PGS+ zt6ZmxmK&w$E3|bKE?iHLt#kToxIPH@j8Cb`wD^)mIbmpTX*J|`=mBngzMrGY0CHLK z6OmeX*ZreP^$t+z6TJh8&E8$|lUA@MN;myRC4BK8k;}5*xFSWYMqjLQzhT%7^-R+# zi!Cr2n;v*DXK827(OXcyKQ#m1rGL=BcP}ojGIDo?k`3{LW+c!rnvK@Odp22tKy`K^ zW=|}R$9Ad7oq$<9uz%$7%v~?cPTv`Isj|EXK3gvNqJj;86oN(5Y9B0R8{Nb_aN$Rj zx}`394?At)`+Pycy{=Aec%ck(JZu%T=Ffc4*u$;phc5_R;bE|JD|mW>w#m0@Yw!+u zpFbDz>i)YV4^Z0BK%gMDOOwetE07<*YcGU(r|N>Bbt-#bpjX^Y@9%6?_ggpR26^`- z#KGC?z{|w=;KXT~UK%bPsO2}NCi5_T$m%%LX2;wbgXBREPdRWVqxl7x8?}tXy}XlP zrdb$f=2`bK(@gN`a({8mZZdXSO^Q zOYkJ7jPwoc-{-yNE+j8FzVcS%=OpcqV&+6yTEPLKehA`m9xm>5YW8OmL`8h@*{yi< zMe&pElrft~8#VM~yfw7L;QeE%9IV}0AC+mJN_s3>X%Pp{nW3YtOY~+|SI6N&ihFlx z4c;VI4QYVT9%Pqa<9+~G0$`ds1~=Cx%`B{gwwVgP0+t*LQ?BV30`}jbe%X!j(+_7@IQ|o2#0>g zz`mV4Ry0uP;(OKU@7?2{7u;W>xzte>&xVc_ycZHEe1_2>YI$pQv0!caZ2jVm)ZEd< zya&;~?$9KQYhZ{Ny?;Mp6aQzR#iPr6$S6bzI)c!5-C&2RXb{=4zfq3Cr z40`fN)Ji;zalVjN)F$cwZnwn(2|`HLM;0rmkNssdkIx-iG#pXVeZ5fpF>}7%OipO} zkHR{e;-;wl?DQpqQD3}d8z^!P(19mZCKsLbn!Ud=LMau1lhOfD;=;xU9V#ZM8<$hE zrzJ3yorl!-GsdD%*qthz=tgPcD%ZGhj)la}MLF3a$rdTDccp1_-`=eJM_n_B4N>wH zRO{=s+HJ^v5v&w>kyA~_%IXD!ffNBk)^sspla67ias^Dv_nHcYp%SPPmare( zDNWsYB{5ccT?FCvG(p%D&fF7IpVa7*Aa-zf%b9pq<_a`)(TS_1Pnbw(WgkP|f}!=L z$s|b(#UEF0Lg>J)EXoXD?<%U$#9b?H8bQtB#vJ2xcHb8d;hJJ|Y8P=iLB=mXR7ZAj zttnCN?qz0wmzTMs5vGTgKOFxChtiZRc0#>{&Af0<`b;8mwo@QC-V5_Y4#!m@zNS4- z`!Stir(XbQ{Bt4FE|u*0bOJmnM9gdzE^C zf)mEn@uORo^*Mwh6{i3vsv;$6SBKDhvv}K*27lwLiE5=&6(V`4<+ElX_j~uZtTftb zVfXRJI8IMkk0=}#!KcBL*~TV3gq^RU`rUY7pJ_IOc|gGLvo~g;=eq*!SsHWk3qqHb z&I(e;v7FT-|40|~QkBf(IrEp_o5F))&h1+HEch(Ah!E9VyHuX@RIbRlQ?8o818u!2j%ehH{5^BfJhKdI$SK~wnlSYa7_Ed>?{Z~IID8q^T=wPa^0d}xt>_219Ee#ofJqQbX9W-= zn{KELel)78P8NT&J+$%XkAA9OoDo#@9+P}@U8{riv`OUbAR8Q_P%kV5NjWj@Q&AN4 z?0{*eteI_JA?CDQ_{1P{HvjU?CUP~nIu8l>92RAVP5vNqS$0>!Qu5wV3SWOL0^Mmo zPQGa@_d=6$ib#Iw#UAl8MvXIA|Nsj%>3LR_>(U{NUZ>T6jpq9lLZuf-7 zBD*CLNVOKemQg1x&LnnH#(gBvl&-5b)$pN!gVVg*D-5$#832@Muc&w z+tVl_c8$_+e#)!lJB)B|!$WtHzGn>h%qr?s%;+*5}q>L2= z+rs#)gK+b;zQ0E|M&g$lDWEhHkY_|er*_VPufqDW>4~iO49WWbMV$H&)r6<@VO#X7 zwJ0pSWhc}&Hxe$zLGW{Jl0T(rWf6 z3U{GA2GsT6G1aA;ZDyG_bh4y$3ZFM$G!3+!5k}f4ev^*tdx7=QTeKbboph(0$fbF( z13sgA%C;hr8AK58$3|3IrM?>!nE@Rn{|X!?HyPorj26yZ`CguuwMaI&C8a>$how8I z#jkb5{VaDamm8(BFmP?0wV&PSq8IZmJJ*W$VwQh?(lrV4T=HxoG84 zSpSqa7W)x{K=Jw*L(2pn_(L@m8gYxkm>y06i~a_K2ocs6C;W?0CX%A8 zQlhlxsXD@Ip8%_*Dui@XB2C$^h*;pRNkf?q{M>*aeWYam?~!)&gEEe}E3N*Ax8wTC z^l%m{zUgpe9p@F+Z&*^AlZ1%nqA|*N4?9fmYQ0U`NmC!sZ1T@n3FZP+;&Lzi-0}Nb zP*`GWmNonDO=gyP{g=kIa)lY8gF^eg8%t!b#k-6Phd(v2g%Sf8*3B49mE4qvc#1$& zd9Tn0ff}>VQpuXc;Ub)yc1$2jrh=IR%Z~0Pe`lmr#MX&+H2H($1ZBH5l}SXP=K59z zZ`5>CtSjqUi`d}DFkT&>#aNuq*Hl(ro2=vbi;KH_dHqn|;*VV7{>E@H!_$zH3Fm(k zah3V=sm0_V7YH>?zn6x`9`!t9Dlli#n^NXYLF8es%bV9TxlX(7fUNw;jB&KsJ7N6I zrRG1%L!h)Oly=QFwbho5CXrv~7(~io;S=k=9$q$C@-hfOh3H0D>-k>VjYSkwAoXEp zh8g=8;#H7Ub$7R{+50=v7mT(~3m%k4F1R9lh$Yl3kpJ}}ijNkOf_Ta5J`DFff1Amd zMhQEp>VfgIPXwgxGH-JsGR;{0!r1}c_=Dz{Ycj-OJ*KsC^flp$@;iF~@p+pD4CN1@g z&gnAIQ@x{63p2UhFGxC(U{Q0aJv-`Knoo&0u(1?;+Pi}#XIzu9Y)pPQr$#J<>=lez z#FFnBqV+!bcF|7ld;5xpk@fkApAO-0b^P2G0MsejMcJ8fz}2+OvvH-U=tD@o?wpS>dfK^;0ztU$3Fh{75{-;rHm z8R~EJ;?7{PRpOTV6q&w>#A6#bq`tHlX*%UzZz4e4KIK561pExv&YLURD}Ue-sh^Sb zw#h*iGZzGpnLX|NicizW%3lLPpoT6*S#|#K{7q^W0T_b)#D!GQ$VH~lfDfAKcTG?p zkZxdgLTc}}QnzxT;*}b-8(6o^hC8*+rj6;*-5cD<-i} zva4s${gtLDMNZ~Vi^Ff{eLay#vidP9>b79MrYU$XtaPth&T9@+hS9uY@DP`_oIFP; zox^;?Mt*gMM>QFWIFFT7o#=YCsx(Oy0#yjQu)xpr?^h10k4;7}b9&nlJE<;<>^D%& zFr3WIw!YC9)pc_IJ;9U6&R(bte_m$=Pq5nR+QDKp zGX*oZmqo<~;T!<};Y~IZrwn=a@)2rOLq&V|RqnoI^Qt&vpERwai31kax~t#JN$jq+ zGBPd7x=1#on{{Lwl*oG-WY*yx6(uHGi}sO9p`fzIp@0SqPH5~ka?Gquk2&9-LXuMq z^u>j!Ntg>LwBI z3!HIkcg^XR2~NaY_93pZ9%!R+3!RD^Jw+fOXgXkCXne`CX$T*44qig`?__FAFIS0A zFP=2LeB1W9e3fAMQ=Nj=o9gXty>CdN^d`{MjZ-b{>wem&`S6?oAo?53#ZAo=e|6!J zF{ioUdXBdYvdE&kDF~GeNaz6M@Z|>ltf!CaSpGN7-(M2sl=AVnZzH)4kXd$qq9 zy5n5}viualn6%b4Szxczi%_kC7#CN0ntXTrsn^(-MYl{*oz2L4(VF_Pe;*#X!6|QR zUn3oMAX={n6FnFyIjj-R$uv0>HX>Ub=xH290)Y>b!bZw|XJa)HIIK~JZ0TKJVe2S+ zR_Iq%81p#S7-xq{M6k90cb%!+Ugo_~Air^8;B0pdrr4doEyg%>#^?FhRg~LNb`y}FG4ZpYKdu98Ou)I9gg?o!tO%22Yh$4{NBZ-vhi;l311pnuD`sR&*TZt2an~ z(hn6%bMam4ACT{&h@3##4FcBU8}4Qh;j_)S@Y*`A1hxd$%{J(!PM#|_0H<`YbrlEHYl z<*z6L88+0&5G2JYM42Vs+stzIBuMhZ`5Hj99|06wF+L+_Et+v)N%)y8_QX*IbU^TH zb4khj9`)F0$VMj7@()(+WnUyRgs>;QsZX!C;i+TlQ#AM>st392juUQRQ)hclv+K;) zKx62wnIcc2r~%Yc`S%P$^EDmu7C+6|qD2_mgN=!`Z^P*&-o+q_5w?jx&kRn?@>oMY z6hvE8K45yj!<$M3Ci!SPrPRXBe~0PzEPHgf&fYrdoKdfZj#WjmV~r8a)O!C$W^cD3 z?qLyvLJKYJV5B}j&wN`;O~0bBUmjI)nL!eSFZ0%Z!^zlAi1lE7P;LHEM0>K3KE6qSWddz$0lo}t_Q^K zU)m)XLGZftD;Bs!1e2uFm4pM~f8O(xMwK;q8c^k%lErI4e0Eon7x%6NLHXo^VgFs= zB`HC^O+{w;h=e;il9a-Q3Mg{>#lZnS%Z?s9_QFL>!wq|0IObYM{jULYa?VtdewVV_ z>zm*1Hx5LpVMX+t!Xi-)xxH~D=0fN=O$Z|Z5Z>-`E@@q4_Y&s(g~QKn;o|v^0|yN? zUl#p(1gqzkkWl@uwSuyc+E454@Tj5{9prJ(TNTiIvW8wnr>2G)M{5`Mi|dlt4c~zg z4~<5`sIz~MZF%=?c7>#zYC1;l;5z|6PQJMD-N6LFyMS{*eKd+LcO`C4mrGCi{Rw0} z5e>BVuAh7UdRBS4=@8cv~Ove2vJ?}O{ zcheRWsPt=bLOJy0Rrl6F4t)Vc!@Ew+kV@(18gkt@WFCsTww+chqym#6UM$f(iBy|G z@37_5@#2G6YeeD^DaR4GU2?-nmP#Sb#m^)~6wfk6>xqo5wV)b_SFmp`=pm;fFRETn zq6~|qBH(tQi6vDZ#b&EvxqJ{*09_|WC*uXCXCe9I@NW-9{nFQCNBV1XajnIX@4huu zPL2UurM%W4ZtZqxAR|s9KOho^w~d{PBh{PDRnU+H{SeWoi9l`;d!mOf{pAc?n&x9I zgHNDBh&bWlYqV6kSFc^KuCJJ3Hokpw>eRIL9tLd<)6tvNU}5VzVh=HNMye>uQF64E zLQB#u0f|~}>#WUnW`fV?D>_^igQ^9g+3~ZI8e;JxKZfkuvfMT3W&;bui7&UZ*s=^n zf}m;{t@(x?>19JL<{%y{6Meg|*dN9s_TF9EkTSQoA?^glz_&_j1I!P~>(|%xXw6^z z`NcATt{b2!ZKDp=AvpMG*Q}Xl1mV&-u$TaXu6`Ei6NrcAhc3yHv+^{Uajyvu4H8TF zSY}xUC-d+2+<+PKSGd@TGQbG6zHGzO!!(1!8&hhW5G!)NS_fFZmPa1O`L^q-jV4OD zAn=%hH1!H~&}!xR9SJ-aQ(7mL)yZ-NRQFr*X!SPd)5I1WWKgY~B)2tP^%D?B=8?u^{G8yJ8hWPG6mk#~a6{XMWth~YH+bz6Y6gP$S`Oo0NwaO9wL}bBF!Z`k&$Jd&i!R8>!N7w;=i}fBZOJy>|SW% zlr_FS^p$Zkru2Yl>E&N@tV|_Ldin`F4g{65*^k_38SC;(eyW4gR z9vaODReg7Yt%;o#=)8|qyuiP2KAnCgGJ7OF?m(FN;?0jt`ycrt;??_8kOk!crL~5~M zMaqB`$~PS3R<2fy@>^-1SNXU52RCmz$D}<_2ZAfc6sKx13f=j)-l58K01dMsCtmfI zAQow=p|;HC57=G%ozU!vsFbv~A>EiiyZ02Te?}y))ZnXgB!^760h+lJYPe1tC;a)OJiVlFNU}axe1?QWnM_vYs zto{ONI@Y|A`ygZi&Kg1U6qQd*JZuMV6Zzx<=bG}&ao|VK_wOIB&H-^ZHo~!$O9&X= z1RuB*661*c;QhE7dhqgf7_!HnD*x;71rx#$WvuPZTAis#yh3#yVvXDN4d!nWyE!&J z>Yo}thtp_A`UFSa=ZlL-#-^)ZkV26qH1>)HUHzLI z_((n!0<$L-n^F0kfCjuf?x(m59G@Elnz@hb2!g!b-$)i_u4lpFZ9`7&h-%RwD&wfw z5IS8QcI+f_QCz!{CGT8fyEEV8G$o}#!QWC${RbY(nYuI2EY7tcSRf?~!$`J{(Lu_9 z`AmvQ<6ludS`X4i)xgAdsgZ=j$G(ijshMtC(l5Y#yocbE^%JFNCw|_$*H=+p;}y0{ z>K*7!3EynEWD)tJi2*%YxAKB;dc;BG!?-H}lGuI+ji^!jm$l3Ftkg$`7zYBILsciAMl7Slk#)HPg6f)6@%p1Nt$U6uB<<3DGeEy z+WbG5Y%+(|NdM8Y%jyfspDY;)LhzBdIWSJ6qQtVNsFUro3CRl6q=q3yz#<16TjEhXb?^|A{I;_?d>IpWZ zmq?nlC>`5*i*q76;BTf9eFC~V3IhJ*KhI@_VXtE6o8Z#~KJ>jFR#k5@wLozWs@`b( zYMLYtMj-sJUBN)ayf8ogAM6)9@2OX!4p9?go<9uci=Q@x9$6m_veA)opuM0pc0K3A zX-fx&#UX7>4lH`i%K3>;g6hNzj-w&(N|$KJ<`doRFlt`gj%n&5`tyEw>z*loQu z`>fim#MPV-7cG^iL)XlbhB6bIV?z<$X>hv6S~MK;9~yi7eV9)ukT2Ur$-s9nX~6sB z3C?M&6cr3I!GzmNRBHR6484`aErR5J1x*w+UN?egNWblbL1UGv)v6sAw%j$`AL^}4 zU28*SF@^WePLobak64^XZP#LtgJJAt#UNyd2;OB_p?drmgwA!z<76sY)_bRC8#G@$ zHm~1P&Oxu#wgTu{)CNiO_mRUrn4s_!q?TQ@oyYVv zobm`22+KeBbjMD&$Xx-C!7{#66_?851(uIIueM3D#t+T+^#9)KbNcUhh{<{BTnU&H z!CO>!C4%p|gW9sDWY`_lqj&@oBET&fH`wKM2GG&9;n16HdzD5>?A4Tz3v_5?-RpsZcolrW>zl*HU+w3&z zoRs`~9vFyc=qwN3>!x4l%=0v2e-`sU68fR{Rn5V$Z<9Y^Q$@28y`^ZkP}dsS>P4zy z{x3V_{}O=0EN7-#LQPJnqzF!58?rZ<2kDv#I*77$->VU<*jz1ZTPrI*L!EW=e0+)d z+V;-GZvj1C`ge^<3aNS1Nd&qH3k@bPwEb;vIx_A;gMP%oV=g=u*&@x*)hTDkIn8Zc zvFYJ2KWuD}f{#FI!b0g#89s`%&k^(cx+J+C2Ln(3n7ANm30rdetm}&@uB; zE8|rND&@9t12@ZPQMxbt+!l!jq*qPFE{&o^Ngz11!OrP>og!hxiR&rSUH2>7no4hU z-Kqzs+$`^|{*xXYmKr)PI(Pnjb-pdOd~he|Fh&qUk*j~awe+6GML&4l%_*CO1G%Do z(UID#$QhWPTfcnHv>C=*{eWSrK<83KEgJvezYpmoubjahccJ-0F@tTgXr6#TzZMP? zwXfBy+x<@zwYR&&RF{K2?(b!rr)d+rE6XRCzI>iUkodrGrU7*!Zmv@Xauq;I4KRTm zEgS@#g2;|o5bwG>hq*Q}r1f_5G(C!G!O}@H!G9KeHoRyrVAewZYNdI`$c3bRgvgxp zf~{79@ox*(b9>>WuLmOjfH+N4#T8TQxFE{>sO7s=_m3HETN7b@&Hp2WJ36?gcCN20 zFKt%~o}=lW%6JP8B4iFi!`-thVAh#hBG?3nQOCf2fMEWs^p3j7$5OZUaRYew1iH+^ z9@)0%UzCTeT%*v(V(^wM9!N#7mQx=#wzv!vK!gsj|EjQfS@c{&r7`vjO1@oFp3EN$ zKMz)j-Lb0ezEcHYT63wVu8aO>?s9-Bz0)chXcv-msagGmrR6}+Z`(}0rt;R1xRH=0 z_SX$P$t48+#Z=_$(!Ef}ojQk76f5Yfo|F{swLVuv>r-B`5t09o1y~-M2PY3Un7ZYY zA8o%05k*j*KQjNF6n6jB*l95jFQaMoK=Y3`h${_R*}Tw(ZYn8YUQA;+@G+0$s6{VW zB$C_XYo&2CVcwCHZ3as|aB2(t;q@i&AL0M#djN!AMNXHLi;GCWhlxxRvYc!FPNM+x z1>w%Ul8z)nC*f=E5+ELXKD1Jdu9+(pe3XtI0O{H@Grk)Ld3(Fpf;WdYYjW@7c?(@s zmsR^D6@e4*%yIds5l0YM#V~c8&`hxlDfqukl6LT!C5tJXiU@4R`+kmBi4(4b1H3*Z zM38|q%(lW$%qFj4G6!m3&=NY4h@b~<+_$_O;6N~7E)?S+NKp!*)zy~2W7RpAQJLq^ z`1wLLdxkIU?Tea)TO|uXJcME(#DLu=o4ccTkN4UMUZ8&yQQ~a=T0Fm!?72vg!OFXT z)}|S}(uHaRLnv98^1mbZOwjP;h{mGXeC&Tol-i;V54RvEeDrf&A1~o!I+G^wE955=?v%KqzT%1YbN>Y=1j8mFAzDE@DuKg|di7N|NY-Jf;fyI~6CH(i_k^{qd(|ub4X^O60pRvoeYe5qOAN+4Q z(%#zrR4%jsTI~pn%})W(KW}YlFPX`b)4Dl;m*48%LBM-XMI}IJqTVp&!^MjA2REYX zXwUOt<&l0+Ss#WIblg+}$WP@RoR=Th=`%J=X1=Y?klJF`Sbb0Ag!2UvvRfA^KlMK` z1z=B8hekXpo9v-{#GvhtUp24pOs1107vypAo>T{5KzF}GCqGQ zyGfvBK~2_XwI_Ia`jDXrxswg_mhY;dYw7%{d9X@)t}CtudR$*zrgiYBT3`UftSXYJ zwRvCTr>+0|=2#_+jp`z4KDTl2t!I5p*^EDlEg$`)MLC_68RCBviL;_yi7C}Uek;Pl z2vnEX>PF!RAhKFXxhzY({QpCDg4u)tSU=A13I}o%Fnz%IYi_9igWf@*K2F(ZZ@j)Z(a#X$TT&}Vy>C2~L-Wn99=-KWMaivE+rnPaEx`W_7K2p7V z4``3@*)xZD4)R1d%N_uC^~8xp-i{Wbprv`R)K0YshK%rTltoNkF+kqmZbfQEe{fV$FG zZCdMfDrZNi706o`MuhhD4}|1>!>rir1il!G$UfnYq*m=Qn#?lXDj8VrNccC$RLDZ8 zb)HaA1P}H7#Wx?@5;Ydo!a$JJ`)V2m&+hk)?xqJ-waN;L_Bm!H>_pa&PJe|ZW@}n( z*j0^|PQ?BgH)<7B8h|y1%woa!|JrVF3$Fp8>tr5@6c;36)VGg>Wij-r-=SOD6369D3oc^neVm;pRSYiMP-DCSl5ssGIL*H`|#H(iI{P4V?I;gxYPmprP0+QuGdc#9D? zl&EL{XpB77`w7^k(s!#ljD4kl-3RDHY9JNh?LqC z`WJxDx)kfu>q2RCCr#G&Jj`>&Z?ZjhCJ;OS0p!Z64 z#U12L3$~lrY?vsvqg=P=3UhJD^4Ac<{gJa3Ywdbg$3Px7q?p~*n`RUXjW==XXAV8Y zGOml!M_D#let@ZYt;hE;ScEss>2b8c^0t*4NQi>JU=F>lCV`hs26rM2otwx^Reug6XGrE_@iPe&kOmCe>bEKeu6U~HXsn({eKp@|D-7o&sPB4?a~Qk;OCb{nQ_VF@){AhmgTA%>0P$$H3>wnac0H=x*bQjB z4ZG(iuTpoVn`iVr&bNL8+haH?hj$*T^AAS+TjL%1^A%SQUA=5}X7^^hc>crgn9nr5 z@|GLXrtipsHxRU-W0IV-u62-SI<$_P(nymCgT^xVx;(Nb0b4oG8x!?U@ot!giBp*J zS^YHszWRF;yi7k|P)|HJM);QovHKQ}@c#^?(sr@!EN#e9oJ4W@3GhnKKa>s)y8A&j zM5cJr{NQS>=P3HHPV`KX{U~d?k9tLO%-6-SDfjZoqCG$*7R6AlI!gSX?h`4HSXtx) z#QNt_zX66ed))`Q&=zb&a8`I^SO2@;TAGPi2{m{F>{L12Cwy`W#?;s1^k{6$YniOZZM35Xrx zZz=wqG8?n}wZ}@E4z4*MM3FY$I9fVaQX}adW#Z+-D7csu3)v?d)7a^uOIzz0vfT-; z`vnUoD+N79=f4}B0Z4@X1w|_Rmn4DU$c(wOoPN=diGJq??zivva$7KOIc1qgb(>bQ zFWRRxLGSoI&~;Sa60y!Ve5Vz@iax7(9|7?YRrQjgm2221GudD0UT!jJBMfVOTe zKqJ@fYy0n73W4cd+M^FFUlQ|~V8(nFD{l17)MI|CO70jZM(w1X9%%Y21+(=~m>%6t z^D487O@jp_?xJVZH^<0i!jK?nCHKQ*8WaThs3+{^*)E`pApdQu5vE8lt;n{fJEo!r zr*jE|hiB1PwgOr2=d0JIvEXr0*Gm36dY=^S2d>FTb?*2%r!v07MFQ096Y}8}+UsB0 zPVMV&CkmsK0e$gUDOajkN)ep1-UKwlci+C|0W&p6nwwkOXBcl7J?gWSv1IgejUdoG zUg292Go&gzO*i-cUY4c|j!xgiB!@*YU{G-!jXvpOjR;>r(u|N{qxk#eOP*1Ab(xC) zWUDPhwKS4I(3n2n2X$jZ%6TWArP-+ z05flfYEqjTBDB5Vo%hqWwiBjb4JlVQA&+z{{T0t;3dGkOpNr|wpHY}?3A}HTNGO){ zU>+8dBb4@^{yN-zX2-UjoILM$uKEER*Q~YYnrn=4S2Zq5f{DyRxPQIE=NR0w`EXGZQVRGgo_boP z!pjqD5{t4uzHz(<3PiOhBm*l8NK0p4D2WXn<^~IXI|&WI5v?4XRrUtY)Era7yZBLU z7Q31qXL78QI!UQQnF)WV;H3B@8fmN5w`j;FV7ui9#GsXwdyhalJTX)LNQ|27q~8~5 zFR;5t1F*J$ZFhq6>>fV@$H~$*?UUU=DeA~SAqh%I1uzqwr^|>ZN@=imZ=oqRo zzf}9`$WVqkHfX;)?hAp+ROv#j6wVSA^DnoA%-`?n|5uMi-EMM_*XEZ3_g>-9>B*Yi zunMez?B35(OgMn)*h~W#-t&q6^>M6K5vF1u3BdxY7UWx-4$YCqRz(F7Al`F*5tUgw zs^R7vH2(Y3z|}%;Xo)DM4m}x`2y$^q^K`N3T5;xPz*|IlXE+ThHM2!&i-&?nKNV46e}CQVS*Lj?B1zpX#xfeD9I`XAMQMt*%MTSRR5{P)UxW5TU+& z_LUAjN!(6pNA8P#cwery3j{AbqlorQE%>UO=GO0DDez&5FV=S`dxv`arZ%Griy9W1)5)P$EwP zIg}q8u|pC6p)>P%9$~#_UNQ0Ve&Ilnwgo+%uePAi1&p+Az)u~P$mKYUgAp!;+|{c6 zl#X;SWexng6ccx{a|{dEjGB#~5<0_0O%E%IxR;ZysBgO2Kn@F&LW4M?a{U*JMcJ=1 z)TgK4f-aoK0-Izj?1w4X4Sl-H<%*7k53E_ButqS1+joMf zYg)Yeztc5=Kazw&EU-z>8(u_bKUf3ddF|K1?3iq!d|p+WuS@MxCPvs1uExF&hW#1= zF03yTeM4wltP1Dd<6Iy`d2XlwVrlEQAdp+;iK8BN5QVC^27gD=BZ`t6 zQ%}DWCw24SRs2IEMPHni8>H5go5tARA3bj;0p$c@n;1hxRu>Y@!ZoT7KAW7@RUyHZ zl=5|`@h7FV+R=7K3nEjczUS;UBt3Md=4? z<}R_Uy)HxZoq$yazsnSQsFlXbf|!dE1T2LJzI0=KrP}tnA?!jKY_>Rjt^LFYv2Ttb zOC#v2ht{ob+>x<1FbiQoh3|)+xGGR~2m2#K9CkWXHJ!__c99)9UZumXDOS$XP=Bx2 z1H)?(&?H7F5MWBd{I-G*x9^l1gIMHt+hd99#N(OfkxEdiT+-9I@Zs-<*lWx@1sQ;s zOmUsuELlaH@3g$_Roql^x^-WVj=I5ToJRD&Rh}R3DXW4<3=+$E_tA((2k?7~?b$>V z3DWhnN5Pvp7s>@aV?xXvj)k9^JwBu8cbaut-b950u<V52K}v=*U4?LhdLZb zxG9wG(ne4;Kzqi4(iNHO8>@AFrLh&ZfmV=mA`@YV@Ua9#e*G~O+cIt_0y_r>Ql@pm zP$Lb$#!EAXpd%HZVSt9#q3k-ow7bzbI4ewc_oFBL0ZcyHv)DWxkGkEq8d8 zc>yb5h9$(jl^D$|Z3fj@%2$Vju{P|5YTqSx-LK0==L=XfegE!Q!f$Q`Gn#9N-;l?y z3Z9vMXg=B>y7jglPRy4M#xkkYa`^9Ye@iZoPP~@l%7s7R1-EF0ykIab`L7~E4?__T z${azbMd@ft5r111`M~bIXSKV;n9Q%E@j)@mdw>9iuQG0 z(=`8xC)^osXo}QTOueR!lfB>YDcLk@M&TFN=Bm2qS3_kVFqR4k*5`F+K%j1 z7PpO#Cd)W;KAlVN{dhiCnd5p%=dWvc#C9U$;$MVF5B0QQq4Lo0)BNxaTiU+j+<=90 zK;j@R{f1rXyUS7r-A^*9&AbV?<1$PLYp0wkG{xDo@^f&(FwSDVS5|`SsUnzvZ*%De zFPm4URxxp5eK}!}pPKKK|ENpvO=2SHtw#W_Dxi2Gc@&$bq-w1bBC*UzG@=&|YEL!Q zRT2b0|4F3uX{6X{l8dc0%P--hV%%i!-|Hdgd@*Eq{0mU?SN_=f=&#Nne^l?39dmVA z+jY0c0p$8|_HZ|>YHA*<`L{@f zI-Y)ie)HMQq~0gR4#67{Y+j{aX@Y!`Q#-|t0+v(aIE>FrDn8#Sr-iiT6`2!U zZIemmFfJ4NS>?SjuiX=8k}K-&-z+QL3vzvemI+;xX}_7|&-U8>HtA#bZYi`Pz3(ms zCS411-2|AVf>5E=8joG9u{t`$Nk~J9$c<MBcqne{17Njdm(m|3@0wuQ+Nw?_7!vP)kKx}D!Vw#<2^5v2Ef*~VR}7nTdj7nl z&<4$IXV`vh)F~LWBy#(^6DG1E;Y1sPgj4m8@|_1pb`!7+hKbw_C*vxxuCZDT zCM5Q-9b0p0{)M#EmA0|CsUx?%desZ|b_U8c`gETysx`$NF+OL%XmU-%;*L=dSyyR|Rk3 zN0X=q4>Cc5Z<*EYibwR8E-1Dx7)Z zSjY};aCo-}Zbe@j8nwj-&p*0=k%x1Vao@3Hqq8r?6?o&oO1I(v&?C(AkW3k+c|^v@pJy*~Eb>@9dHp-=MZg=YW5siX=<4iW-Mz-11`{Y!`Qu z7##G=>Rw!ea(Yq~K_Ft^d0LPT_dBdQtE#xy-@u(wfR81F^q^G-9B3{h1;5KGUbo9i z5n&OIyt1Olohp6l?`+n#10$m%A!3|;Oc+TO5z`TH+mAiSYPr86z1v(l-WfIixjVsl zpC;_Gtc0SH@oyuK$)jON1rYTop|tQH>y=Q_LHSqaut^~s!gKbFIH#e<9B^}Ycpla_Pb7syvGMQ{f$8btY-BXep!o17oonCm ziZM1Ju#Ip@_CiGLrG4P25`y`~yO5TFk4=gFxL9B@6U@v_QQg-16`tGe-Hv1vXmFpb zNtT?0W{bS5P`EO3!hTJ$j&<6{$=2^hu9l;kd2WvPdAe|B%IkWLu?Be1--0{>1W(GP ztZI1_*i;(e1xp92{1rbPFyGFyV=Tf|a?$&}(B1HuT23L8?#PUomP9?!kfbOVldb}b4lCs~=D}g^n4pS-hJ-*w zES<$Lx+fX1-mWril>5!LrtlR7hxFT-oBbo$+A#7PRZ6La8A^Z*;|NlIw;rsJZOlVB zFor<4Zq3$%PYc(0!ly{eFxs2-%RhK*@oCcC!AU+MAjf1!q$tJZ9bUeD8V^BH#S(J9 zLsTzH@|dMb100PqlmFW@0HtPt)-pG-nUB`N!a0O+d)uk8o+`{rmA*_&rE;ok$n76g z7Rs?|55kUR8t>0t2Xf~Tp)mNzcxN>5IJHdNM8W72AoODlZI@?vWtb^vP9(h+_KDqA zr)4f*`m*{(g&YL)+i(ZYXvs;>?J?%driTX<;pG0MOf=%wh6)-cjd`wVxhMmV3S^-s zo_-*RT7h3@r<^m}Z|3&E?!?p#nU}XXmX|3OYl(i9olxu*gxCjCUwRLp$~yTLRnE84&$zY=%TcjO?51~M0$lR^e77xvhPMoM@kXorD@Y8vYp)UXcvEO^ zhTfSpsAWuJ-e}2_bF_|3i(AAZKtBi@Fkr<-RTs;!&40f`NZ-fE1a9I0t^FN4cet(I z!iSk**{{iSWBFx^pUb|$@BW6hE&}=;fA^7Sesu#DBcm-~JJkizMRCTCV6fcxdcMhJ ztH8&f#}?#-3X-=AVo%RIgR%oIQ^q>}ltf>yA09b)L+l3bnT#PFca<QG~gpVfTPcj*(Al-*D z*ai_>!tw)q^Br1sz9Rj)y@ksr15(z>1cHTbGnmy+6W1k*B8JEmiZT0Ciyou}`YeWp zl3p#eInJ8O1cmN)MIt-y&(5d>Wp-@(*eDmCLFg$G@)5brgxJ_wYwnf)oU zKj99KOICfkS7M`4X+Xd72^{oLKdI?qTUu@I6~xAny!1}L2b};)T?8SQ5)!v^TCJ4& zIzB%?1n<`Z>HJZ)#iBz^|=SsrQ}>a+(aJN8)*YjdTS}s|uLV(mWE+?Wcr5Wwnh6T9zDnJ-7#tPrkc?m9Pk-G`(3Gi? zZygNwe#N6)VQ5>>QsmfjT&z-ckb)j>slNY#wzvtT*u{k!5?=v<%`lDd#7&$dQNW7BQ=R(?6zUYfO~gpozPu)_SMDXax~qY-h&#Ozg&qidXf{? zZl$2=gZ;DgU%)Omv*s)+X{d!$l;*-cCK|TG%rn~|_1wo^;ylvD@g0ExyPT&W!M4ez z(EY;N+jHQ@P061IiQ|&fGa%xCZ{qZrG#&o zS-?U_5k{A@0RR9G)%>@6LX<|7nFv#V-^0|@P@uz%Je~?3@QE|Tot0<3nB`t?{w;^~ z=ZqwrerW7Z4w(0i1mtpy-Z<>pPDrDoz|NEDvZ=xuU1*tqe-Qiqq5Dp(E*pcuIr+O< z*^oi8D&Z>cD_T}jCqt66V>dpLn*5NL*;(Eg(&NPG<67GC{{Vkq1Nx9JYIdQZ!;5n0r;2Wt+kY zQD^u8L zxAC-q!leWRxuY#TtSQ%G!UNZ@@oRNKfeMQI2JM?RLxa;?ENkZd!Ns>FG=^3<0q()& z|CW%ZT5WH5A_faN%t=kg2fvV{@#gSMnB0~Nl3*@?zMfGUuUDy&YPi7(O8FB_w0Elv z8geqd)=H?w^jUGA#Lh_*OWt`ht#>$-w1dx37J%f7PB2{sL1N0vzr#PovBnH1h$Dm{ z$at?RF5jgiDtZ!UGRyptX&94&<6lD@Z`v#Y(aCCNQsPNqI0GQc14P+o4)-(xLKCmU z{aGzn>YWEN2B(n$+=~lHtfHKtJ!u}M07j2QKpDI<^RsX}|3N44s=wEFiO@bg2p*RI zV*;F`n)KWj^4c1}i?y%H5&OY*QU8h^aQF4Ne7M3*=Q^zxITL!C&~;%f=r{p3*r3se zW^q?UC|>~JPvl2i9`VjCJ2?CE4ixb_;sT6>xU`FUYK}FCyU-iV>9MggZK2M5CZL}k z?QBwA!H@rO71U4uSS8p*M%sK3oc=NE=-~7h^4*(hLu-vE!+w+T$CvxfCsAy)sGkkp z%0(D3%y(W$5MRFMh~z1AN#0uxdM6ST-mts9sPt814jZ%plnYXUL*FSleb)&;wC%rg zAfH(|n_>o-1O^iE+7|p9>w3avg}B2C-DD;t1WErGm=PcXlwEUCM7(p4q<<_xx zK}K#|orQ2G1hYMCh|%)?Zk;mM)CgFTiqq|V+|f&9Cx*zEJr-WIJO_^`_!axtMe2A&RV3Q!@N+MZ+F>kRH_e>5?pza0RoX86YiTJWFk z8UA_w5x8+H!)5sZ&Qh&S)@sXra#kprsP854VNfG<#sLg|IvoMKc!Dq8 zjSj)AlS+i2OOVM((OMnU*fC;o#hers!iI^1{0GiUA6Og5p=QJ(CY1sO-;Q+a9_$=Tf6?KQ% z2(&oYs)U@HScC;N4TF;MjAz!8(D^ac*5I2~vthzOBtZC=^X>nHWA+y>QKi;0L`-wD z1lf|`BCG$M1$ho6^=kgqcHF>-2}`@mohp(^NJ=$t^54PHqjJB=x8dM~X5Gv!00SqM zTXewjXm^~;o;Ml;ebH6nqpqrWNMqGH^cHPmFLPq!1-h=#bq6z}s=XY_4g-Rwqx?i< z0H57@pcE--{PMs1w>}}wP6rQ(aiE~07n2Z9A_hrzR!!lefV8O4kkA0g>~-W4R^&gT zgzfB4?EFysJ31x@hML!5k1Ed6Jrw`|D(x*LtOuH*2gEPK!jW%9!tJF1$%+@IIiRN~ zJ5-Q#Ph0puwvcfZA&Sa=%1WKs?1{^akkdcRKd=_@a4Kr?u>PD!pIb!FNTi1(rfkW7 z66+l&gccFJ4eyxyWWVlX@uA}2Y&TS0ktPN0S2tKAZ;DjJ4?`RE-+^F*!s_YwN+v6| zw1z@qfED3smm?Z*x_#XNDRYsR4swQp>iV1!6f_Q?AA1*HG*xGa5HnaAe5)R}f{Su8 zLy3@%766i<&mlfXz6<~`{{n@0lTTxHf}ZH}G6Oh5&8Ps749x~;C8WUf?rZ-SKl80~ znG%wJ${>^>6WOTp5?R^|`agac4`Lwa(DAD+VVV=Vdp}KFjDO4d9t<$D?;cFZ;BVuS z>1;m5FWt|mVU-{VzSl*O$LR1ODI($5(lJ39a#*RsoIPXgzD&RTh^e+h1<#YR(TY++ zJieLf+rVyHdJOv&jLe*+l@xC|o}m*HMyJ_5LjZg=%{Bl;>iWFsTuNz>Y#$~&Ce)Ec z+&}?4m*@e&*a9;${no>Ht%mv6AB6t<8x26^1wgEyC*t;@`=586LqH!H0Puwe#DM@9 z7_;}wz|+##Z@fpu{!{M3xD3$AwXB`Rh{H94bJE5Cf1=v07Al%26UJXP8Kl}f#<&?+xI+^u7lFr$}qCXxn${1HP< zeDnittyESC>~W}2jd1>BpDKMDker{xYibV6%~+`i=r)zCGOER#~~DhDLFn`mRq2+9?zy(z9(v&x(_&e}S@)we9r%U_!?riO#K zRs<3Pbz1_64NWiwVX|faN8Wf-*!J9NT0GjfrjQ#g>10YnUjzcau8}Lil$cEcATIo! z0kMdUCjmKlM47+)T&qfzK#Kta%xYD;G+qZ$T-yLJVgR}pj2fL1u0PPEiG<1tBnHH+ z@QaW1?whlCOeHflK6lvAlmPu@6~2V}L`_U^kV+JyRh3i_`w!eBLu2|eoCo7-wI6`7 z9f$66Pz?Yj!gpINJ2V*XnVuRU6den!u~j; zez_|k1fM8jRV=W{9n&s-vX98$VcY!O-{Vg5oV0nUK$L%sBGzNdgwr(i&X0f0eR8++R^T=7Sb&HiCJOUO@ztzBwmZ<-_u7F^b%VW{IVH(lmC@D~uO_1Oi<3 zf-}A+;^Roh@>!<*%R}-IpYq$|Yx^57e)%0ML~@d)WRV4FvUo;#F`#=6?03;TkoQ3f z^K9_ofzVfq1Y0?L1cr%nAci0r;a-5)Lr4c9A@+y#jRpMn1@Z0%71!b}@r%54;H;cq<^`ofb6_Mtgp9vRtt|@xlhFu zx>Xs%n6{&B6`HA~S|BffWJQ)8FUmo8KzTs@nnEAFDg{7t2+AdqrqgU&$t`UGb8THa z^bu-OBSxzUf}~XsN!J9@sAdUA4gZF`KtT{@f|tx!CpnV7DL?(Ymjqx2LCr@0kab+l zM8`>ERI+Z7oHc;}DB1uVN!V|OR zU}T$LCw*I-zZnblgKL8!%%c(aXVg78RkK$I&ZlVh_$M)enAEeGUWuo)Nh%{By(OJ> zX2oZsIw}Uyf+LfKMKq%{L@aY&zt1vm2gQ5VoamJ<+r@Z)$NoQ~b=IppVqHq$Ai-Y* z*m8K>{*V5~Z=ppAmlx?kE9pkpI3FQK8zYt`Nd0^d2;$4T)CsXK4_0EI)Ef_09xI0f zfVC8aR(Tn&|EwE36-2cEWy%5EdIpTxihoH{NKlb^?#J;60Hi+G5is3+E01OVAEM|# zWoRc?(+6CPa>X4!5r0c&rqC*~|4-o|xUJqW_`>c-gv#)W;#vM;al)FeVywo;V)0#q zBSk9WSiO|4;WRyvRnc%1WqKGQ=bgRM5mKAh20ij!cyANa_XHN%Sr3X84DYCuf*B8Q zc}4jCd~7n?Mj@waKyi&z$pigvC#UNGDAc{7tdIU@I60TVcXNfSCc@KNI;vw!q5PW| z8_tvUAkPwqg`p1O80=|ZsI8R0Kg>TBq}P|`+IJ3AD#h&&E7)0R zQm8-%cWVLJ_k&F@iBvM;3mJz4?U;@7`@;T^7f_C95+LXsJ33YIr=+B;ys995@lG18+5Sl|g>1 zpeeCKlk&pKh3^AEfkQ6?z?)yM2`jlzBlGVy1JmDY+xuth;qRiC`38{3jb5Qi<@NqN zOrcQU2vIxP6H6(TNycUS$Ktb=K+N&Pn&tGNiu`2dyrKA;F70iYmgq11GXtzT{C%-0 zgXpg4F<;)`)eI?_Gs6&YRQ1sY$97`!_UIdNAg3MGJ0ct_&L9Q=U^`&=l^b}HoQ?){ z8z9+duDPaw<@%7};{hPund{U=Dct!+F1Pb|7_=PsVssh5BsqOpF3d;$FrG(0`96M4 zEsk?BmATQ5?2jd*(yQ%B!1&`!SV%mt3a1p!{{y{AAF)mC z$_$1adEJKQyE#!gV2fxJ48R9G~cAzUcNhzeM#@o!JJkU-m-4v9%=SE ztbACacot}F3|VAa4aaRAK1XQ%2n*1*d*%w7+oMwK&#}yJS60od-jXVS>U{H2gkgMZ zXGLNBgZm~Zf$uwK>i;NpzXGzKUGekyVt$#D9RHv*$$rHvKS}T@4;a}ba+KK^~RKjG9}`y7N>MXaH_JaJu^rx&|QxN3g{=k*BYP4cLkB}d6QjDE_e9ofJya7maO zV6Hy9j|JBnN?XHK2PO>IAQL)7L7gz;d%Il`pQelsM1|)Tnt}U2H zK+oXKE~h$DfcR9VVf#N@ko~k^{y&_%i_C2P)2%q|sOlYBh{q^Cc_$KfJ8Da6sH^td ztbMn@H?bzk(sn-A%pdY6zR1EEABzJc|Bq?1dAnEB;RuiWNnnqB`S zE?IaGlFUsjc7SH`Aa+{FQH%+`b*4QRhCk2LGMmpLAC0`Q%tYQ_))lUIWe6qSGYl-x zGkO276Os5QWLBZ*9+;_G3xms3CJ!ibB}gF`BQmge%vk!WlaMH(2{xvDM<%$?71GVG zZa+MA7;&vY(7>cgPc}KHzuQFhYhYIk!40-L1P2gz4gavG#)*a5Y`AlH$~>5MHdxMP zB@xD^546PqjJcd&Yf`Ep19ozvzNg>E5S{Ed=}+p*vQB5+>J3If4z5$jvt*G@1D8kk&_1 zQbG?OvHpX+tAw@Yo(_Ti1tn&R$vtt{Pi(<|<#jQY=kxMk4&5#PAwm7!{7eU&0t6lM z8W;=cTUNqFKxC^R=b8rn!|s+@4wXm=5e49K)!AZPn5J>#$d7iL15ypfI2hC#D-N&$ zxontf<>(@xY|)0}52(ziP<;}#Mm;lw9_SPALeP%x6=h>~qrhS!{T8&x2{w!iuF0-8 zTkrWLd#4QijV$h_&~}n}Y=MF&39bd5re7`Xg`RXc+GKdSNpUfd?&}-Q)y~qIh)Ul7-FG4e$7V zMTIbwBfd8wFcbawrQ~!>=%%DMkBhZ6Ed3c*cnNS79QaD(&LJgPwnj!;|5~{1fuwHo zN*BI#6Eb#|I1yUn9as$sGwL9IpECcl~Zh5-F8 zGV=X=b=Fyi9|Fzq(lW8DW1|#ZF74bkiW#FSVa4(rJ>L$;2IEVi_EZ##_=Gj5xqft5*Bb_K+b0P8$j&yMyIV>{@N zl=z>xyj)(V!d%{iwahHsUd8)#C(T6a$GA4mjbM@3P1>Ro01WIr@ee05w;!tN<+*Ie z4Us*WZ1&Gw@Dr0qB2qk06K3%^mL#sCVVZ{|oq0RyQYXHGUgucnCN*tLfsjLM6+-$p zsm_Z@8PW&jUr^A0s-@$YnQy(U&2}6%e$_ZE%*Q}s`yzz;+&yE6p6SHCJ$AKiSfw(4 zPYEq%%8}=&5DGuEsLI3;K=*_|HDhFjBPfv8q`_lP`76DcHo*p&gz_`c^IiAt<_ray zM6KK!IT|RsT?hGaAPUJNKOmzCG1Z?P!nR%JZ=dwk>w#Kc+3|Nx_T)YOU12FEKDeC$ zCb!u9AFko{Ky&*6FkC(*L#%M!z zT*y#q$ zYdI%t-ZtVCg#$1WCVwk}rEP|+KBeIS9iNiBk9wIA(PE?TF;sU$2?m^&gF_05bz`Tz zRGwTq8V36Pw~b91^(*~|Yx;wXnvP}BvO(NB{h^4F_1_Sgf!x3a8cJ%3=1~9i`c#N? z{F5hfcDt~uLb+6{vHPrH4DGDH|CGg4oR{?=>jzTQ0PbKNz;j`=6mHoF=Nz17!gLdO znKv_v1FIyr1E8m5;X0xi1CQu7h|6Y_p|E3L6XGSQjJ7F>BA|oI3gp0(9Ou{{>E+QK zOVJm&kNVjY(e4$!nA6ui3JdEA8B;U9!sqETAaBQ60g!6!Bx<;joDxbkmD9P~|AtpNi|L?Oz|J^#Nako+T>0jXVigY_6_A-h z4PhD_WR*)1aAs1i^dRy)i9l{K@H3ZR?NZ36Od+s@*(A*Wf_S4756I$m8CRTN!0bgL zsW6P0!a|k(+Bi+!a5aZ`;i-|3$Hu zCI5K3>ij!b14Qi=5w8g}?6;vo@xnJhsk3BpRSM|+_ECi6(Y2T%=%15f4`e-0WXqB< zudc?Z*ell0%kgN4<7@nt$D?3_5o15bqtEi$Q9wK!L$Zuj<^G#IYxyZpw%+#6X=O%PYVaZrpV0i+ufR%d>Y1X);gjAi}Ak;F3rr z#DvX}wpVbA{V-4(Q!lAXB?J-bT5Sb-9pmfKUB?G8~scc`I!4d+bE}@3P?N zc^AjdlV%mi<(pgExe1PVy#7FbJqV6;>BB6bX5V#)ajE10DXmSY zLIe`Uvt%(5b7`%x3y$WIlSHPKl~%?k!*%P=g58OPGs_l^c>jUkbI_V;JXm4^6&coE z*tMAKrT@omz6^`b2H?N;(61Ktib0`N;#n3a_CUL%b3Tw=_{1xSd6ZSVodC>!x4|{} z1f)kU7$`1V;lhx}f&Xez#jQ3jJEg)Xm)4BODUd)%M!a)Dj>F8UTvVp$0Kj+NHF4-# zwJ}$lRpg;g;Me`u%^r$OxzxZZ`zFHvN~@+IxX`+a9>5A5tBXo5O-BMIfp%MZ8qXAH zw3}>HIjR~m*L4hpnlKm#Ond~CZS3Te%f$8K_)K#Pgn=+F@C>fTu7wl5vZ@7sghtsB zC$87Ps@vcq_l-J3_Ss~g=%mzWBw}8h6MP$q4nKZ)B7c2Bxtu=Sl*FgS9JZ_oaTY)> ztI)k;>oL`jUOG4L-Sw6giSbgHG_N`<=KO=>>?*eiUB3G`FDmD=%_E{0NnV9dU?}Nl zX!IBQ>LWyd3~3Ai91f#9t`^yANs}W-EMZNkFyi7t|Fu&157|Y>tB~GrOf>rdB`Q>r z5(!vj23B*@s?f`P9J9cC*<)u3Q^VcgOi+Z3es9SHD0Jk|hHhzH;zTxyE#3(cPmQ|o zmUYBA?xLAqnps1ugPryL6`$z0!Ec{neukk4BC_&W{0r2bo)ShR#9LY3O~Us=5muPc zHRs+zkcaH)xGCB~gE!Wsxi{`1ms0JkfpRe2_s}i>)f-n=FQl=V$WQzo@3*xj6Frx_ zHj^A2{IiNH4=~p2#^_MIBWG!(p|yo}X%oiqTa2gDamVOhZ8k*~^8O9S+4)eIs(}MP z%wBq)zbFVQCy&U`mSjD)N8I+;|xDwuK2HJJpb|%SBLIOa@`;08QsY=OQ`&T}SQgoj7M^8@{;a z$64zAACdDm`|+n$NiBJ{=aa|y2&i#un@Yy{Nb8{u^e<(X_{hMBScW5FlP$rkm!_*yS0`IwJ+`^Yv<<>H&wBJyB zl?`TX2NneM$YSCZ5X=(hh%H93ga}b@YRsG%k9T%Qjc$hLv~!3eWkgM!(w#}=;L2^e z$jTN4&p@`HjCA4H%XvHHk_E?#?vf}&*EpCJfV%_zYfS#Z+XLzhDs0|7+6|rI}AIlp@m>ohVT01KYWz&qP}lKTHhfhvWcw>BK?(`&zjYw_z4e#t0LWzS4bw-s6QjSJ^rMl%ZnvZ+Vw^II z7}C4@K<}rKZo50ZPIJ=-6Za)(Egg3ov-Q`890}6M6FBZZ2r@oG<-c&--%yT{685Be z4!Rl@@dgt*lCW8sDhp9HSt4mJ{vFljF2(;vh8cLq$|w@P3rFn7x>^MYm5=NXm59H- zjV-XZk0|m&1)@e;$d3RB(C~8w?v-8YG}ggBY}g-`v z%fyI}ys^&%Ixp0%s*XO@hVcdUz!!DAr+pd?+2xZy{|LhVMVDBGvd}&pys~K%x&4Q1 z{lxq%y_=OseB6xEN0kv1<;E2IB}q~8H201-#wjd3(a#ZLnlr)OVBR$;WII+fU{G4u zp`!=mnS4MrdV-PT$b78pFmV0Q9|s%ir~=b!4>NI~!90w2*(!-5j`}yNj|aa`6-0@- z2pIqX(EvTmIAcFk5#e27zn2ZN{>|qkJ6AuO^UEv~Og3!&p0%N})K+`(`Z0wkYwfFj z$2>S=+xhsG3pwJ0Uka`g z$ap71pVnu4Za;y&!O>ju>3+QuN^|_TSeyg^Le!q!+mn2Qk$)5pzS^vQitJp^0H8_x zhbjSpkSC$^RV25Sew7Q`NmKk)Upp`ihU{{Ve9ZEJ3xjeW(OorxE0!VKdu6#1)rL^eFFI3GtQ^Bn7 za0n}WJeaPx`>cZAYb!e!;!m@jO(_G{|U>CQokL`c1*F!;UL;vyf2 zsMIc2Xwm>D09PO4P=rOXg}iddw~J+b1RuZV zJbL^gWPqmg;~!3P4@7%-@&x%V;3SkDe3WbWsz5OcIgPn}YtWe%YOv81naPKmhk3 zjb7(UvHT0yRd7A1l72r9P_RsxPnvo=WtU2kI{+Cv)}H?eJILwiV_1A%-e50GbqIo4 zqXX%8+Bgl3u40DnaHWYVXPYFF0%!#it%4@vGY0zujQY?_q)5W5V)(wR8h882&*$<8 zql@CEuIC}f_*?Q%?IZDdUVmxzEAe(VonA1fuML(bSBoC=q_G6L`jX~)CH)q2`im0+jRrrzyBP8}Xl4)w5^yqX z2RpRQd(a+EL#Lmhc+D~c;c{=K02YcDKDCyEif};oV-EjbF(M55F9ONnD#>3BV$j!~ zU#~D>08kX6mJXeeBF=Q#Y@9deTYbELhxSCbPUhrXhV9)_S~WRJ!D{G=rm@<=jLvpW zBCga8A?r(Qv2t^nkWoqlsBh42wVNR!yY{iPZ>sLq zV#?3v?e~vgk!%B06hZhgQ#BI%j(@z64yxisutI_9^V;tH;9>TFMiSv+=p>3NC*Yl&8TE?kU4_=dgnN>CkfpKQ`Ald z2#$VogZRgnP?qg|q5V-w#d4%(zUR4eMlmjS(?4!PjXf?^I9MjA8N9`vwDtUl#c3+Z zE#Q0m%CPWHPOpJtUkOwwMM#mhPpQ%Lq}w@qFoy`ex`NRs$J_BGDZ+I!-vh-GqX9cW zgNpdoFk%vLFtHj021%+j;lbsy4Fgis_+p6ga!imuADV$b13(HuQ|jA>^i_)7M(2L` z)e|4qUb%5G3PgUYN5$J!>p1_d^7sg{nTA#zBAMemPw$Gwd#vMC0<{Ti zhfTNWR#d{Uw1GGbT!c&7gXq5;9HNg*=7Cw>f9G)%BNh(eB3eLI?&+l@(QUF4F;ote zcO&g+F5p+=B3;uitht(cp`KG6#tTcg8e|imee6mP)PXnBi-aYA2?N~d0wAd#H%xbe z>+Wn3QZhKBH=N;uL<4l>-Sl?g-*qVkI4Fo7Bu8P{#>l}aC03m4Hq2?z*I;oD=2PYx zrs7sZDX#-jXMH6sE6!;jS}!yd>vo7^_tks?WE|d^NN_(Q0@s3(O{DB4Ys$dHwNo&y z_XBmrj7!)WEFy4BwbA_xFrO;I=AMN&Um)Iy^Kd{@C49rP5rJS1?=Nxl7Fu#X1t6eU zd-Aa~l#Q#kZ;THCUE$ttJiU>v^R&M;X;PD#tnJtAVfgy{!o71S*}7U_*jnA&oI0f6 zjR!R+dW>s^nY7@NVBA|#ny{&VLX{q!`IX8A-K89bSd=~8Yy-UURKq161)F{xNF%Vk z=}2SCYb2s#UR+nn#dd7jUg?tC} zToBl*aXhHt5R`X0;0)+n0bZ6(R)$@fuDeZTZf5~^MvEu5((E#>%V?ipVLJqv9q=nq z3`CodjZYcSAEkj0HKQDUPUmm-##KAE34&82S0$t))#d33msa0+QmK`L#YOBt`>Ciq zXb}3tBS^{Mq!*| zJ7T0w?U2&TgkkHipamyajo7xve2NVnM$k~UIzDCao(aHGnB0v$l!aG4Na`#dKS^cG zZ!ewY)X6!*9E6zJ3xP4wn8l+Xd)h1s(k-%A6-_W~lC3U8qc45Uk(4`xRjPZo{+P9j z@tlrmN~uV%C@DRE_Rt9<4$ZWrglKb&2{A_`g%U}22GZwOl7ufBTr=hUJ@up~ciy6S zfzLOb3B z3RWD{R#~u`xJphJ>tqWAH#~hooQ;x`bleyZ#mUIDe6b7`Yddu()C59_dhZ2SyM0r(i{aX#IN0$tR_CHCn@*AuDpkRYpCt+251%C zu-eJ?_!L-ONeMymqn&EM4o{uz7p?nJ}Y~KKO;5#k8>qU)6#> zq9Cy}2u+(-T-Fg&ZW7wUX_+Meg|+|@FbFUQ{aiG&O-Mm&r;fP{`?ov9hz;v!8O%iv zBlqW9N6ErR*Hs^6(jELpcSNWkF`6$fpM6adVk;$47qP#^TQ>HvQ5y+HN*cQJA&n%^ zS4wl#^Nio(G~iSOyXzMfCp8&fkV!nO{8nGbfq81Zw9D?G0d7TtGodnmPcfcc6oqmreW7ega{X1 z^dJh@O6WG)4iR9)Uz38~(F^{87kSz{9|> z8j?)}OHg1ByfHY6{c^Ym)_AB16`!5Z0000HHyT&Uy)3MSk1a%QCkQqi-$Cs{-b5k5 z{FA4Y-Zw51JrwaqQeuXIPUe6jg&1|MEpdG~)g%GQ_9C!vxhL>rkamN2#SOro0yq)U znnl!30|Z2lMF|-CDls+yodzGTWbQC`#yX)UOkB;v;!ZyhX50=E+XuV)1(+AGZrFZy zLux`6ehQTr3??O-&LHnj#$Ry_7*R}#Wa;`6>nbD)2{?eN&7gK&gM(oJ0000001m!Y zUp(HpQ`ercbxzOm5W`Tv=A}RiguJ-KJtTVzbW#Rwe2^s(d{H7(bd9NuEW}-&nyhVP z!o85Sa}3jzGi$Ph1(&b}c^7@>bBlbM=gp6KCVE50)@ks=u3R%;n7r&_yyz4iAQRFq z%&0Wj=tiQ29^fut>HcSMnfuM$@MQZKR~wno&Xam2)u#aPO^Qwh0Sw4IKLx0cXbyk? z0006)5!T3k3VtI;`o6#SeHIyUoMk#Tk4y}r`~Tf^2bp??tNfAFdeexJgn@u#n=B%j z*|~?ZF*UuEZo>^7?iZuKmJ!f%t@+}fqD zq73V74~Y5d$F}D2a);XDa>5}y-?q*;u7@L9GQFTb9I#om8+pu%n_5_%NjCgkba|Zh zEsDzevCYjj`(O1lJ806unrwbcSp%0i6G&{Y%d@Ge-tKNRffws+(5Q=-fI`2~AliDU z*qk;9dfZg&fy8G5zyJUQ0mhZK001@7f2T|z)Ho`YhQEmy^%*tAlEemv>;T&|E!vE6 zc-eTgwIiJ+!lfV+)pB9AR=t1uY+<&y%l0`U<_Apec-&_4&JH{6LZ1PEI)zMYJ-dXn zeH1F%R9mj3Xt}8nTM>`Hn5ngZw`)@s3F)X!Hg`8w{>4Esx*_(GqH}+!CI+Y|6hZ)} zB47Xj00>|K-CwO*1VB5_Q|IB^H2g_X)?N(wQJz$UE#DjwhVcb8rQ@f@#eqa<6@xnX zqI)Ux1{|oZ&snTP-xz`F;7xz0{t?U?*V{3D|1yG2u>bg(2&&tNlx3t{vfe%(*_ml! zp4zXPRDuqAOHXWSE0nb$F$H{w&D1R<)IVi zNpAXER{?>~DLk>li6^%DWBQv+1&3Ix2nP5pXVxD_CjbBJ zLipub&^A>7u?Sf2CLcVijp6#XUxiARXNP*PhUx=p6LG(yWLn2WL0;{dEYvy#4q-dr z6D5e8aQi9Fb=5>kaxPc7q8=Rr<<22TTC;Z@19RwS@M5(`7sK=~ZI%iIg5PJI-y%w8XOO23E%HR4DVRa_uvwYCEA3j8pi$Iruy_ zPvRlvqC;9H56}E|Og9t*zTfhpoG5jqxN>-2C)R;E%k-yZJm5OVTR=II=~65etR`z? zH=nT)x({XGAq@s!0yx@&XN27j!D>N?C7r>yqhJJo*Z=?lApiqT(+smSQ&vW25K%Jc zAD~2wm_)B4tWHolG&|=UbcdOh%-m=|T){L7vvc+;YL0DF5f z@oB4$uTV2GSi}liy;}Fd$RAgqaKZL? z^38nblB$%cDN?IfX+b9M|LRN0J|U;4c_k%)s-yRsllZOjxVu`) z33(X+a4ITQM{i7GrvOlwc2^W0zv@YNkDKQ00002dh)Me z040~DbauCq2V}#r!^0o4gOlp)yGy7{&RK1+rLtcJkt^Ilueau=SCgC_lzlBTCoGU8 z_!n%8FTPdnd-SonBDsPz;rnx@jYL5z^vjI5%oajGPf^VvU%GbT{IR(n9JUMoH*T0s(^sh^?s(V&*D@?@ zUjTh6jaF&!=#tKv+4ofZVGvn4ji%!_v*f8#HYoz^=@#2tbMR{xqL8lZ10D|`zHC*H zs$7)1j783j6oDbjWKT`cU*;7FxV;69n2Qi{uZp?|1Y{4 zyw%#vC&E@xwmq}WWS}FH9?7)+pDf`}ws+mb7b`BEXlFBk0CZbwI>?y90028+OTfDX zfZXxxYY6?j+iJhcX(!ud!agkLKY|CD#2JFBPL<2lA}~{;r`sZ^V&Gaqd}y0EuAu?A zBG|?`)4rSz`~=M`Z`5Zvs`*+?OG_$;Gw2ftA9=KY7Ej%{5kS+c9$tYpmMzuo6P;gU zlpJani1e)bZXHOgTSd?SVG5_~$&`x!C3)tr4JD>p%z01Rm)_R9FBAFmekQo{)#m04 z!EKien0RTnFHue>qHC@vYlB-5^9nrVTW8XoT`hWMG&#wa^c7#S{q*K$mftD_+v!>cL- z;n!0FwKWq}4b$ET(E}7CE&w(F6v>EbnECM~m=yu^%@(m5OmVjXOEu~oYbM}Xjg+hT zHTC;4C3t@r<$258UW&UDw~&iSLlPTwwE0OGA`gG z0QvLcOzA@!Fb_MM2SD*p=s8SUDRN51YQPT;;X~Z#m6HSv7$OZl2I?wK;`hWVz^rvAYR1G2!>m7+-Mzo^Xk&q{9E;S+s?wX9`uYW z8R~NgrCK`30HnOu25^7`{7Ajc2xwnuR@7TT!uO*)gi35(j{`^jpO&gm6E^~urD6oB zJ4I+u%;Bjs__cZ{37R0fK=B(l?R`P>x!xa02i<&IWK`?gkri41g$IlWHssGC0NV&X zGAUGA??8nEWL}Sjtd`DEG~wNRmd>)5eh!4`3q5&k&vDWJ)2xJO&QKt~7IBp;&qg28-ZBX`I>QU1XH78cI zXg3i!d=r6amz6LooRJbEZ~fp@MztO1Hpz%sl4!aGPSjXgKa*{L4X-gd%-MD!RCC;L zr;y`qs$$F3j7u9^bt&$x`fF@l&aOHJ8aUqfnjd3UCgd6Y02O8W6inuuneXh3HYmGr z6dt*?hP>S%5()-fMzw9|(~E!0R9=`*%d>B6XaJ3qL#|L_R`3;Q7b}?}C88&vGC0~v z#yu${kxK7pdiTED#(nK3^Jgb#%A;4gMe%Z;*Vbqp809$Z$oZhI#C}rF*PqpLfjga# zF^A0Gsjtz5?tYdPavk&6LHTi=miyl8X&ZPj1@TNsmO7z7zzh%s&MENr@(nB*&2NIp zO%RSf+P}-6v&T5zQ>t65F%9xO`Pr5KPfYT9q2P%|{MQoU_$)VRDZo<^UtjSnO|G%W(v^Mue#a6_3fStFI-hCoJonv;FH^5;g)# z%!3jEV~Y<#zZcA4ikXO^2g?Mp!m4mAL5pMgl7<-lak#JzC4U3Tjl(|mnS3wP+htDH z6S#}^R;7zUTHLk3rJ4paE8hN-w7bfX%=!!ZyEc|m1BCWH43>$J`KCuWrJ>I2ZM&bN zxTr^B5^zIx)3vf12WN+9#+|*@(i73ZasUoZNX@A(K>W|m79(EQ7+X|PUwcOQ0WYq@wkKHqlfVc6M=vJ zwDCe;Z~6Txdn%5i3A~9{^S~}M7r@gdPc2~t3s#W9SWL$d0007p{2GDWCAK5H-q~Sg zrMU!z7ik%cU>8=ujf0I0ij4V2o&!b;aD?EbC^fHs@)zC{Z=3`@q5^D@oolP!x;mZ{ z<4gg}=_y>!z90bBxdL3${*`zpkwMVCJnLT1%6kn| z;}_gdjhLsk`*+;(@$-3aBJ}n8+n*4mLCodI3OEw3EqIoUmXx<~C-Z zajaMzO|pA3I5w?Yrwt!Ui%D$Vrkod$9-hJ)Z12~qIpum&{qI!UvmE6J#GC=6Yk24? z`|P}EWLt(vlEx}5Z5(*eXt|P!l1vUHEiNGig~y#tMyl>E`DECj4Hkd>Hb-A~VVA;w zm(U5y00wym!+8y07UKi83#1!#%i|LYs@zla2YZRR{{|uhI?f&24vIxwPEn_&HoQjJ zs9nK1(7Vnw&`8rqCr4hHdmA@R99~<~Lf-oGZca2bLm){r-BCQl%1MovHx(1Zzg`Ao z*e9+!!M=+lewQo2pDDgK+%(S!Un>w=i)Up`GW#>s0_PP%nO2y+l0~IZ^m3zkTeuU` zaJauOua4D!GMTX%9-0kL`?@`8Ukz0ObWq)$j=Amf0OzL)p_*YHIW;KJm~i0NbvPkA zr;8IXu07$!lI67vzolu~qIz9v_USHNXSx9UF zH1*=`C#f|R@ zhKad$%(Xj`x)IZ!CUwr!zsg_)ygki;d5k1cY4o-P6~#ehp8sGDp_{TnG-I~zfZ=yq zzLw4Swjjm5VwWs}#>EklHD>_K4e>6o5J9J91tf!2C_4@@EXSu1%<5IFO{irmi!FdU zZvIsAi?3GQLx)zNl`psTiH7qsgZF360J@4haauAbW4e^Qdc;6R5ex)O-M2VlZonRl zR}6C*EkT0w+F@sD?rkgO1-ModYg(ZX-OrF6@34__c{XQt$R1}kBcfAle$f2S(&9rR z=V%bE&AD}QWuEz-Rp&m8wovap*SR-^vRDk{NU3#w41Kra zBp(vzp^&*HvGzSh8JHep)U1+mzeQHHSfQ}44DLvC-zb(g&hVKc)^6>e4v7czJ?C?e z+4MfClea$7cLL16l4r!@kWzHu4rw(R7qVO=v-B(zav%kGzvEVo7m{w37t_%Z>jqv33eCS@4`#N2y;l;0AxPc5IXhmO2m+uO24}3V#JGO3K2hAQ;g5#$KsBEEEd!2=PCTduN9870QXm|BtDz97bR7=M+AxdF($8~8&eIcQ}-GodF01+Lfa#KtiWnxA? z<11XNLo!gp+uQEJmeRg=VFJYud*VoR?mlE?7D-;O&s9w1&pDB zY5*5Fzd2^JZ2WaFADeCo@#FD9uEr>9uhSXdY^j`7xmWmml;^f%cPPR>7T%ZXk==g+ z>jTaJbiH3}hU>)ZAwoj!I7J3BXcZ7cYOCUY8p)xT5FWOW%@79ZL8dkm9|^^Tfr<+K zV!&?MtQ#6-yk_pXc_izj^+s5+}v{FUq+fiQ8W zS>kS#AjSMxF|#F_^nwnMYVi2*I+5bHow~}qcX{51N_Cjy1KMc798JubwAo{b6#t+f zu6L)XszT2I98&YAu}`7#wJ{)T#kjFN!283fZ@Cz+4$FW9BJ(^vo~~#6%QY^!{pAZ% z*bS_&v4N;B-uS%)574_dBfbB|uc*;Hb(NSH=cJN8 zb2k{a)>&u&ldwq$2g0omfHChtke9I!EgT{A0373KPe7@8e6Z4a#udoa# zziCrW?-6pS)>7L<(OYQNc8%^J4dj%!9H(=_3Ny)0{Vf4u`*BM9(pL$FdT!unHoZU6tj-@1!#D++g@zK zyee*(rB=;ZiMP#24K_Kp&-qB z$H@SoxKb39z${bPlZcC_bwA9I)qf{u5Bz_V?E>|pPZ@HLn^ugbB8M&V$ir+H^x$^d zI7#ml9!T1yKCMBo2s*nfRnQ-21mpK{LrPp2iT7OBn&mHLsL5wG;?f)%r&3DbRG{709X!#drLd=W>e#M7DuYklXPzJ?7P|Mi`ZRm zTUU;&ib*6)OluW`_($1Ha%eb)(upADk6=Yc8 ziGij_Z3`pKihUDCtd;%(WsY&ysYOwqPW(Mzp4WeHRfs|sTQ%W8o%d55EmpQetTUQY zq!M)mkFrycq@4ofgF3|q-hILgd;Vxe51f%7GzNnGE={ZGB$)cy-yZMgz&oej!4t;I z?a^nT$&Yag=h<@xE7V7m3aZz22X9s2&)4TpJYnzRHZ`I9Mc`^jGcyawa-omNaR;h* z%|l%6M9B4^)ZI-0R-;rz0>WL^mP!Tqx!l}OI7h&UGqRIsW03p)NLwSz42$HC(gGm> z1DH%Hm~OZclz>Yv11EsW9=pHw42>H%;YTx9&5Dk|9;Bv(Q72Dq?(Vnc+vc6-(@xq# z%8$SHE zihl=lWe7>5OvuU1Z%)zjRP|L^Y{O4eRZ<1w-T(kHI1Wl|xfN7N%zdv)9F8QM$PQBU ztChSpa;h8wM+BQF(pyqNrec|HkfX<9+x|D;l1r#A(EBlEP{nDjjMXH@{gK6@1ef|n z2@zxp-+GVih?t!3Gu^trRV8S8dd=a($PlrmotxdS^p+JJN!{?a$?uSV+wB- zfn){y#LNdLp+jceaARZ01MV}Gq`6)Dv@2QL?{3?hYP?_BT62c?uNV^f#}6IE6oyCD zAOpH_Z+_?ItG;YS@N#PjM)*orY@TaMhNNJBOz-Ed9uK`NZLt*cqqy#X-r z4G;PYr}?%f(IvMNHW-c_XHEk$0P@12UM8|4!?$y(m&0Tfb3q3G2bfR-P9$khECOcx zVc53X!6QK~{Pj=3je)1+M*K zZm#PffPlmuew}2{6nTfr9AOAv*#Z>;!Spb6wIdIS(;H~I3+YV+0X?WVHNZI>Rk)xN zlZC5cj?O+IiRo*8?3DhaR(C@mQrwdW)dd&RhAX;_duBrgsq_e1yw2$d(AEEMf~))6 zK1bMY_6ia34p-&|BeOXx05GX9%qmdW^T}sF9G1IjWs82PH-s-mxf6 zH2x8t6&zSS5c~O7yF=kP#nU-rDqNHO9a2#Pa;A_s9GK#ANSRgIOj zY>Sb&jz%)wh*896P>e|eLD;lVgdL&nXZ7$RKGBJ7L>%!%{Oe%8BFqM~W5 z2r(2#WOlYR>Lf7=&|Db2bjyHlpb?vPf3YZYFL~Rd$!wP9`cFL{%_&&2Wbc+jVnPp4 z7r?MjnIIqVT__QG2}Me}3~CX)Fy`!Db`5ADw$}4Mif;6+msq!e&01D*iXcA15HR07& zkf0G>6Xs!e<9sc_BA^k)t)MSC6vfg3`@MSc{z-*S?PQ+4WuGF8nYXbzH+%AGs_&~a z8cz8?d9(x<3DX1d9K&vjS1cbIXBXUkAtf2T#!(bqR((U0`N(=D3ZT^AxX#zX2Z!~*0hr4GJp^rl0ObK_ z7^zv(P|Ps%+s<~47k1B^y&uOU1ggR!{CORyYBD4CcH6MEg%f4HH!d z|3Kq5C~kiMF0=D#s|>H~hOyAD@1=Aqh`?BpBl+PO3;+NC0CYi|01AD)a0+dNIJ5RP zHBjHZ_+zJo2k{MJ8`0!|tm9rYu_PeK*ZAJuSp3nk7>?&7p?7@r8gvJyI9_c|m@5y0 zXT&Sr0@bmdKB0l<4)vE&>Vo-r+JQTxz&5CYe-3H-MWr(_OA5A+`SVL04?j^k4f=## z&oTCvgxKNiCkK9nlOoJyC{X2k2avue$!Kvk=qcR(^AVjkDwnTRl4~_<%rJ$W z>z2!*T8slw<=|IKtuOQi#TdDlKvnb&=osH&IkazVhyP{p3A9|bHB;i|N=|L)$sjTg zc*VE9a*-RFtdr)F&*JRII2)m7uzrOlhS9=Gs{k=wh2r=ReV)za2TiO`c;txXddAUU zO+Eks4{4V>dpavHD*EEQ>cg#f#c9l*H3MzUY4@kn^%1)aV3K88^(nCMF{j7c#Veq! zx5T<|H`n>{vRf>ORxp-^B4b|QYC5?a5!oDzp+;fqlBx)gW=#H1&xAmsV$wLIxk_gDBlP^MlS z*25|8eY^{o#!pU~=LzxrV^7CN7zF3|QK@^AYaDOvJt7%=iiE>EBg1|ZhaR0&tVV!2H>LBtxdSXM_q_2++Xnp{ z2$+~%yBL;PZl`!ENfaUop&v-!Qhm!0fn)^{cE{K{oAuZ>(#wa9cW~|g?|!|juP9Rp zq_}>SyRT9gtiDB5$1J}}BltdwCIA#~SqXZkg(J%2@1535*Z>2vNKZ?6tNV)rG;A~ST9oc(w}+56cTlEvbX%A281>Q zj4_CD>kA4F)ZzdD47A)3L@lMG#h|P(HZk{3$vY@^sbGe z0GOPgs~olhgh5HDWmu!Ncpt!hZL>zT-yj_nHrXl`R;p&whzKto^es*0hTkjGG2MqX z6DR$HH4S}I>(6R)jt~1_XQKv`a8V-eUHSS#28;-9`^gLj>KLm5CeRD7z7+Y<#ODp` zg(b4?wr)lMY@|p!E{KEI0^bF3FYUgN6x0vEXEDxz;2cXyos@Or2PNjIluFh533W+h zry9?=juQ*jAJA+qa44VwDFDjzB}-TU00IE&r97;GkgexO-WHq%!b?)2SQA8wi?r*; zD#3heiN50TTrH`DQ%TG#vv)~;HP^+|R~v|L*i|s*0^H!OvsvWoqksl%2%|v;15Bdy zS0ZFnGG@EBax1a6fRCY}S4Qxn_z%qMi4{@_U@0#l7RFF(O{m3DcTw3wWTP48RvCQ| z2-u3RfZBin001Yo&>%S?XE;rx;?ByB*a95=)10_)%Q}sy?JP+LF}r`qk{pIS;B+G= zjxCuVcF^`TR8_{@CSa+IdvqZi+t!G?hKyG%gziM|#$dwYkT_173^1s#y2NzA!48-1 z?Nz(o0fL;bt{x#VlNv`^<>EU)oYvy}-i1&A3!S2ds0J`*zyLbFWfp_Hz-e7-R3huH z`DPzH+=s&V11x#lEw&71ru07h;Bh00007w1Yqo2=TgZbFU=dIu+)*hPeEBP_!+M zuUZp?{ElXtJ(mg*N5%nK4q&v#^MJf82C8(-wP}dHsuZXGMOF1^ck31U-IxO@;5Xl zRrmQDkUc`4xa|;J>D8bVBtv$;&1WmGunh&;uJmqWON+k5qy-@@No1?Y0Ph3fo2BeF zGyHg!E$9RyjZzSE^Xl{4)1D=oQgZ3bp04XqukPXBJ`)tG1U9WVQ?Q;&S zR1RY&O2lMvjhgi!t8{fcu0&~b#x#T*qI_ZvrOu-93-b>4!;ua9tM-fl`4;>u>zV=> z0{OfY=^A&y;3NFoP6J>>Fy*PT+a5iWQ11q`RXSft7|x>UPR?TGjB*LVHO1+4Y9$OP z03z20JnT|89KwQV01r6wmqsI-LgkZq@el*6J7o5k?a1{`M-Pm~khEJVcZ*tdMOe0GOOsoC?vq z4RmtMg@mM}*}CzXP@hse6i+TgnT3qQL9(thB;NL+S@|lEYg@HfSU09D#^^p@z_9~m zk#5ADA=0=(g1gB3=A|x0B_2NXL2rY)W>{L?-&R4_ z)M5FXFUMfFZF!uf@23%-x}zv>Tx*>S)%l5dhy~*irizDe#%)opRDd}cxD}!UBCKsQ z9y7koNQ$0_x99Mic6GQip$Pzb9sXT{k!b?)G5AvL7WQN1%}41DvovrLdpYi!COT4ch|3uGa= zL&7I}{{QHn>DSU3bie}NJKpu?wW%#=1cXMw4Y4l7`;!v&B(LsMz23m*$LT8m> zK6t_?t4V5rr|f6|I5Q&5&iJGx_%8E0;Z~;adGI~!US_D2yAi~;PShhG0FMAMuh!tm z=SPl!H~=1?jbjgn^Ge;jW?arlbV+j{7oGex{1V$cn4AQMyH+=lGEBQoYnhRh+_j5) z9pZ_^kiov+`;q~2JJDMp_Iv=_DR|Z3 zspAlvta%%9ANNian*dO|izBLbP)pG1S}qBr9`n4w=QJlKpnF&4J&b=nd(s-QVq|!T zUJKofP2(Y=r^AzJYzFgOkg|3PCKWEYlNP=Y7>D-9L`{z??RnOa6EL|j>H15urAq)1 zB~(QnV?XB7X0jUA%c$wi0b&>cfmJp((imz6w9w!F{^~~)DvN|iXihsVX1Z5g|5aaoIVVUL5vGr=Y?e# z3p#ri`S=1#29m320HuQ|!cIQ8q>WsB4!Oxwvu2@Yg|YoJFtUKuZ6@NhAjOc>E@`K$ zYk4oRc(^cU_+G{0h+Gglt#q|IW+3*uvS#R6BuaNTotp+cYhhov8COA3aiAR2enmbf z0!jpBa{xC>cx#2^5m3V|z$&!4Io{NaQUj+}FG?X2Nd;F-YR}aTF8&*LW;%%0Ctw+- znRJADPE3aFaz&?K?72v(##3gp||Y1RBWhH|6jN^<)VAO{ADfnCmBQG_ zt#fW#b1O%ASX9|OuMMaG001Ds0IC29I7`k_cDTd1V~HZRS|M;6ppo=hACn<+ILi6= zC~{ZmOP7ZY?EsmEp)~bV(P=7Jz?*szJwWQxujupgw+s?nGj)GGYqED)gJ9RYb8Jre zX487(inan(A?bR!od6l{W`Wb*#0||DP+Z%CK!QGRDt*t(?UC-DHC!6dbHv7v#b<;M z&z6cNV5Yp<&;S4c2lD6@FPUk*<~=#mNLF$x01$W9DEFu@fGl8fl5$Te;QPnGiu|{! z3KK&5%f(x9Y4k}+c=GDet<4`2{YhaFD~ZWzDmh4v1iXg~Xix118jN9J8LLO^COY)r z`Jt~22XklP0Q=c*8zHajSyeqv9gE2FX8*dB}hC*L_XZFj@2!~a@M$he#@@g2@uO2Ttd{kc$D$qI~by4fhas^ zUL8MLYulN{?js@)J~M5EU^I>9K_q!9vkV5+(>fn7a)Pj>hg8g`Q-`vzf)ja@FrV`3Z;D+*F) zc@4C)Bov@NW0^m*X{cX#&z66Wxs3gt_16i( znIxQod(F44sA!}SrP^8-qLu8T3MEHL;EjPUYLqp>$BcGrB>gf~ow(dZ0_sq^fs^s&3X zRTztA{!ZoENK~m2>_0Vb95!g}2ptZ6oedP^FRLTbNq&okG<8FT2lmx#voGwEr;geo zG*H%URxf@8D#jBH@3%c#8-#lEy2-_RYudaPr+Oz`_WP9hVf*A3Q6G$+;UU>voPPpE z778hqN$mg{IY$Bni~s;4iL};y0d0Q{tw1x$&Idfsc(ac&jNs5Z>cH3HSO%M2H|~W& z9^!QYn-{^!PkF~7wfQo`94OijJkw_yYtt4-UE>KELUPpKHkbFK zvFpbxrSDs}x!GvAar&`ajEme0B1>>KkdqIQbIaGiMGsYk$THak-#z0_ zT?mu4_Ilq})dOEm<1w!I+$0NSd811eRmaqXE~i6jVyL&jC0 z6FKk)#eoO_#JJK9;m%w=L#xHlYFgYftoJyh&8{lbo^~#m09|xoT5pN~@%Tck*e_~L(IrKpLq%zyHaa< z;zFe@0Qd$b`-G-z6313#HoGuRl9>o$e1AK-s=k~oE(8`kmnpA~(g1t_w}1eff)ZcA z16&(XpUZRD2m@>Y0DB#+JvNF%s3q19qqROiphma=Yt{fB=y!&V++92_GUQoc$E>`@#k(i52UDI6sltnw_ezW~Cz z?{-6pU#R9_J}BV63M@Q{)2H}rmjTsTpAgF`n@`WQHj>h9IW{p?Rb3C<6i*zi@-~i0X9E)y%ax1_DZ^5O3)KdEr zg63s7Z6fIIs?5SxVUC7?LcbS6Hk*)|2LEN>?pV}bYJb8S`B;d^EgVWUvrpVZCe4?c z;RI=DFe7g3tDZ>J5TD29@307W+PQ{&L*mv+>Tx2G?wRvRV(GHu?(6n!y5*)}$2^dS z0hS!A-^&z8rvd-~Y49ngl?;UQ@$Cs10$#vCAxkB=G4WYg5VBut8$myQ++V@s@t44C zeCV`s{p>WN=jLP_y^q-?vA+sWiNFMazHP9?ByaPStn-I=vZ}T|n7^ zRCpQvF6{22BY->w4s!xNCqhniOdxCk=o~-^d@lkfIIOA(D{2$6JL z1Mv+}14g_VBsc&9A5~t%;M2T-6SNgrMh2Q=jzP?-TmT5OzS6S|fho{s|LJ7k(U6Wv zfX{=eTq6Z%1DkiGv9B{Fj5zHN&-(=}rPa#^!<`XtX! zx7yt-BVs>P40El1$dZR}&P{{B#7)kO4-uyYTxdqjTbeeK#mvjGF%0+nLo+0RP87i^Xu_XzZ0b0;=(~>sIZ0R9gh&Y07w_X!s z5&?*x9oqb_SmpC6eQBQ?IL1!fUCJ6ko=Ou<&W{TF;LujZyQ1kpBPfZ&hzurYmJy>m z)qOE%fGF+Viq=|g0y*^;5A*n$c40~Z&my1--&I0~?aVA?rK)($E&DSLbUueuM@)TR80vaUUOt2uI=H-{z>aWHE zL|yKHoy3}l7=iaX&f0cRhAik>>p9BWw>U}u)TtWwn1%!YauE}m=?#0Z9->HcTqoI{ zHb?xXDSU)k!-t@*YmGkijv_*piDD3ddKP2bs%YE6{YTbpzhDCr#VZc`T5XLP%S3&X zT)O)-DzbY47}cT~Ia`T23wH1Tf&o2kvCg|3XsoTQ2LrWn#VTe90cJ6tDuqtU?r=U{ z7K@ivH1z8ic9zpLnU?9QKl_o+rODZjszoGW#3}&>v<3gWG+W7J!T0rkFg*TyAtwKJ zb6=uK5Sy|5bi^j8&x77e&fLBA`~n?yc5VbzzXX=3ydF)FwhUeBPZFV%?pE`Dw_}gd zHmLDLo}=DSb5YKz20Q3>_lg?)=~;ZL>-G3}6{|eVXtdf^71Sz~dGON`BIh~#5o{NQ z9M~P&bV{K?&e_UFm3PgXt)eyE zV2j8ud}(KxJ9Yg-aN}#59kHAh-@}}GhfLV^`d%@+RiIFxS?m61odn#)~ckQ;upG^UfC1P zJ#SuX*`eTWlZs#gl5((a!9@*1ScUA>-)`+EeIme#EO#bo*-|w#)f|fSE$-OmshZJ>zIP^Rx9s8dhoXl4>jPr6^=tD)AJG-xkt{LfU%n1;BTQwF_wf>uz19F zIh-{ur?)Xgl0!j57NGmR&g}N!fIvZu^O1;_fquaazCFwGhb_DK=a6 z5&QrE4eYR~iM8Eq4Z^UCxzkc8xi!kl5qDO;w6LQREi z7M_?b$BV(`hDh=Ge-n@AGpZ)2hT#BOe2!=Eca@|#{d?AYhHbG>YQ}up_s0T+Z(qQ+B!^s`%KTke3|w(%AFBZUkYqlmU@x@1FDx0|zXDxgd1 z56#C7RVxQx&-b7vxd<8Lr_@9mxDf}yC~I@4&9W^JUBLjrP6|&QLJJ+mCmmWtdzn86 zJ#X5DKMR}1`&);GG&;K;rIjKhS2orO8R*j@^k+kE=tfZVTwn~KG*P*RfiJ*>H@mX2 z!;9cJT7L4lah8yG>k~d335#dFgIy+Sq{{FhztR$BUIHyyzJ|;c#t#qe&YUhLXN1>0+9Rw zUO=J04dm?^n55OV<_^@l9=9YAozaCgfDL=CJq;Du(+)zkX2K`%LoaBUjCcawkHYjL zEh&8JnV?$XY*D!nCp2~@Bk zDbL~KZJp2!^NDWKKrlOtJD^Te4Z>;9am033UPXL@xEtI`fm()OpWeqs{w@hEHko&d z*0odKO{wuzkAeVw9Ej=GyfuwR<+!QfptaL2g!Gl|Rmp?(ahO6LT>f1(lxlO_VjLkW zqoEwSegLD(alDYZly$VlQ~_PPnl_`=9+@u1K}v_{G8~%ocb2I0021eF)*H0?r?c3z zacT%7)Lcy#oa97OJ3(bD{h%A3;c#IIk#4h-kl_Ze#FO~u!R3NBHa&yL_FjMyr*o&; zxZsK?1qd{Fr8r}tCXpR9c~?aC#&v4MkP*lgd0JNzdKQHWez7)}*hrWM3^$@Z+*+IY zv+tq4co4F%9d8G4yFm`J$p>d^eX1^Z=Z~FAm74Tz$?bkXg~$s2=QV)xJR)b4^J{1uJ^@$m3^hkjR?>%gy}y*Y;) zJ;XFzm<`SbYyb=>NiGq%0o%h;$Pz6utE1vIj9Q4o)NAsj-Ak%-zd6@R#61dK7yO+r zM(tXW6@8?=HUpkL6sw&KaH!nu`_i|`9t*^A@ojrA=&cHjri>wp{SCVRRI4#ZG1L&8 zIa%TKh+lRS^4V;~+zdYrfR5i};w&XGYLZi!xjjm-;L(9s)PLONp4~!4hfneBKUOz# zdL0YnUU*Z;)*`*m94krJuRYkFl!-~iee@A+cyT@kgvWCFED?F~$OM|!o1w~~v>`?X zOii=dlmnFUHWYa#h}1R+Yr`C!8dgi6gVnGo72I+m1)of^3-EpToCa3E%41BWvsx$t zf7gSkOn8V4aB_-#PSh{qAHpf()7Ls?D-RSjRRAYI=syfmnEuD9wB4xrzron=I0_f( zlUsm=OJ_XyK`!xgLhALjGx^Sz z&1Qyqf(!!gCu=@aWAA8wm|ru@UD1P;yeSM7nA!%zmMtV!rQzpN^yM|}Gvf|?b~5RP zl^vb(sEppXj;SfXhtwHB9X7>2nQpIF9sT(=0EQ5Hd7Dis5tLuY^aGyeco3rBWHjc0 zcI}GP$^@c7zN$&hR?)tnEzDxK7h z5w=)edn+aQjO^nTTr0AB*u{_-BEaZ;397+k3Yx}V6F~3=i8|!S3C+KbW5i@@HBdT? zv^0|w{b((U^iv0kR=|c(@a$hj`aO9+w7Ex)iC`2x<=sUh&!ZU)iz649_>PJEMO zaOCLoCjTL?dlF)b>$6P_GJTsn=ggFOGEISo!mWmmHgo%-^b6a7BH+f^w*r3d4~2rR zH)wnS&ySp-b=YS@s{eF49WZhvn2M4i(0JLBYz=M4a^x=xk15xE>tS(GMn+K%aGN2J zMoTX6KUbnB#nO$nI6xH22utkh>B37}MG$U+V#7;NLZf8a1p=)dfUWPo69vYKOzoxM zV~>fY0{s@9ZmDitpl}KXQOoRS0ek-x5aMYQ@$w_IP2cjTF~tnRz(yLA##k1<5wn=i z>U2d4G@~2D7TpXbH2J4^F{x0`y`{c50Ka4FG~k1s^j2Xk-%Q`lTn-L?{j+o%rkwRQ z0n8Xc0001*YZ3y#rxU{HYOOdAN{&NMRYkFsm$>FeA7+(F50i|@Cj-Y5RT{U25M}}a zG}XmXlK^n-%^NV0Aa00}lk!`rj1aSscgSHza;XgskilQKo~o*?f&diRQ>txp06yeO zP z@0h}m2#{tK>i026B>BAyC}LNmk!+qD^R~7;PD%e^#7F@zsAcc zRw)kjlyno;U^*{QV_ry!yyInGh^^6MR7S`D03AyJ2q-{055AHlgV_rlujqGJqYlv0 zD}{JQ$W1KAfKt??R#+c3GpQSs_e_9kzl+A^$$7#@_qIbUaKp+s}N3%H_vHm0;%VV&8kgD-bc z0yRL&X)=Lp3Q1LZDr7yFKbA?O^@7E8Ag*leKmR}>x0m9s;1zs;*Wkh>ON9+5=bcwl z09@YEDwhBBifqtc0h{>pz%Zji*Ba}?NawOqCW4?>&cwWHK)b3`YXyKt`H649@~9Ic z)CWkL*7uSEap5^tq5x=sThZao1X3Ox{Zdspd{yT`q^M%+-}p7s_$z(0DeYCBZP>L{ zijztslA*)-DS~rrzSG0h%i{ccr8L(;mB6-`1praTEb=pMa#LH=HDJaZwZ#D6RvR;8 zV=+R^qm*l-3?la$|4H6X%@ShC7;P)t+34W_P!b{svKss65i$J1x>zPc%;~A5ha-{j z@W!+FUr`bQ=Rvj2AV;vg-*Hgx^lTRnE&mYa07pOlQ3v~%d!OqB?2O4p2cPI;xir=K zm@J*_WX@mr$QR%(8lQw@I4q_MhY7iBTkoM4El&d*kuiLLUrDceJu?F4 zl*)=-AWLTr0Q3gzgaRu<7ytm19{>O=!EUOdPbBc4ixN-kTQ-1nTWHXNc}3-{L;wNY z8R<8u%Q;!kzypeD5rSeUW%)_IZ+-#kxAa;;-4>*1pHGRQh;nhSBd-CNw_FxgELicj z^5?oCWA;mN0>YxbvjO>9VylHkoV6ne=|v?8Qw}eE?hIkvxL~C9z+MjI8OM{7GU~1? zVS!0>7}&WGm2uZ%^w}v|lZM-T)~2^-cr^kpKoJ&xv1+HYv@UgX(#=Tok9&_)LV==E zsRD}_>b^LVs@)qDB6e8-yFaT8ey?b=iHF@tA^;m8000E3?k>8@tTZsnS^iNs^n3ST z&W?4D+V(J&>M5ksqe-kVVFVm-!M2hQuJVBhyC&aSlC!u92h|9A=%%-$6-iNg0Y8Yo zoniz^NdQQmV^q-5QZQ+zl+9^_%ZT#9Tr}G0!nr2*gG%_I@>cbnkjk@*usQW|d)vP` zJ}12o+jhGRo+C^``$rJ<2FK~+c1z)BGen}=6TRDBy!0lay_k#ROHJ)+#xt<5(_274 zaUSV&IIHuD6!>MaC7U~;99ibD`XwUds`r-7yVu&zt0$ZtOcmzTcuA3PjH#jO@|Jiw`cQBUI)S$kPafi(*}bmfVq5tFYgSmJaLY)e7)#) zu*`OsYT#j;b+A+?>5L~?+i>M=aJY>~tqI}rw3y;o@-{F*MZYM2DYY5&3{ZP{h+?5# zNCY>mm~2-_y9kq+C~K*Oo3th915IO80ssID6E!}?Q!S5VfUTdE2!{gOiVV}fZTKyQ zYAKw{NK98K2!l&_kQH{T`UiQ#J=@pCQfJDN{!D!$#J5?4PKTeg$V1U3G0;8@;A}2l%nE)yT&6 zTHusWVpg1{6wRzMpEyt0`ETlQj`LRe9y+_lybQ2%yy@+%hjs%`(db z7Ps;giYFBi*0^8bf0#2bJ$CNUZ})~W&D^lgSroClE%e0DW0$EiT;sL3tkLWR55C}3 zqI{J$b+1P_wiB*yrcSQ7^7ImH z16sruqD&T}ot_;QQqxW|bWX3jtmg1BFfUvOlliIG_H05BIx!s#E=}FGmm*l94R23& z726J8El&@zNR~_B$K%HJEyU`+M*8I?2N&e z*kA$9(-(^9PNvJ49|Ms&b@Jv)bdQr0{!sh?B6Cwyga7~l0IarhROYx3#&g^!VHJ50 zqi9!w>>_UtmBvRMGn(MLMtxco4_|Pvd=)eO)9mEIuLGK|D@CNiYgKd6(r(B({tdR2 zK*TC(HkvVytRw$)i?A9M!s1%ocg6RNj|vB*yO;D2G2#ZBh)x(8?SDl=Ld>=ezA8kcTC z@8`jtJso||W-7kZZ`@SB;w~SQM+Hq2JGxg%C^E84g9=HyxDhj^Ru*F38O6^Este1( zc`_rO+6s_F8;i0{lnn{hzhW@`T@kdZ$=x-W>H4fwimudESR{kn!{kJ|vI1qm001#` zAIU=xefZn!695h>||Oa9Ms}ig0!tn8G+<8RIm1-91(Re`ysfG`Fu} z3|SjTc;;t2Nlq)#fpd~9uuS|&q%6>&J@JbWa~C<}jDt8?&Xb*9@9m-CY%ajpHGCwiF*j@1(&O_cbmp*abJ?6Hz{uxI8d1{58iJv?ro1M3kazH#%mSsHLKk-mh zLaSBHdaz9%@Nfh|_lv&KB1e{ctMTMtW~EDKY5AJ1KK_9w{q1vLh{+_?YZFfFxcx~6 zpK;v$6XVnRo8SkYQK&S;jrVufTXBUA54sNIQX!%wK9JX z4cj5HI>5_vFE(ltcZId86t1GVP8rX*ft$Zx9%Kk@l~XW<$1^Vwg;V+EEUJ?_mMKx8 zAvrjk)lthRk|D_V&v?O{Y_Gq)eOnGio(!kXcR+qba?BNB-%AU;I z@)m3GO%jOAG%~Qb=_=i9z#VEi~H&e)QtB>m?rN;G|pvv?TM_f6y?;Uv}@=n%->wyJ$7;4+^_BN$ca0NBM7FMpE_9S%!^y0~+l@Cst zxJ(Rem!lxzICi3V=a!_8K-cE7Lq$7w)GjM7t;FWNqIWtf3As52a#1jBpH}|VXU2F} z#~aAm+GGI|LItiQuUjcstbxDq+KO6re9ZQj6X}2T5esS{A*$sv={EAVKmP#yyq{Wj zf^YN@9F|G)YJpSdKdC4;4rZ+xc}?ZzQd_SQ#ZpZa)DBCw+Zr%Qm?9;RtLFL*^m|TB zFkBmI)am)r!8e9!#7kG%Di}#)E%dYA>cX( z{%?_3w|1tR>s4%#BxQ*=LnNmGQ z&dNGvCHLTS$;s|u%QHYzK6W=WTx&JqGXVv}vqQo*ga7~l9Rf>&{b~=Khwpk;|_%^`3?S|>7ZU?MpuY_~hP2(>ycU%|rC;7DQI-eU-eFue( zx6)z)Qo%~Pkb$F6??Mt3w8s1&rwPGdmpsMZnB-$zAdn{s% z;>Ug*z7ii!aTN0`yM%!yz>lXrI1WKZ)Dv%gu~8#S@@2ew z8E1OJ_$HP}0t(JYCVGxX8-=zd*%meP+}J^uMQwM{*`!Q|x6e>Z#sWDW#j-Iy-~y;8 z>EOmsthpUkg`vptsiVB8IoxgzYr^HEJ9)-8cH2Na*5(d?)Ln>|Et*$6slZPT{d3c1 zm*~am) zj7gSWw~Uke?oX&grf|x#_9&}}>8HDh(xU->hL22xLzv;QQ~kMfCK%n204ajR07Q&? zotqg}pEzAviaAP(Fyl;i`UHe9!XJI?COe)WqXP$Ja8TwS;ODT$-!|bvGgIUjmArc# zjqtyN#IQu$fnHX?HnoUbH4`r$mfJ4<6B`>07><`nf4+V$Y++862M>?aIxIGxtuhPt z1df0hf7MH52FRT=mAFLB86F-1pXFEv&6V9>ZzSkvL@esg9Fac1-oDr%+C=a#hjwFr zeL~L8E3xfyQ{h($2}2jX-}Og#v#z?UPD}TFy`QK>{fSeY%7)S{+NU^$YYY z#ZzD(4kwI;Ya;wJfXR9A?SRA{35V;;wI}CVyf|-l@Cx-NlWi|nfEP#9y!}uRt2$fh zk%CJ9jre=mam(JFU3*aIA_>u+jaB4Fj5{H9Vgr^0Tdx*MS0v{)q8g2SSX96NN*CPK z5{I}W-juyVT3-DZRXYp;WWfV{NGZzk-kbvvl$D=k1wCLTsefuNJzgQAkK!@@*I8rl z-+|a3l2>1x6}~Ln1k+_#Izr=}Ky0FI}N#NHA; zUkHKElgEbZYJ&(RI$)yMcNkNW1g&-!i|zOrZ@LH!ELtI3b9-%&io@4v$e%S6k_Rp6 zt;G*zWgRF1bfYp2GtE*{=`*6FWu;0NkND|dU_G0*i?p*&_vIiqVUnm?7HD(6I7y_T z>v*@eXKF!}FZe;?akn5B{0={5d7N&9F!hlT!rOz6fvepRr+6WTj9hJJ-V6XMrMCfy zSv15^}ay2S3(gxPd{R5QYq)0qECPxrBQmp7j4hr_rrT55{dcbcBKT$-(dT z0bRgbZ~#7kaJBlpL^m>2Ov;K&vY1Fsq-6|6>wRvZN9XDsNeS3jdT=yj*L5-xl!l?J z@KLMI9q%rAup#VY8FQjiKBRsgOu4 zn>MKf}C zeK!(}!;*#0*Q5OPu&aNOddrSgsUiPL2yV}ve$02Kt|=RaPt=_|R33c0_zAAsv-OAT zNd)Ot=I66h2UKyO=r29W%EW&>nR=sq3>4&=-p&o5f<%@R-$nBr9lJUDB zq(6V7`lAz~(09YdXKuRFGi);W`hW$b{*o3y2$|*I>q2ztyyqhKhav6f!rE+7j0xZs zv^2&JTYX};uWkiL5MWc}gyleZy-O!e^d`J1QMdGb(6=h>i_x7lp;NJBbI{Ip**#!@ zhqmth+(uTtCXUNa+4m|tROjy(LlJIMx;R@~j0gW7J9eu-%gre%b~VVbRPk2{6jAi6AkN#yzFN?W2TQ(E%9 z8Y2N`qTOAPc1=@_SG9s1zT%QANS@pHebhpid z=k(!^6l6+H5^XbzB)W&Q4GH4@d0LtW!``w_nv?|yu5XpT58qF4z$I!Z1m-BW27#B| zF%?Y>cVF_Qz~;0pH>CA1&G8lY-=e#iP+Tv4Ak_ln;Mvr7CUI}V19>bht#da8O9t>p zxD}&qXeJrL9q0N5`12`P;Q$_^dp|r1D8!Tojz%27=y zt|=X<&wHF{=V?tUGNL^PQlM|0@%>f;DakDYdff5|`yQ3EGNHFq?frWRtv~Z}{yPBo zDD`+;H`w~Oay=@|{DI7E)QrN|J~aBu0!7}Vu{}Fwim9W~%+)8dLr0{C=qBg*3)1pR z0vA#$GD?@Ib25=fVhr}bYxW-i@{>BeHQqG`kR@y*->_Qj`FHiWQG5qCOr%l*V%Puy)Je8#N~P_RQHu7^BHwFBn(4r? zi=f!sTvkx*`l{^gO;C4X)N}ff;3B63pk+_-9nv+Sa@w6e?R$z3?K0U8cSk|2iogv! z$3E9hn<%*qHf3tR>q4X+pg?g2TfHeRXVDV{zVf_g-B6u-{v( zU1;YY{kC^DIi?47b2Y}_r1q$_L3DsH`X~fU1^{5Nrt&$MmHQwm2l5Oo%@qj-sB z_`_|m+f$%k@ih%}37fSt0NS%fx`T|_DPQpfA%4Ag0OR=RlyQC>d<^A5eB?6!B}*r*ZwJuzd|P$`o9*Umn{SbADD=;Zib4ci-CE zZAdQpRl0h4G4X{k_X<2+`M#GX%Zh|Yl|v!8&59z@?tFoYja;_}H_D?MK2ngrXtBR3 z%sM=A&QgF;9NUCBSiNH=dUFm(Lr>ucG_HJok0n7cN|KBthE1p!ow#trj9y|0Jtjvl z#8C68v^K0}m)@`aVqcWiZ%r^T4CqPx4&6{>UTLtdjxMx8Fs26xHW#!z8qmHCBSZVPqqy~qCv)^( z8XFGO17FmwvNyc;K5trBN`dfRyxNyKCwehgNOco{CA4F)Oqx(6h8#31bihV z`v%Gc2Xeu7CoGJ#l!0vLvHWUSrX3ItnDdV7Kd*wn+o-96mGm~<)ZJwlFFb+&y*8_y zr{C9mXYtgP;8szt-bG69u9bNeZqoS@E%_0L-?QqvF(xC+pZog@#!}L+mx-*C35o>g z2kK`A9M}+i!`F!BpVHKtRgEblc^u=iaE#lJG(IdjU{$s4)DOID0FzUF=QQ#c53{_v zqek4W$<5=K=puF^0HeS=8VV_m8T%|Qo1X+1J3S?wm%4ZECu9*$vj zZa%D#r4G(A2qsV@ToiyDsSzj=_Us{c-o;0|RkO^!d(g$3&P{>pcce9&%BQrxeME6YTou??&I^L z&soWHBSV`>(uZm~X~iE7m+j0wv60>B~#D;6+~^@C?Mow zRu!Q`g~ga2BD<-cbCi06K^0lt>gIIBn@yB+LjZN9l_3Dxvw(;)L#MFkes%DiE5X~q zA=W@Grj|y5M;#jR!#I666DvNvf*p?0{5x!uocmxtJXPx^OTM$CyW%|RZXUNaTg2T2 zxIi8KgT~ikuP-~b1ijpOM?x>CgP3Ug$Tp6V%STA7jUaDCA^8P7B7XZ$H+xS5PD5jN zP}XT4^nQOb>96$;l+$}=`rnnVNYk-cCzuLU<8l5S;=A$j73HK%zOKE86{?FUv$`GW zP$<#U`|H{=ZL|BS(72g#4SDAqjCF-}*j(A3c#}^g&_8XM*1HX}xyyaBh59`_6DO(d zcF%PN&`Qb}v=oQ8?wBnVFq+{{sr77 zRmZC{!#@MgCOJ#Er!|XqDvX>%?>CR=nJCHmM%Wk2&p+b6T-Rf_Vt<3GY7idGSP=T4 zI&xhnYctC&T9NyDstH6nNG$SY%U%_b2l35<+MHNnm(j%p~L zmt9zylzD4VXqd$-reVD)HM+pn=HSb19D<9I7zqaoc2=R{|2ex`L)n2li^z6xIH1t8 z8ce-`6Up>Goyuggw+A?6Y6`J2OkVW#W~qqKZj&~*49>+U+Rkk&?614+tvbldcu{pw zp5uo2+WW`@-Tc^(jXWSfs`scinZx%DpRCXNGU_lCwZ))Qhr~qD^z4*o30rP3a3A_V znA1(0zSjz!j`itO4KZjV+9;VSM~V#yq>jkXTTc;YP9fOf%sofq@1z<6dlQ zUBHh_Y0`Sh;`^4K2c~SQ`Ncd}{Z`z9G~Vks#V34Ac-hWaTN-gc@)BoKB)LScBhUS4 z(Bk52uYS;=xKzdrA^8dr;(%7FmI}P78aN!T>RKvH3w)r5f_$CC*%Q%RwLg@qW@u0G zeP>#Jm6 zdhWyZa-n%K-7jS+mvG1_hxPs4^^6HkOJg`6%;&-P3zb7hRIGJKQV zeE4$E(aNBF4aCB;_(|;@(Sjo^}IxpzzlIZ`f7aq*_A0{hNP9Av$)o1!t0;Ma-EQ zCeIF@GLIZpbec|Y14CaKG!?)oVDUG&XTSdxt?P4))&v52UOWNC2hhsaX(Jx7Gx|K2+gnXB(s{=Cg)9N*C68eX04A@@o9JAjkBh3_9DIuZ{Op-a1lNHbyyb0cniOijP|n*Imx3#f&&l^%8}sx{86J6p1MQ9g4byWQ z?P-slE>d+cz;S-^G*p3NgjTA8TB#rRc^NB0Yw53(!PnYDaMKbMo+!qGFA80V+azfq zF#zBhg)7t0Ok8sBo}JI8R$Cfz*CY*M@7>@3*;($oa&D&n;>eKixNq%DS_^yXi13url5V%0A_y{-%yh#$NCRrc%$}sXAP|cBV>bVPn&4lpl`bA$P|a zcfa`6l0gi^ST66jJl>IbpJbIfJ-WckLgm;XX4x)I1%Z8pd}~pni+WEg9b-bz-wk8v z*0jUZ_*|SQL?NGFHUNb!NFe6M+^H(EZZ41o&}oJrZzl5wtp&K7tT#Hw-J)7(-+h_E zUnTPho{MzGtfX$RG09!Fy$-u1Dqw!l{3J+~v6YXXq-$*;;Clh>+7Y@*nwmFVl9i*-PBSW9H^Bc@Du7Fe2mj zj+xGD)B*W=RtjX-q;qy2_(ZDuJ?PMlHq$}5%&W7(mO6p*ZfZ{gQ=5K#Oq%I7a2nsG z{s3S!Ttar0I53Dim_vaJ*)8&TvwMn4vcAlsMEnR@jj{T!DE12VY%HT%*8;FPJ|DIi z{K20JICCHA-z>Y!e{DsXLT>?6lN-V5IitMBqTy!A$!9a|${L>@u9SZmJVEf4M^`OO zgx4d}SPQ-!J*NY5g`&MPWiGSRX3>-1$|rQ;6c?V){B=N}nopD~mA_#jE2v3fty(tP zofu6EQ(@zKJEJIC;z*lQ0`?) z<(;PPSG|ALir$M63;n4b-}{(PV5j&WKwNgRSK;*L(?`;6rQ$2YY=GM<(C0hvgj z9gJZuHlvfX!efV8f_Vq{4Ut(E3qcTQTfT}t>o>vOGeG`{f&pAPSwjB1b5f)iNgoH} z*c(8iz#)TC^N=slc0q^2d#G08gdQbbthcY(UJS95fSykM;Ue4E9vI=1v7L!BZcL`^ zjSVUKxJL}uE9l*;tzip_8+h|b(X=ETthIfDyCnyxrcY5!Nc%(y5TSGb zQKha`_(l%78EiQrHiH7xZbfNBwL>!JAW#NKO6N9%RXcG~x+Z1@F-H;5+tXo`yhq!@ z=^;SEH7>NFVTegKk1Kc84T)UM*W|fyr}=(vUpz(U^zK6+XA_ilQifnEc!!&i47Kol z8Df{tmf>70UfO~7(QCCa1gRU|s+BFGY8cRA3iZ$E04C8mf)};bXx`(+ST(`>v^r|p zx2u~*oo{%@i@XZ^5=!XemxCd_Bf!=127J4ewHH2z>lb0y@!ADoBAowwnzdE|NSLH* z7&(wI-yFb>VHZXXPeer9H{n;wfcE6M3{#iCE{4;PHTvY1zQV5oRxpa7Bj*%YQng01 zb2a9V<-7pAKaT#mS!vm9z%N#2=1>^MtR<9&;yRnf;}B%}==vk9<--QraCWZt#W&p6 z{1B+u_N7yxZ-6J>5mE(GFA=P6_Yg?rRQ{jetk8OczbSto?<48jkn4TFhdR>L#dE-z z`GAGHMOJ%ZOS;OmkHT_)5dAoYoPIny&h~-+Zxxf1>|1!2&pD~AJ2K%JJH-VC)oRs* zO$LF9A1~QS|4VPx`*%&^WtS|DJeG6d=;WA^{*?T0g;-92@25Laf{1s=UBq}?&(M_$ z>9s5f;$X&)a1oZqo<6s^wflb|O)rxTSSP(yZXU<@N{gk_?nmI_c=FQjfBA#W(F{8J zxWzDzuikRW(+6#q7}hBy@l9ZE$oOJjag}JQEI|10d-1RXbM9IkGm|+dO$V`E{Ka-V z5SzFSaO2stk#HQ8*0uYP<^>Z#pd~Knq;0-afxrB2Q!Hw?)?N=Kb0P3$(M?JsY~w=D z#2Q;`vC6l!w6M>nYP0Bk$B)q13(E-3|F!~*CqZweMyH2gAKp&W%|p%J_3pxv%yfA! z>9G@pt5e=Roo1biiW-aqbneGJP$YIuw6*%M$v;Yn?@K7!LE03^%ieemK}rjh-)a-~ zLUkrxXv>k19rDdFoaupjlqC#ZXL|)K=xRI_Jv=6A3>^UO8T^ns9|U%F<24y-z?OOS zT3OC{SbHW6#MNl`yGBe{jzaoPf2R&i=2VCj@`_O? zTy)qWxmztElo7p1--ol)P^ckJwIJwY;6!xKoG3y3@c=)p!nxe`3>96raeOG##m_kt z(jj}UBYfLpHCT$lLzmnNBGEGg^tEAn4y#)^$Hnr_ku9sjl~~jm7yye5Z;ymK1W3N5lAO z4$?^5VL^RQv<}q1B1|MD0x%ezmbJ7Lv03xF=>AoxAeV%97#I5y43r`_mfgobQ`2Z+hMHR zg*>2ua>^}mZP!+3;am7%O*tVZ#7de(5v)2~3Ik<0?|PGb5CEUiGw^$NF3tHtr6W|I zrMUN5PEeRav@)o(S*HJG%CBP(^;FiI`uoE`lc)e%+L^^|uIH8$*Ue3^Y^%|Bjg}Rz zR>(sK?S;}CQ}FwNylJq(Q4#b2uo9?@A{s-cNjFkflGb*$8<%{}AD2vSof4T7mi|jNRLe2I3ef}z0tEMSC<7-&nz3-EI>0yl@4&I=BMQM7PG6nRm0FY(6g&$JxFj);FnmBmlL-ZhVt* zv@0GIU}`v?!{u^V{+)8VCS63a?0!|gvd|GIF5JVa1QLVepz0cdpv6UJgxFAQ=7?6F zS_22ll4r=a#9W%I;4>aR5Z94%&8@C20QgLJT#isK;L!WaDLM*R$KF9$+oz)!M?!=p z@*l{o9u>O$2ycZ0H}wDKX9@Cs8G{kRrowlV?%-$Q`JnU)2=nO*g95%XfYUMCl(Qi` zZ!2m>o*bJ)beYm>RcV(Z2C86tvvf4XjcJXP%_tqeJd$+fWLm#(Wh}1_apoXJKYo5p|L?o z6&Esf?U~??VOfkj_lqG;?*zcT9cD<=$}-ztXXor-1*5EYyF{vp!kwDxRm-Al zQm!wTT2T8j^{w>Pd6N`X*(y7^6NBA8$!OGL%MIWi_d2Q17`MRbh>2+kFj^9$cbx+Cz?X?rnV}SN+KzD$&YF!* zYAhPO%7pJE_P^K8G+TkjIpw7K)sz+}fhHKB7C^fAr(nsL{mIEU)!&2lcY)ftZJq&f ztl+(0IFy+QR3eO=UmcMcG^g*~j4$^ziYH}*+=siN{<3%C;W0+d1`bj9`6-1%W3zd;Kb%^f#qx>PN=2V^<@O=D3_&j}?ANz~ zx;JnFOMJYDicj4t1-7(*=hiJd*F>UIy&Ob@ff|qD+7`wCjb4{W+V>{tO{4OVsONH( zUTyWpGTa#NhS)3D;w(rJQh>E7Z!onp*RWbzCXCSTMWIMc!E zW_^6(F}}-qto&r4x9L0|>E)b~JHU}A-5Z8!X#-LTrF%)kR-ya9-NrEx^Hi!MRs{A- z;O*$TK7=^X|AwKb0B4n36)ot?7B!2b2zE}X^G_0G42K#UBoS5FbIeSyIf#jvQ9+Ftc`D*ts~aQr!^EPrs<^;@-g`jO=+zA3C- z^eW61Vm&4swiK9frR0J|Jl47%>r9#UNnykggyl~_IDx8Ap?qZrwc8OfZq^s|8IGFh z4d&r!5bVA-tZSd%jAVK5E40JBhde;4aItbsikI|{`a3=T_<`JG3floJn~uZlBQ)hf zo6E8$1AESB92pHUgK2ElBDBBaaDMG&OcV(>zSX8$e<5wQ(hdNzB?_ zg1c-G_X3k}^!IwLT*UC=C4{MhWCIZl1+_~kYPUL9jde9Tn)ma4(iPI>=_J73=a01DmY#U@M4@Qurzzu1 zW1#vDttu@-I`hat7|dtPz7_Cti5y$|g8^LCB1IB*BoOy-g*-F#UD}h6I{eP?N-*f? zFP+lhJef$ye_!!}kQP$%r3kT<`eZGCG*sunp0C{rp{AW*x{4YT1@ZToi(9>{Kj1v* zwiFA#T1A7|Z)7#5?B>h0!iCn@<~9k;&Y|9!ySNDgj&sWrF8_t>kL3!^jc*)U zM!NcU78%1&J)<7BT?!l+T=xWyR|05c*d*@@8PEwP2-T4M^N!3`9KB0SJA<}-FfLV> z_J8$eAya~FTK}$F+5$BeBm;zkI6)}YZ^n6l2LD=$bvXO-Ju$SH(`LZ`H&65klb!z~ z8%a}VI`a+yVNygHy!{w$i{t^X~?@Xoi-}Mo1B}SkE56?7- z0X$b3*ULeKs^`t<^%=b2jQx5&jB39-ytax;jb(Yp$_QxHR~n|@B>Gj@`~jI?WmRxwFt5aIQ1#;#yNbXmzIwPf0V&!>owCLXF0pCZC_qoxaI0lg)1v)I*aVky zqiGMHf<@F@x3}IpPu)Jg~JFfxT2I(-_t-Wq}J7@w;mU#h|IokQ-EDa+z(n_qGM~M$(OAm|q!l7I04qJ$gVl4Rx1O$}xNe;x86K_l zP~q+!w_KYB(L#VOAR`A@b^^=mfM%NP7qZuv50~=Z-6;W&eo%KvN9%5P?gw7&l}G?d zK(@bT9N&7ej?*k(gP?@W94RTx92Bot3PEGF&zkNTQTog(J14~dlYA$YpCYO&j_B1e zcWPyGTZRPm=FCx%RFWcfX$Wg;8b*N3B2kd70On+#+#NX&!6IQHHsso6p!SjW^W4^U za2t82QP!H-Iyoh&~-`OzFM^=l33CN z=Nc3a_Inz@m8ZI_yTe03ssd3QU0s29%TG9AVh}P%os`H|_I{ULc_fU-pJKZgRkP~I zZn14jBDdjke;GsJwBseLQrN+?{Phnit%7*dcRP=X5KaXznfoFsp_5`? zxP1N_&PKnPD{!_Q0%uv*9-p9I0jQ>pkd{5alaKEEqoFSVxs&(6OI&iFgF|?0OAcXX zSsil~x6SQVJ2V4J@z*vqdrlBtLz-LHOR96udI-G0Wcv(ptZ4Q+!hZ`eh6(ya0JX zIzpPG#c_7QorIXh0-Te?vXKP!Vy~OGYj;Z@H!b#}u9KiSUbHQUH(*j)%T{)i^a4&R zMJ9Z7Q=x%aaVXiANEEMEj^+V05YI3E`Zf*2&6xhR9PNT=B@ z>&08Ib%4c5nVX`t+~Wr!mji~v|4E9nbN5WpqAjxJF6KxyHrJcFIeX79@I3DcZcKn( zeP#B}YcEXCrWSS^jq?j&9;<#X0cd$X7LTa;X|GhTD7`<7YhAi=eJq?F6`I?tEl>~& zFD>?`7Cj?h;AehoN-!R&?oB!U);8Me>wh(g^}(~y(bq(5n1>r-hRsaRr%h!5gn)V# z#gwG=<9&Q-F!&+7*x#L9^G@#7*Xr*S7By=pqICi{Ri#UfW<~T#Su;~68U*@2c9qPm z^9`K?w{MI^NAdh^a3N?ZM8LM#HG8f=U57P5*t?9-13m(@^bnghT(=Y*L@-?vcF|^k zapVn4=8csf9m6{GZ51FllZ&^Jiji1<5DJwm{=PdD;6Cq+U zkPD{GKq(iJWqXi~E#^iE)V1QEUmhD4g2jv$?m>M5+ci3uvRn)vCQmHnn&CY}p?J@J zb$@M%;@6(Mjy{5~gP9jQFk<0*YDEy^EmI4NCB=R|3R3G-AngY@O7) z-6ryR6+!u-iG6g6A{NK=73K2+Fc716%hgR+awSx*%P zBu%@Qr~{_YNY6t;0vmLj3bccA8o@|lR_tE)RVRYM=<3ik0d+}|IQtBPwV$>v-n(N* zhODtUr)z@bg+|c2);(?6V7^HfEJRCG1Pz!^Ko z!Tbq+Lem5XvNDGi=#ra{IX}@Z(-_OV7AhX$B}A;?i>zlGjLy>lepW-pr`EeNx(;7C zP7m>Z)t5`!tMy!TKQo{e2n5A_KCN04)+Y@qTlYRiWC&3(;y0NxrR3V7t0|JcIQ9^_ z)vC^6@gH*{5WPr7;VjSOxg0BMZ4jpbx}6$>BSs^w51{`!58J4|?*9C1L7w24(p@BF zkq%#P+VRj|AQ-MKz>xJb1c#_;uj2iCVRXN=u~Em<#pY+{VMJK3DTW}NKT)3IqT*`I zdIddkZ@zMN7<=&W-xG=Cp;=Qxm;MSZZ-e=)aQql1xzc#U^+!$#>Z?vHRDie)>c#&^ zs;_8!1@xU|t=r2~1f})~mQxOf!lP*cqSzbM30wrBaX>_4gPC9L+`)C>1-$?OI6>&W zD!SGfX2NpdKwQ$wJdgzG6%M)8gmEE0(xLqFWUIDudO5G{`5;VVISx9WEtSFZKCyXz zhJ#2*6+0}H2xnFjXK~4-d}QJh<}ergo`y?b%P4ErBp*;&_yV?#-morU#~7-tR<|5v z_gyMCpc{(7+k^%;u3+a3oamLc`C}pkXxVu8+3^v%RA{R@V!~ph_Nffcqv~0+Qf2<- z>#XWSM+*LGpSV{)5X@ajr~O6;V~^8W)K{m5Nl8$@(P`ONPw{v=SK|Gnpcf1kH=NRt zODT`lb%W+5>EsHYTni6|d_jWha^AkpTig>b;^tMsV(Q0cznomW@$z_VH~1euH1t)f zvL89ur+2NgA0O01TL9W{zgA1pY>uqj3&D=fK$75ie zrc}pSSd&U70|-mMN)k+d(@cF{#dIe9r~nY^nR&Be%!n&l1rG)Y^E$a^He)Z>=B?j4 zLZ0U4uns?^k+>vSDbvV>H8zb5Ga+ZGob z+PfOSriTr0Hrm$%ZN)aLOB1MZ6*)o@y{0CY4wBT7I;r%atT$Iz&h49lr{ zT3rXV|8zXh`6=Q6nB1K5J%X+buuDL2mT4^{&o-bQ3J?GQ002UP_y=zVwi5s0EKWGO z_E55Aqr-Zvfo= zf+s@S)ZGqQ@@1Ce)E~&Yi9snEpUIlJlqESVaFl)sR-ZL=$ae^)Kd+s;?0=C-+cB>4 z*v%eOZ^&bamVdPPit04{?kZCPLk4q&gin`q^T%9Ykv|0^$@@*~nE88d{C_{rL<9@6 zZb6uC%$Bx?ZM?0P(WwVQZqj|>yAxny{4#mY`kruNzJKEf;r#Ftd*sBsPSD%Q)A*45~(R4PeD0q|rOKPK^Xi zjcIKiJ_oJnQ@$8oZjP}_KK9|qH~Fo+bE3C3;iN7+j?0-R$qdOX?(y|EKzxBf000P> zv;ZC!>tU6^OkzBoeo1Ezb|-%aG4zydt>buohi@|-?0pDiMMi=ofmoJ~*At;IGA^6H zW&x>0LHYEIS1I zdJ<_0U>VVDlG;`C^P&`Xb9B!n--ZGfnv)~Hrsa8LvAZyaDaVPO(UOQ*!|ydl_jd!B z(stIUGoPs$Tm^QxpXlj$d!6>0GpVjbT?W+-4TTuW3GSH{wx7PA41|9o)1?9WdouJx7j2Qr5^^VgXrCQt^{i8)JQ*DEB;Y3# z>0WLz#BB{=kVM}QKadJOxR{sWE`g9y z=&$>F!-$^Oh`f=wS1{q~myv6fBNl1W=Vj z_Rh50UG*qnrzzmTfjz9x@?C8VcqXz6fm_FbMKew>#!D4De$*{<0ZlZO08{h;AbolL~ z$_qd>Yl9elu@@A_ytv%IVX4MQbqTrM(;Ha12n>pMS!J5EV7$-0v$+f63&_*DV~tl6 zCyg(Y%N}~7#(m`A4cZh{0YHVaYj^q^E6Y6=g7-k)6O5b^;vu+OD2B#%a)+Bk@1{tN ztnf`_M?x$>wW&fT$JN3XLo-i0C|gYbulAU^G)T#rpnOReM=pPcR<^K&0Cj`|CIG33 z#y5kBp{9X42{LdDwMuoWrO`?Vx)!OaooqiIPxj^my`+(Dwav=9m$re!%8lCGm&rU3 zcVM_e)Asz9-ETTciO$|p%K1c!b#_6x)jkV8SDogc!B0aCsyG1BhpX-?3a<3Mepx3Q z)`^2HtOv<`U3YmhC2aDaPMo!{29g4uflM-GX<(kI&kD!B?%i;wp;z&Pbmri)_XaVC zcf=+lmLK8|7s&)o;%2rRmcBO)fIF#%0~r7zjM^08sjfi9xucSqA)%&T+V009QrX{c zL)H%IOHTvPsoKW1zJ3fIugFcKf}Gr3{fey6S}W=j25H3+GRlNmWWroN55nXdW5ANS z8*#Dr-ipN%c0QCR{swKpthBA`Qn(ta&4H1ijz?Sf3!j$|PW2CQ>z*!r)tn?NOD2PgI!a^P#69DO2^%Nnz@o}i>!>VT_W4l zxf*W50087A8Dt>Iy{zmZ%jlV|r0IN?>BH0&z`745U^7E~Zeg}6714kMG3pIegIP!y zUSvz zbQ=TbSz7|22}I8d_=7Q*r8B$186LF3@jwyRW$lj$DHTezvufW6y86ycGf|!Us!qSw zGIiO@WVLZU8f}cFzP5K+!)w}25tpeTSw7H5+t+SiaaLJJy)hIE4b;s)d2ax1YJn5% zVBGyh_&1ujDY-bSP{A69-lO|3*6<^1PwtRCGK#zQB7TB$Nh~gyTen<5j%HubObDcl zHV1~ihn6Cr1QG?;NTb>t_J_AEjm*1Iww-`Q)0RhRl`M6%y06qNm`|_c`XFLJgwUb1 zx2{<|1gNE&>jTdDORsg9*edQ7W8vI!X5X_Z`Ia5F0bX94Los1BvEpaUIUI(*13Zku zY1{IR2ul7zPPFn?`9fEln7b3%ng=h!onK9<>#O5#r{LBd4(b8OqZQ5Gp1Y*5Alw!g zcvE+ArQNTv_FvvF1Kp4ndv~C8COCqc1u{&VooRl*ER6~)K6;N$B{d*#H({OnnU4_d z{%;FA-k=RVK$^ET<5aG2{z9^6u<>tGqx;6IGAQ|ahNl~gtZhU}slY*t>Q07aq;9+j zfiMv<*xmTk;SlpP3C3vqvYouNjG$1hC)_!a!Mg0PyvRS81+}s~mBTadGvoI~_WyWk z4qZssHSYVYshUDttx=(@2LB82RN-Bg_0OR*9*}oIQ?a`YfGo=L17Vz&Q?=&>D&T4r zj)XLi?GO;F8`Pcyeau^b8gl^cmbO72u~2XG2_0lIXzy7&(VXuf!Wb*09Y&YYm^MJF zNr>}_*SClZMEfGX=hvfS^l08qBMEb8OV!Da0!QF6={S3HT*09xu{r%P5kO0ckYio8 z(S@b=3$LaKcf|OPhAt>jiA(?jj%udOkzq@BtmH#T1E?$O5v^6NK6mILj|NsC{f1&u zKPQ8D(Wr{@0CoC4A=EB(21!B~~9t-Ij4zvJIme&B7 zliRX!HZ?C(Ylid)v;fq!pg?E506f1DhFB@OLO6FECe^FJeLy#|a;V`ZakUnmd-_0< zWb~^e%j_|V7Pta-BtQTR-(2m5w3>hfUmtbJ5JV037{Yt9z-laq>+^MwRw`slc`H5> z07?#h6)fI;g;zzHGl<{XxBS%0d4sPPtx}XbHC+r)d~+Ftxfa?!&8gU~=~}b&2tj9K zGk2NAn8k^EGnF}48*pEO%`!ydXr?%Y5|-&&YZspf`+ng zvI{$sT>@BJZPsmH( zCA%c&F$*?~-N~sW@A6;>le>uCH;mThl}G>s%d$=;?+oncG7M>{hU%oFOS0&8joH@C z{(AqM?C!`&;RWG-_hbVtJHx zKLIZ8*2PlKLXL@J?C0q8)xhPrGnT2Ij3O3g#ZSB1_n^({wf^mpvc+X@Btds#F)uzLV;5JxjkUeEDE#mrNvRb(;|E;tl5s>ASk+ z-=Grd-v&Xr{OE~Gn;n%f~8W&bZtoU z8=9O@W|Cu70*W40?K>YZt?<|r_3*6vKeOn%k6T}tft+}+bbg9BIoWskvYw$dR2dEh z-%!+o1Iffg6r6|%CcjY&rF|^$kByoHpKOPA2Qm173(zZi=w=}ckR^2yR!}tC##n1i z^JH6LugJAof}tT~FOG<(f&PHthUMx9a1qMoOv-i+c9ho!BGhR+Y7Y-pPpxkX=SkB>1OxVQjW+>Jfe8eMvhOm zmWEq&xLR+Ilb>Ng1nYdmAM}shDm?eI=`-+!D?kTwcOn|Ngu0z4`Uf)dYuj~pL~nz6 zRD^aAsDWCU?4d7QcxtEoD+iBBAso8>b^d6o!xqxDt=N#U?+SCLBv%=K>cOdKsuXw1 zM{8LUyf3T4ja1G;2qc@rNT*_96nCnZVKw|9e6d7nZ2#d{DAx7ulQXpSA~3Jg z`3bdyE{ehNlh|Fg1cTf{4_Mx^=KD;1e;=H|>kAu?>LhRNe79H=MU`sim9^!ttXzV^ z5<5RXU$jjz>!F+cYSxgibb@h;=0}``HXqEz7K)Wq3CZ#Pc7siGd>lEfj{HHjV-9k# zl2QYJm^V-rWR%gr4rF(wyhqpSR1c}_V;IR5+BN+^IIQf5byB6r_YQ8OGr9&!|9@Wk z6TlyzCC|J8d!8h>Y$xf=w#ZGZrf6h#Q%TIl$nP7+n^_aQIwD}Y5vhZNTIt!S!!T7S z5HHf_9i80o@WXtChZo;d3L6)`f0D3;vn90g1!(Vp@K;ncORqI<*s{#$_bbAiu7NxF z>eppI-_zhP>Z1ZW=i5IR9Pu*zaFKd zTZE2C{deBN^}|X2L?V3;!r@s5cyE>{Mko!$o%RfAD3#@@m#qY%S=awY<@TJOkmtJ& zH2Cbk`Yr$yoWuYj5^NC6Rq3lRH5wn148WqN@5QzG_zkB`O;=}*{VT))5*O$M;l7zpfch6(y)shKQ}k| zvKOqV5eMXj%dzyB9-cQR01~EdKnUs>W569NPqYEMBWB%<>O-Na_Bf)tA9QC(M+Gwh zsE7%C!!EXc;XFmip&zHgbzBW-9Pzsl%jXK9pimncd@wqc?VoOT)04bq6)ZGyr@0Z0lyBv+P^6N3ZO`f_8EUk$C58M60=6=GdfxYeGJC8Y( zyrx>duLw_x^o6Yhpl-WOb!5SY(rSqCU!sM$w0#b{ChpMj@%jh}P!M*aG{g;PHdRAH z6;#p?`h5?fw%rDgx$Nf0-$T-PKbx300)*`ZYu!jhx-#K!hd`1Uzm%#k}VURU4s z6z=>88-~RBmg&w*@D(3zqW4Mf*~c}s=3H?&`E=g?T)?nr4%x-Vu;~~2Gph_-fuisI zH)shG9oz?jIv)|dtN`9sr&NPWBOkxkMKoR8?I+pQ&&egmKg#i=f|Tmd8)Ek(`7Nb9 z4f0MH?E&q9KRWE+lb>=w5GNpBs9%gTfe29Ta6N3LVa_)EtAX)EdJtxp4&~U?vna=3 zKHWgDYNs_Cz~bT5eUK(JMV8e2W2y|VB;^9)w9~P`WNqYY_V~28RSfp&Yy!Q}MRFL~ z)YH$dYF8bXZChJ3Za8r=atn)sGH&fZxr`&-DIAfDZ<8@ffnhf(GZuIO`|0M4Y~X%I z`jGz7`YDqUn9>9Tb_)ZV*C3^I{=IGntKLL1di2}!xe!?PkJiZ#2As!F)14`y-Vb2W z+V?mvb#=G1&XHAfH!VZAz~zH;)k-P~Z};nEY7S#E&{X-&=Rzvt^jt$NeWXe_$C4r!N=GN%q$7yypbGQc90!lyX;6secgs_6kA3P{MfF;KkG_?7QRj+uYa^ zN-m-S08e~VHnhC+O)EZ8Q)PkV(=ztOxU0IPsS9xUGt%CsFKXjZoJnwIWyAZ&lOJ|? z_3Qwu?DC5GP*_7cDpr?h#yq!kQU!@erMLtIr)+$=dZvt7)S= z)UNuV3}-Q&UVz%~L7Er6{|3*7*NMOTKLorSn0t|Vj=Hhy0cH@>zn(td?V*tz@kB5H z2c-;>?MlaU7?^S&p(_|&Uq24g6+y{rWaVw6ydGKLgTEB+j5;Vl4yZDc&FKu)HK_gg z0iFCkajjY7iLOZTZ&whGJoLvR zMd!Cb!2u4yICr>LNr|-gl5giOrIo7U93~}%J-N+a?iEVr!(CO1EEd~j3`l9! zcV7*44K2`!N3(YirPIS@E*JQ%e3w{O&y&IsgjMHR0FD}Cg@+iC`39+%6Y>U_qlE@FgqDn@ERFL!ov^U{&&@gN28t>mEt3cXZ9`!^7sb3i^(-eJh zg|AW$WDdsG^vOJVLWNEQZ|)uwpd?z3s9Fg5WJzj_4C)Oqa75}_5-e{BZgFlPK?y<} zYdvXS;mzT!EqJsA{)Laiu%d}DAWvxKVhd`fLLVzU`SuOe<~ z^;i;J%n*)5sfdZa-%_)FznhV?PN$U+7|6Q?^T_gV`Jy+#2=U ze=lEs_b<6-6A&^gH{IMV31%`U$H zwJIn5qhlx_Ubu=r&7d^^dTj}twPa-+fB*qUKzt>1oYUZIgw<}6ZHid*0vt;H@KLHy zkZi4{HIlTFzewdOfQ^S?*veCyAFGm+rXlvc`DEtvIl0!TPtrC>%g9w-E`*El~2y_b;eQILs7O<`DoHs=^qfjG&f*@Ac{*QO`qR(ZZo|odJmM&zHzB7i)$O51k1QQ1zNCSg9?Xkiq)`-`wvsW zpKC3TGxGk>S2uh)OwyU=_k6w_6G8M4VHrs50=HE*GVQ)`O`sO)CMfN(7|*~{Y4J=D zrkA)YCM6`^9>#Z6^GvwmEYX?c+?7#NJ!T6!ha^U}U4WR{($ zbH^Jq-@ha(wn7VS$%{gqb|rU&+IoOlkj;~Q2-Q8K7}=SY+i?It5*Dou+_9rltPCBG_#|3&e zqVc}gMfUK><_I2rlHDmDD3O#u(sU|oe2)ZYx3G3#k zHtbmogc9N_SB!in=fmoRUqyIY>5J&WV%yC%UM0zR9_UK_2nj9w*0OVX_7p3dfI9pYp6NTq7&yb{Q-3XVpEbI$#RD`$O@y`)Q){8uV+JR zi12xG8>eD1ge?*g?T5XgWHUeJ<>-uckEs;Wrt0o8X6e0yV8N-)E_qJ{(Li7b#KMGf zC4yK!$iYg&zw04X+>miR6#q&-5BuaZ5p4GjRS!ZF5sQUdMerKTE5ly%n@CT+0css` z$*X>pXb&3h5l+nLhB{M10&rx@iN9zk8Q|}|BVM_ggP7%`SPe|Y0AB(*A>d|okq=Xk zH?44odcPrp5*vBU+o^W+SrU){j=8)6E}{5=MYmf7SSx6y_TZclw0RFsv?A-Bx+$Vi zwy7fh$9qYHDV`iCM_t0G_9SaTC2Xa&c*N$&qCL9MsU48k4?T zG5ba(sL3~0QGj38B+MmUMiMXIdmHcq&H(@mlO7|o1j}y zaG`eOW7MwS^Dn2x3hVhC3(flLL5?PNsyY5jp#qHt^{_{ex-3z^j4alB1&y&9H15{mw8k`kfo?q>hp~!e+hk zn7(1ACp?!Ew)L&oEQ@Sh?axr>Z>=yXl3#J*3WoyaUXb_bLXT$O*j zHB2$XHit=i)U&q}(C&b9YMKBYG76^QSaqH!HV|B$6_$oxXkrM+>PLC;0qwueHki#= z$_GUJTMS8XVlJHgO=05C7c@C*B_DVI6G)rW^qsBtO|2QeZ*s5xoE)?wC$gZ3n!3E* z)7_^+LOjtB6qI|e*FA#(qB;(--_Nbif8=Qwt7OrQ>cupngu1AkeLBUGdtAD!eJild{KTdSIp4a=ABzq}?0|L~orr#k78VEjUb}q*5^5>}|=;OpSXu ziDvQq;L&g5A^hWKZi^~asgZqbxSUw>#u(ta1t$()m^V`9a41v~LPnqmSS<%zGLUvM z@c49vc2L-Fxgq|w(_@0D6yH?Oa@M@B`bBhrN)BCF5KE12?G5SNkO$&)DMa=fb+`|9n{;t=^JH@7q_&itXQ7%V*yH>^ppEwwW= z^U~y$^uX4@P6Od;Mi_O-^D|o=j=73zcQ#N;kK2W9)=i{1vWRQ3UByR;*a5cGOUF0) z4TN`v{ytC6ruzrHhzc$Id48-C`7E7(Iu#JPKlh>(8H|Fxf9hBO`uZoPNaa=e(NW?c z%guOw76dywQCmZKsZyDSHw^&u3=eUbu?1hIvLT8X=L}a9um$n$-`sFbLJalDt+1j` zZZdv3_LZ5zi_1RRUI|thG1TWxm=-D=e`t{RA7PCH&x>qd(kId<$Yq5pJ9Q^#V#~HY z#oP!A)5~O_lm^+X>*=7W#m>b-d(nFEN(OZR+=jnwS9U_9wd4b0ve0)@Adz>_4Pny1-pn@DB^g2=y`YYah5Pxv zo7Qhl$}`6&H2o`#=G!IFKt1#`NqMAT={t5T57`%5C~v6Iiab#nL2OA^gywyx<5{cZ z-~nGyvGG*>uUD4deGfkHcj*# z=BQ3BJ_9*#P8^vHbSvf0)PNGms=B5y@4{Q$bV(HI^?=vONgkmlYV?%eP(?VT=r@ zSHdSPnu2&y#s*!QIG&K4MSu*Zm@G5k6X7A)6M9V`bp9@df)gPOwll+}$AFaSg>%mi zUcK%M6W+HXf)>UD33f6O48=DPq|etYap7&&pJ$c0HT_z*<6drwMGIH!#4Klj%a`>a z-OoK5027>_hEfa7*o&|q{HZ>Pt`)N4vA@6F-&e=U|0kS~D!=pt@;|IsCy?dGQ|8h~ zAxP`qsxqW=r%4yjU2?l^JpCEje?~L-Tx_Op z4>}Wnkmo8bSq?t#|F@G#NOB&iMBk842%zCf^_eLA=wtwdBJHyGbxI1AECZ9A4)@>mivcqnVzF>k-&cAS}shEfJ>{ z!mnc>1-utIK}7+wi*JtU$#96=D;cYqna60_t9z|A?!3cdgeHmv?K^&Q>UqZM#0rMG zjWkV!q|?z)jba}_(@kW|w_RX)EUT=w8q~fBQ~^t>{QL90ZrA0m-g5N~JFdgL@9WQ1 z64y|p9~b~esga^T7KJN7FjsR5!k@$tR$bEaPpXPRRq;VMn0m&M9HS%sBEEb8p3Vg z&j{2GXC^H58zf8wP`JitX&2{@Q`^X%_FKGdQ-yy2r~qJ@x_5knr(`_wngYdQnS~l- zP(=K0s2KL;tS3(e;~^%=GtE?emp0YP7tkwcfAp(h>SI~=k30p2q?l~+H8!`)gd;E0 z{JQcB$vMxLSRRus@2tJqSgc*%Fm(ECe1sK+qr2k*e?;ycuqH?3p7QNz|1VR+Jr_{q z@-j>g!*uuQ))*I(M_CNlBWuG9fpmi(D_`OfD!x_%U3;&?KoC}aKV&5HqEI=scr`n! zq5t#ADyv6RYTiY;gZ`esjOu01mEVI4wI1f*R|l}xlH{)Oflfe69wEjv;Czto<&}gC zs0qNj0H#EgNX_*yW$2%nM|I&QgBlZoK_Io{r@3E7UzUaRQxvN-4np@)O%wpl7QLHX zwE~k1a|{t61mo&d$_U+&=>zxt%ODImOM#jSMw2wZQpAoe=f4ZO zQunGH%OJOeb*TZXVE;kWL}TIHrQ3ws|-A7+cdrVyQ|YpCyQUQ?S-x^8+;1zB6rabSkt{W7Sbvpcp$ z&a%Hqa6YfCN#opJ1tqAq{17`0?!@mnoO{l$cAnK2$2s&|3^pZ8po}2zvbKK*8|)$7 zZQVn9XK0g@+)94IN?`p6VfTxEB-wl+=^upVTV}rr0Lbt7{wW&0Znw3oE1dZKsT0kc zP)q$7HDxa2P~{GNL#YjE7uKwWAq%vk#r(N6n>T{V*)@@3gNZaHX0;|nm>-TFTOt+5 zhjmZzY0o9RN1)SW(!(1`tRJf5ijS*s1ZduNraau}WmFfi3`{06J^KyMBXf!_?nENl z`z(DbX5h=5cAlx`$kLK6xXt2<5p5JOgY+Td9CuXH1rlkg2g>wM6>e|tW2Vm*gjOr4c{Cw9WLxqz6Bbl^20o}uU$n6)IAWnJK8 zPcXsV0m!fOnO=4^?bX5g-pE=U=nPebHO3quMOP67^S$C6b*_!c$p%VvYcGg~b7v0&cpY672a5 zKh7=kMveSX)9x~F(mMTbatUu*#3>5l37rzr69n-BFcTs$0~~Ir6r5Emdf_?g1N(ub zS|`E$u9$UQ}V79g2tSzpzn}G_8gQxnMj`BC6 z6zt!B>FvKI-6oGz?l6D!(!Z1=#~#>Za!7_+a{v))kCOqlOpPToPfIvx5M9{o%P}j| zkt;t1iFp#sjukDkMZPK(=)B_kc?_7;$F^arNiCnHBt0t*t#MY|NpQu5a1IIbHk{AN zjUC3KK6?S`UTFcUZpcm`0I$#X3kEo9@|$Wuh!{6a4t} zOjv1u8tv>L@~@%7vSYU#<4Mb=D4gmks!)Sofvx~lfPe_8gv8g9Q9rPWQefpZm_-Ch zn7yE2gp)QM|LT+|WuDIG6ZJgH{Y^HO51L7j9PHDovTs{2ih)n;0@zbbGH8e@0!8Z= zKJe)(+pk*lg=#rMx4poo7dOgBw%nmqtXY;VBvSgdf$S9b7H<(7p^={yiy*w*V)D0G zq@IZc2i(M*um(c_pjvQj7w>aM6mb;w6 zjQ<)Gf-%d?=SfUTlpHQaDXRS=s{Tgk4}u6JlWQ?dnCMzlQ((A#CC@3B)Ez{ek$^m1 zJEE?|2r0M+93)ZZ7XGv(#^@>22il1OHt`1yu!4UNkUOEDsCPU70%C$8XnU7>FQww^ zW=GwJ6hC(8J}Zkm^KjRk;8iZs!a8}~zyPAUjpB#Fe8Sn0W+hN%N;a^IxMZTRG~yX- zItL=L{MK9#I3GQesaFG~wk&;p&=}1-91h6xM$}!tgf>ry`8$Le5lh-~LW|A|^Tp{f zq*!MSH%(=bS;aROG}{QlpxKNr_C)>>kC;QiOuDMBy)W^9%&n>0XLQI3wA%u^r!367 zS8z7Jh@ES~fr*baiQHXMCb%JJ`BCfC=J}*iRW>vN5+9yhg)gXg*i&@OKW{S|#2(YR z?CJBqRYxIYaNQG@S3JZ)d^J(R1qn5jkHasimWV3i98j_H1+{+DA#Cj^c3rY?qjcwI z=4Q?o44a+K7JT8wj72G_y z4A0v91hXqtzp|`kfk?V5ji6R4-4DuE5Zti6=8?IqIegt@MbZ}sDfoW9ixQUT@c7CQ zjT|5&s&KrksVYUP2yQnBWSw&WAkR;FZ!8h{Y^4b@~36ow1hcUi+|vH{M8Tr71=PWDocD#yHZJuHlNE;By8*B1V= zuzXSeV00(J?#XIyi)1KO&<6!8<)!@3apv^F=Y;EhH6XTf8o(2M01{s)wrK&therX? za-P4E+R4=cRiuTU>Ab53mJ;Kd)X@*#2_}d(!5RL=aw|kN^vBuZfllEEz&6AW{s2Wx zr&ai8PE9Lb!@863SbHVV@(p9;r0J(5-iS{g@q=!g)@qOP?H9&~0{s5B7mfMr=dm*z z@#z=UI|=w1!|Kx^mBM5v2rx9j%}H1e_{iZUDukJ;LrmJ-0p=K^M?vBDxT|yz)R-@M z#Phb`^&>o!jt#FZV5ed12VXwR@LF+e*8r(_! z+VTC@E8OhuQ7kRFRwUfbrd{-{{2SMTNKQjrl4di27ZmFB;M{;@U|1S6HRE0)?(2dX z6Dh*HEr?t7=$k{dnp+mqerb5wlJK$>PT&JNj++N@sG8a928ilWdMt~c9`V7U9bVBqxMzS>7=guo@=4VG@Vxbd*T68>HRA4C8ddLDKriPcLYz(pM>UIUe_6xY%u|JhU- zjAB`}1^2HlXka78_{#-|$ovs+zy=cnNeq;Uo!srJH8DD)@-(c6$9_pcw*L^+_4J@==Oc!@sc(r+0^MfM1gv9bhZHm|BKzI6=g=>4m*C zl`*`SlTmJF`hw1_0c>RE>+W!D7%&u@^(x;$k?@hP)?A=fvjkL-oZ_qtZey~$QZ1k1> ztE_90LJe@}8yw1W=f#ki_c1#HyCHjLWs%HDi5=(rgvH{1*RQ1KiH9jk@$1_fKq9^q zMTjX^hWK09aMo4dW(yPkU^oW@|9o=i(zHfqUeHoaDGE-Aq0}HD%2ItbCuaOtoqxj; zV;_sa>dK$nWU%aK0FQXIx!l6eFMFLE?hNH}gu&)A^f^qWE*ec1r}@_?NLn}|v4Xoc zb2h9fY-z(XfG&z5=i`6K00FsZ1i5`7f)#q&DJ46VAw4uPlHSOTCb=mXzTXNJTR^p` z=xxA=G7{QE_XffkMCJ9*c9`n4;2%twz`G@Tk+#wq=T!@!^g z9^ysm)l~mpfLYp`%^l4U{pA3okI54|0)zpO#z^KCd}@(%;_vX*D=X#J#+CD%ihrF0 z(^s8mmjDpiPFC~NULnVOSZUcpijZzRx&yvOOLXwoL6_dsoneI&R9)*gF%jNF=6h(2 ztv4WNcwueV=ix7)Blyn1-kEr$nM{vnU&>qFATc%O(yNGR{jaYv_RyrVIYRhXA~moW zN_p+U?n03oax25Md~PI0btn&~&uY*>L+xj%cblS{roYHJUk$eLGcP==TVY&)^?l=I zZr#gXgD5WbV0I~%9#=tw{nA06J!#KB>>Ly=-p8mvV8>fZzNN9h;7=$^kjr!t$rlD6^v^U>B_qD5*p@+wU~j% ze>fuYF{wnZnw0apeNl?%yNgVG$K&A0*#9e$BkL_e4`?!RkiVVq+!S5Fb=O@dpP$== z1g3<2z2Rj^{@Z$fX-@F(Qqm!|W6A0lfdu{N;*9u4v9XM-2I;+?Q*c;+<+N$c_|C|) z@+m;DL}pxlhOEU$-8h_rBP|0D}Ji0z;*J`&OA<^*Yu>V@|Us#5^e>=?$9ZwE+nKGp3=C?)ciQcN|)o zYNJ$|Y)|R?+`JOB89@_SFuvCxvGClJ{VzrCF>c z2&EQ`de|>C_Wm22oI&0J-c3KX>75*Ly)P!Jx@Tzv@77`9@5fToKoKOEp}>{b zBztsvaO9skUP6rQ1f*}yW-Ae3%l%LwBG|C^)gu4^6II7i#}DcTrBQYLdyBfY!2q66 z0Zjk}fy>m548X8vpH+5I#f2)bu9zAKWKqw~q}?#<_FO@3R`oAVI|9lTW?)<--guYl za=U3}dnwUb?XY)h9E7)W9y#jr3bj5=UV1_?iaxvCz^>Jp}Y0YwIiL zF(CuB6Sqmn-t9aV5ent$NO-7D9oL22_ZCZQ3lB)_j zl6i8iS&LbZ;+>hxUrh@t5x(ag`;EY9&hBqZAAnqKyP7_o6?791^1Xp6K`5);Adz@o z{b4@9o9Dnf47O1al8!(5Up*d;5D`Mfr#C!uv-j}24AaVzQ7AJ-Ie-0xh^nBYugP@GQTaymg)E39t4mj6vnO_tu&DC3;zn8{H`B@Eq1pI9% zPgUXOT+C_jN6T-Dv0JP`U|-s50cT)|hIgTeZG8n;6+zekUb?%xyE~;zQaYqNr9nES zLs~*YkPhhv=>`#$5Tv`M^S}DO`hCy${O3M<=f{~dXU?2+c4pbVJF^)bnve}iasCKx zP(AgUzlNvtOs5lHz_f8)sex>=kVmz4iGv`wtWxl~>AGVH3IAJ%IkiuPb3|7{TWCm! z$kN17@=TudVTOV_zqUFj(Hy=}O~kq*AJM{F5~6zfU{aUCTdvK~i{@inZ1(zn$5he0 zot+biW!5aogj(hGbZHiOrAP-KzsGB37_uFTnR34G&cbC@18d!udeiF*{XXod0lQvAIjA3=u11Z~#J zw;V?AG>oe5LvG_LE7MtBOhwkQgzujlci~NNUI}TWVC{-*z>&TuW{MfrWssTZXj-T* z4y}1bblg@W!f@Fo(&JoNixs-Lse+ZgBG!17^A=yQ^5a+3%ue~(?v*TSJOHUAu<)Z* zK+de#SortejgpSxQrMRFX&FCI0v$Wyey!x_wCEWda^}Z6YLk&GJc!T5BC~eX3UTTX zVM?XB8W1Q$*~nq&&RwKcm9pH<|r)JBC0hHdKWTOGaGQE#@_E z$wW|89x~J>GTU{*^NkRiMKf?=hVd)18WCP;5=RCsZ@rCQUvoS0l7NMh6w>&clM4MX z8WA#0*F{9l0D{I!Cc_wm!a{f%ot6S^&VBWAF+w|WrpOmInBOHoEs44mKt0!2Z^|q#Dw1W6~YDT;LXtpJlXV(QImqT_lP62Tqisaf2$g&hCBK=bsL`c5&1_FY$jpT;o1k z&Hr$L!SrNT=~|0v$cfntoPQkdFG;62q_&JhUeq{_=zi<|ijPlTaqw6d9q!?Yk*pKu zK75BGZC;}3Lg?lm<8zs~i^}0n7UXAM_x6%>6KZj7QaES6ceqhhA*6_Uj-9fpXTP!} zSaX6fRj8A3^D{M@${b^)*YW1(fo** zl_;yWC=zX?0>E`YYp8oAFJk&+!`6`C=FG&s1;(@rtnU%(Kd(|T8c2Uwj|7C`l!ZpW z5T+BCZOw&al3C85FO=ZY$Typ(0T|7u`ORU>?ARr0LNgz<5_e8!6~l;e$?8(n6I2=M zdd_e+ezNFpHHgRtSTc3gG&$x)rHZ1Fg|1;imRJj`?_9$r--EyJe(Rn&zw763#rk89 z;obt{1bMlB8#Q$nQJVnN*O%;$o>y_th-M7O1d!u#1`*Z`o&@|r=Zw# z17RKhPnAVO>F<;K*MFd8@i7Gn_sp@dCu_Rl!v|`|Gz+F3<@s7>VkIzzjhv#LIpI%e z-jz05jjBgWe&&9Ru_mvvdl40Zn1lE3K6N9uqwy>#Tc!0tdzV?iW54FTa8R->kzfyG z>D4p8!qt~swCzlBRi3>Dm@cFJlXi5-h$Np?=;OFwia3pr5Mj24GMW1=`NVrKUDdzZ za%4^1#__#_!7t=R45|WGC~vLGiolC5jnxqkjhu@v9R7gY8L}zFwS^*Ku z7W@es-D3`3Gu(60UeV#xnWzzj*$=tXKjJOUN_Nf2Di9J1 zU!1(7`a+=NDMmYwRi~dR(fed=8ryaBc6g(BwBgyUBTfOLW$#B;1Y8`WXp_wYLPQF9 zOQ<%nh)eXiFVhHnX1v}U=Gw6b#pr0$eduO*g>KJn@Q$cQJtb33A{NP+sBLvEy=}r@D8#UvXA+>Yt zIVg6tB8^Z&&yg|xNJs6DdyslEFn`#&I9T{@$)x2I>iva5)ohJuLHcR=M$x@9jtRJuh`ytpfG=8m7K0E($0Lo zh8os1n_e;LfE>}x?Y8o6Id|yPpa0(KvsGMp`0nzDE8OO>lglbI{ROP3w@Vx+?~cZ% zgG(ROIB%8wIl6f3I8XeGXIl$qA;rZ7lF!Xo&UBI(ybdy8{3l`0Gw=iomZwp84Dm8- zX9doL6*Tc+_=n^>wr+wCxBP@+mkibPO3C|eOQ!1A-d|McR}RE|_-OWIg|YY)8vRj) z@caj>WVL)8C8e-0)4QsU$4N(vPg(HHotCI+XwAXC$(CA$vQbKo-Vh3Z1s%ecfIf9& z0oODfpzT{d^Hx%-NlMty!d%XC?u6hb(yvNmJ#ZsE{+mi@xJB57SbueziH=`gjODOdiIS%O#^1Hi+5 z_myN=S)#V?Tg;_AGG~ZL-^s}+E)5+bW|Qb3>AOA4CPJG^)^x-Soey%aSds~p?ma3Q zrU%xMbb25#RZ|xI4QjzGUR`u=*YsH6d8CwBZ8GQDzl!y+(h$Q~(b%Y4c5j=r@kN$nSNWOHU4j2N_3xD3~JWpMpaQh5^9wjesD|MJL1{VKIH za;=5MhPvtla)`*;7P?*9sSQMHHj=0EXV}r3A+L6+`J0=zlb|+eCt_YRJh4#~=(IL9 z_XB34-9h1mXlPy|Ga1k8u+N@|Sz@OAdm|4ut%Aa73 zx@2BXHmT>d#dl|goECSR#)Jz6+oH?-`tZ8MaZNOvrOcII#Rwpav{pEZR4#1Mcethg z#4*692L{ z*(j&;n8#~>;t9SPu5p3@g0hLIQ}ND20P!(ZaFl|OIxfAVm)v*-uOeM8Q+MMhp_gu? zk^U*2qxZCyz%m}+$}^Y|cDf(T!P6`J4LtU&^>dpl6f|SS=>}D4@S6=reENsWAr~_G z)5~RtSg+h5--{j$MfYDUS0dV1Z!D2V?>!_CRX+^oTt75(Fm*w`bPfTWJvLiZJ;8_I4elb z#o{0x6J;9cK>4+mQw6PV5E$x~`$X6SF~QA(G&$s7=y5Y|Ac+TR#JRI`d%e`rTV+gGuXV3cbz*HzC?A*No)?|&bs2C+k;@k*W;llVVr+c+~D{p=2xJF$ElNpVN zWUd~gt@oxd72#`nx*>v6#s1~BfM;1mz5?*X!f{@Xte%jAFelvFZMSSHTu0J$rRFTC zu3|-+NcEl$QZqAHY+^as5n6^cIY0kek;#f&z__pOdP^XkYMJ63dhjtH++eyq3TZW= z^sHVAi|?&@GZjY0A74>m{KV#^fI;1i_K?n-+1Q6yMQhU%j?O17 zcOn~ZGLu>-${5)`BZ7t1Ul8}`i>&Zx<|7_^iHGz8XnMB7;=-OQv;>g!BJe2VLbjlw&%6nI+ zHRj`7qkWPD+~;Cu3AK>&NHr;O;CnmS*_&}^sD z%a795ZmC3&ieQ+^Lzk>DEg>B#LFVdxj{Xj&N@!lBS*uc8_3pPzgpJfTS>bN<1&i9n z88BI!*tYe^!E^wT*4jdF%@1UzyJfG}ZHWH$*dHL@RU;c0EoGJ*(Vf{SNJPg3vSRUe zW2J@OtdL2W3WwAZIumN-Gat)hh2KHu6gDeXm~XC^@N6{b3Gc>2w1+>#XzNJe9Q5TG znEc|N9O4^y>Uf|ySLwMCerA+7;nl{&DFTDFiT&Zl-FKmvS4`IKNU1_HLs{6U;I?Fe zZCe8gf*I-IyD3j3+Ii@$US-Y6Zucs-byzK32fjLazG1fRSLqle0>YyXih9t_XR;32GEg?98FwFqj4FpFZ^q#S@;2c z_!Xm$nnB|Ve41ZD`ec~(v(jYaX9>4Hwgm}kv6+u4jO-6?&Tfv_GPg(Vzf>0@3Ca}! zf|Wu&dIoq?w9xoD1CN5G^w5Z>GQbN!+NcX_$5l^j78qtWLEqq zCjMp2*6XemL{f*Xo1;FMU=S@biHBHN z_n6k&kU%{xUS#qey?7Bkl!9Hr96rP6WQ~q4B{FZpm#2(W@VAP(&}j@%*AQLHw@w$fL;Y3~m3^%`f5JOa7F$ zk>g^O2L6V?gs73Z@k{G55#@LD56brAi_XZV<0Wegz>{7y0;iy)6g@T|xqLKX*c_|~ zMG@MdZmEm$K&dN^O6NyW0c`)E^t*pZ71O5(8zG|7#b{8)7qT}NwP^ISQn|4yu%eZH zUKX##bj_$~dN;J?x1qti0rnjaz9YG4z@)V!9q{WJI%h;4vc~w>&?1g?g$xR62A62?^l;Cccs>oBY+h z=z0s6u@Q}o{}Q9myfVRxGkvZDRaTJ3=3e&IY+=N+7vD>sHCA*+`Ln%##xh!~n0WU3 zi=`pnH?4LRWvrsx&54Co~14vM6Y6>~G?_nAySHogm1A>@WNh8Ab1~f~2WSB{+2lD-D08~JT2FC4t z`=N#mjc`_S;rk|4Lg*sPH zb#=qPK1ai^EBeGNwf(tov{8c=qp(qW0wSq_iBhS1Pi}tScRfxQ!bbSQ1_vCF_@#&N ziNbemH_s_p#Z)cO!+Yxi{`6#Bhj-74#bzufUx}_HzR&uK6(HB0RszRSmv^J_(S5yr zH`!%q*0aJ+vk{_AWXDAr={KOJl!&#O(T8N4(T&;r z$w$cj@Ckyhc}#5EaEK0f@g3<$%t^5Av>?J-2P#J>b#jB@(0Q1lQOV;W0C2fas>3Ru z8F$gqwkf;VpI7{8i5+eXULUHWxOCW{rZ8(q)@%LFiH_J_q$m1WkZl2vL zxir$nD?G}cB-Vnczh(r#BM`oPFG27cX5on|KgzgUYLlo;SMq4%A#TEpS`Bw#h$f|KnQQ&_&UL#d(MrJY$kqDkY7$+5nGhwglu_NNQ?Qou(( ztJ9Ndl`lY>PpwBc*-Z^l;c%^@k=yPbF^p_tL09lUaMX+=NNDvMr23+>jSGA{?NpVi z|0IAY83awU^ZLH$OT!s~4l-`r)SI{E`fy0UAp2ijn^Be!DDgEGbU8wmhb>QQ~`@l$#IHM^4v3 z8=I|-2F1^{W(=;s4oJt5U~~D7b6f^|Esu_0GT$=fBWrB0TA|9b^0F+uV;#k=HsD9< zrDM@1H?8b6XSh=cE>#Z*9vDo=8aD1h^yvfc+{ccgvNd+!8xp4%9(Ji4jL48EHo`63k%@+iqVnHic={e&|9cG29(ls&Al3od3#w1S54 zl!JM>h_6jXPq1|G_Hyabz+7iyVkX>y;QA8RVw9vW3rb%VcHYvM*ZZqmX@0)}6ux0Z z)`>0)kY6Oi<~nXgljd4l&~pVpir3af+T{86@Q3Qnz@W`}GojS@_g!x`=?ZVGeHAfR zj#?$Y4DJS$VJg~Z`Zdb=n;&hJq$0>krN+|wKWq61)8Uu$GH;g^UNH-D>`-&5=$Y7~ z@mOeaQpMQw2f&ED@<0;`bU-XE#g|2bDxD9ZL`Y>=X*6DxL?UW>f)YE zP355#--zDOQw@X}IQVu{M`Ap)+D!~H;PgQ5_HCRbNP?a$PPsFlZSxKv2$FF*Zr7EH zJWN-_FYYG!7LjCvPM0+=T3+rHp6uL|>cLWT7H}FA?c$f_N(0TuvFQ>7 zD(QTB$*o=GMv|I0mdsY#&+Ck4{LFb1h7|`5!Uh|k5bz4-hgs`}GRy7;fnKcYtB&C$ z1x0doN4t2TNcWL^Q=d^?9ZjLtrH8iC^VHVNS7N=mSq6CArTpF9ID+`{Z{l9)Xj4`@ zKIwYR<#!Qx^D*$gWQZHlEvTe(YnXu1u}WplVrvI~kSjD9GBW_9?8^7YCGRvhl;)7@vb# zxMtNXe=lnd&k6gKGm--5)IIT1cgEEP(#zrP7D+EMSJ4DZP$X6yM zJ;}9q28c4m->p4Y9Z?SYEUU4dfRLlW66v>V*Hb@_l&iOFnl3E??Zm_+OA9Fv`8{W$ zVG-suPtpW;T@-(_5XlX}9@==Kr2P~c!$AJxjX3t#3*sm-3%1qGpBd_qs1OP^hFlN* z)u?ao(1w+DkgtDY)$@<&qn62VABgwvBFtD9dUdz&koBm%=xQ@15M;j82{bshb$ma? zxk4DVSFhig;^VzsmwUkgSMDFJbl+!d$D6MYtAr)rb7XA}Umv+!CizZCE2@kCr)(pD6w% zMdsMe;A=#VsFo>$jVnel-$IL3BEtusg|XkpZ05#HMX}Z}?4$&x97C%E=F6M+kCmmn2;-3;0x3O^|uQ*;sLVl1qV)ZJ{NzZ(Djx zCw8|JrTqBjrt?BO2Y=b(&{g228^RqsjH$`xjV`tXQuMDTHIO~%!KI3!$zQ$f#wxw3 zWk4qiEhDHS<4?IHrzDs1;7V*!4*>**)nj9}!sHjTI*dgn?wdK`Kif$o{R}JQhk5hk zLC~&0?nS7;&cxQ6W#kivvQ4S_jwbC7Tdui36!Se@D2|Q&mKwC+*4yV*CWl{cP_WBE z7)3KU#cQyHg3n`+Ukiqhn7LEyQ_2>GCJZ5dR(}qAH!KqnN{)}uhI}cOO^G%CymzKB z&%nz;Teaqwez??a-2$>dzx4najpys~B$kH;32{8s;XM=YyAH)}l<8_Wb1p${XbaDQ zIxN$Co{sNtnYEKJ`_Lq#9~GKteHh6QXQgY!;DcVK|6Gw4ZPEQ!+`9Vd(%8dt+Pw?#Wfg*NTp@${`S zn+F<4lJix5eZ2wnLnwPrp`RZy(Ry$8WJC&mB=Nb&wH&&G8Im^cT0Z(j!zb@e$1LZ) z7Gt;O5ZNyA$NEJeu(ADywUS?V(S#!0F+tvBFu_3^qZ=O}e^&;3PtQ>Xqmz1x(=b)^ zI3s;-G}GbH6|k{*7_pv68BA@FZtbz`a98yYYgpx{cAzI%5h$sW@-)1ujDb( z6uFyCWu9N8WI{t;ba=IQT;Nl}dV5i59Oc3{dTG7)?i7WClT%9n^!SuK%YJJ6ZV0NL z=nB@%Dhey0-g7ltw7P_iyt+OCvK^_gC$hm}Uke|o8pIqEtZDhR-bIgUB0SanR(dF! zk@0%;g8Wn+gOKK$VaE6NG)}Xk*PF@O%3M4Qua@6A%G8tgTZH9JK~LJeh*ImR%{?Lb zkP{V(?tnka0RG9Y)O*3IB19{>c|q;tVA4yu??Y^nJ!TqhXTHF0E3V@6 zrY3jWVXCInsuOE9V|+%O9f1gW_oNepPAjy5SuF4>X?1^agDRBk)29*y${TmOegVZP zc3GV}_Ss6tAOSeD>>}aDxS-}{G#2||8ILaeeGP|9J%s7d?`9U-7tctpr=EREPoUeC z7>p{I?f1td@Ehf-lRh8>1jXT|<;vQwdl@f3G>b!qywc;cv;y<=LKhW(P?K+Dew5L( z`Fe0Igj}+-ZND@%z${_7oeJ;lLdv>POpL7qnT&ih0cZZ?BgZ}>*F~@!lQ-v8!N@W( zJ*;Fv<*sYJkSNU{j7^R-M8?LU%fR2oR#)0(7*dL({ch@LBIj8Dou#j)V)CKAL2YyP zdDgj?U!Jg-|5QXJ%Vbl6oBBbfRtoD>G>2r~aiC2EcM^j6{F@~8Ro6_G36!KzZt%Cd zqudOldL$V8^b-6hf^}4E%hi{b-pN=f(7PGx$mdNAJtAEKcC^GTKB=mKC(rjNVw{&m z-KTUVDS<#w;;6u;2^yat9;dnuBXp-qJcVM1Wt`|u}WykMH;7FW#7>gugfq@A+{hP_GKof3CHshW^xVY=sdW! zohBpWML|Az8wTc{Yd*i@y#S++!atJe>S9>e3QFg*%)>rW`BB@xozvL0NKkN~?-uRV zTjg-ME^b@NRZPo%r>1QvX1}AFwbr!k^oCHM)zZC9j(r6m;K~nF;;x ztFUOwruqt;YSU4%QkG7V%R?5bS(@Fa?wStvf}|qWsC4i1ik;>dnVPT$d}O}i2%wW- zX1|-BJ+XC?+BUsR{+OBuT)j~FXFRW%i)=S;T69G$ zontXg*wUFVH}Vy+zmms@DF-axaisw3k~Sz1^dV5Drf;PJScVO_ zrS^3(4?mhCk9olK6S@TW#Ym49_q7^hY&buJ!GAS&;M{IB`?O=b8}2~8Ha;y$>zrN{3qyNDSr>t!807UPd{c+t_G-!6 zgORUxGn?)itNgcT;0@0;D&e5u@6j!Co3XGGn%5hMQHRGu-lx<(+Xoq2ghS^rY+rX5 zdKfdwh%d+|imyK@e^qZr`{mR#$i^j3HF5cqLD0&`YJuPLGTK)9*%uxp=m0Y4X4Y#@ zEiC)aQevjsu1k@oMC@A!%cV%7yiit!E0|mT$jfK@eE9s>S%X1LV-z%p4T%g+oJBzw zjtm#MZPmoq*?7wtO}4_<s)-_%1(oiHw)SupclatfN_+d;`~MyXn~1W{}^1{zA*u zoBl)A>(K?`jcn5`qCkH6e$f|DG#U_h{Z#wfb^n==jFkh|sX_824zwNH%y3Md)*|`W z?9P@oFD}`&jFR4?K@c=kO1FY|=1eHhIv&y_-Cu>viTWKP1a4JR=G(BU3JLb+4Dg}1 z!p}X1RLgfn+id4W)BQ@faJhRQQycK6yQ9bnK4>K>&7*0}qx`+CB!iDLiZSQQVI-){ z+JVhYndwP``=pmnd_S2OoOI-CL&8+hKVv8q+jhy9H<8S^N_t^dd=Ow@$Ff^a-OVVr zHg+l;K`2l=5rX}Nkn|v-Qe-YC;JC0|Jk`K4_VNq8v73CYBS?U6~d)1YkQx#e5rn=xoV zh7DP|0``}0NB#9jUxNQB$ohmluR_z*>3gA5>RTi3=Kduz4Ux@woLl*^AFW|$c4uMk zFdL)4kW=+y<%qoLG1Es{@_DK>6w;zY%+Hs4xRqPijXr|M7p?tkemB*V<0hO9n2~n-iljh!!?t$_Q<`XK41uc!QpM-tjvVTVN?`*o;5oFiVOen!2jgkK7=K?>A64 z1il`$BM)7O^iUdAfp zAJ0W#%Zx0)T2CW^-8Dd?&{KG3jXChUl#koS%O{PtxNT$pn)I{E69*jPAc64+|YtLktiJx zMoXHy%wk^vuql&}$d`OEO{$H-nX$Z^m8)ojha>nUGIdJoJ;QXNJzb6z%K-EtL z&p}cf`?;p!#u#>Dq;una+@sc8vbuqTJa_HmOnRF-3Ro3Y%!^@+4BixE)L#o7HZ!%yW- z_k{`nb}xpL(h!>{uA_|WZO=1N+BbaBAl;*ghbi{$>$l2QuGR>Nt+K&v;UomSZ+A2 zFz_ykZB2z^sI3NEyEO3%&|nwPrr2+LdU=|yH)O1Z^){v&>!iowV%IL|&L&UTqdfAt zx4@00vUbTp(D_a`XR8D~=0}_E4PMPUngd{pdckg^lI6Zq!N|?*}k?&NbQoZYjz+!EOjP?uWv5tCyX^!WQc1r9H z`d{S(Mz5CwhMc(SgjX4P`#)fWjXzc3A4=Xi#H%X1aC#BE?=yf~S>fm<yX-eP$@*$U!-%REoT((#@J3;8 zPN6?a5~N&djz|@2#d6f6*iHUoNa3Cf?bkQI4OZhnXh&cssEV#Dx!dM`&}ZxUh%obL z>^);s)fY1q?Uw4r#id)PPlu47_t^%QgZR4L`IR{1p%j(a{Lh;155A=WZ&5lr1x)zt zE_hD)d@$mn;gDf_hu5lJ@0__@Dhn@0nZD0aT1=xRHnA|-h)t0h-*bI1%H*LoX@<8I zCC%TT)O{HnNNatcP+`qCpnDG?em(_ZM1Nk*{=A)-s!MblpIhCiYA5)Bu?OSpdm4|o z>O0G1>Q^7AfibC1lk79wC1sR5liB8HTDif>z)*He(i=U!uLoqbOHERCGvRzJdlT9p zuyHGw5m;o@c@tNOn4o$>nS&f!w%7-xL<01$9adpab9nKRXnFVyE25jbhQ7p;#r}LC zHRB+Tr}vWM=6WbVSA>#%{;4(pbNFl&4E`HP;Fs6dsNIpsXDFW$^`fPI!0g-Ap9J{! z-=?ua!oe-JH#2Wy+t|lwg7EJZ1!#Ho`Lhis?VlgC>j#`_*NE3A7DV#F$@6k8vl}P{ z95A%m>tA+xDYPTZeSjIDs{){rgd)8%GPfkrE0lP$u)gxE@Eqz-yY2hV=h*fWM;mmN z`DfRzRkb(up; z&sEEj3N0p`BgONnn_LAR$ow!r(Pim`&6FGIb&6m_Vq82Y?P3wbSj!!xzh&9dK}|vR zVWO=L2c1YCEx=~gRmVA4w5P?goQ_)`A|947b*no$zj90Yn5V$Z9pCW$|&T3Em3g2yB1JiHp5;v^QK{%oZwI$l+>+gIQ zVM1L@RrIl}Aom96l^6X-%EQIF*A33`YF?COlg9y3JrKEe0p|4li4oP0)mVAd43FG! zwPKtXhuX7Q4~=MobmYF;j*FD)uI(A8b^To)lXoZMoT3OsFU|QvRYM;~q2O;z@!pYg zhn8|Y_d%(O+=$k|mwXYiHcj!-TVh@`0|1a(U90>b$rQgAQ^tK`L*sZx@g^!o-j~92rZvu( z+RlHzS_w-=h~t2=B?sg6{ZzF7=6NvGB7ElzSs!0sbKf@pFjb^Q_zOR5_cn>WlAST*x2{P_uZ5;*0*9a8h$P-77w@r0DV z3y{-M8;RQpzU-l#T3#+8*?mdP^pp1a6vEQDY_^izmZ|%!s?Sqzeg)oO17&isYmM62 zdz26>!g|}A(d&BQ+aM^(QQp?zE=wM~+*VBIO+TS8j*95TTR5TXnDiq9DnP&{^wBe2 z*=f~0CvDBLvbEYkwSBILb8&dTPwfs76=;{GKCkfb+poH-qx7SF>672cO71n1t(b=j zCg|>G3;KE%iZ=zrk$)`{rbKh@*t^nWs280ueTK3Wt0*N*ia2<)%J_>q#~m@*tYTb^ z&^%Q<_jaUQWQ;k=pGUs4s{Fal%WQ}EDlFQ1ALF!ak+yAYE^Y7zCn|sbVoPVS_MHN4 z*naO0J+XSgZ?l^`;{(N+wH}OO+N3WamC7sGi5v|W%6X7fE zQ%sEE*xC-ACHoASA0w;tt6kca^L&}m-#Ob3kFObYyW8-$JbjT2Q=Sm9M>X~>F^dJM zalek}6K~)~^oJ1cGD&uv*y@!w*b$(cV2vJ9Az`40VE5e#x$cfIGAqUnI}a?ME!)U2 zS7<4QX0%{B6Uj@Ug#6xCb@Ok8%>e{Amuas$bOCBA=04nXr%W zHuqiO{-$3B&qnv7LFz{`xyqmi8RIefR|FI=G)?PB=}}>fQbg;Vw&W|0*sB*1Ml7hRB-M}zEM6HL+ZQ^+E(p?`at90Kq~DW)HTmPfKi8;rJ(e-LhG6k#mdU-OgcMw=jAh-XyyAF9j~%KI{8Au zjlpqEaPdnO(y!Ma9`C=K;>mZQm$uvGtt~Ps2EC=OBL+yNAY%F z36@Y*Xk<9v^L?BOmR~F7GusCQo#W1 z06tw6muhg;*EzF@o`BYM@cZNUqXOeEx(6Rs?hP>wq}7*UcW+i*E^XlG^_y0Zl76tM zcrmX_mLn^ZaJ!r74&t!CNjWnf4uvO9o?KKy-fggX7$Q}|=FeF2I(zlr&g`sUu(jml z$n#%IC^RPh;;gJPt&z|%xk)A21F1#RY@Qc&a#F1h+2g5;^qjpr-Po2>*pz!_06>%n z)eSouQ+;mfDjK+loFnlti~d83r~8Ml3pE^R+D)XmFmFg;+r};KDh9MF;RB*!*S96f zZxRPtM`e1Sg$FW36xM9BuRWolb&|ea(IJy<OH2R6+h$2%s9D)UxBY zv8NFb^&e5C9Tb{R^~6SG;Ay5|jOb6a`%CQ)^x$9cTP4FVKU=RtvFQ~x19zd4)l6g; zvb-L&Tcn=K&x5s7V(HkN*k_h`{|YoNKC zrdpZTtLiT1dhDqET0WXdJtFek=iVwG3znVz-ou>flv97BxG#6H)cJ+~%^$gns^b}I zim%Ja;J_IIZZm!=%>~a@waQ3s*^dG^9G0l~Z@26LJMwEQjwX@;-$W!>Uf>5h;uHJu zp)tIp9)@$CG%|iSdk6zN;?hQ^5|bF=%OPSO!b(Grr2q>{bFrRJF$VP z^>~vq@XMNPk&DeL^6ep`Rh+sRpT=!Q>*xq^V*%R+e% z$gTg1!H?jsy9KsyV&sZ&XaN!y9J%(w^-IXq_|u5oM`9C_*yu$wOjp=Fo6)J~FpXTd z8gaJLu)7QcJy>{OIj&*OFrS7S*668MywzEhb?$vNL(BPmOKjtkg_gLct)YlvK9QQ> z>6FOp`Xko9Jb634B|D4XzKKOkZ^EP8>zontg)*A08`>1T&6vHD#&5FHK zth0@oEodle)q?lQe(VS9a7=Bl=qzBHGk0WeV_RS;WH&{0E>~N=zM>UYrR5Ny*w{Uu zUdT@)^i!-{C%RJdhrC92cZzv#IH9JOp zDL^lQVf327gp|5KOwdc^)qiy7(zx=LMYuy}e_Ew4#|NM5k)2ZTBg)d_Vb3F$e>ili zo5|veL1}f`{%G$uz@L0+gauQw6a2N0VWh9?Y6s2%FLgzT0#(69EEr|)LM+a8s z+jwGQ4U@~VoE*yev|#OL;nu+W5$qY75bpO9O?+RHR@_jBUQec&819O9ZnN%lUe1wz z>ja7umQqM#0`s^{Dimx#Qq62eJFX@y`-sw$SXC!Fy?rqm8}X)BfWk;tNj5afV4<)U zlXIXOPP-C)Y&%%N(u~1)m2o#I^_$^_=2>Xf@+JY2waC*FjT^;l+6N}(Hdm_sfyw<` zI32-2RQT?4fr7%Vv%>}(6dS0fAee+3o*nFr=ynV&<}n1!Dhws2=Xa8WJ{HU^=)^sq zlojU1;UY08$v*GT5OsdCN5|Sa_k|TKx57U4OQgMi+Zdobq`A$cYma~|kZ$P^NRLo9r6uG_Ij)=8zs@^yL%N@^(*b-WVr zoXH806&AjWs2lfw+)ZcuNJ1V`6(0CHD+s}x(8Ld)s4v3~?cL;ph$z3`WKTkMP4?TB zR`s;kak7eugF%>rT%F^ey)=7f)HF_7CJHBAy5*@BB@D$~FE;m<3 z2h_96*`clBffsn_4+RvwZ#uFJt?cg7$ z=+08ojVDO>KoavvlQr95y_=@0iQdV-<#2p{87i>sm!>;R{=rPynMC+3S*=SH<(1sW zu`pPAAsxSCF_Wd2yql(}f}oB7Blwzj;zp=qm?MwE_#eVy5sTjZTr_5_m6apq5CO1%FaQ)li2va- z2*ZDQKnW1eKXu_jzFG*^AB+RyRtUIe44D6xIT2wCz<@a@5txgl{fiML!M_0sXJ-dX zz*f!Xm6Ig}C)aP1Jb3)({gZR@v+=QU0st2W7mpAphY%Mx`0Bk7xI6@x;Qy{g8It)| zKPbD9oPXFglInkSjimoCwg7-c0Qjvl3^P3h@8i z7U-1^kUxEg{5EnS)PL!}G4%h!u>ZwGAf4-vZlFF0CxzU9+6ChV5u=dj4`u-|UZKhV z$OlFJPQS(fb|?aP!2bXI_y40Yb8rc9fD!wDbMQ%g+aT+tODeJ=^!V?ANp@O+W_U?IDVQ z`oQ7Ouqb|M+PD=D%`aSpe3*JZNqJ+g}V?ko_Mv133QGeF1R)rGt*+ z`HMjd^8Ujx0N-B>MFQ~u#h}H7{udVhhXFw3ABF)W{$T)k{trU|%KvoG162O_@io|A zQ$Y0(W(M&Bp#F~^0%-g%44N(r3LdHs(gPF%sX#0c4UP$Mz&0QbHunq=0F5~h)d>-U zS_R61cR&*O$pf???SL>K3J3z6pkv=aX+f1jkwI#JOdtiw0&0L?5O+{k%B1P1IuH{=eu2jwS&b-4j)fEWxLXCN4q zHwig|>_gxoQ@{yO0=xoT0U0pR2|x)$Kq=4_5SZ3b+6{fH5QiEbjnI1;O560wf@pA1ECaoMd!> z8weFd1tJ0I{ZktYv}gd(2|z(YK`r9}7>FHY9e{;EgVtjMEv5$g;0OqZ*g#4E2A~<3 zhFAijfD=?M#2BIgNCI+zCqM>~g0Mm4A;J)Ls1*Pm^cg&KG}IYH7xDm%fkBl5OhHf} zc#sar85r=Wz#AYPk^;pKMFLd@(T9M`lL0TGR3SG&6KErBFhtCp9c`?XQHvknuKY$|F)|9c{K^1IW-Hfkko%j|E!7nU*^A=(%*(b2mBw_-;==qPGCm~#`*#Dr#q1P zXLbPdKeG{-qksqO|GE00Ff%o`r?Buab)fLFwXmcxH+8ghHKpKT<8pMQuwv(A1NB7* z9R_+2fKma!Km-eZgEIi)J^1~HF7ulX^Ouf<1ESxG{YN>tKXecyv48>i-?~UVpf-Q% zD*mpE`j1BmjIuv;&EIs)e{@aoB>f*c!9V&-@HG5Q2d$1|0S-aG<^OKW`FC|Nfy473 zJ-}tKf9KGk-T-(l^ry~m{eEA$fjK&ufpkc8FleS?5dZeU?{e<{)s116aKDH~*hm9pr*7wFT#L{r?A;RK`*O literal 0 HcmV?d00001 diff --git a/media/moss/leader_rest.webp b/media/moss/leader_rest.webp new file mode 100644 index 0000000000000000000000000000000000000000..cd77d294d1c2ac2e616cbd730d9d919dc3e763dd GIT binary patch literal 88928 zcmb4r1zc5I^Y#IxyQC5625F=Oq&ozp8|m)uP(d1`1SAy@q`MIjP`W#$OS-(sLDu6YU#j0G$q88HI(_ZP#_QpJ@7M#3TeTF$cT$86T$-j zguoISIXKwd1FmfCT%1&;#3;0$Yf~VuL12LYpnr@^oE=1!mF2;I{Q3Ltkw5=G8M}M# zFbnuz+t<0#e4$buwv|mvUQ>i@f1dTf`5VR5%-IBZ>_wRz|ArPUK z+uPfQzkes&0)dqCLLex0fB%l24+6nPg+RX4IT$$^LEjDz_&=<Hs|DkJ`RH>27$oO-QFJ2LLi9o5XkkL+uO^W+uQ402n22h0%^4aEQaE(A`E1I z6gLBg@jGfOrifnYpixCjOH1}a?eacTq@~@hi{<3zR4-8-Qo)Uk#M>p`s>+s-+n$_V zGRwi;MT*r^*>v7-9gL+309SS=)zr+^F5{J9vJ3U~tnt06g$Ow58PF>2~khU$-&&g68&iPburxXz%n$p(T?{ zaIocQOsTo)v6l$Rk(nmX zNYha0v|g)Ma=mhcbuFgqsVsr5JItp3hS*N&g3$lzr8u|Lp8xGhioyT4*FO3C)0q=3GAWuP-G|JzSE4-skGde_brF z8BGp-vz#+C9RI#^{37t)B%&7c?f{Y|$vrHRB z{=MI=3-W(&af7@3+<$DlMP04gZlc+bf@$b6A(iWL^>6BL&Q(_F*8V@7ka9+=SISY} zzmE1(?pH$X#T3sD`x@D_IPFqm^J6yGF0$cV7>8lrqR)kYZSQ}zifrD0SV~j!IXb6T z@;_ES`iAPOa@sufy#8fLqr6SZ>T7qF#TFU!A2v7PeYX0y;Zg1B-t9Pv+aHVkXf}h` zpY!LK?ChqFMFBgMu(WDI01eWFB$?;`&wPDw1b>@)4X>>`ENrc1+Q@|Eoz33(Xal?Q z`v&%KVsoTM6aT{xV2PeW@56Tb&U}`H?w;Z*HVW)y`NRAG5;V|%4E6rHbJnT7QPH@5 zz;_hF5?Fr%FRz9lg;xZ8>hSQ-YVLjy-TZv-v@ipBBe(g<->$^)H68HEi8mvfPz(1r zGqC=*2W$xE?UwPNKI;gJiTU`)nwo1WK<`x}(-yN=y_oxb!1@tU&epX=w9qrj;$sB< zfqUr_2iTW^)GuIX;^`Gxp*}uf4KDb!1 zU-}S4DxXGRPaERD5>W7Aeu@QNJB&;UIIrDC8u)GpkHB{eI9AtmqAQ1`WA9wzrU|Hkj zDRztBp@7E^o^skL%%-7}B!I;8jU2>9P?+5VKjyqr3EVEUEC8wOPXEV;)SLi_JeGOO zTTV5$1>RFA`9B~UUOY{&HSuTPzaaY{pw=?IbnY+wHCO^o{tn^2wLN8V{{iz9lw^RD zmZzjt0e}P8=6RbM@Qz+7g#F0i8SNfQB}n#n{PB=~o(D8oG)vI+QUP%G%l|(D26W+n z)+O`X$)09PU)EdPX9D8UfqxY`X8;tH{ska+3+a2XOn(`5psNya`m+FLdgq~Ug)`7K{Rv$0(AWPLpUJcO+Zaq{!4JZ7(l37ypT0@}m&&7r!+v-yW~Ax* z$kPc3XMpkh{pY#QkdRx{wG9HUP;;UhGMBeIJ7(u>%O1CI|HFS{FFBPvY{HG;5;ii= zeC1|!O7CDJOb7sFg*nj7;$oaZOMvya|I5I#MS|{#0BB|NXa52is6o$xpp(sqvf7#L zAGP>9RP8OC@5F=(UF8T40;snVTd@Y7W=^*b=tS+GY<@2)bd3XW z$@)0KY#({wMb*5Uyxr7YJ2Gkj%8YiQ)U5n3?5)nxNL_t6>M&_8X;AGCo*UG>-DrjH zo(Yn;zAsP^yff)~dsb>s6F8Too3ARI{;7tst9@sQGZ3zKMg13lJHF4fP6U8%*7ZuD z8Si*{7jD0YTJ-LCnxUR*dM*5KgI5Mz>au;OvR#T7tpyK9_<4^%ch;d62r!(itLoo8 z8vlc{0Ctmr^L%T}K(=filZT?#40GxHj=20%m)(`pPUoWI0Cz5*yKP>vTC{DmQ()tE z#{jXxq<2CFU>U`@71<*DiA8x0U|@-e|0@u`L^K9^0xf7X16@na?d*C_C|K9a6VKgfiPcz zRyOI2z?*;p_d`>~Z7OOfAX!xk%7x_T0GuM$sq6win?i4iE#EFLadIX|F785pi^uNa z!{QMZyZbuhXtn8&c0at*1uzCg%zF*!Lf(1c{t%&iAg~X!JDI$xV(G5I+~OY^B>=HL zy4Uw|q-jM{Dx&Lo;33H4!s`J)cLNr zrhf}hsR2aiDn&1o-lZTb33mYT>^h#Wa1H3m7=nig8t`LweqJCpK+(8PW*Us(km!=_ zGLmN<3OqeN8}2j=-la6bVmDjLrPp$^bn&0~a3PjfVS&&H_K8+1#Ffq#rV8pL^oan+ z06ctppzr3YPUZ^++(>OYE0C>4x(=6xc)!Of&2bEL86KH)!2)=mDYxtBxTc<-;}y7} zx162UH5tkEFLZ2fGtx!xSYWtZNUyW}$4=`m$486AyZ1`Bxyl1eU`XtLXwq^ORV>-l z%;DS$Tf2QF7E!BivOG6&lvE;gtk&P0jd6vhL4TM`L;FDAEM4TA2gp{RcJhj$-a67O zJ>Sz{akW!x0+KoxnDU!XwJ7+Yi`|THeb)f=O>za9h^- zkWu@eRaVU)>opC9?FRj|?yA!^`WSkBolgk1mUc*OOW~NKKgMg_cWj0|msZTr{)ne7OIY;tkPGwU6dTCc| zjj5%wirPJUexVw@3Ai8C?-M}&SjWJ3BYu|~PyWKie0vSpaX|a~nQV_%=zgT)aC^01ts}pu4=5V8C4%{T*~hWC17e`ih+;nnI8dIv(I>Ay9sfSWH_=Y`H9Y z#{`Caak2hl1>PjT!5hj$rrU@+erN*$9>=KtAh^+ZovEh2@w>nmO<&kh0f~RI5+_W;V+ZlKG%h^hnBU@jO*NT@DMVUoV<<<10ybgBtkjO z{)ct~?HWj=o{o0NU9xGv{9JeMBM?0?(zN!vQ176|4e_}iXfiEZu9EhLQf1;zLT`Xz zb;f{`CozMVQ$?@O4m*mu1@QFacw+Tk7I&E8kCO$Y8321v*T=c4ZJ%mlh-RsNr}d`F zDEFwq&bvxh^;9YZsRmyHA>3`si0Xsjv);uoPzIm4Ue3zg>;6cAVOhP)$=v*HZGg|K$^7kiB_^=pCATgf>;z?`YmE!?-$cjT#z;P#aAHFvH0HKON&G$-Zu+%9Lev6{ zSvM)_w+ELDb)RwR2MHjoD>X_TD3e6PT6X#hO(z4$Bw;)}%FmF0)&evmnn4z@itSxl z)kVF>+er`YGm-%WJ?UxjC~;Ey)c4Zm>2GTzM?z!?oqhrX0?)LHLCf-Nb&3p860jX+ zM70VEJ49)m;YPAIb_I`8B&8F5LXe{t^X<|giKw5F{4d)Q^wER;k_~RhiB`WDmJ+s{ zGRTpXy@xoM@;deZ+nrZL?4&+b{qN@8Y>B2crHivE|$k zyo0@2*sIe#F`dAU$)$kivMZ{k0(!10ZAOuWV>?sY>B&BK#6xekX<|;pufJZ}5Z|6} zO5Ns*iw}@KZMj{Ax!KubJ7;<6u30|4beJU^Ulq-Xfajo-`(9;tj=`zX$6{(FIa!_8UZ5AH{4v=jPC$9>Y*Ud9io^z z%OfKp`Bp7}i)w-+Xn?g{JY7>1-jw^50EJ(1HE1WTbA9+oDOPadA=BVXxaEp+FDyl- z7PuE9{^jp*A0EzMfALhO-DT$)4#7hiy?yk(N>HIqEc(5`@|xuF+R0jkV8=cFA&mJ5 z%y(9K-uf(h+nrT!H7riFCUZ}3oA61ldpKByLq9Iz50aAmJk-Vfm$e9tRa@Ulr3v0X$^2UM zNpY(7PMvCd*nayN$G>#8m^gK$axJou{)XuUnGxJne7(I0iVp-gnHV#%qCLO>~l?yFH{aDn&W9S2k-q6g|Ln>O|N@RdK#gP ztV2?m4tz2i2HNrkd{7H;AS(c&)?fLxGf=|mjmdG-7umiWaXjG3`;ir}^2H^(Bz9iy z$ECz*%nDnx^!hwI;)h5<@;I27a8Ds3K8!DmF=Eh8H;y}&_Dw&;iE$t7c;C<tjPL>y0*D0y1Phr8OgnzO~Gh}fRKVN=sJ*RSg5oHuifVD#4n@t=#o=7oo<)5 z^ry4J+^~~rMyPwdn;{mJEUu5?;n^k@su=YxVcOB!O@3tBo{F)md{BHXU8gU?NBCeL zPoa_6!~cO)R@3;{&5iEJ3=CIa@#4pcW5bLXvhO$W;@=!%QNfh zxv3{zh92p$<2l-Q)$^lOUVBli39>meUF!FL`5qyp5#Do_r}cVw|J6 zZ4Xc*x@SPWP{C?cgu%KjdC8e0CEPZc`!XAWymnIiQ~ZNU^*t-CN4_HcpG+@Kg>1?Dx_`Qx;4x5hC*51jTK_w20wIeITmezInR&5#3-pI`#JxI_nz4Ea3 z-8fAx8#V<>9`Xac#hLP9gaq;2aEg;Loy}wK`lmud*QD=hiM75T8rGCJ`){KgAqSMr zQ;G+$iLOLvX1J?9V%kNI;hcTGEwk5!c}h*IFoRfHqgE5JAQXwtHM{aD0=FyK94JJN zR5S>*deKaIv}#}-H&WSz{DO}YBQxVkokPGp$P_hu&Lv4ef)U8XVn+HdNN)gti?Hn} z?NP$QuNMMBA7{fJ`9{}zliTLyqcy=iAKqQGc4xv@cM9M%q0RBrj-RaJlRPq53bwq_ z8W#2Ts|xg4kg?BCB3r^~KT~#AlRh~ol-|^wsnS(JYPrx@UrBzl9B$YtPxzX^hkU+5 z7mixy1+}vaHo$4Qldk1fV$assX3nZ{b>+cozdC=$g3$fXW*|3NZ4duRde?2z`lddf zCala62J4As$|dCJJZhw~=0W;U&uF%MM%bjx<4L2=huV|)E|v1F9LX@bR=XcHu=wBTs-|06G%;)9+pKD>41nBi8XkAp z694*f29O#Q?pEs#zr%$bvqOf03Vby72E&*YU%LaD6%aET0fUtyu_BfU>;02OR;Y*P(|&dWvc^&29I7MgCk+8YmzxoV}s-e*GE7LQt}S5jO{@ zSPgECWV^XjOgzlDuax>SggZT9yh@rZ25Qf0=oy7n}U}95X0?wmT;+%Y$Up z(++cDQ9R142zN>$+H?*31*W?!X_97%ZMnI{o3d?NkE-7lw&i?aZ+C5tTs~O$=G?>Bd*aWsx%V-mMqGk7e|! zqK+PsQZ~5D?Hgf*AbR$KEtM^LY3)yYKu#7l)XfT3Ntq2fY=5UQQ{!`Zt`2WiHX3TB zJLpff(MX(nb`5^{I3XH`f6t!6JogjVt?h8?&R}eOgerH8FHIx0zlhT*q$!3&xz4d5 zXTA9WS^7gv+^PpzTnSF=7tZ{G!3@l*hc=X)Vp?9feZTCI2uWRpRP?$BG$xEYr#{C} z%uJ!s>g`+DE*W-zpiAiAx4MDFszV%)V`W3unPgEf-LnKD8Yr zmqLH<#~^@S$tRBW96$nr>0skEPycOV+_45)5C7egP_4g@#0_&yRpYgJe6^Rnl13oR9j0O73_93C`n^(2wDmGELviWPa_#z&5_4 zC{AsoC;QrnN|?B!8Df=^@@3+Tc|KYC*|pu~A(^ErHCe3O+_X6ez?|LvVn%-^U7;p&#t>%zh-l>14#Pc9}R=OlnT}4j~*%*(e3B+;V5vK z@ALvT8~>X8XNMrGqQ6OOs7n3z;K42#mm z36|HTR&AMVD6fs%Kh}7^zn_Civ0pkt^I0R?uo&j5GnVfuJ>zEL?S&h>%ag#4Blmke zcAlM?!#y!r>NUkkGhL^iJcpZnQ34crb&8YrO{i%wZqoH8-7(hrNeY}wjG-LukKwWU zHP1Unz23Dc+P!)_X)7mQ`=y{XK(^yW5tdwW@dsB{g75hv)7Q^FFItP+lR7?Jz#TZg z|3V#;uO(-KcZ_1;7(#-{$MmZIXasi7N*CE2X8SBun`sV1awmmLBbHv4(FIdvlJrTC z@QGz;ksWtASdm0{m7ot)Q&wX0?X_iA(ZWRDqTQ>HYptb2iX`bW?V^7>2bbU4#;Ax$ zET*?YwVN)^7@Lyiv*f{uYe`mX_28rdrk|h}rBk>a*N6C)u&K`)K+F^ot%xZT+}eclCX>yEA37vfM zTgBIYo=-+IJoR9dZDbwC!wPVLe{kd8^Kg^VaGT33(8`_j0W16$`JlwHF!?HndInrSmSEl<4()T5$P%4W3ba&@L7uLGJqK zto%GH;R_s3kq;xr`l0r%^C};!hk(MVg?mK%`&}NFmCex{wu$$|uDD&bSR392)ttDL z@ySHQb8_yIggQ2?Ax)PeYWM_{lYXXMreql^#xUl}fjJMUuwQ+akZTH-WOb8cVZDe1 zx@j+!N*&JuNB-gMQ#iOCSQC^RQ zgVabMr^#67*|LS1Ur%CviU}kAxbt!JJwbK5w2~)vOe%Brd{NQJMT_kV>sEiKn&tVH z3N^E>qy`ysLx)Yp*B*+xvRpWl`X9oAQ3P6AdXryxwz@KpB~@!#itWPbfMvujsZ*|9 zQ-;?zNd$3{nh|sjf~_{6{1-M>Vc*Q+C|~Uxaq~RoOxEPeo$K)m}WC4Js)1g%B}NaqC#0$j;lNYRrZWC;4pVf z6?N5_a9&mV5~gc5rs!*?W;0&Vy|=Wzl2ct(h>vC6FiWrPkg{yvc-SPx!_d&?O4Ox^ zqrGrM8@xf}rK1Yyw{k^BlelYl_Zl1H66=k+i#ap}h$3cQ}oBs}fM#7wnkk4>G4~~z(rX-f9}2n;i(_F7 z)|t0vQ~fo{$)IKTnVq5XCHB1Y*f5=AAQ`;= zx`z(a+QnxC%W{LYj?~?KnB;}JxM&|lSfUKJyFSoO#5m)Gd$()nwanN_jpN_{u~<_? z?VD{OP@VpgR6WFBw|#*8xMg+4V?XA54Nw9HtH)A3^}a2I*<@e6@`+1+Er}&}Bk_uy)j8- z1Nt!j^^x#W#s(75?%N|!H4~RGIrO;Yu0lNLrOY1A5u<;jBnIhy9uNlOpic24bDoae zQjefs%0M9Bx^AA{_nejxi$2czqnp5vHF9mrx z-4b=|ydWxiE51BabJx)H_{k_ZB2{AZWNA*Rz@0+2`}j4ghK3)MEbPLKxDl9#%FCfXfSh21>3C?oa0E zV)B_B_vJguoeE_Ti)B6K4CM28Y~+#xFEaC(O@AIP+%8SB#xQdCv^{%`d!tOM^|jRy zu4k?Hp($EaA7zPQ<9$f8T19s~T7)dIoei3Q&yj-Z{u8A)GmF7K_YnO1xZ5^OGLJSs zp2ISOJLTmaB96=?`spV8?Gf_U^SSOfc(hX?4BqiWt5eaoO*Ptbi`q8LFl;D>JuN`z z6^L6njkvWKd5JenVb$LjZ{DkPq1Gs5)Noyx2^_aKh&J@1X0HZnhyNU_TWsDA5SJod zxj_AC(wCur6J4*1<7)qU-}v1YQxQUh9xWn^T`$&wJ?*W7W(`O2k9>Q4iv4G=&2*!q zbL|Nsuq#KasnpvnG#|ueehP#bA$yDK{F>_r>f8yurECFxu&=%aPSa34(bD2OL|z?V z-y3nKmu&Ey^saG-mCAU+0EnOl9)VmvpGBp!hS7;Iwu?o7a-Wb=~frNYE(9{ z>+VBJ%0G@fFF8hy(%q!jtd%wmfB(r!(x!IN!fcD7h1p2-BMxeOjUhZv=#$t`>(G#T zZ1!q}88~I+5M$7Z#0N$jk{*HWuMADIJ7L&d^q+RVR3>ucrimPs6G3u?5NJiE>1TycBM76T=D-f!4Dd>}WOu@AyAqTV zdFQrsLpuisxZq*e+riR+th&Z!7$}H(NO}AE$P{(FWQyc-@H7duF-MqMn1RtQ96)Pe z@5)y^CoQ&$)0XQu+C9PZ+UA6e7!8^|6snGK#~GCNq#BHOmf`IPxnD;UHhk}Nn}dCw zfUPC%ZINehqu$`f~$;WmrvROh~=I*d;r$#e7mCfA&!v%RY9`#l0x&z+kv7tY> zbDhLej^hbY6XI8t1B0CWq+*l7hN31$ABB1mfoN1~szB6GG#lNO#2(Pz<>f&=QT%a? ztSbQ1sXB#q6v68K`3P))ZU?g{2RSQhzbpE-+Dj*~R-f8V`A1-=3Y9*9P3S}QL@nFO zp3XJlywB$_M7;a%<1TUt`=fp*PZ^gLdhR_FG<6UK+pY*S-Hm`!OVEuA&<{vF zJljBS)x;p&Jz-Q?{q0V7Emo_KkclK5+Tvud0@knq>0Y+W^l;WNL2na6+W1J`M0p2{ z0`U*%WIV7hZ?<^4Ja%$Y@?+1LMd7EG1E zI!mx;-HC8b1zaz;_#kbkyO@adHWSjv4bnq8H_W+W3&qsh!`-eCkG$jb*dB+ zd#I+6Emk;rP?+5}AITa9Wj;h4Ea4(6s#7Hb3_Z82H6A#IwAd4NqOD`>gNpavyLCcn z_ZusSKdgQy{UQ^<4QY!C9m-$-mPo}rHEzw|kdnWv_V~3Ur%?AU+j%b_M4-z;A~WM|Joh4ERZKLDLLc2ioCcG<#vjz`f3Wk7p~LmIvUGt<1QKUqgy$1$qd?})1II(m zA*w5L-h5xU(a$FD1NPw{7Le?YuVR zEk3G`aN{JqU~0Y%tznKWpJiNfByL?0pQbD>{nqHpl4`M6@B9h}q351kFfyTl=6j;| zMto1b)D*bgoc0zKRX@F|On<=T9syrnBd1+gPu$z}9lm=Iv2%VO>3Uu%N3b&r1~1^( ztxVe^{U52>`Zo7-l1{GW#;%%>5FwrI*O?#yKvhFPNvsDDPMRO9v-rzQmIT+|&)RG$ zHdymsV9VWh^}wZ&&+WgkH+J%TzpPYX$tiYN){h7owho1GeRuF)!$sdErk%vCP0Up;2;xsc zw7YEGzjSG&X%_;5U22nj5}*~@R7?Y8J!-(t{URirO9C{jXgNSJe_)?H@3>hBa!g!_ zfd49t}HcQkU$5;(~BzdZ7}@87eCxxOjFK z548L2nmztcZD{H=$4n4DJJ*u0`#i6#9U3;hGFOsXk9b1b`?%VUo?(^UMwzB}q}l@W z%y{LQ8Je7@AEp8)_E~>1zB8do=If?ca-mD)VJlPMIWExZsco zHRO0et+4SLG;@Xun*o#qWK>V)zB+946ya)jqEZw3jQYQL<3bV7YwkR$FMGWb3M%}x zKDoasc_1eo%y7wk((U77F+=aNY=RXN6byN@L29gil=mz8_Ph4FL#^CVuW*vG1oZ~& z>t6-i1q)U#W0o{Ob5ROk@cK@K6C3m~4$qXlM)cajsdH?Yzp>?>{35Ej4&P&AA~bWR zc%P5xDa~W#?nz$?bQFOC&PMvpc|eH?>}?*Ti407Q0I^u!?%$%~5_e{Hd1)#acdThM zZ|18fQ^96k%Y5$(;`WC_QGj;1OHNlE%V@BjZ)1!|?}~np1xcdc%1TTf>Yk1y)BG(q z>ZiUQ$8JunMDM_j*WS{y?d`meEcW4Sk;?R!X(HP?Sts*K&5jN6Ev``-jmTvw_o}Dy z*Y>aZ>aF-R!#)d{xL9v+XP}m4H}F&GG`4}VIdoR!3^}tKanVp9!T+sGxVcEs{%nr1 z2kOV_Hag^IRSp}*@%Uv>DRHzk8H0Qr;QS3ua)AD>|;U5NQ(zhf8AwM5jrtPP%aTFk0d#(0@mCPc01_xFn@J~YxZ;kR|9VWE3a+ZbniIyJak|A`C8#Nnw zG8HYJ-2gSLUW}|P?wLg_S1D{-jMc5EM4Dh5{jlR&K(;Z1s95S&KL6_bELg>pJZAyI zO=oCcF`!L#8!r*Mxo5BFKM-f9SozYAIw#=TSf`ILRvdZn%T#A<<+F2yGQ>h${}cTl z#vP3mA{cb6&GCgr(%zbrTZYgLE6nJp4>Hu}Qe~&)L1%dZy@pX}viT`jqf7%H!z103A;S zQ;`;o$mwrhAN0im0+|yj7W)N8wy>PkW2OQNsd8)Qfc#_OtA3_PAsrkc4@F;xZ$vMy zdHX0UpEZ_xetXGKURqHsAtKTgyuo)#uqTE;Kl9BWbEJ%y%&XdhRMIZR2%))0e1|LpxDxJe2E0eWA!vBrOU^S#I0yT>Wv`mhh?sL_0eo( z3&|$=^qbI5K-WXDj-QIf6E=!a8JL9m&~WQprmoJXUyM5nH_(kkBCG5x$4D!Od6`e2 zyG5yN)7fJ#Cnp&M+%G^Am}qvJT&N(7ZlA~S_PF0ESs<{Nc_xq9o5A7vFUyzRKP4= zgM!}fqssvwjKC}URUrJfZ?aJc0*nyRbzk9<3n1V8)m=j!?xBu+K8H)TQ*(Y5JuXf&)*k%A2&;HLVTpC)d2P*o_{u;hc~T)EgNX=ZDFj zlD@1yW22!<%1XxRB||VTY_PVy&Q*V@*SPJK#m9dDD6*6r4TX+NawIi>v`HU^9fLCt zF^)|FH?!w#2kM&elnUL5a zs5^Ik3nA*@*DRA?NWkqGetBU%%kwJZDD?xSwk1Afe}i+a!^R*S&WF6&1U+Xooa7V8 z2ZE9*87-X3MP_(aHmcYxOTwUNT?rIaZ!ZUaC2$zae&=)33d{~Av175MpvBv=$L~lA z-Q117c%`;DsLSa&$kJY+8c&jtp`&wt)5^~uysihR3%`lYy$6GfgVI`5oh6nQ)$$0?eTk{sAS@_)As@(W4dbT`25u= z(g!b9`U(8k)arb!9zEZR(F(xw!nhZqUu*<5hR$_H=MA$#vE6b4%=llFXj$K^3;N$( zx}%&5)AhVCKS6y^WAg^hIH}`lc1Zi&P(_Y#D!ek>iIATS$t%iAQk2zb%r)<17(IDt zmSZmhDM*Kese8dkUaw=LjXZMJQVV*-caw7&qq{P7X{Spl+-lX zb@x&Ij{}Ws1eK-rjO1p4Nvr8g0K&?6{FAq><<9whzFCSZ)c6HG&*CvlbD@)WORqD$ zB~K$PlZ)MDyge50H)xWCv0)Jav%N*@%VSL8P`-wMOUaOw;tf z@ZJePZ*C?`TZQBfX;0afJzi9 z)G}-Alb`|`zz>W#)UFn3mQh%9wR_a|0Ofe&_5?bEmf{0QAUDDEhdgRzv(p5@JF-V* zrkgTlI_~`;H#naLM?LwA$PT@1dPSqPCYwESh|stmqv*Me2a7sS??=XxC7W7%#upYc z>I>SgcEzuQUx|NT7Ge%yAT55p=0`>w_Yx+x)f;HXBrOAQ?Ue$R74Cx=aiux)hO5`M z`x{UzI8Bhf0B!a66iB8bPzCqS!@i|fGz=!O_~L9lJE{Owv3DaPFq<}9<$hw7e$crLBJWd=RLB`M z;?odvSx+h%L*D?(F*b!{30}25Z)GK!yzFMRyB9Jz zGRLWejW(YKGWb!)M5E0t9!nLr=P+d#Z}hk%ezNqXWLXa7BJMhx3Ja`lG)TUp&Yz9F zujVJ`TLr>$C&#qvG0J?AI)c`I-Ohw?^V-Gb_H5t->1(?DJQ!w&yUQ%_Nes#~{3soK{x@AFet-&LKwzvn^xdF+R> zjnnbCpzT?p&HYNOq;h>*wK8(pdzXWuvY)1ge4W`jC>qD=a*n-X4uFZq7Wl+zE2e75 z&_e2Pm#eOcase+|$1Fogw0(ceS|3B&_2^440AA}5jvPjjSJ7A;9X%6$cT^aI()D`9 z0_O~FSve3on#b1&7WUE2s-mV61*V5q-_i5j3VfhyH7(y!cY3_!jQN3 z>}G|*%>Rw-Q^8k0>D^*5noNpBvjI_KJApnDc5fm&Ps8VBze)B5(S9MTL9iq8?@yfU z^EUz;syr*uVjTneI`Oi|G4 zN+SD~jrTZurJuzRky37SCe;he;~|RoK&%tE)b?*tjE?zUdt{f0JAaGQ`*`0)@GPx#_A&+ zUT@+FU~FfTAb!Nrq_oh59k1i@G6|=ha!=%g>1bw{l6**P)^%m-VrD?YSRu{5M4I-F zX2?J()7^-8s>HwNHsx9dTVmM?tPcA-`79L4v0TKchED6K)mF{YO%3-Ek`zOS5K}h$ z9`*pmacCoA0J&Q}hsTdw-|0nbV#kBFof~p+V%)}8$|-O~d)sJSfY##kr4vG0e7QSa z6v>UxRf$N@{N&)R*ytq-P6*65Au6NzCqWEEa``6xGvDpu*7xXhl)7lOS_prlAM;$~ zNI64}S@C&I<{od~ z@uQ&ERnj-SWiAz_C2EFf`g8Coab&JT5Y4{(C;_|Yi*O`gL|^5}pCBPeQ&?8g8&XVM z3e38a`IBCW#=htz5FyWQ9a5JJV9ki3!cLG#Lr84N^P0LC6|93pn)a1?aU>YeZ~udR z`LVGvz`J<+tAKeYr9wcsUXMU`H^m4>OEA5i%OA)E(w6{B2YijxS{Yy3sc_-?X{P(l zuh@a84Gir&f`WHl-{U>r-ft{;eDTVFu;PXXH(c{jTa8!vjp7)l$JI)d)}9_kS-m)1 z)p1jVbHVbgt>su`W+z4f^gyt>Pp`(=9RD;2SQ$m&3OCUlpK#9qz9D_0e z=>wClRFeeDDw6^&(gQ`Ku3<}R3wexYf#@LT^JmH21k`UD$m^fZG?wQJaVkXA{=ySE zk0jKRq!28IKkAiXh1bf)IcXY5_Q1$XSlUI(sO>5GJ-4k>zQ+v=2_68`5hDclqrecl z+jtQmPE&n%A|si1!j1=*#*szw~_z?v{5i?wIY6Klq9&IJKQnK$6QZ0aV9){)nsVRgCA%KYwv(J3QLzP~a1r z0;+zj@8bp?4i8<|-dmmyG^Cswqb>XJ<26IG(dQg?3(7?_6ErG^t+C8}?wKN-%E)4Q zF@|R$W?cBUw>&X7aivc}@Z;x@MzxC}Fuaw&h79LN@Bhm7VRTXU;S2YMb8GH4!_naj zgid>bw+s@}Q(01L{}0W5E^Fg1b1t`!v3EaAYQuYYl_%RX7a98TB3dx>?@q&R27Pef ztO=L^X5{qp+3Ka&UB+J9sb^NJ;^LMUK0w~F%`e59f=s$y(oaky5yI)V+Czr6x=8DU zyeNeTj0)fL#m}!jX+<<=&Dkjhzli`ql4J$hOol$YJ+kO4Th{S)B(6b8A0GAl)V4{Vgy07h z89H=4d09dVvE1?bp5U$|drOpTvhgQF(Y|y+oIZ9W1DMXOGW?BO(6!jQBf6&=vFLJ9 z0$;E|IW8G^KNIm??2q^#2kfO=A6CJyd;nCm&}8AoI;^EHEklxCg#62JxQL)^diPhU ztY`G<3^i0i*hF$j{CqGny-N~_#&fB=JkY|*Bm=GrLuNgmR{~qB|6Sz@tN;OxqU6{u z*E!J+`T26-D=p^Y5D;`=Ig(15M(_Em9(GS7*MLFiN;D*I&-Mg)*~9z`sEoJ5(wgqzO1UAdij{6Jn2R+n<#Cy4 zB^nV@#@=A)m~w9dwbiTf&_Lwz!Vkch8BoV+lK=SaahW)OygPEB7mW_b<9>?to*2ycP|K;Sld>R7O1EJU)b=mf*Syg1^D4-Kt2tmj1D7OrE`FBfV0xz z1hcKW=HAg_XAE;H!yAcl#eTh>4b0gat8kA5L+2GD3z;e)O@d&m%t}CSwhnKD@uOP{ z?x*>w2W40`T9rG~jRKnJaQFLNJ`X>y>vdIs`D+($hj=1<6A&HMtEHOUFQEYRy#O&T zQwQdt0YZ;p1Kw%CB{I2ISwwT*Zv6MBNAvj3pY~6=ej-UE{BSIwo@OOB|D^#Ij{}ay zY^#~MTZJ_Xj?4qS?e41rlX6*`in_ib zhxRD}9gJSpByEz`>D@^t$pJ87ic_(@2V}}^)ofzxq1m34vCk8NbVc#2RabZN7n6G@ z?k1OAHl48R1e2XiDMlH4a?j4~_QjMNMPhXi$2KN2?!kI&NKil9Ke4rW&S3VV(fm`} z{fI~_&k&6Al|$FR<|{1?=@EZBLvrkS2MkigVd(Vr_4sB^M<~>v^~_m`o(BF1d&hU+ zU7gSLT!IYFb5_!*o3&TEzZu%5>e$S_bYw4J&3vwW*+6!xW(1^5fLK>{XLok! zGR$ibNvUu=I(=&AhFL%|E=WxHzuU>;LH9N4gjIo?Z? zPH@Qp`bgjr?vEM4AJn3XeBJ1WBQRO)DW#sC*Xm=Uz9r&566qx5xEVPgT&Hm0H%=J&f}-U#7V4{r?J=Ot(<9Ioj`e7 zaoiPJ5gJ_|GiyC*R>4~=-O7$a2MHEdrH9#WoZv72J4~V%z7`FX_79IUK$mG#Q zaF(7y}fSGa=~&bjc(^HA*M5%(0fq+tg@_`;MKfc zhWtx0;yXh$uvl>jojS@X7+qigODxhZKgMjG36X?mD{(T`L+=dEc02Y`_(V_5QS9bipX<=LuQqJ^pTzfo z(i6%Aa}Mre6&QV}pbRrA=b6o3jfmhoX&!kNNI`@bxdOTK^Vp zppD(@t@K)WOVL@H37?6}Ud``wqDT&B9~N8mT_d&H>mPUIpa`{S*Yl2=8 z;&zT!3;4>L&dem+qXx}KsLvX%zX$(VK>1}_ z(Y}O8tMJ)^5{T}+j(@%;4BjZvfHwoU6)UU1ssrF+7uoi zjiFk~4-oOw2BwmjclKRNGRdp)G~(-}xnu>L(wc-;3MQy*1?sTlocld0BfNyB0t6N9 zJ$~Tg#kA7|Q*7GZH8iZ}h)g7zu9nUixg~LReaP_;B9HjfkxYl}yEOoR1Mr^SyJPUh zF9sqJ)L>RAw#D+Qq<`6@IMg)NP~1N8Z$9GD{GQ?;x_^2-Q`W8_w)((KF`pnHQJBu; zA|3Ehl(+oD=67>Vg+&`Z=x0uWIFqT*yfLIN6;`=S;j+$Hcbu_^ajxb#J42P{?!lx; zd7k|udzg$rS%ltbaKrRQ^|z`~uIoXie#aw9XG5>$!dmVWI=*5Epy&Bu1<7u7z%c?5D=Q~Z!Ukrja`Zo%k`PWP`-!3od&tf*in;j9BhFjTdKS@{I_1794YbHh2t2 z-39OY%6w9Lx6;D4(%?hOrTz)icqur7{?Vc1oe4Ch_cegRf996&ss;6SgF~ZV3x$?o zjAvu3>ve!Sy8@Rw%C)4le_1OsBQk_FnNq8b@Mef>PoN$cYv67_%`KeV_)mE@keQ88 z_vx4@go@3BL5-8Z-w3rFpMNCFs;QHYpXm0qPJ0ntQx6qV^>eW?^xs~+>b!i-%7@v0&frQ!vY z35lly)}Z!*^`jCoj)lvEoInddT>-s`Ry&i#YY?Fl?MNX$LO8%=8-&u z@v26Yn+=GG+hg)K9R37Os}4`>apv~}y^8Ue-P=JXP9MKuZHFsG&H8?qFD}ilU940m zyfQZrwy62>4EO$;ESL>k(#hmIbB_Ut*}bX*hVVz?_(%0#-5u8N(!B_N=l1m#)%y-s zRxe6SULLGGet7F3O3gWQjJ+ZvyVW12Z;UhQ=%{60jCPz5XfjJ}$!NccfAf@Twa>nolAe?Y({P84ASfSu3 zp@+qK_~r>!(ZvqBWyf6YxRf9PeuIaewDCG?QAnIRP7MrmQhoXFGrcU`#g#UETbivfU|mv4+k!;RYK21sYrAzM#mzm~Itqaqa@Yb+5o zc+mrW52^4M+XByOdh$F+IqEkL1Jg+Ce_XGEjJQ3UA{1PvpKws2pPeg_AYeb988ou*D&Iux@~q^Nx2mhEOT-Np=*M2d`lcrV&>oWbThlEoHfHE zb2eT}02iPP$;zs^(lh|>3$Mye&p59l?2$_nqjAfRp!=e?-I_W@i667aO2t@;|KM>2 z=DBzDO4t#L3%Ag@FS~w>Ca)?sRj*(y4kZ6u@zVu4bX{v|qI<;1#mR>rE!*=`e56!G zbbhQ^oI~+lFMZi#D{^@z_BH!Cd=-gUR6vcthra%YyTxE-{F1nHRB9htQ;W2<2QFQ| z+yh|S7$}p8wetUdWV^3bPyXRQn(p0(Lv*1i1S{U=pmxhEXYdp7g5(R&&QG#FGIWR} z(WZG$P#wJs@T53y z1N;^L$ui$kOKH$2zqlku9Au4i0lD~^`#(^g%;(B!lN;^ts<5Ly$Y>u8r zQ@JV1oC!d{kxzSlchs`+{F1B5jsuA5ym;dVS=a-?o$TIqSH0M>X5CZfUPpnF}GJjzTNA&@~=Tw`{3Q^ z7oz_hL}EpTy?@5pRsLRM&XHBn+fb&ZiTDsWvh$*7&)O{49l35mAJ%Kf^UK>bwOPia zp&W;Oh3Yo$1$6eAnXyTIYe0&7)zy^-+(n{zS#P9<7vt`PW^X~m5%O^eh@q*oZ^MD@XA|Kyya%`7C9t+m=QZh8NlPN&_ca3QT z;?WBnY*|ynYJa`wlWpNU0107lAvy}JUeM+9a>JQm36Yk_3`9#%15i8>xkclcz(nlN#1t~yJmzy+%0jy0O z0mURwuK-{}OL)?8Dwl!lU0~H&;aUyXSp=G~Sa5j8Q#O{+8@&B|yDcFA^1==`c6#=6 zs()AZwDXLiEIdq*yf?u@HWy_t`S9(;df7~Pnvl5wh$m@$cY~bhB7SJeu(lbGYg1+nnRnc^!eh>>~RO1-W#u$JgNw;Fz=S_0A zPy2i7HMQFN_5u`tS8AHg1kzpcOXu!Ydop07nBW3Me$%%yxR@tKEzOA#P5<*TbZ!y7 zaj3HdTBYQ0k5q}Xy$@*|)%J^b#XyS|J$p+X!XU)KfsKmA^&Wk6Hb%R7OC@8}9bGYH zuWjsQg3{&)3tv0;@1NI{qosxK38YTmnW8yRWlU&Jl&d}RN3%X-V@4nA9$rhN^&neF({k zY>;#)#2NR8D$A^^jktA|qRZif<`tWk2p#n}!%!lorsnx|Zqr6F0g{y+Bv(9S|AsH! zZjdK!@Ylm+IZx`-d9E$KvL0 zffg8~Xnku%a*J-Rq#ImnI)OouIF^G{FzcZeN5v^Q(o>uqwL(~lPs> zW5J8NONu}%0R%JvEH|JTRZRc@P3DsL=bv5f2R`i0&yR_N-At=?Ov_Y;ZbKTY7K~~G zXNx^=E0S(^*mIx;Pa!aR3o(~9@^&76=o1|rM<{40g#^L)|7hn|h}OxLIt=nzR&J{I zuWOS2>f8`Q>p|8vdc-TAe1R&wwzBrJK*B|Ys{%{r5t?|-kogV~_onTy(qtI=9Uk{6Y z;-~T|sP27AZc{t}iydXA76cZ8N8X6^ZvWGg4q&k9}LKb(X9`*TB^B?gZWOT5B|7BJ79)%i7$n|5UOnB{UYsQZ*y=E zkHlf8@@@reA^Lk3mu)sWV#j$!)0%fy0Tz+osNTTBWasMwTp6U>qge(-7v|^)<>Ggq z8T%{$X$GNb5Y{1|nR1nu*Naf}*ATr$g?Qyw%}{znz2x-TtRxDIu**p;t-6i7l@Ccg zY~<@!j}^wXyvbshXQk+6$D(;>yX%w&T26A%#Q00szZUSakSE2Bz@Xzx>IYKQ8O@1; zj(-qHMmg*gy!#M~Z-ZO%Ln~Kwcg+pQv$jZo^R!-Sc$&MU za>4QDGyP2ZHaUCNLes~u@a=blESit_`@YEc@rGEsVI#yG zlUdtOJj9v1!`$ejBvFGhctu523J3qD->a+gMUid+y(NH(;}<2F51Z8TJ<29@X05g0 zW+42%ix<2hJcPDA6}%2Pqx6fkZwgo2DKKf{6upfO_053c9xZK=}}`E9CQ#K(q*kO_lDREu!w?7nIm+gN24D4K?HTrhJZ9v;5CK0GeDohAknva1PeB(|Cp zu>LF^KeIP*+fBVHmb%QZ@Y6&SK?>En_R()L9}$-%>d5d_Qti9PQ!@FzR#5*L2k;|E zfL6-+>E97=B`GKVPD5<^UFK8zKg!U!TR3!AYY5&+AN^{5zA3|rCKc?l!aJ3^9@3_%EkA=A*cMZC zjxBPEvmZn$U0LX{=!x0ZDpXXuyOaG@jB=guDfLI=Xh1E0n{dAPS-Kwi$N4Cc8B~xS zfVheBn^AK^`FGVBbkuZbnKZ#`JNA!a7QHgQotQ#+AeW7`a0cI z?HQ#TTXVt zdMq27%J@1nS%XrF(%nc+Uvc&p5paMEAw)OFAldhb@LJ1UNJ|ZZA&IYZ0&=kHi*%aa zs(pOJ+zi6L6-A&8u|xfwo%;$rz8e9YPB%iAaHyTg#RjuN#2K(+4gA$rSPz*W^`oqvK{${I z=Rfvr_TlbdQFKy|ds$m|jGdGjnM_lz=5&d++f=&)Kq-fU6g z_%rs)Y`t(;<~wsetG}up;Opjr(819A$nO4-206vy2e3!s(51FFM?eCf#QCqOn6wEx zkrfMW1pD+>L6Pa-x4r%qYge6PJu}`SD&dY%4i^m6d{D4#e)qlE`@<{Xt&zviW*q&T z*|u?ma|SF0kapek62-FM5JZi7>y+t%Dt+rpQabbEE7Z2}yZ|bhwf;QQl=?`$i3#yx z=9_hDS~N>^Kh)poAoG7VZnWRj0>DBhi2~Sg`$pl~Akh*#gHHNxcsF6SRuC{v1sAaF zr7x@phh<)#XBX1wXlXE+SXB0fV8p3xH~k${7SKKQ`NfbSB-UCE9D-R>f>y#f@;c5X z9YYyEPhM|TPHW@bTa#Bc1trB;$xX>?gcKosZEPv9#C~^eR6e1z81`*?U?+HMJ7Da5 z%}9PUH|VVtGoWPsd>_JR&}1>~LahPy)@Psq%n&88Yx&BZi- zxC!vGwsZ%bml|Dw{k<_4J%xKq5r85MfJg#Jme1MZ0CYCLJ*D#ca$ml9a=F!HtB9m& z5)3iEmu&p-byn!VL?qarU-=1|!y76&X#TYQVK{_u4djW?aSAk^fAR4u^p8uD6I%N( zyaK$I+oVb7F;}(k30oShm3;=JK1R`dTLgTC^H?$iA@&}cS%QdoC)3EKk)YzsgQ1lV z_w$t2FshrVH#<^ylnDQ=GXzt3{#L`f=AXvce0Ze)1$tM^)?MJFgMKL}*sQa}0<)sZ@ zrpMVj&O3WzoU&+bh;31T7<1otyC+szNv%yIB~Ee!LpT+b$LTKk#-D zbgz0#h0D6133SQTuQ7aRqagOjI%d_h7C#$@$Sh)#v2EOGDn@Uq+Lo9Hr@vo>p~mkS zUNrNf0={W2Z0M)5(gT>P!JL1eGqL4L^jhp z^d`t6BhUTWxkmzTNEI9f(WkJI^W=Np?a}d62R|c7(DcN8QFQ|6Vqb;TG5RXvDkbNvzbn5OTS!^HH513EaZJX6oo^7U>`PbjKi4mS8S2#q zVK&w}31`N|4De&b#{Gva*0P5Ouy4;FoiC$Qn4M851tW0WqeopxxewBBaR4b<+t z7Ft9Q=u^AnLNA$8#?@8VwbDP?f_-0SEc>XvO&XcjIV=xABe4K@ugOBhNtWs2CDZB= zv^Z-Zs^NlMnK@KDWCuyLlf2&!>8D^}?GM8~7eJ|H87cJ6gmmaquL(P(UaiZ?H6*(M z$KdKF4T&?c>Mg>C#;9CK7NWJ*Z86pvokwmZ9@1E+oJ4^ssGL~Z#VE0ckt64G99}Vk znC7sJvocCG5uW71bpqptTS1_O|PP`*Nv_5CzRqX@STwwSJ8d;uP9TyT-&_~H=Cyd zrcY15>7kL<6kn@dKryuA{{TM*wmgvx`OEPJ_(qV#+N7=~xw)$_rS#pMwr*{SVv2?{ zjuIbFsK`jm`g7AJghpp*g1z&K`_13dHl^ki-u)Nu_;wzZ%BxrCIAX8Z9j*E201)R+ z5f6uhVLUQDy(yV5Gi3(;xBz#%6>NlE-Sx-<+_>AjAb(*CL2wclXr}*r`2Ivn`_xtBS#{nf#O`<&GkeHX8 zwS)HeB0z6sQUmiLz{7U>#Fuo|y>Y(qCwUf8-3r|eJ5rq*dr!-bN559=Ded9a^*+un zum(cF-|pu2@|21yH-({6IPg<(TV%HT)lhvi%>h?_dpw1+E(j@Ad*1f4<(q;e!jbm-qT<*RVYWqQ#=ea}6-bl|tidj`8pZk|N=`%pF`VNI zOpX`1->h5Id9JRCqrDOW(rQ;)nJJCxubN9yxg z90kM8t4Vt;lC9nNAk=;$5;i!sJx;7aWN2O7fSp5Xm37-?*?-B5i)+ZSagqt*q@OGQ zYfN!^8F&GzvMk(D6T{%+(3K3=v}hWsxd<)5HF!n|mx2D|&b37+{p||f+O(X2MXEbI zB$%cn{{jq7tp3*x)T21_GmO~iWZ?z~)2qaAPiw-pgdg>vY^IXYuL-w}s;WV!Mzkm9 z3pfqOCV#X$*WPgwY<|VtytUf+AoH=r=OR;{*-?69Wh}3Osc}DpB%#);MuK;fE(JIS zUDzK~@`Y>ZtwU9@&VL$%&g;Qa)SIJ+_S?#zjXVdh{sGPpfNJ6J$HV#V$`OO-Y!OR(~p1- z(tA5n2TWZ9!Xoy1Cxys9M0tkM`|czmo(6(QX|yGeK@8~}Gk|zO0;579mc?$clchd= z)K(4NY_43FiY3b~u=dgrWjL4J8O9&_x=X~i838@GB}cSEv3s1 zSe&HA9|$DNCm)fGm|Ow6)O1_XsV~Iw{9JCY%0W9eTCR$<;tx|ujbRpOU}jafDSs=D z|7r-l6I!MD|Be_xnOJF+PCav$9EeLDHoOG z0j5`(RV?aHb!+LcY0Gk21*^9>NrFT!1#D$QY~0Ft&rM|d3Og0y6$=!WSi=al!Z8{J zsfilL%T=4_ArEJUbnA#sY&QnsS=MzQ3wh0LWkc^bf4F+qKE-|Xv-LuqTGBP( z&3GdyS%mY`ElI1dZ8#~E+pLBAPGF5T44-RRy6^3>V=H~MXoKOSnHB@T zqwun!Bhw4fnhDWyJH$dpN#a*ed*#=aFO zw*I*cY$O(g!;qD?m^=l9d?`|a(Yoe#kui7r^LgYw2e-N`IWBHFqzw!&2pn6bWK!E( zzuSf+_N@CD?xb#Oyz2j6YD}B}Nd-W;Ea#31xJvYSUe=A!(O;)3>zCLo{!$Yl_zUyE zYY3BMCP0}iwIYHSdoorE=^Hg0%vtV92QSmv_2*~F7T>J9;WDfdXlw7{$ViuvvcAga zmmkN0lOX02y6&I!E0FnfVutUHzyY3spRH7xrDgP$8 z3*Vf+>v}o)(%a8{xMG{)+w|ojNk%D!oc8#~3|;X_9;qOWfbKL5XV!(S|9v)s43>fr9p$yUYpGpe7|> z$h!L->MS5O=rB0G&I8=!p(ec94XEXlfj|L2k51)2Rz8xKZWeti5tx!1G{N2PJKtMqXoGtS7J<^p-Eq1#q7dbquk0X)ePG3FrPY%W)naZ-Haqv+ zq^`IV161u{$)mtluvci2^|_;G2{%(CG{6J(O}J^En>vyDl4Pa)-mgh_R8;drUBUc= z*a8&A0VQQjNraV-@zu;kK$ zEon}!%R)THK$)GqDxq2IJM$@ zd5(#Jk}wxi-_XssePAp29rFk@5Y1M8ARU~HV z8Nm#~3=;)az zVYr(IPgMH=BzA8T$?u~Xq~u?K9x{~JpRpkYO|cks#tn^9hDFdgs4jZuad3SHKq{UJ z-ec(oQ9&>-VpQ?b+LD*^ELN9rjBM+~zqoG011dTAei?48Fx&HasN1KWLJV%6l&_dP z=gWXm34+C!*d+GGye~L^t+olr1)ZU1i;k6r>ZV*jM7hQ4pT1=v4`}M4Cfe2T3hg9? z+oRtFvW5Z}J&WWd4`&&=ZglqgZ#Kcwt8Z0#&kORe==X?twI4FGwwRri<9Kzkud+$t zrjG-R_c6mbDAsJ~AX~WNAAr_4^+@O&|1!+7bhz)R@8;Biu9TYvAe89(NZ^c>-<5#? zv70Uo@n9_|^i1c%I$O1KcLuj=s-(VBE~ob|Vx!?;Ms9nO^f|&_G5XdGng0%0wG`t6 zhkT=Q5jf`J3bZiM7`7tND=b^$5%E)=v$hRffA8E5z#wyrODrW%3BaB3Gk&RKxng;r%H zRR7qCSawN6Ha*17CpLoTnb|h${7Tg#5Ak+3C{DUWKffu7#&&Vfx(4S<&tYVxb2dhv zE9e6zOGK7KA8i&wE~L&EU2Vo94`pSM>j_5tmoOU`};@ityU9r(}`)9&4H}nDteC=jt=;UQszB^51YOE&287`?u zMmW~;LNdVyeD-A33Rt)FZ=^2u1$cf_HX_kG*RBC5)Ab2_6(49$I=&r8MijrtM&LsT z*!bWChciev&u)UOJdrGcRk@c?ElC}~33v10Ybc(fU~u=m?-ZVnq)qyhBosRNOi_Bn zJB}Pq(?lq}LmIwcJ716^DTkP8bs*1!ICh=jj}#}#gd6s~Rhu>a*8qdo+c4dCU`i^y z-@y&}YVEP4w`F2m^6hB*Q$SJ3F{#@IHn_Pig?#gZK-uz-mq4=)og**WZP1Mm}&~13_C1T(qx# zO&qilaYq9C!Py9&0bl9IxtHQ6weMZ(-;qXA)*URWo5H}g11^-fQrCP9HlRwGb6{MD z{6pGxT{8xkIXo4PoD#BC?*h!vb1{|g5G=He+OfXIXgrD!p zI2x1HaWUa1(68<%gxTS@U7udX-4?B%t{5lyhQl1J3Fz7zm~J~EMt-gX^(88meit)l z{6?-JF5y_1Ux+&}4HAv=<$dD5BVc=F2DvVxM(ejbIc>R$0P4%|w>J+y_aOMsKX_T$ z52|FCQp*31(eLImfMq@<4}(MIk5G}+M&T7!Cm$~0Z9oFp;<$M9GpLIh-|$jM=QOTtntbob1cz}w4pF2$z42Y%(s#V-33hM`BevE@RDNTk|bRQK=6ko7q7!RR|LFa%QqKS1;9cH>wCatu89VgU@rt#~e`DaA@}ju)-O!}^On~3d zmw{kiJ)LYd=lJcmDbjGtxK7~q^rn*DRW$Xx7;Wi3N@a^AK(DALEsQIF zU0a4LBb&U==xybCdvlXX67h!&o#TU~7GQTZ=@Di^uvutz0{Kw*k zV)VbK&UOBz>(0ZJeYOq_kIa`ioW*D}*l2S!B_x z)!(-Or>Nax`1dL+9RGBuxM zDaZw?J1{JRIxdlxx5k9rLOoW@`QwJy$iM`TsSF@}?FPJf4=DbjH*cvDIbyA8 zs!I{QkN9;=RLu?wpnAA28y5kLVhlsg+_w!NLf-rBu4`vb_14nihSjADthxHvxLt!t zD6~q2hOI&9xBqHm0hw!`q$xo(z%8#z@o0wXEc=@ zlyU=51V|qRG{$9YJbq{PAQUY=H>3f2j}%(m+`N@590BF0|4Y|@A6?=7d#NzaQ%%Nf z07Z>}eSQk;SCb$fHnF4l^_cn!_ybf_xZnaCYO~GwBnl|4Vi(MB_JtX*+V;=Vi1v*w z65W%QQt}c&8V49Xo(V)l18+P~|B6Zvg6-z3$7gd?|r*R^S)JT~R$wNPnr z82@4tGt8NWndsixL7rC3enC^N1>j$ixS)nllnU+YW7xYn?gByC{>k2HFM#OJcE|3h zPh=Pe1@3mFi2nV^jWE+HXg+$iCSO3Nx9T0<{c z^aNx;Wq@46ccE z=CS4XJdFWBA}F?z==)@*NQBbuusZfUVb4}KItC6aVa)pK7cwirSaRZOO+Fk-QK7;z zp!h)Qxral@k%2Vvd!tO9nAD!D0mvI4{zRd+gS_V%tkI1XkCmp7pGL56l7=Y_K%g{V zU^%B*ABuYW(^iDa$aqTUWZz-15uOgc$}0vChoT&j`mlPE%NvZ^YdP*>qH!7$(#4 z2!wk|H?<)o^F3=2v^XpLqCx@WEe~!UdI1g5n~T7*b_dQRRQ)En#al;1Ee7u>2d%Q@ zdKDq!gT-`gvmKJWQr>FdkAW$K*VAQw(=m!XQdi~6#5p-BGrG_I1tgNzr5$};YY=gu zY_4srVu#epAj*5@$tnT`U_T}f8z()6hr;rb9CZgM;wq6NriB!|!0zGV~!Q6bw5)X8e zpZXh_(Z(@SGj|TFcSRj5X<_GcV!XV_w4#olVqSoq;M@1M);}b-aXqPFa_l<>;9#-> zXs$1!WnTKdr-pK8yKM*s(W9ZhICu%GeO~P0*-ozIt+YMNiVmwyzn;5%>RLi0*jQnU z!p8;gj1GWa2wxXkFp1Q;dyp=k-`B!uY?En+MV9FV=MrqG>IwtK86j5y8AtmdI5u%W zO$+Mkl*fS19?pG&hwU14Sbsz&bsRf>36h3mXJre(XAYppjJ^EW@#!`4JWHEJPkE!j zwL~~?Ur`#?yEk#2da_jxZmiQC>XQ{U_3e|wRwV&(6^ z{%dnXr!~nOZ4o>JOt$wchUE$yh|?m`lxgsc>@k4a8m9wJ;q`ha;Pfx{=T0xmIgZL{ zA>@>~X&LGty)&~Ew5v?Ngx;4(FYn-f1}DYCn8;q-|{WzI6|cjm5v1y#7? zugC(QHWUtz&9K90LCSA3A_DLCcmosS*tSlb=z)u*ubJkAIoLo-<=BHEz^=SlNH=qai%U~_a96) zpg(#`&%tP_8~3hdkLstY4>Qip<$c4?7gk}*NbMr8?#Ay#;dTdKuU?JCLg*fUe%z?| zgmMw8$lAE_SwFHYz>Vf;Z&$eVj-yKcT=1pj=b#V7VCCM!!?=kjp5PNaHs<6DL7;$n zf_8c)pRyb>XJRi(eZhaQS5rU{NuIN#@KRE%=i#0kRNw=N^fJ7ilWr<^XtziaG4Jx= zuGeak@ibzr$oT}*qyeh_1$T8Pej^nPSUzOef1v#7un)cCD>{8U(_NRe(zvw;L<_pB zTF3f9qqTofTYgYlAo&03SIGbqiZ?`v@YQ$6xSX7agpf;B=6ithmE^31c#AM?PS_4Y zR17jS_f!Zc&JH{OJXQ-1{q$c}SPm~&grzE6_ZWCF^u1(X)s zNl16cttRL4Dn)~>LUk*5#o-Wl-W<0tV`>`oj0iOJ{}``!dvtw+_6(o5~7Xc93|HU@v|1WZ$!c&c+cdE2aVP_BIHsS;0i z)wkgfAeU@M23eEe0&1Ea}WF3#KJudj0@zg_9 zDXzzwfZT>*I5Lqe(2Pm_(R3Pkmk*x=2FhDWns(7~FFmQ-j}1pugruTv1p^Qo+^9Ir z;OX=N`EubXOD^&YTOj4xY$B0UxNIFJE=eabLnh;(*t$VD_vQt$()ttj^LwJ55V{{} z*lIS8YpBZ%DdXndnnO0!1G=)+|K4=+>)A3t_3EY9tu?FH_o_Xi=XR6nwV;$}qxmWC zBIb#^AS51t6W)`0_VO3JF-GS351?0Er5p&7DXl1{$t!}%^$Xk8oVkseS7L^@fnPWDJrWy z8mC7M@ed`E7RNp8YmH8Ur%BY+5iQ3tP4Q#u~r_eH@$9nxVqi8VEA0Po$%nTvO75UU7DmFu-hla+H6=o z-AUWOOTBh&X>7YgaMT^_{f8>sC;6g`79{Mb%Jk3*fHAUElT`Z$_ESB3Aha1U`wRHC zvYwyIZ(f+{EYRn|+frZOrjbXmB(c7YLL zp`~z4y9t;9mC9XzsJme~>GV>=VbbLl57}Yd_GqBPB`UYeWPj&UVv&=y=Jv%+zhmGH zWhgP@!HCc^9U;XP@cuc{<6q}^EXU*iwfLZ-QcG3WssfKFEX+eLSIWpk`IYERkR*=) zlW0!Mth`ZxUm$wyIJzQo>r%9~J(F4zZi*#($YJd2Swy=7H*EY=LE3EU`ayiegyutw<(LQ~FTX>&lA=rEkvIm1~C<~fX z+({9*N$`?sr7iTz)s3_!~?d3_0ju zF>+JS<)=3EZ$B)t?WdoH7PN1QQkVv$k&U$o^=Ju-!AL0mMB;HOs;TV{u9dg$R~2E^ zZn9igMcyV=<(*z~)>NV>fIT)+`^Q^;^rCI?PND+<1SO0gMq))|+}kj&Gnc<`M;Yj` zl-jAViniS89s3>YWYam2i0&(TI#cd#c_I&hhP!$i9mzgd`Gt9H6RIAh3ikY1O8BS?vedgLqHJ*2p2=lV zlyBQ(kFH;y`CHTUn_cP9`}bAT1_e%%i@i-2VkK@*oxKUtem0YHo^$oQg3zl51y#*X z0-e#_VF+sfiAl`0P|eT59V2PnJRGKnDE?NNE|L|2-M9pQmM8q{cUkRQ|K-@I3_yA) zLI}#U<7fZ+I~M4dPzePK!mwWt*AbBoW~AOsPN5GDvX1}WBUG>B<3t57b=HYubH_+( z^8^eTz>KJ}{@4HLH?VTqSI)UDP0c$+Cd#hnDxjD<^~V~b(LooCRZLH2{3HFJFwr&Y zzzMD@Ctc!%T4++bHAr7z78O7s-$5wU47OS>0y+|;q^RjA^njb))G@UH{R9B^z+NX; zg~M5xL}5-PUldd9rtpB#L!*KYIZ_;)4V02tF*vD?axTCF&?qzH2^f+i>}#Qq_oWDi zx+`I>K{Yiz8r2h?yVFk$(KU!42Vb3= zcry%4(sZtLRa|ayq==SDD!~UKcz3Eg3B!5?K~oVEm`D$`f%>l;}R6rG9Q^H{X& zP>aE98!R)z=bVx`WqRf**hqZ>%C4ISM$ zX_sywNjYmEiWTc=YR!iK{6c8%i-KEcJea$q-lR=4jgk0ytBsgPWh^rswzA^tkomi$ zF@%y|GlG1N#81AeF(v@pOPG!C>$lNYH+lERk7H>G(tld5AmW@Hj=fD%|9G}fb#}fx>FWd*7rEyWD{>-`!Wl11(=KLYk26OHjcK(Sf zZNZ9|XsHtz80Wt#6e0-;jbw1)Slcm~?>d9tp}XF7#L`c+;VG$=w<&8FO;ZXD|Nq!J ztAIF~rcux0?(VLOh7jC6Sbz}RHMl!08X!0XcbDLl;`s7L z)T3TBYV|$?<9&?SaSY1ogf4t5NzcsTVOEbc8TvhlJ`5c#OS7kcf;bFK#9ZB!a zXi#3PYRDNIk+wQ_QcZz@5yb;Ng82a%(ZCJAu(Q!6{bB7}9FDTI{dT3VNM8|}*l%I& zKH}~`O}hP7-8qHPV617|Ov6qUoS&;ZsdHhW83bZWkR>C~nxw%kHqq5TV;!;evA1c=;g}gCKq@E(d4VfmeerWgwU-#W@RxUk5Q~$u~(Y zB%wjVc^`%61pL4y8QzDdg+MaprWV7@0mojxZWJj#ELd}><11mSS9TtkW zV#o7C&ujz31nJCGNdOy_4;<%#0EP+ENcb8QKi5Znio$tQhu&6Lw(Y?Ipkw?Gf9r>G znib2UiGcF)mV_u;FNCZHbG8-yc#&$55*M0#Fr}EyADo9xJQIyoq}^-5&Ey@eBsx{ zXi^TWK+1%mZN1v~?i<@J-w1Iv)N=sEL`(FxqZmho!W=XQ?!>k?uU45*%fRf?-cp$K zvzR(LY}u!bgo;)z`y+a&rP|wUa6MRy{l^Wm6McE|Kjgq#bXcHvhu z)K^RS_9FakCv*1~JwC0elSHKIdu{4eZg&y7ii?jwS`yp@SQ-zogZV@;PO}n`>ClRp z!gQFmyJ{!y@qf}FyhHJHJ%yvM`T$N|d4}9Ed77})M2weLTl}WbdzQnMr9KruBE_?i zt&ckqrPUYycJf-6(X7zs6l(9+$D#ARshx5?(qVWA{s1mhRCLU@Z-aX4V;0M)_@svj zQSgN2OxC)p&*^~lEpP2XY)2)hiRf$0h=RphQc+h?`tCsv5T^6sker$#AHl(Xfer#FF^=KJPns$Uh)1-2O*xZx2Mv_wYu8ox_9j zUn5h8N3oC!Af2$m9KIwUECuk5d=Z!%FYP||8;MarV-=>yayjr14 z4`Zkm;Ly>7xY-$swfGMbIS2)beSz}BOhI2;otVg0pEf~!rn-p&Cv(;N|Pb?!UiS=%!YS0R~{s!ppXoN!D)|% zUm2{5h$`RWzLG`wOK9m{nwh!X!+7dfvEk!_tlrSzr413v5#7ig)D70Z2Ts40hpig? zolmKU{RxTORvn&-8bkLj72feLH}^n)pJIs=lfQ-)!z%09V8`|P*~G7-dQtXFgHoc7 zwv_Iu3p>LqqBds2BB@xSHF)b&0gh2n|lnMt1 z=C~J{y~vKx2Fx_~aP0gSj_qAQxD2z&N)7pup-^kHH?3sK=n5^dnGIb3DZ_^rDv-HD zDFd^Cd4!6j1Y0o$d=Be%M6EhulESQPnO`VS2-*#=)$e*IShphnVQ;N2#Dg&j>eMc{ z`|gPC2ChA;_=e+aWHT36b)qJdw(Y-Jbm0=p{A@J_`(3*Fj{mD88M-=j(TzK0{gxH` zd7Yqz`Ru6DHAr zIy|sKejcNftF5>=9kTsNKx+AU@;&-H-;T@JhlbD(UetRSM@7j=qq-lqSH99rb9o}$ z!Q)E8BMcCmIW3j56+lNTS0N6CVu;6W_H77z=Y;O-f0@6RO+Pio&TwHfC1ST)}3V5YAeUfsnF8+#sv{ ziFrP4n}{aWwWXN|^>g3H$ImksZd!`c#NR%*2Tc@yB!q5;un`0=oq^PcZDCo|-w;9- zrMh^^91eP6>W~j<#wPMdh?3&sp@x%w1+W}C%D9Z-t|h|odahg=EF@h=IQBBZlmKBD zIlPIY;&aiLi9KC|^`&SsZ=x#woX5Ha!e;t-apkpivQIP4S>Y{kR?74jmS66hesX8WJutlX1F`n}?l2LO%c389O>3wgkapw%fFTFv@ zJA-gn){AZn*&jE&3RF2Fs6Vcj1crA1(nxz8Rco|3_D+mp}TH=$tdZUrACqV{n}p~O@X+~-znNJBGg*WR^$O%Nq0 zVJ_s*)mEB<&OQzuD^ggz)aY(4nNfZAE;|rU*DxPOLPr#^rkf{2a4W7-gd4H3B2k;+ zzg4Pwvb1%*pyD+mflq04l7uPZ7f9+W-wK*KQG`wdm1T8z3Siv~w%4Pc$W`|RLd^kX zJ1=IEbQeo^(C<;)>6y8`4@1+}L+Z{$iI_v5WM4Hb) zoAn6T+b8fzbeACqrS%5FGfj)XVSQg;(JhP<)uKapKxP|g5nMXi{xLTxMjp-mjr*+z z^J;~`H{))HDozN$rZm}oE;rwyB(}!u@jQesi|Insp*`8eudpuxPy~OThZMB4uXBIs zy$4~iV0BmG%REK3rY#&KZMGV(H)c9WEX>~7slXjOO)#TqQ3#`TO_1mvEYFbj?8)jvay6Y_00Cn=-z zGimYIMy^~Ug=x~-f4=y#+Mk~$b##>W)}HyeB&vz7J)8D+GDs`Bik7nssDc90mmI8; z6|akRf2E;Qu1~uX6Xe&Jxc_{{h+E&53i30+&ZeHNokr4;bcOfUm-0eTLUpTPALh@N zn4gL(VfZhW;Jd%kBTY(MOrwx_|E34}SH1Iub5rf33lde0w^%4E`I;y9tKpt+!ZgyP z{75Tv@BmtZ$6j@Z%%hibE6Fd-r`jl?(-Fl6(hnG9TgY7PiZn?QuUNE68s7i5X4$3r zk-L2AGpA*Pl)kMPH{I;Cn+R~xx(44V*^-Ea=py@8ru#R8ItH$P6WisCP@L&lU|XJ? zYHyY1j`GTmS&c&4*Rw-?cWkYpxw1*Si|XI)L`dB*oay2`cv*jKfacEl_tF0zb7@19!9i@NrY6ACC1^e+SB{5Vf5 z%_x4LlXDHImXn54f{Whe{T{mgWz#ieP~!Dl2IUX3k&5Srg3ebbOgwax=XXTvV8MtK zk~>aSEHRVtKJ6-6UoCGzxw^l{Ss{%o&4{S$SoZ(ebgX`#`kUI|6%3#`kOv&Cd1BxN zx~jGwVZaJDsgE}!j@AjJ_6M;~K705rOB|VChlkk{-GJ@8AEAQ2;rzE+#;Ni4H>)`; zEots{R*j^cABX(06APxjh5QyR+yh1LovI~zaPX*6X>4#8UJ^U6H<#!?g1qxYPMo3> zuTYciH>;J@^na7{gkLhz9N?9$=oT<9f+D4}LX>w_lG_E>rRIofZ#OlObos z2BPgCJ@e;-&I+FKIJ-LHg|8!ge62K@<=wx^%>OloP5rSJkEM!3i`a!27 z6E~wYw_{U%Tfiz?>l=|(b`%AbX$J-%U#%`PaZE%;Br|8jPZ+g(C|V=N5GfPCwWMr3lTKB{$2=8s_BRiCwL}89T{(m#E+lLF&2eu1i}>iN_bgiZo)0NU~_6W@(o;OwP+-06^aW5MDf?H`G~52-1Q5 z8D{b6y-;j0fz}_yf%PqxG64hoPd)e=VYgiGVL}2e&Wb%ylg1^Dq-&pl{DR|a0Dkb08GM6sxsLws?9}Q z3d9bKyIb0faWzqA>zwecl_(Sf04%~AJ(VZ9Y=@QE+K7y!(OlSMcrz?~0d5=;S64$% zrQQk_AT43=5qnt--jP>e%IdtKG;%WeTk+1g-)1E@r+4(_SNu8{)&xEofXw7>RD!gY zV{38J$V}q?&gK|7IH9p5HH>aeOmcJs82(`d0607ehp?&l05@Xemf65XIso7~m!EDCtMb%JhRfss35P(mG zOJ}@eNDUn(+>Kv$#NX4aL`-y-s6I4}s~5f{kvcN~&E&3EXnC!M7BW#E56HwAJ428c zk7d8pWirFaom($`^acQ27=U7q9QZQ`0EE2&Jy?7+Ee!x7ce`9&`tn=ineMJq_1@a7bz8Mg)r|# zuoOWSNF5DEK->U;4+aRrtQ>~3oU)y}bl3k?2XKu6s7!!K2mq`?08xPE7Wq#%X%KRt z71#^_2IYp=y8*gqfTXV*z9j{AdcKyAaRWe+&~pZmZ_a-}8$dw+1^`ro-2fQc1dOWr zIDlC@V#e6v0X+x(;f}Kgpg13nPwM^?eGUOY+K@SF3adtS8K_bKn7tUrKnetQ!LjS` z82+F^wi^KOy9s-B0B-93|1Jjr-Vk930M|A7j5_Q|`!WRHjgV?~zxP1iQ-Jmw0AQ{D zI|91oxVy$vFstIEbqlNq(dg7B-z=0J0mNKFc&q=;1E3#N#7u^bMG*V#SA-7O8Wu^; zDA;Ko6*y!)(QXL@X^xQpRRhr2qSirEga9h82vO#l7##*;@RWf#fgLiotHe+}L&5b{1=V8gi;fK?TPyKhvJ zRE2>}BL^g&NIk+*p>6R|L5GDc$i|9a_ob?XV5<-`O@o4!5}TY?$P85q;13p{8x8=( zG{yjHBm^~ALynBVnHm8O(2YplgK7p;F3@712^C){w7CXJD&!twA~rc?z<2+@Gyf}$ zSpdKa`Pj`GlMcFCo+4FcIPW_t71N`D0012o0F))No9{`6bc~SE!fKM#VEh4;5+Lk$ z^ND|Oq1VF$K`*r^iy+y&p8)U)0I?NfPo+;GrGymz*Ek$eU@+B^mhlDv&>(s}=xJfn zP}G!}S&%o%8D3uXI{YUwXmJadLIS3(T&V!ZKeS&)!m;3@@WcykV4!mg8~_0T88HAR z?Eukl18|&rZv^TF>489Kk^Km()80&uP?LqsqunFQ(t{H3edq8D#n$JAp{M3Rx_Lt% zlUYv&(rc8@R$fE|12QZ`DX^zQ$z}VSjT)J3EVt?(drt>GSP$kvhoq zmYghmw2=OJ1^L>nm9XLNtS3CMn~_HDpA3Q0*r2JchBB-6r`{^#7UfT&l${D4ii+4; zAH4ga?@p*D42U-xVVM8`%V^yO-~khY6h!1r;LtiWDT%W4;dX^5__zbVTp*k5gFj{a zk}YG79(@+5g;-}z0@f>lx_|-UYfM9jveBvGD9b}52bKGcD*3-B+)VW3)xSvND4x1p z3uqYfjO7*BigaS!S?^Ia!hL6`0p2!v zHU{D#a$*30xa%1L22k&zV-Eq=PXD+TCyw5A(inf#xxdk5cphJau6>Q&CX;nU^)Km! zH0A>{p2Dv&zI((P8o6?&^wz@t;YB2n&JBJ(Ge#%w=uZna*$P&Vk}(&GYwG6f@9z)8 z$9g@w)S0xZhn+PtiDQNDKc8tZ;BaWysGQUob%n~V@6kqRw9{&L5W4$JEwF zoKh-Q^vV&!O~WEI*?bN}UE!32qclCZsmYnpdyn(A=iDW#bD6_7X}&)ZdDjudFz%%Z zKR>ik$)7X#^lP+u?>At%d`{Z*T7EO}vnjq(_;!^5u+jmDn*bK|J(BcSfjV}O*dA2> zdAyd9DPC}}3-W)qzQ>QK0htk#ZIY&a*z-E2iH;#I&gHCGj40tC7y^2PwA`+R;hRiM zj^8b2YT%Q1Pg z(FA=Peo;iC#dIrlKOQJdQsBKhDfvQQbUM#b3{g*gJOE)eR<%!z`tCAzN~XA4k`;gb zO1A1@4mDpL$t{1O``k`f>+nblrF~)L7-q0x5In+ByB%w-w=5rFFX^xop$DOK4t*j< zW^mgWRia5Z@=u;sdWx#we*D}JUJ(RR%AqR<3`UjIz1ruOTpr(@iez-bc;S5gx~fq2 zv13%$>tO#AzPb&jjqf`nP76bk!PcK^M5}jnn`H-pQs^zD|h$07? z9Ege-Gjp+m(!NBoOnXdTnNx*l6jYqhg6wAmAV{J376Kv3VspCF=Bwl$V~AoVCeBeb zf(fX$5&WBifnZv=&=QZ=RI? zV-lcEQpv-QU9+7I_1{CW#oB(XTXq?EM+r+(HQ=G~cyrHTzx>lI2R{?F%~>+dW;Fz& z4+s7=j67_K&&OY=Ik9u{z8<70d>8n2bSh$*sx}!b_=)nkQlHqwO{t_Xs0as1ZdAP> z;qyDpy+1#GyzJCiJ-1sC`ulUwS@ZfJ8~j6fOd;i~_-f&X24)l0gWcrNjYcEXI&E|~ zfzw9)P_^OjGe6!)V4>`{Vb%Kc`D|j9Vw)J02 zn`u|lb8anaNCBxqo#|`_tmT>JAtahTbH5T1$wB9^r!gKPWAgkz&=@Z7MScJVGVco$p_48(8**ZXH%3BP3sL4IGK1 zjbAesnJsE|qT-66hNz9(iZ;BT)eFyaJt-4d6a3g4yayDLiYb5WgbKtnwmwV2$y;N_ zAR7vIt#vejwMb|Hq6D}O0ruV%=)4Njl)Ox4E&iCBxO(-X&C-ap#$?q&=B$enPn zt$o2Z&e48mPW$V}m>eEouvE~D-Ooc;aQSYYVe{`lxnw}=@M*;8hhyb7p$Trx`&s(y zBy$7i$TRGuGmP$Sf-0EI#-Q1m#+D9Kd_6;8ZKw zC(?;J=(7tvK7)LVtHQAsElX!dwO-PEFOglm$9bAeHxQLXka-A54DAI2`Y_wRFPakZf%r6%SfD(b;55TTMroPUW6zgwe)rpa); z&p8%)r|;xD?hVl;Ecxg_#A)}3v zTDknS(qjFSe}DmHvknvZ?-`6VZXVyB#Pq3G#htUyXmqcMS;LG&r8w(Q^dhQ+a2%2$ z)8{dbQ{CQ&b0Be7V6osbEcM|{H9%UVhM7=hE)-7O2c8qRX#Pb@S?ctk)e7s$2#)Fv zt?UVu=KUyqhE739(pN?3A@w`ElA;&Jr%UZ%g`LuIu^aK&0&`f>c| zP2)hdW;#sr`*80}%4T?>#Mj@pFjLe9u)w^MtBmN#dlR^K+61Shv|_6&1OEEX=a1vL z4q5bSRLIDpVcczjANAB@s@8XsPgoPa&h@4PlHpaw2+({ zpGA3py2Y|Lqs^nl9oEx!-+=~w2>-{^cS4V1PO`j@wwcCUai}isO0#SoTtWMTO1`aq zak{!ERv6EbrA&BpyEJ$Sz`5MrrO@MN{^)(Dt7{8wr=e1{Q5V2OavUP)GxS;1Dfd&%hDO6WZhP;HO=cQEwb8Up)za--+ULi-S*nnxP#Ov?X4}TylU>g0OTjXKcSHEyz@7C~s7$F_LV+cN?!6H|1OU*8 z#yVbj)y%iLL2X#BK^qMg`|EeKpRrxq+xzPFD#s;gnl)|nz ztUWT38u6%;dX^L?vJnM7iQaE~!dgI8%t9uf`}g(Kj*=; zD;sB08NTGL9hA?+r<=mBTbglN%q19);)w|_%A}B)G3ZUham5WmC!P(4nps zVgBW&olVkc`tKC#i>L|82ZZ zC+r_-)%;8XIoo)Bmo%&)R+w?9)HW zs=E4T_#K5j`X>|ha1z`>OPP|b-8ut>M_B;lE=;6mwGowtZa;}kVUbpl?Lzndp-kU? zY|O3Np4!e#&HS{IL|Rv0>&eDb|245lE$H`h?H zsR~a=4{4O52p00A=jUwZfOJvv;`G0tAjxY6IUARvg0P5KgaNvi z(~{QHW2L_Zj^z%l0lYdo<9Nbh9tdcFD`9~)$RFR2s+YukM5K{J=myoII(u;V!^u?^ zD{mN2s`U_m_^N&Mz0ir9n5YL2a{jm~m$MBfxq|WOudful3O83VPBokm{wQ*hcGON8 zGc0DJ&z}OmBL@8Q+(U1u3#HnmkQ z(cvab4_o-TcJ1(nkcmKCg_;T6x3)v|Fn2!H-LYLk#e3Xnn+X=jkXQ)Xo%zhS!IaMz zO?Y_{3x1yiD9+eZjeJ9MC_w>{P;6Y1;Hf zi!Z=w_@(WhEfZEFv(d$%`Vq?!7#g;FEhx7V?;Re%D zaTI%A7usvLy}Md2v?HglWyO`TW`+4=whP&0q@HMCUpq*Puvm;mmilVX@G(cbV5o6= z6E_3q!A2Vb*r4L7LJdMYip1FAq3j%D>~Xaq{M`UydXCF+h zJQ`y0@6KcfQni37_YiP?6h2{N(8!dF&{NRIlvNP7tL>(aXTUUX)n9B3)DSe?HDC@| zl?y_eIYAcZDlHfeB8l8C{9LUs!H^BZ1EDsrE6H*{ z{~3tD)?Y%Y6K-;Bvr=cnC^auC`hQEa_GK2=oQg%)DLAQST4DAT)*P**!rqU1xs_NWmKQ*$o;0*e@p61(B=10 zlA-b7M}alLs%f^7C!JV{B&$~7)9uT2Iex@U4Kdm{q>s@Dg{})rvvS|rFjA41} z(%^;PhCeqA(-5v5$J06fz+~6z44VyFnbGsZepJsKuxyvRU{W9F!l)3@#Zt-6m}(8v z$PBh=z8x`0BTPf};*tPxYiQsAp1$EyN&9cQqO}!Y0fbL^`gx!4^eTe4*WT?2P`Nt6(Rz z^SJ`s25@vu%TI<~Nf&zl%_1s+0FdGHI*xE1rBXMZFMkQ@wcbOmMRFh0BWx7ux0dpG z)uzTFf;_=@PG`oc{Cph1xkf_gvZY$R1})O*A~_a|z!Rrm{EM6uXOZMz-> zvB@+Eu-&0M=w?8ajnqPv?kCa;Iw^C4WAU)*8J1|gDN?^?WyGCay6H@O6ISRKfnjHr z!5EHD%VeNxmYS8jslQTfV|t%eIWQhJfGCBbd}?Aw(&==Zf{c1|_E;t5%45Ct$vnPT z!6ld8PO7Ynm~Qb9MPvSpjR^gco#>(BUySF=QTOYH^)DJcE?-7*Z-jfe1@5+_5JDYI zY`Pw9D@k+f1qtmDoZ!%F9hTp;p59Kx!Nd#Y#_NQs=!O%I01z>aZ5Qr6+>oP&ye7J3 z2VtQx>!{`a#DQmB4mZTw(=`##s~)huMv)!z51vkO1) z%UQbmPf>zZ{!)~`A8q9E`B=Y$^O!3&*Elr{AU&Y%$~k`mn8i?Qgv>iTk-t{XO>aFJTg}iGU>h_#3DQM#lH* zkQbkEx-Z@9%K{@bi_xC15iL;9v)4FEZY}`gN7A^CBbR%)tp%K5SZ>Pbv=()Yk`HA! zY>xRD=^c9rDyEilJ{)^TH>1R`Uk&j0?vtCZxxid0;NpucnbI>y+!3cOP)|F5wZ*;9 zW;l3YXR#Z1+F<#2Aa(*1ZFko5^1V6rIg?p=K2TR>u$Cb7duf0CuM)pAVj2OKpiAO2 zC*Lb#r}%))afCPk2Zve@{%Ae8XuLZaN5@@iv@waUGi`GR6jq;lB8HL%fAJXt8YZWZ zEN_~D`wUjk8M8z?RE=+-fKaMn9V@FX`#%@Tb8ciV{#g@9!iNw_Ce}k?ynBtun3rb9 zTL+2GUaSE|=&OVxhpfV^++7S*?LnNzt|h6%)%M%ltr{@50kr5nhH?2*x1;9F5k04G z?i-gXkL;*FYc`vZC3rC;FFgY^m|}-|a8X}vc43e*y`Jk+LhZ5BOY-Rj&#K>c*HKj0 z0l1Byr&3bT4;^G5D-X8-CNPbW;~&8)Y92u2{^(k*#6>Q0#C(FT4TZsp7S*tI(_z05;FR{J%MMVkd4NAK?F{Imhio)9a@`Am zXLs$NY?N<+tLGd*g*wo<4Qcqf_&;PMdzru?!-d;VCuRN~@CWqIwgi6myGyq3l8F?l-fch9drbL^Px z@A-eFPDUBSeO%pH{JyaZZ;}waPpgxCg*~gFUs_{uY~?urg|D`Cec`q)Q@fi1?6-~8 zr#`ujfyogF@Z|R4A=M$ma4|T4>S%NISVVnuS_ne+U2Pu1e=%mVsKkVk9Nj8fuL;~G zoYH~X8(|>GJ~3glsHhj~-Do!vDmOc9flhh#3WQAC+V|ja=kS`0!Kc{?JNxkC(nxvR z#y|}m9UGdP=|tNf6!JyS7-Dc9R}Um#KEvdVEfPTF^61-LO631FXf;Y*6`MU2gxI~q zud1J%6EBi)!?=(~_x75i;Nh(!tcHYbj&t)v4bsKG5r^P#*gQ6;E)7${kC{uH=RQBT ziR9aAYily^M$VgV)i7+>ZP%ph+p$u}__jBO<)%zs03<;GDwlLVu_{0@NV5A)hIsNj zm!jSyLns9+KmLMYSE*h=@*tXbIRy}vghZgn^sBgV-%oaSp};cz1-}f%TPxZBkj?n% zTf&|t*qmF2%#@e2EsnI=yD41|z5PWo>~z>G2Q|`VvVYAOg0uefb)-9LUvenPPgNyr zV@~6bBsgZZ!0)8Sc(U;+komJb&t(&vm*7W+PpBD!!woi!(%i05x zuNVJ!81wHntOEl5!`_)+x?9**YvSTn$3~*M2GX?DhlNK{O8!}4eTi;Ia&>~;Jvv4E zpV2V##;WdBe9fsVgQ{p+DT(xm=q5KZ*}imSMMO_M>Gf3n!2| z10wL}$(r))JkeyojHn2tr%c6Wq5Cs%5VA#M11#bwR9N-C_2e8*My&X4NHRU=#%!+) zr-*0)XSsJvhE_(S?*HJwwWN$m{eo!FmsRng z8?Ni=at6|*?vxz=*jeB&Eh;*}J^NC@ml14ra`YLY`ww$9sdb6Fp1RX$xLep-zKdQc zYmL?(aU;U%R8x)bNK?sTv)n4{P~L)y(aqwl&YWMp8S?zw(2Mw1Sf*G(_A2-xcwyI* zf4q$|#OP}`;{d|F46_u$%e#SfLwY6Eif-sj1tkp*fm=+;N{@7@8o`HYwG>jcH#xfRys7g@Dx%0{`=YYHzHxB`zb93gjg9_Or**DDq4P#+-=I(ZhU z6d|S5Y67_VGt$zSqn}|3NX7hyyEnQ$Zy1YjI;MH{At5NqXim)y7a`P-thf zq|w5zZ7D~za(basHu$`pJ`b+9j^!<3kHxZ6t)33ymdmZh@V!ka^NE|5uroaD*tkJe z1hHOtJ~qE$jG2RrdbmIZDZ7Ud@;*n@ER=uM( z-JpKmVOPt-AYYrcd~3M)n8CRiOAQF6kPG}TXh zfPX}zQBID|V(Ym7$dgSD@=&j!t8d!la!77S6J&1)k57J?BrNy}GC+1#q5woVV6gYh z228rV1w$s@0p>`Mhnb5HXXgevf zJYl62gf|&n=S9s z{nNw9pH74%{2wihp5464o)l-D+}5^h24NCds2J|0I{3O_);_J2rz{4eg>0=3)j}8?=_Yd)gIM6!j>y&Xk=uT=KN-y+tpSM7?=ZP>^Q*o z`om(87=0xEB@eL!l}wHFa;VzyEx=u9*&)}z(I4LITto!vh35Tv#5+ZShFt*s5PB-o z`0K9jErRK7cxyTG84}X8AU)x(9CWIw9;gRlUnB1gsf4afy3&xW$v1|MQT_4Fe z7(RUzgh1#|D~M(D`kQ`0ZrEyW&aggq1H%viSjh|C0BOZNtbs8x5X^gtu)5=8FQ)iy zg15tRzcO85)+~Etve$C zWN_Va7}-`>EEm#Ut^WMOyT|D5QJ;t7$c=3TKVmGP`eK<>1Wf>+IXZ}mk_{{6kLJUH zuP!AzBRYQKac;tV&AH9!!paeH+DQQbv;EB(1TPqzO`UvFH9R;?xB+)B27N-bo3H>= z=6hqTS`79m7q-dW<0v5HCgUo8Sg;)!)@kHZ(%P{7ilR6gSjo= zkUc4tU|6OoN`JKMf4A!FS9taROwf?$1IJksc_g@kxHYk>$ckjxp)MtH3_gU#0Rh_4 z%yf~sOqBTPp7fl3jDPzYwbuk-)L9P&F!GG*1$Mc{$!ubqU&YX_?w}qrBL<|O`$j5D zcW6%;rnTZAi){%f2tOIBe*j1B$*pFmoibMlaDU)4%#7eco=$Y|g;UZq6csVj)V`0M}702Qg1e6MvAb zKqYH3YH$hYr(i#HDjnEBNr^M*C|rGqPjQ4JsJ5nmvPPH4^iWIV^SR_Kg#NsaecH@{ zB7lHhP5wbp&4(IJssWD(0-$h9aMOG#1JL*ougKu5kJ582oCg~1M58ow`yPIwve4_@ z{=N?~+NApN`%lv(w{2)18+x3ddc`#Vv0D^8&WQ2|7tAE#fb$0F(*~S#h?fQ>%DL;~ z!A~{&xawaYI`>YQcRtI>D?8jVZAY%K6Gy97;$VieYvQYfsr45!6d7(VRftfnHL$<0 zrA0ckflWueptcx1@+Q`L52<$zDP3gSVvAcJ%*%nWSCR-lc?{-f!;cma{h4=r;<$8=w)l*2<+8n>b)td*2Pdw=uw5XqqB^{OzJXZ8_FXmRs=|N6RUT&# z012o%Z~G9+C0@Yzg@Xtdc0>Are$CO=NfT}u;o!ZPcHO{<|6(5d6O-7Z-`7R1 zq05Qo`u8Jo^+CI)vRtofIk|o7t(rWG$p_ZnaV{Da*^^D}*$n%{ciLh2eZGFI355RA zo=P9e(V8f7rqqvR(6JqpuvJcvmkBaHqo>Ro=W(yoI9;a@Tkc|@W|k65My@nvVvK2T z9f0=eKtyF?6oC@eB=s0*gV%D{X75*zuw;+NN2q3h!hk-Y9Yv!%xr^fD!i5aVLRPRP zM{3)U&})?2c2Uy3SvU7EmElG2zox`?idM<~rVIYI@>E)J_Nlf{4rF9OI7e{_;NHo^o+&F;gUS<7kQI`*1HCK@`Vm#=#qs;kqhl ztY$96*(Z>|wl;%Z;CK*Q_KsKt{q06|X~9I~<1`H#P!%~_hT$IIa*RTZXwqX86P8A55kl4DtqIdg%8;9UpsH`VrFu= zo`d~IhHi$L68zReX3=OrJj^l40$Nwf8eB4#?;-D+-QHmt z4l?2byH@%ICpRjkTY5=dg)uG*req%wSZni;sI8tNy_!fN{~!6NHcgcUl?b7UuX>!N zk&eoZ}HIuz(dKous4@9tj~wu zZv}U+NY=Nf?0U8rSJvQx%h@$q!m$9oyDC-p5!PsU3N=ZwkG` zYY&hI>sq?l@nW2Bw6rdIS5(xMOEBQfXTEe^pkE{a{O|2gQ8b*y`yhp16v8GXid(Fa zs&LM^%{vD@F_7=kN;SX&nFoQ8Ge1bDYq=u)P)c(dUK{3Sup~+SjDr}hSCDAzKs{Eu zC}KpgmaS8kE$u7iDH!`e0ZR}-0BvBsg4LYpxBvnKKLV0yZA=v&4G;b7)GoVaR}kzt z^qp!42Gm=+_TC48&SexYrk*HP zt8-pYQ^v~-j{Ly&9;JSG&?+u+P(ek zFwVi&urEWqr@d-@ou;Q#+(78#S(u%005~91M5a)$2c`e0!Zl$wcYXL{)}TX9&v>85(5(VYt^ z9+>cLLD=?KKKjb+jY9T2v2>fKH=EZUY@Sd5JYqWy;epnTad2fHf~;mfU>wAm&W*Uo zh*t$Q-mXePya{ZvO<1mH3oh-X>z(>=3^psoJ`8bHeS8n|+E{a$iLW1Qfl~I<56JG2 zMwq4tOZdBOr-F7b2|0z^)7i>&ffmZd$P^#5pLo&ZMG90B8)k+4Km*Ztqd!|R3uDj# zJHE6#bZrtQ!6UbjCmJMk;$-g~)1QU=*ONHD0@#7`-5O|Zx(rN-3d!yrL%%QwIl0_p zF70`3P6y|mM}X!?Tx%s}$UA|_gK>66k5~DA$v(sdqPfjx>{52O-1CwCU>eVM1j=16 zmh2{Bnnu52CrY_nQ^5CxyUKH}>zMe2o+)(nvfS_vFd|U#jJhji!H~gxXJrss7zQnm zS(u5s0YGIF!G`e>L$Oex+gvGOS8-LPdG?x)XLui>&a9bGuPC;BJcEby4K9if6IefC zrD-*=lZ~+iE0)AfjFYFz`e=p?7`dISf+Z{fE`b%ufB_YMJ+);#PgGz4W8qInCBdim zG;UD^^}gJw4#Gqr0fTZ?9LD>~j_pUlibGItGQlj{tga`pOW_%63ak08QDaX~hPW0e zH~;i4vjT9cK94?FELXSETvAIKlPqkGuDK0T)W)pJEIb?=N~*ZN^Hn#)Ew_Osmj(MQ zR(IcxsmQn^flfPDZF11%_xCdN{u3t7(!8EAOe&M4bwjB`B>fl+TGla42A4V7t?qvs z?{h7r#Y|Xy=B?Q@N+T`?u#&W{j@VL23beEU2Ng+Uw~{C_;w`Zw{J*ro-J{l!%*0XJ zjr{;HHB{P17+k~{&v$nmR2;A6n@W@xiI5exwme0^R*S^)H(uZ^E{QnRC$WURq^@ID zeK~xU)ex*rXex2md%+qam<;H4>IHRRNzdvkZ;mbF1trFHC&Z@~jW%%$X=SFA_68&K zK?-K~3vfN&I$JKB;GKn*?=su0 zwt2kVkH}3Jnyo35w+%P|Fz#8w`dk=r(S=w52SAUDOXhq8_g)Kf1NB0usJ|UnoGPB_ zmUWM9p!yX*MFVMlYaXpyY?I#M246log(9l9d~}BUnY;i1!j4y#wq(@cap0-N2Ezs2 zL#uCO4u`0_o09Nb(vC852XVwPovT19QVW;RfznV=(J}|s<)T@(q4S<0{~DwR@iyt! zKN!)BQ528g@#!mvUsWd<^y6;{$%Mzqn?O4Z^lRdxK{yaa&k z&@u9ujwf4!zJY>0S8q?==8Mr}RX?bbK1s#2%`!ekYvdb(A61o)>-7ix6)nBKIE{I8 zGUJ@xkz=h5`{Fee0Ss~*FQlfyV;HmQHLkkHKr+Q(19I*FKo|6Kb)lgFMfWG!q`i)* zfEX|f?fWpFmj*Y%qFSVgm?e-rZ;`L39^`(yVFkKq>%Vw8cZ7dty8sss2~jB?hB`~~ z2o)Qv>caAZ*L!eI8GTh%i+$TExvPY<7Y29@%~dtE#%f0IU!u=blkkQ#^p4S=D=n@$ zG^&m4Kd{1csq>wvtklTHa(G=@Vm!iyI6~cCx$2*x`l5o8a5A-R|K+Zn^b#6oFt5cM zcqbr6$)U=CAQu33SCGD8qkOkidX}At6uN`MKD?P zTDLxFC1o9+utCfuXR`Auv`s3y;U7Pnq<)&lAKGzitgojG=sIZ0n19JzkM4_G(!Z<} z#>n!;ea#Zpzd}p1^aS?JG@TDcAfM2HN7jjzQuI3@j&qMii7)ud*cf#%+Cvn6O)VKZ zK9Ww+rumkLk`T0fb;3QRdL`p+LPJQEyPUtv^qkmL>Xbhk(5rw8rj}OD zz%gI1&6|cU=oq1Sseh7{z-WB>0h6~nfCU6f{fy;$d(95K(9HXV@v6i?{r~Ihd!VtZ z$6kIvIPf@})5tl++PDY1>ChZH?%;Ia0Ecqaf1|`x4SD8zJ}DC!u9y{Qw3!Z9&h^oT zMs~IPqGWrPFQ$E`CD-6)Y))=Bf%(6s?BbChfYE}r$wiZMBiZ8LvIVb7dLWbMQWs|8 zs68P{xlYZ9x8dC|%(hYh4&ZaQ10S1YqgSS5mKHz9KpDHLKIs0Og^Mty!m7nuM3@aK z`r1HmLSR<1dY{LHvpC^DlWuay2VT4;$H?T?;T01QJlHvl~G{gGLK08TBD8v?b? z3GP_EL+7uqu&nuPCf`J=62Dqr=*>}Sw|Fp)`t}n%>)ZlToMK0A0>-E7qreTGbI*Nc zb&uZcrM})QZ6+_H`(r6y4x-{3)K~o_rxZ&q2QVS`Muu%bz5ofjCCq-u*wG&XTJr2A za^1vH&a7Z_*Kvk=Hbf{ekh&=Ac-#X_YAJ|BHR{|1OFZFts^8@Y=KJSDzE0bZ$|2#4 z036VJ!Foq2iD-ST23phdE*S;nJzuljij#|Eh3PBhFGu~O>Sf$$i9&rkVs}TCz(*2b z{?uDn6DT1d$c~ecG37w%q7ocS)}apv%f`VtQagV(euWABMHHFr6aySQTGq*(JlmYa zs@8Sp$#)jL<#Nf{HsOm7y(BnSOyDD0P+A5dou`YN7}sm&H&3{|6rc@3p;$N>ay(Zq zoNfIb+yHi5j1VeD3dpxM?u`$Z+pb5x6NfHxsqHB z|73U?(Mb&0l(V*@F~27YvLM@S!~g@b`l6zkd?Z7`Ykrp;0(ypxXaso7OAlp4*sl}; ze2#zt$)7LL8nQjYRx5)qcVUDAu>eK=w)XCc@iX=!%n*cYs}*4q=L-h_t@$Ir;O9YZ zXbHBY*o?$Sf)I)sn%pnqvF5W5Ngk-HsAI;Gkn6vA>Dzx8U5UU;P$^-Hr5;D)q#F>r z|D+;*33q#j92eWviwoh^^7KqoKgI^00w8R}l(lV|U2IiaUocN@KD?wHWH^-}!shW{Tk^UF#I!GE zDs6D)tW*F21|Z%E?IO5p)^*!EmkQH*!6YKrr;ehl_)UHy8zp5V&;SLF)x?J+lU31w zWh&B}O0?Z5yK ztbMpPAil`9ZV^e$0_!FmGNEw*e)b!5{%|0X3~bON~#8c2;^3mq-;{ zcB3q{>87@)MW+Vby*WQ2OCKy`*l^eMot9MkdAxQv)FxL(vc^|#zdh%@f+z~w_1*eI z^(W+=`f;*u0(&;g-A3Mxe>x*vne+m1I8k>)(q=t})LQw(y-xF>O>7Ri6Y+v3Vcd2X zCH3rHQ}e87UNU>^a#|X3X1S>4^~NF$(Adh+_*22$Yb6nx;WFIC?nBP zD+aNNVz;O)d}O6?tM?^Yq6lFz5cdJ*DBecFnrVrltFdknL))lHrMox#c6bAswSGbY z9%64IJRKndjc4NY*@qW5pNLAFaBM&d^Q4CXMppm;GQx(kkZ+t)SieELx|Me?+rAT2 zmlb8oOQ%*K5VEB>Jxf1iFnG+Hs65bAAW>JFJ*v~0dgsE*;DXlqGBLn|^j=r`@ko^h zbMo(HBBCOl8H&&!t)+Yb9b<{45c^Od2c!y$(Wo>8(FgKv^5ige5j zse2^uyS$1*nHao8TI|L$>o4190%+dc?S`<3r&ql5oCp>AG3db0^`}+i_iIVAj~kqB z(+^KMc3>9M7?(8HZY09T?S&Yze`FW*@~5Az&I=clSH@|p&nQDHl+Rg*K)ax$`5RUK z9t5ZWdjmUGmNL+gLbw1u;`{)}#s@XX?CV8gDG~ed*H+;HuftJqGAo9CX&{D!lnBQi zX5#6&aLDdF_|EPB)417mxs2##@t{^o{Y~}tPh7mAMib*Clp}S;zGu%19&6dOkC(Dy zI5yVl8{PB(0#_Q$v{I%3Q+TSf2@nC?cjmMSh#R%t+~NG~&n%v>KFG;kwx%E^fKlzH z=>oj3luNzpJM52%V(;K$ONqo4-r9CsHpVGmqV6Tt&UG9D)bnQa=mQ`O*0`D8+qA9< z0T2H_unW)~G|z^GaUum(pz|%oumpxop%xtE`ZNFl2>fOPhN!GYQRLlRcx89M)yx=% z_g|abJL}oPbqNNo(N0m8^;42LDJW-7B-E5xkI%*P7~(KPg4@x7?k@5y{uDVh?9gl*Iv8W*K<6k=~-ex4K{9sr*nfCs+I8TVda3m*XLTp$jB0vMfN zk73hzkSk@7g!>3LFsrxCfvHViBK07V?5chYTim{P+M0#*e9j-c+Nq^jTd?mcIa_Pn zQ~cSEhog9T?54`fMQBMfB&H8|2!;@mgVLGMeE}T^_(yUfPqzb|nQ-Jg(3g1eY7soIQ&;ti_=udb|h&T(A1yq`g zvJ~-C;?sNxgLa?>m%sziVZ!y6!XHl8!iCcbq?asU91?%=fs<;;Ro{Ay5VgVsM**F`jFvhKh6YH&=# z4n;-4Dm`)Ya3!G^&=83sqG}92C_xp)|JKi~1rgS25%Z_{~ z^KN_*^9vg!0fT++wXkS`i+2xv2&0wt_eKXVCe~rgQD89pMH0DNph$@4tuRg6e~U$& z^gbAR;I5B;OhRVtLGZ9SDa=QYs?hwsEWxwRVP!{*Y|*ZEd;zM(EX=3V32bo7u$(n=bz4JTl&TEUX zb8m|a$>7&kvgD;Goj1H4Xtf;S6=W^pZzZ-Az2syiVBx9-)f0&VD{im zLbUJ_hRaU2GF7M0H#qw?`4IF5xcHwDb_8K7rFU*8EIign0&-GjF%J4?i~t9%AfyX{ zpSbn2eBhZ)e(XiX=>4B%I5dEhx-On^IY(?YNGjQqCJ4GK-PFL3oQ~F~Am7Pc^A}*o zs@jha_y?gZX9Ra``ZUUvpU08_4lO@je;K)diM!jHQmpLc3y*TYbsBC&@l?{ec!Fz7rMx-bP)nWya+)-hL$D5<;rvAs2vgm#R?u@Jfk@{9LFvxcPs zNnHSWVDxa96zQt?y8&W4wMmA-JP_HjFuC718yw*0=+~N#c$G57=dlbPJrC2=0=BEe zDkr>vWv_s8pFALd!Vs2XdAA6_g0H*~h@7JMsqFSpjiesGNt2EHO$|z}XLkuqRr(H~ z8E*;kRLPspxC<%sWK5C<2P_WC!r(-{vX0I2ecp^hF04f6^f&lpszKWAccBwEEmROh zt4sTUV~zd=uBt@W9CBJSb~$44*c9*ty036WtJyp{TWgy-otKJf3JQ3jSZ0qxS+gME zgrT=ER0S0%qvsN^!bKqgAU8dzSHKDpg*<4H00JxGQ{l!SpZI#lBB%sK?9edZG$SgE zU>v95;KoTo7l4FJOKQ0ptDg`2W}_KOCLjMBwvJmv(mPdW9ykSve{(CAZ6xBpaI~9* zZeQ~xG28sRmv3=c=Kjdd9_~{tO)1V=R-aEOq#ng5cRpF&TQ6Wg~ z<#BFoOn_>`6NIY|*9{X=E5KyUvXe`JmH?he0*;y}6qQndfe1@ruArY-?I2o2 zARg}co7YbGneP~en0Zmp`@0Ts)$NQt8M9c!-Jf|T!GcxO9fhmX@kD+Z-oab5#}Sqz zf5WjB|23y;9HYxHx1!CF?h@uiN@6avh_UqKIR4Qvk%%2w?vg6;gJ~(NBY!_r%1UYX z`A1bpn+ISuJ0~%}f48}@wX=NBY3C8P#oFMysrQhO++RQa8rm!gGGZ6Wp;5Wt*=eef zLHMcvn;U&3b^vgwbf`w1`t}tQicC1Z)yEwgs$9*4uK0Eq*h5hztf@x~bJ5Ql>{F|6cs#fZn-PFGjz@SQp8+F!Y$<69GCwG$^A-ZC-ELAtHJr z+%aDyNY}9~DG^yX1`{{eF~Iq)6`jRu4=Ft9NsBV=pSNjBn$V-7qt$cVY;n?}=Cyksz@WknY^4%-zo+Ds>8 z-S>0H_>j9K8>ggCY%2tS!Y84gCrAaufDeL2JJ(4P-R4*;p2_a82p#pJ*?G>;Its3U zToM3cLPW+Wg+^}d-p+&*`bTwA6QYN7z}H$3vvrhk%}>ygjGo8zj`#dhU+Srt$13l2 ztO^5>sl1gp;6=9OVoE|ouhmj?@@}(5`)gWtSEL>b**NchAkFMVx5`$jwrbWFCuV)? z2_bILIwN?>O4q8{W{o;I!+Q<` z0v)x${uV?&ZO={*L3Cy1KOW}-T~8o_Ygd$AW_@Brqi>6}NzmY({p`c3NBJa8$;eL=~t1Tq0(qp?ccu-v7Fmf-i%;-(|F$kP}CpR1B^d zyzC@Sh|22=5ZFTnq;Ik1lH-&&Ohf%Cu_?Ii8$5CK(-c{oGM@IYu>_k*N=b8;)dNo+JU-cg5^I}sR z9@7+%E?gurp5Tb4o3Ut0(ptaG@R(14001`3XEjRvpapX1M}B}btrFim9dp2TQtY~l zh?|!cx*sJ1KKOHkg@nx{$lQ40S-0ose5J)g-`CP0hZvT^kLQt|t!W@C$WU>pxsEOhWiP;x`K{{FpEd>@8IY=wry zZ`G)8?dJboe`Y0WF>ypDls}KdK)@K^`{Uo_Xg1c1hIN;fbm8V!Bv>6S%LDg?vO|s1 ze5Ox$9nyriCl!KlNi4L8&AjIj3IcIY8U0Hmo?1QiNYKz|cyy{Vwkc>%)-!L~W1q<; zcte8FG>0#IS9--10iAxMdNHvd`jdCd*bi0*u3vfPxD6_&+qdO_d7H<4xx$ApV3EZ| zz$W>G02nvG0PCx>5O@l~xpU>D_(?S1UPJ-lqa27=?1-wq(gG{0fH<%&`-H>PU4gQ3 zvercZ&{ltutfb}QL6dYc7kJ1sMZk4};MsE3x-K2MB{C^NEk!N6?$mb|2c=4QZ<8|8 zW{r;SeTUKv&>mCZH`#;j?Mk%o9ws-zwk4`e0la_6su~6C#yR&iMOmozHDSZ!+T`e{ zqDX-yj+joktM@nwNLQb0f|{GUg&=0HSvm^@zwfCaQM8E5OliZ9io91(g*U{D=$9ZG zi&<IhD#X%=j|DL8LY=`& zjIi7uIk0p#C*YnOq7Wv8k<|1~Jh(OX*;z@dxTJ}?lRYe_ zEd~)?vMy9`X!Q0YbiEa@xbHVwLBr@AfvAw)C-56>vHcY&E)m|5(OY>*MmpPsgbI(v ztR-q=@;;MGbl`8=Df&(02*O%Lz%^uhyNvk_i)0-JRKO8C;EqLB3vQXwmWxH@W(Pwe zm@;Qa-4-J%qcGW!l0GV8Kd=9AicEcQxRXi?_ zA_p;}1tlIUO~j&gs?=3)((6OsEu;ACZN(r=3&WR2pNP9&aen-{Oxc<`n*ei!#&1!0 z^)Xg()i45)=%C7T-6c{T4<41H94*^F?;CG$h$t3cJ&K@l_e#E0;?iob$7kO0Du4j97O*n>S~27s#RG--RqHi ziVzC49l&Y=B?a%6j?(w@C}Ib(7nI)Uj%$36r#n#oR3_&%ttL#5+8gnzeNv70}1 zq`j@62_+A8C=U!!(tNchGYXFg0Jn`fr4FMd)(!JrZT4RP01sTi8@9c&ic-(6EJC}o zG}bP%qIX~MmIN>XxlBUrV%&@BL}ctIuQ_kQo^pFG301A@qQs-si-fdGu5^d&NIgsD zahQu(h_XPb(j^ic?w2@KUrIE#y*2T=<+X(q@Ipt&JjZL^w#cdamuMVfbJAjf4BK#_ zd`{5j4P=zy)aR0|LmYoEKcTV}B71Hh3HoZnoXsC(L(Y?=Y)LF3p0jujCWHFL$|^IO z=~QeM7jv|CadVvP&&h*FJ7F3}Rd? zbKe(X*3f$*c+k3nN28mvPMZFV+fwik5ha%8Afva#YdZ^OJ~!ZHhfX4?*JV%Y8XHtF zV1j`*)O{qB+*>S8F?AZ_h4Ae7N9!*HYZA4om_#yasHYjCa~JVEd!iciRs9S>n665M zFalWsLhB5@?0|TuuxEa@RbJ)koerv}x|HKG_R)xX8M+Vvl8*9}zW_+0RJ&SwmFEia zNzN3p?BuQE-eNj@b!O3)S4;UNioOcyB*n8NvICfO26r=a*Br-Ycj&ufQ_7GH8WvE0 zVH@7<_jqjRvI}Fx`ppSz_mPJpFH?YBO`q+9O;cb-!444jh~+%$V?Oj*@e~>K?dk|q z6g0vSOg&|FbPM%FymJpH4$T0^Yh8WOqdSsjKOXYS0mH4@(#LIRc?GZFiTzQsn{)6O z?l3y2%uYiqwFp({h3SV(az?_YI{KC*7Y#U&u*?b^}A z1S5Y8gmc1`Q>c7>;2nMfaPjGX5v~48;Sbz@c}t0<*sI8x&7K@Gv%mo-=r=|3>1JZc zr4oHIYbY4Urs@;OtWh1Z>M|n0{U2Cpfd{cG>tG6(==C2-U?Ew!n*aP{t?b0WGLm?D zT!)g{R`Nz@4&bmk+|cm4Lt2d6rFQr~SvzY^R_4hG`r9=|NsvS;25wgax-cxFTQIH0 zJRQHXT&}={aIctKMYdgp=!oi8&sRSPbzJZn=W3M7c7w|OR3FjUXfzAQC4%iE%@RAM zvHKN242ZK<+P&;(jjmPwjuAp9equq0V8Cm)t$f``QFw52&cQ6B2ei?)ec~ z0G>vZvZ`U@Ree{WJt&x4s4gA))Hg8SGIMOpr8p^`1=LF$)kLxg8l0ryA)bm{YoLYI zEJRW!XZF+g$+%vbl5vZ^sShP!&85M2RvF07ET=S5L%vk0ep=*K_v+Ji!~zudC&2;@ z4auE8VKugL@a~h}z>#BLo>#>$F}(a~sraPwG{oG0&g5S2&glDh#mi@=zGAdVV3lW+ zaWP7AFfSpcH z*#`f+BY18bgeb&}-^u#sTBZV`GGOT_Yjufmk8{$)arVUvsZR*Q?*m={BOaC*Cdm<} ziyus@*{kBdqI^VeF4ZuosxFpT?fpefNDHc<5)I&^ll;J7KKs*K_wSl!9c~>m zqb<7BUr){>3paM2&*lyr!RD@5c%2vXQ1Fpchj6!RyU}xgYxP|Q6xp89@?IWj-dbd8 zgV=YuuL_ILO^yhhFR35tm7J;?@nN<1Qxoxbu>gi>i69VdY~uNx#Ka0ZhKlvIGlXlB zQ3oIQzaU+!Jw!D8_lESNKMIqM4Hnpcx_9pJ_hiSa#~8t1Ajt79xi{q5kDA_wr8^uL zJrziKGLn3$0JEnb3|HTVan>;GZcet=;x>;gy%!Rxqr`?~>4U_JY|YYn5GSCu0wMoZ zXHSLmQ?VB*IgTZw{lt_I<;m>(dm9*028kQptj6x?1sz0XE8Nwo-NLa;riW5Y1NvLQ zu?u0UTu*ryjVf~>dW{NC1|^!Sz!@$gER7@3x?JW5T@0FQ?S56XKJr>zQdPb66)5Xn zxmEM^_9MmOSNo;pUlfa|3)6!#GLc#xxWt}mS;XBja4a2_JPSN(>~xV#KONb|;762U zTBvJj8XSGdFwf}gI@Fr1PrwrmErXr zp^Y{Z?gBOk(%MCxwEuW0gL+*1u<{W;Ir-6j`E)J`cNorD+(5nYhlnIkc_oqk?GB0m z)rSvRX!bjCA5{ESL`E!o0jr|El?IStZ<`#(|xEyid^bp%ppXBW;sS%;JNE9NBkNtC4l|)NbX7@WLM2_Srhe_+4B= z@_(04(^t8*C}KVRlg4_Pym^BJ2$<#xB_lOv42JwlKPcP9-TCuxM09sziYGD%=4ioZ zGYt8Y@j~}Wznko_WaKQeq#xa=1GnJsWF;C;t2 zWj=A-Qz9Skd>eCq76>O+XSEhQNpu_*v`8W5M$A7FC)mpKKScx<1KH7ibOqxw{=4f_ z{$1^dh%}XEW=-+^j`)q1vX;6MHit`zj+Dgkep{3xluDT$Ippf+4FCp-UvK~bRlUbg zeezkI5%h_Kgg6h@yHlCwTtZYlDGkhdga!vxGq*Gt8X_l&iQswLA~E&o<3Z`cgH!uH zn#ELe%AxL>zj$yG+B2|w0x^VT?3KJQ$V1L_7$EE5RGk3KvzYWDh88j^^smcq8NzVVYCS{HG|80wqytL% zuJjBjB6WJVR(;9_XWH2@QdU%uZw5W=8}oQ z(SGvuw!r52oYuXP-5MZ%h)_1w-v=uCe<-=A_eF&u`#`kEE|ZYu9!z0^>c3W5x|HXy z!0((;?w_hCZZYzrn*O2rmbCD>J~(xQFL`;Wj<-$< zbop^3Y+p0m?`3zV$vN?K|NZOPm^0uHeJZ<3pVD;%T9FS7e4Rtm`?uDXW$b?=m>wS< z0006W37=T@Ai)IiTJQ=xN~&Q{eeWE}^ujVGu9VZYrSfNc$$wG8e#pJ1%M6+uOv<-{ zIP8#*xsUB}zWPCecHRAsFz-$b63Ja1FY(;UiE;4wbjFzlHM7;=k@)FDGr&(Zx#9Zw z`d}gSzs*wkgQDLjhU5UiDtHKnlVnkK6b}SHl>Q0sr@E|dOlG_227%fh^rUTQZQl= zub=oi=!R^=kZp$sqn>w3tj|Lo_l!}8>*9onR;a&u!&aC=E_79+5hS=f4GT=PDF)0C zJR<7j^hUyxd2>Ov?{|I@!_6s#iP*ltbew>kzk52Ml^509aXLz`_@=1=c)M0K30oew z50ztOQVbYd(er|FImom#jW-uo^tVP`U~zKR#?;Dp$}TeFk;-Scv7t~}Ov;wSw%9a8 zSSriCU>^WGd{j`fD(UQd=tm=>NKTyl=MYt{co2ccv37_Ahp`2<8H(!MFaQ(~!0Qnm zU@o-cwpSX2b7yL>8Be?<(sN^!Ufp9K>V*J3b-*uPxtxJPjXOd-^;wWJ;Nx2{YfhV5b@NvDCV6*mGF2MssU-cG!3{7zYGZx&KBSB9#%GJ zB#0uPDx6IQeIDvST}3a8sq3YzJKoFR0P`4yWUM(bmBc=0V5#oGB%GJTA6#4%uFnub zuLb-Tyss8-;y=InCJ((a`B7c|mECMPkGEi69`A`b{ry0A0Rt58N1A7!Pf;2f|sUk-V=Q2HP|vos%3d0wFrK ze$oQUGuTy<0I;45%B0`RwN?894HRbI`R56Wv9rDfqe9>bfI}4cAD+U*Et%~Ixa1>!m=dKr z<@wCN;~CN1u8V@%Tmw6{q)ZnY#bi6u9)NaHeF+#5ZXQGftw+ZMTNK}j&$7n@F~fT^ zU0exysce5-!=H+skpUJg$D%NH#-SfyO!nn{=_%*%Tmb|i zlcUWGImvof!b~`RN&tH4A*eM!Q++y{-Y0~NB^awYGS4uOqQU++vC)}<29VGI0v?Y+ zj6+rc00+$m-Gs9%aOz41YW6#}?6UR{$;TWrH|Lc@sR}a)Xpe(d@5s$B;me&jUN1AG#Xry^Ar7L>6#|xvYK_f**m>NBJooNaN%8IxeGY&9E@Q;1-xQgT|%TYUsFr79% zLDbMuQ&uo}hyzP*`ThPN(fFVNG;joWM06QwA1~65+hQ{f$MH8+l8%d0W74i(uJT@H zqY{~>Z_w2?U-@$QBus&=>&#CY^>+As@~7Mb&?DE|*opqpQ*w4dt|SJpG^p(G{;~&w zKmU^pTfE$JnP~;LN9eXmMau8$XTdeXe4eO>_hKm?>W)3QIV3V|lkR@`H)6wc${8qk z@iu~RF~@nlrU>gatm3w4zcC{ zj~IYrO1yxv#)PvK!YgP_eCD`#vYeoOn!%iM)cTN~)~IjoPE)h!eMT4kOP5O;mUh&@ z4^9m$-S%I346D=#t;3Cu&Cy3vV>;M_I`SV0Ac&m(j07E2uxv;DB=*=0&*xU~$=UC< zF}WSFigrG~Us}76Bl0DwaZ>JsaF2+5CKP^TAt0!Ze7B>5@3kpxepT-yL?VbJEV6qSg-o-2<;E8U(t=zeX0*XMhg6s2E&q zwS)ark4Cj#zCmQm6;Q;+LUy`1a#$fdF!=_iJSQ+0$bQYyohe{|>96pFEVpaI;W>@VSjw%xxAo%K1VP#adQVQ$m|9M6MolPqp z%#6KI>Xn>>xQ@6M1Sg0KC39Fk!x}x8M)^?vM1v*4Gr#j|y0@s-H0y_Qh^~*Nv6_5& z^8XA>A*Y}3)8X!*&9weLhUS?^6?$xx-vYVYnTj|LroOcH8&S&TNz7=>LP(}(;Az(c z*@u0!zz<>p)U=+pT~)Efz_}|ycA;oC|L1k zLDH*$u_v*gq{IO`L;5Z;^Q$iNQul*-RzUOwHT(!sG~J_IRSFod39sFfGH=@AR$ysb zLP)M8=JkZeTNDKf4>)i70Xmi`1<}T4Nl^9$x`*l8H27m}2M0uLE)HxM20cGDcssR- z7}kStAE@AAx(mjjXRw>KNlB`|A$moGu3JJ+Kr=qOe`|)g+L0i-PHs<@vUaz|2^$QdRFs5WY{xgz(aNPi%Y1Tiyq?ldXZbm?o{QUMYN8wu5?;#{i*PXKzpJSNcO zF%}A)k6lO!uzV&dgNz0&YH*Bp*tXH@7+&&p5elv=QR@%@7C9#zaN|d4`(_AG002#Y zh2!Fx(jWl%epqw^05l>SgZCpdM29x-=b7>BIkbdDX>sl%l$gv$nVr>75;VmXIp_-& zkyq{5T5D!0q9LI%W0b|YM3mpJ#osiTKTSp!&7Nz0Mo4+_8|Zos!|usIUK}{6nm-WP zWt13P>R4pZs84FsWxh+js{c1y=Tfy)bKf1eV%`TJa{QB?Wzx%Vjbh0N4r&>C+mqJk zt?T!?&Oo*mv_Zsj{U4GX#!=^mne+Np4u2zlTmqsWzgn`5$oC^{6-{rKU``~u-3ysS z9TV-wdl2c{<7Rh|+wVEWo2$w9|7=l!n^TiEla>GCU;YsAt>i z{4uCbJGAz7^^K_k7E6JF(5?nwi44;O1MR11pf#ZoWRRrb3FsVifdXHXzmY@LeVo3i z3-_1g6&>d}WHgX=pXmM?>hV5f>Jw=B_18L^dc5 zA-L->?GQk zvSV@BG71cUTo&OEqjILziYAIm%VxYEm9L407a*8M@|i_?9{mJdCL29|o0H~+bBS=T z8&;iquk|*1Cf{PhZRI`dLH>miU2McKg^ARItWxrmFa_Jk9fObyR=ITCB|FF}#@;>P zA;Gkm0KW)Wu^E3m$LHwtfLELmFfnRUU(&R-@&%S!cT_aYNNEq#VBG6gZLgn`*WXzgXisPtk(f?KGql5`>+J9yNd0xpZEMPaomiE!M&kgH1|tA3~R*YxdjW2p|9jnKDpnWdTzEjB>U^UtfXA zI1I94WTg#=(PyT;CK9nZ^>rJm)$Ym|UP7&UjD-%$SGaP&xJ_N|Rq>?FFzvS80WLgb zwIFJjV{bs3PC_d?fna$C&?qQeZXV?#fH*GxQ!eiUGLoFnly!66?-`sm1#D>=!;@~h zMlg1Ka(l+ntY|Z4B*KkGTTx&=Y@GviB;VHPyJOq7Z9AFRwryu(+qNg1*tYFtCY;!w zI4}SE-Fv^c-g@1uR{eU{u6=gxb84;bu5h=J(O#K3?+S;!<7^Q}^xOn!?pGMNa2T8Jy zggH^rY4WU)x3)l~lT2$&T0f(nY9!?#OLorehd#4F!-L%UpO znjB6Wqm1vU-o2)$S|WS%T36`nj<1)5B4cAtzH2SV>YXh9=7DhtX$XV`#9;&32?b?@ z&_q$x*(^}hMSlp?Vs@s$llr;3n(XY>*`s(#KHs6t(#qV&7+;ASr~IUX1U4-~vk))) z!Zb2_kP>l#M4p4P*CGKN+_3))SF$ZV4UjDwJl{ka$864;i8kaCDK5JUL3<1knrt3F zmoM^iYsT90zU`Vk0`Aa>kw4RUTLWVKg9WoX#W(T0q(Qj=d=Kp6OjZ<*(glY=#(fqyJ>^~Uu0MZK_L>Ob zs?}zm1-^ll8%24I$T6CpJ}wpadf1pkJ!}U6j{#jgkRbt(z*r*4E4Ll`XiXbWiR`zd z<)VW2bl)RfoPnAKt_H{MYAQEjec=O_4ZY~tV(yQA^}i`MDdXpVuHuWWyIumWbOikA zvhbKsZwxMtyD9lx>a(J*rLXc6R8-a_)8DIENt1EjINy2xa8&oHqA6c5$5EC1#(uGS z@35Jna22EzG3e0P?$agkgRQAml6~cs-2=UE3e+5&%!6>opvS(1D~J$0VW>n_Yp`jN zdTl?wu6!^^cAoczvc2$5I4}Na`_+WFKyg!tAhTzN?tcHgcgw!+=ARGOjKwn^v}xVT z;X{V<7utE&ORPXd46_vGjgnuxQ#-j?9wV{)`Ut_!gc)4s#pf@qNvv$J^aAEN%5t4( zxeSQX4?mItvT86*nMGw(En+!OAF8)RzMQ;YyLI)y&SbjDF}YSWX7VwduPJiJ6f3sG z3?S5~ulZkMe)#6WL5ws?tA50@RRO5h^n|{q#i9cu-;AMBrkX%DuY$3AG1aE6ZCc=x zhT{?AXs~45^WEzk6KiBx1`nb%W>u)2!M6hrdg6}MqM0N_9q2OOfGPI4@BK0|fvn2c z!sVp|J1FAK1GO_37b50Hp*9(M^Tx>@x?`uZw5YT#15B}T?)Fb{L1~c8pf(o8y%b<^5_16kQf@^PEY3d-><=xkzlG(xq`w6koJbPPm z9@L%PxY^Ot*c5j@6^+9MYdXUsa66v6p-qZIUvsR@pf-GfZRgkHy--aAW-yqM;}1%o zFbu3;CuKxY@7|c(-YJ*m4B5!#L~0;nb3k+Xz#&(LWet8YrX4Tu6YnXT$TJp1GD(2N z;_Oi>)R_3(SAulaX8JRB+=lAV-|JC(?kx-#cF@j-{kFiRG6uy7Xf860S2lm^#ga`uwxK*+z^(K-ND(apg1fc zVA#lPbdz|p6tESu0^Rju?HYpix_t<3dR}?8lYYEo0?s^e$J zeNYl3yZjWuxeg8*?DjozzYWR|?WHXy&nv=j^)KI(TK>4?2W)>bgbdv$MLKw+jEl@w z$x5%0hmLBDdHSRiiVxWNTYia1>Y&>sl7{w=-`=dsZD!8{uTjREb9Ye^<{PoYo9#WB zKCKriS%q;&YguR9m|orijjss=G`)WtT;vbQ&IK$@?I>Z;wurcY+25yro7-FtumvYx zSIs`t!opj*DWhp8HVPr4-8^dHH$Sjek+KCT34kU0Iq}zleZP5#!z5pNdNoxB=v=p? zz-NkB5MQNXC<*uj3lx-q>{#^sS$w)GM24xwOYP>5o@M#VqA7x`qLM}wj}FSmym>HFRZZ~Or9SvVYTiS~e+0_CoSmWXi94 z;^%TAEAb_L_J--TO5A4Kg()1(&E`!*NF-JC(Pj&l;+Z5HCfvVOD%UhF9SsyiWUZ@$ zPEsK6zVWdUs?Lk;q`FV^o}l*So6lj9dc=-zZ@5c8yyS642h!#|hNca(hM}d-W&O-U z^@K_9+q|nz%)2SA@{iZGjj{~YOQdoI!|MzD zp2A^oX21+OF*sPt`L#JJAIg|2u=&;+g3 zj(RGF@l>qcKo|%*wCy~+0PXGY+QL2o(xnyL-a*o|zJ=hUz z_0frebJOR41C&isqh5@pf9Zr6WQe^cyme0vL8iY&PI@sk!Y@p9Q$kSuMDTWbKr}?i`3?Irklj!k17b z)5`YS`&a_s%`B{7|6&xV64t;@mg9sTfidI zB~nj=z>^KEUqu_np?na*0P@=99rPtVfuw-o9KGeJyEFirQobH)=i4_N$zV6!lrSe~ zFS7Vz@#3@Ni%;&{ImYY+bca9zKfonQRl!cxP8|RE<@&;A z_Fn8RRDgVY%zZIL$!=!}-aRkQg7(S`zuVJx;X#-DnYLE_cUY@H#Ts9Rn45^$%Tj_I zV&|$?xU`m=$ZHKH<5;Mp4*{VK$c6to{*97;Q4n-6%413#%2}I<&9~MijOd3t(Kl_V@%Ua6M}K(;%_RKbr46tn%s810&|vt@9>-;Xo=Awk(n=FB&|*}xB^7pT&;u=G;yctb}>Ir;T2WF%E|nW zvC~GuHC5O+>_7wM-nHA&LVq==5v0P=Lxt;&O8ED3B{If^WO&<|qWCXlzcSaE%DoN@ zoRG!5M6Wo}HbrO0z>^y`BF81Ab{+cs%qwmh_b=sh=t!6Hl9P~`-BqTG8KFX0Qkk{@ zVEaA#(j^PrK{U~16J0tu+)U!<^1!DS>K_(i+O)mU@%eFW@UP|%zU}DzOd+rS8-DOp z;r3EqiEq_0&4<{FYFv8Gl?d)e*6R~y2XcI$4!kzGWg&(7ManuE2Ks~XRD!G-T%SPv zqA+nOf$`_FOaUEYzPP&({bDrD!n*NdOsu)ObFebPtEJlXGy*G6DuTB8Dn;q)lSDwv zl?z|WHmv=mbmolN!!!gO{-PnvIXB&>&u%8MRMoA)C~ZQ^2%mu87HV#bXHtZ@puu^( zWsUZ51oGuDm^?`K@}Uf-_>YKjUO$3AZK~RtvCllq5@d*b#zm$dp07sDEj-0rLQ^;`T;`LcxczEcaY{q%o zNkbtUJ+8+Cwd!${1%d<4cuiU>4&QmXGmHr4e!>{p^rqgHSh}C!au!~MmH+kQHGqfCdCN=uo8?W^O4{8AKpI1)FRPI&BBKjYDeV1mSSSY1)i`edHom znP))mAwV{9RW*NP+d@^htd$#$|9n{jBw|l<%t`1-EP!O&T$I4dl$;XRS&YC}*R|rO zQQ*1Gi@6}nnXjLV+v7M69wUTy{tBg3+yq1b5^AN18@gAVcz_JC2d0mJryB}BGO4q&h`UptXT{y*Gv3 z{M8@)C!EV6B)JH~Q>5(+d#|gpO^B}Owi5aZNv|-=SX%fs!o$a#n1{se zzQ}@t&EnTfpoEM~JF>I2kt%kpaQG^Ey)E_w$+o9y zE2q6X(4aa;yMe=aFqH=h3hD_b(%qqWICoHmd=A&?ZYUyoDUI5y6Z zCUdCwkhLP;4s>nOjGLvnwsq@U%k-*mP;#YPfc0k=UR4xFm6$ z^S$7xbLBJ!e8WFoPY!(-y*9MO-dmI62~Qov9kZu$DG-EtKqOBs$a4YM!6$G=wW=|w z-Z6AkJ`+S#nW>oY+GOdmAKx==U}A=Wfc+-%NlKH6Fd@}lY7iT$))sw%J%k+PhY)M^ zHN7&Sg`_7rzS#A*q@~>=!~N+K>he+esF)SPF!LK39pwF-e&qn>4%7ao%glXCja`!0 zqn1vp_sV`ic>MR#>oG&cQpams#~tNi4>YQm{laZiS{b!SV3z9GxRRhBbJo1X4(G5Y zrOoeIv2aW{Pzt6e>EFWJ5-`q45!Z?xB}YtJ(AG!~=oJozzi2piz#(k==mB^ig@KSH zIOYqXQGy$h@Z0>2GEBeO=O9|V$EwRpbQvDPfqu&@QPyF4e2chW2r9c zqlV@7YjV|ngd?aD3KL{%nKI_F?pkjhtN}X8nIjKnU1tS(x(Q9=@kYaCPh~DM)^S;N zyq@l}r3E#?)wY!g=LAJCuxv}Pk!E-5Fq>(3t@@kuQ_+g#06;@iEmz_KqRtLXXcN%2) zW~rfOnwnf1Cki`!D~AB!H2tXciMZ*Dmz{>?igdWHMHJ(#n0!V?F||7a{poPH)Rt%v z2Flz~5n_c;95146BNu$beI;X;3yts49$$@w5S&$UHmvU+Q#xYP-&RpDma(>R!SE-0f?7U~V3y|1yr`-V zAggVs5@zDo$-rtla_sc_%_3I1mue>yxDIgVik>hO(MNc(ujMAp4oIDiVV;X;M!k6{1nayUFL{LR3G z9Ff6fj18uW&edi0atx?$sQ88$1h_@{eFQ`ZK_vx(w^d>J&g6_|n(WguSbRt+mdbyy z3=Z7aSQ=wR`DI~p(hWuZnk50vS=&%;r;^Sn57^?ie`?rSMGKIh4zC;;|FH^MT1~SX z@duPfF%TSa0U{P39+OA0g1RpjoXR(zKo0`OqJ&7;RJS^J`{CZyN`nng1_8IwQj6pp+@5<1| z*9O6OWwO`dlLv`VBfcW)#G@ zqkhH20v4xNZ-!g7CuNbv5JT#&bpPs;f|A8=#?y^I+hM82|S6(=?m854WNWx~_t@R%Y5 zyBhPf9TA@cYZ}L;8B}BwLM~6*?rb`~H83jtxD)fuU4{QZcVpzJ>Gut2Ql+~LCS>wl z*yE2I>ddsFXChmhI=mg~O87c#cPFr{MBHCf;FtT3H#>0jK;8xW)OOZ}D3 zpK-Z;$dg_ZXaq|Ac?d0%=KBZ~_G8>|543~|^qLT5?iu1~$DsHn`%Y2Hz|&NPF%ch8rTEh7jyImIe*at-n43 zg+X=qy%l&9Ed~(%0Te~eIY&9kC{zuyRq~;DOfh~Av{JZg**8@=g9l|3IMsT7Q#(2-tTrcy0f~sb+~# zM`AZ3B2}|frHb9{jO;zMRTANf?HIGJnn%g&*!}%Dr}st^3_@Fpi#QiSBNO{Ls0LUj ziGZlB?GrODC6s?okalDB?<^fGLcqR_Etxl37Af<>RXlifN7qpZk~S^TTB`1igkw>e zpF`u2PsY89mrvyitKZ{SJYnj?&y<;M)P1e%>k&5lI()@th9aaj$Y|nx9EL z8G!vDNuh*MOT}D;9k#Hcvu9F&{RLm~tz@R~6-c3WArHvjM7W8qHF0(ezSH6;s@#1J zFFwZQPL4HRt{bWSkcsRHxstQsL@n5~TGjtF_{KF3`<>8Cl#r>SC)%7#f9z!1+CIn@!tNNZx+WHZm+-#E`7;$vUP& zNGg`9H;;uMt_Z(e?$ta^dXs20rvBMiu4H(|lCaJ{#BlmGj>2B~rxUF3j?X-cNBFu@ ziIi9go@P&o^lTqKYduNM4byu9z}qUxW6W~s*!eiK^>nUQEuIC2Z%;^D%c3U{i~64L+lmFVJRTMRaKVzTZ4proiB_e`c!q~4zF6;5Ih zEY$0N*J152h&N{&|3##hKMI}dA_N=Mh}*zn2F%YmBiTPW!TQhb_RPd{G}q@`P!VWQ z4Lt(Sxy)lrB;R_3cEyJF;vm5s%F0asexF{$or>qyPx1`05-|D>L)hH^cT+Otjnk7E zMZcNY^+o?a%huBGlHi`142M*qOJc?VOci&U>dq+R0}B4hhSS(U^PFmM<35fic78(( z^dy6cY+C8j=FS3z2W0%{VBaPh5)Jf88-s#Np@#|{OvQ8lDuhgS?3(V`x(K4}1*) z?)}NsV7v;W)#cSgEZ(9f;xX-qiE2R&I+=!lx>)@rJe z2tGveNIWTj>Ek zphJkXA#FP>YL7}B(O%ABsmSoyj|CU7zp^(YDx3=5W7)}s5Al;OBw4)U3*j)8qqs=b zeH{l>Tt35iG48OI$`(6Q;c;Bms0`^ZLM5^xv?R3y)tmXQN#^v_eTN+WoDcLv=r5uv z;suWdtM=p#$(cSbm{ambc)+sGas904#`P&u}w1R#zWJtFno5d@>J$D;>yH_4U z*}a}VZ8#pC+Sa7JtLdaoLGvT8)icNo;jIA`RQ8NsF0+w|fcjKz zTHb?=-otk{Eswe>{tQHuzwNy(#a3R!Lb_9GD|}5@Ydz@Jx6h>kLPT{eFmU6bz(pkah@Na{Ef)CeYsunWe$V@|tuJ zgW(Q*v?D+|TBnknGL&On`L}#-3(m`$PZKI^-%)~bT183Ck8-d2Bs;kLsRD#^rY<)d z5RBw;&nq05n*45avNbJwN<-%zE%0IDMfg}d-}I>8M!~VbG_YdhJPSut5Rwgf_+M^^ES8h5 zXTo=t?BpX-(PLK%JUp<6Z#CU~T0>fQrhDG$i<#_z`0kt^$@0|F85bC;mso>?tj_OZ z6m+T^gqu)V`)wjpY?+h7t2?@57f17xqvtgth6P*2G;i4^%o5+`wvUGk!w-3!>Ay4D zw0*>Ed4-M0Du;tLFxa1{0bR+IMvxAy121r#MzVp*ah)05RLnYoWkSaSUgpRk=v~WA zV|C#sClW6fcnL5Qfj`5yW`Zu+&$@Z$eH11&YZjiS+C)coh!+uRW*&V@ZPuqie(0~l z<^NbQYAmY`D&an<6CX!#tN$ZTeegy*@1@rtV)=(y0-!Y{QShM>o{@~qY@f$tL^%JT z7^*(^tmaZ>V5R0$^of*m+eCGm_$#~x!e6Rm5t0Gjwqfvpso%u!8j1K3s!fRgn}Wgb8M zu!;UHrO$}|)76n#fG%&`E*Fg;S~au+7r)#2bVGsND3S;7j|dQ{VRH#;0a-W69l-*q z90ltpwotjG3x8dv>_IRbU!0Um9j4NY)~IK3O|jgU6`0DTF_et9HVj+Zu!eWlxX8Wm zuXmS-#iEm>=Gog4y3ZZc(r&JOMujqB)1^x5#9h~N&ov-_&y-1w1IzFd*rg}qP|Ywa?<>#h}ve}X? zO?(|B6CBEMaGn=FZ^i&-Nl^8uxdoN*9I(Is*!z7>)qj=#WW9ewbXDinT5QzE60uIi zGKzUTQC^rmoF{A5X)Fk>Zj7&SrvzJc$~t=aBr}41RvPs?j9X{ys+{dubo`k;r-4Zk z{|?Sx+FwB5ydnd3#v}}%wwep5C-a}%p3#MJds;4mKW1rmj7QQDqfm|u;eN!@f_rS~ zb>p>B)J^^U8NJtPkJUucQL*99?pUD;dA!M!CO@b|)@MKTF&2#Vz7_oU8AwUC7dA-< z9U-~MvecIQNc=`BO3W*pjQ%af3|Ad4Nlc?kja+hE>d9?In2fM$^npZLAdp<&@Rnn_ zId(TPWTjh(LKaXy*}Hfx1jjUefQq96mK;8oPEx_vxv_%e(a@67no|yi)Oz$5P4}pG zceCihC1UEIYRCM5z<%3EDYt>OVqeX&3MhbpGGj z>I$4DA*NFrg=?vF17Njx`4L`$^vuSQ$}4G=l`CdlyQboHv$FY(E`1)R$J7#)oBBCh z#`Z;`D(ZyzSP| z<~EQ*(7hR7id&d_k!-KOhfCGWGUC7bl!UN@c}Xk0t=Wb+B>8bH(NpZ^?N~{MjOv<% zM;&xyZ?iDZNQ>5!L&I*CV0WWu#$)kTcj*NK z)WONQqOe6FDBv0jfWN8X($Q#q0w%^WsKhPf%Eg9Qy^qrRE`iT3-bzM&ZRExVnlxa~ zvHP=&B|OLPG!uQGm=Qyb+<8{R8?Yyw7#pP;R|=b@N*s&KY68}bI;3g4TMtpqh({+F zr%;;iIs|Q{aUPBEl6T3ICxEND#{#16UQ4%IiBbn@-xQKil;doKU=CQ__^M@oKJkhm zw}Fd0gGv()OGJ)$83eA7v{LW&JW2{xp*tVL>*@attkzR4YLG(R`HM1-!yA+|JW`Z? zF&o3;k?@d)8I-H?4e6_rVsTexf9TS4C%m^IyLCH%JOQ~^ftZl+4oA#WCY^%?_C#I%kP zQbCNji>u1=P1&&ETY*~hg^{4lJ9Uj#?+0h1%|wkud~d#giLHOpojljR+PEeat(g=g7n zS%b!~^=R5rf$SM~#LF93n8T}VghJlo4*pcD5r?lY$%pOti>^|;_d&h=%^N1P#aCA5 z+V$IOLZs#C8#!SknxKVeeLxYOqZA2qjF5|2>!L;xqY+%NsOftcz8|_CF@*F)T#gtt zr4F1YDcTaUm*^9sd_3;Z=oIL@{6M=Hz8QAhsq8Fx>L(L#=z(qtuQ7+rM-GqamZ4{7 zpB8sMga}0*StX41rEzKJnNn3VW-60ic{bs6^YHf-ce^o2AE9KXpT5n0eI z9JMBRJ%0`?b{)J*e0>QT8yMa{4sH)c((lxUMQ+uIR`$dV9#!Zw{$D4TLlnbat9S@G{~+fztE zr>Y!{G|CNA^?eO?Eg^aRhS~tm6G`%vYXN>Z)s5w6##TV6gf$ETloxa3IgNFApW)0} z>sYm-YLHP==guG+I8pR)&bQ(_Y%y)7d5Y%%KxSYjU?h1cpS(0c{ul>i9FfElUi$L{ zwDr_wia;81hHM1`Mro@g*mhON=KA-p{72*IlQGK!-PeQ)6>YI~8os5@G1(DTU-rGY zqM%?BMSk;@Are*pO5mpfA!a(EhQvbI5LOUHCiBnVW7ozjW0C%|MYZwafU5f|ic3Lm zUuD4fWVkD@li5famY2t-e@`3wi;?poE#SL{c)~B@Kdy0al!iqwVjSw@m>2V6v7SvY zynyu45*jts(n7)zM|IER^6R&5H+n2;r}EKaAFPnOA1#tg8VRwugZM-fohbxLDxru< zCPNxS(;~itdz;gNIG_M;@LaHPRBSy5Ak9_!DvHx4)Wgaf!m6!v(ad7Dq8rIn!5HHiBm753y26lG)cEFwRVl z<#2|uTb+>!Y)v62^3tPghtRdVF2q$vXTV{5=cp?A9j=0lLK{#40QTl|NV{l}03@|R z!nZ^I6Ah-Ed!KTgOV(go zlT{*l`w}{JLAvxo5)oZ#bI|h|vj6pPvp9L#Uw3VlCmYjQN;Se22keZ9OUSssIiZq7 zPyqh`A&nCSt}{yuE#lDXQS-pO5ATVoGd`d7b`io4E^|LtYz+`g#u^Q68DW*V@e+8s!COw+3J=aC{ZV>xdj*w~St({a%m?&sI^)&W<8+WekwoM@AP?6hCXKL)BY zPUZmfk~%GUicTmj%p$-0T)g8mim+eD)HDXlex6?SyIad^^n5o3JVeqWkn~vS z6BM6C+KW3pzHsEFh?ZWVpWgZfnJj?Wxxm?E15x~IPsh!}%}#ln%J}M1zkAY_9w=n% zbpEgxd;jQfj|4B*_y%70)1FT8CSMG*pHpC=#bG*h2_`2dUT>dz`cUx4Hkoh3uIhxF z#(tj8TthOSgCnJlrdHf43lQb*R~IGo*D>UT^AuHFJ3;9h{sIxT9W9YNLA#MpSI6)GugU~HAipPc@ z(%5e?3}XR;S)sy_-cJb%_^-6--JA!QmuhfbFOFKh*KUq@@i^a;>SyE4typ5UaA3eE ziw!FCb6rFHiYE;J7+lN>lzHwDf{rpBz67vVAh;(Pi`JRRVzmt)wPZcPddxMgBx}Lj zT)vyU6jMq6xfYPFtUMK+lhk{_0~L3mo1)qb5J5S#h2m8$ypP#hmeO+c*;3-BDy-gw zsbM<|XxK5Mqv9uBOwcMrsd~pmoQaqZQznk%iK7FY z%`Dr(IGKmK?ecx6i&0EorEJ5>v8;smHh|v}P`_Gedp)~y1ArYp(-;?v|&kpgIR<@ z|6UG-bV$?dl+1LmpB+{XrR~@5dEh;WM5z2R9=3)}gtygkhL^`Ko_9qhIgzs;F({O} zWcKDF7W;|5>pYsGjC{d~IB>1z-xr^-iWy)zx3{q~ic<==i(A zg}`@@8<3j~HIqz#=#^ZQbafPBncYj-PoORQyA^kQI~blH_sdF{C)zGWd9u-^HnANy zOtM>}^W>h@eyw0vWQYe_c!c+#JNQ@YFukE@h>&dnZb~{!&}RJ$Uume;N z?Vgd~^<&kA&Er-2_QYWWd|bg1WzQ8dX$)K08tl^krdVSh>p@ToS`OwYjh#TFb`Rb% zZ;rl2hS-bW<@$Xi@{GQ>ryqq<>?A z7p!!6Xr4m*DDu}6J@TK=B$E2ZDPbV#^R#E7FdL5FKJ7UjkW!A@uvCWRmZ1@Kd&Ln*YPOAU_7h#Jau`!$Eu#~yTIo7B)O z^U@&Yog;-aGL(kGOcsrl9o16&$paPo(cLf^iJ$rkbTYc)Qh*QdT8dv%ciUNgSf3KylaJxQGrE8NnnB1yiZmx)@lFJQ?%WCH`7nXS0i41GDKGkQumg+J zwhz4nhL6}x^CrY{Jkp6C@NC%;lL!$oi7WA62rxQbr}3ygv|AR6l5lfpYR&=JV%8)1 zNZWf>Yr?iG5wVja!WSCTeJH4-`>CuSXqS)usQIeZ@`+3w3Tl($f$*BZk+9$}X`HC- zyz^5-XvLEjLzi6)n9$^?WLtAldf17Bk^ZI=2{2)6FGwjiD^kbgg{HV3A>E8<@%%$s z`Dxa`JV7EPm>SKgrJ%8WDl>{&BZ@>)wF6X+_H9>7eXZBidc%FQ8FI-0b3R}&w=?S3 zm$C#Qz#D)sU7(W7nv3nN+n@I3C1B~95!ya$Gt%cSIv}0vu z!o`(g&PTFu$~tyE9QUW7@<9O_L@W)qG?Sx?&bGsmK#SjPy?DS6(G4kbYqV+zcYx;g zw<`RwnVl3E7P~>QV@*W)UoPZltH4I64z`()$Mw;xQ?R2LP95^8BMrpz#4LO^kgtU5 zh6YI2zsy?aUgHXed*L=kq=a_Dp%%ia(i{wN#lGg$0)Q=nk+_+sl*4KV;s#-wrH-bp z0mB%Q$H^tVndJRRl45iWwM1I?&p&CJsE4&qK82S{-r!>%7+Gx*xlSEY%ufom=*%be zTz7E`XZV8CBVf4;wZ6fC>#-?Lx=E-Kz(-#zyU4!QLRc!oePBz8Ru19#$d{`a=6+@f zT?1W0JUjmqO=)HbKc?LXBX~kLhrNASl3<<$1s}#&3RWg=q5G7Z6U4 zg5a27TJrpUW&g|(N-s2fx^7d0SKsCzXE>iZ$tXF#R=9*BlDfEjul*ScG1VXf0Q_}F zsRi`oT1#@kQX+sgsX~_OEyb)@5F90bCOW^8G>SfAo_0-hynop+5^Ad03Z$k{9gkAEQ6LAn2B=LnMj^)-U>-)ss1Bz&bV`f3A= ziG`IV0rWq9gM3c_`!B~O{7+oI^gxOdkpCtBhbt3M{>u$XK)^q7`|=m0BMIcc?G7Y? z{#QPc1omHENP_&g4_}c@g8nyuE!j_k`R}FQcz;;6#t`IcSewFL?(uhuTmmRcCtUG@pKvMjr4E2YJP2@zWc*jg+oEfgeb zQev3BpCO&>NnrhZ_XPqhOB{TQz_qyLb z-<^9WS(42`5v`2**uO%FDRFa z64W=!TKNm}_!$d$1G9KbUX^F%aoNSlTd8--IO$)9X)NM6@AL9Hqu)l|m}JWoJP2Vq zuE%@$5Cz^^P z!>}12%W1h!Za^6xLMO**krP}xCH!1O8V^%{M&6Vca4YB1B;6910jyvSx%9ph6F4XD z%be_$&2k!NQA%cZlfnyJX4xF23?In5)ZZgp@OnBg}sb_MZC_+Nir}c9_e9} z9*L2kqdb7hxtI$$#ysbDLY^jnlb0qTlgE<_#7YZ0D!*dMF+1+-wS zxkdBUdwp8O7xroKU?>!hx#NLAxS1}0M<7)*1f|?uij5e^dla^c^T4w1U?3i<_eA}g zuh|pTeBnSyYj#KCS|AW@@%lZ{aD614@=;l)Wn2XEGfnaq6nX8Qc5j}%=*U_iiOpmOPNhPsRW=1uAj6rPU$CNVb!CmeA(|3dY&uh)t$V9E zFbi;vsaXKimYZ|&XXlZdyh4d_I)Y&!{gpqFD5nf=vM MU0IjR0R`3n0Yk>uIsgCw literal 0 HcmV?d00001 diff --git a/media/moss/leader_rotated.webp b/media/moss/leader_rotated.webp new file mode 100644 index 0000000000000000000000000000000000000000..c3426650a673b7b679f08e3eaea628e843e63372 GIT binary patch literal 117078 zcma&NbzBs0)CanBcOzZW4T5xcr*wBWsI+u})pDr>81fmC?<0zmW43M0JgeoC4@FxhG z(A34n0TviJI(fLM%ZO9xzR{yV*ablW|DGSF=I$Iz_F=I#czp_?Z3VLKi-ioEZxn4Z4bbc-Q2~^0|bI%2F9x19xjmaJ7A3K z222VVCqTy5f5#<|vDx2o+w(q}>Jq>{KY%fXxs9m>Fg^mt%x3@RbL;;zc69KBoEP$d zTq&xhla>bXjte|VK$0L^kUPi)&M$ZQVVWEIP-`ZVF-Atbk2Lrr9TUmiXXXPLe+8YoEX9D<+zPl9{ z=ksEK27zFfL7-kIpkgQzI-x)= z{Jgf7O>jSd?a36Fl;QH#rtzPEht-rPk*5GK25SJtqw|x<{^PL7)gpKXeELh}3Va&y z2<|%km~!t7zW#IhE1(~IdzJ_m$qTr@`}~LjCd=(Y$9M@oty*gb2Mk`zxv?c}8`I91 z0WaUW6%ya2Q{A#kof$-Lw-XHi-S+?YV^0R!|NA|rh=qAW0#T)&F;t0m$Ad71rMQ2` zor)wF_U4I*^#nGh=Mb^k@e>SpApOtZIOlH#-(dbZMP1T<5oHYZ z@j0fKAp}&n9D#ypp3D9UW2l2Ye?wl_E(DohD|t{|A1crE6OaU2yeV@~?I#H|PlO&q ztB!qsIuRYJ+q%A2pf_XR2CHO(K7QR8(6?4ZklJl9a43wpe`Xyny6z!bP*jt*r!byQCu;%Tj8C+rfQZ&*X+w1A>j&%#c`EXJE0 zyBZ`!Y>;4E@4ImzHBnz9FhXE;R3 z#%fMkOoait1A-IlPi^St0;vJ}x)+6J)P~L%m3NR5G^hAvoy>p3Anz~t8xawcbFUkyLkC&%40=8|6&*w-nec>#!UcNua|wlnJ% zJAq6`pWN5P9sosR*)Ajb+V1ul8z0xDt2^OSit7cVzwLjR{aofn#p`MN7YfnaU!nAk z{Zly2FaHP4$DBLO^W37No>OiLOX+4`JJ$B#flC4q0`~OywLnjNEHgmjm4$oMffOY% z0_3)UYH6y$NDYHL^S4Fk2DRb=ms5RR2haQnaLS8?hODxmf4B>u0S7rwUIzqn2&KY{ z3RuY-sV@IT^4ggLeNKIaclJn86fx`z7|tdu}qKxV|wTG zObn31*r;D3ZFaeSW+kU!GiqaffH4Hxw35z0x7Yfq1>~+`qWwoCkdPB$Wc?{V7mosf zFCgX#-)W1Ks~`rMcsKLiYd)Yr4BwTpN1=I6*0tV3NP-T2Drk!A%hN+H@u`(Lz!~1a zsT7Ms2c^5)@7ks4N-z7GjG3aJ>yL;{o*5Ufd5ZkW#o}@*N?shS#W!S2i<8rG!w&$w ztsd*|LDSWN3VIGIKvCn@gSyACzy~9wl00VyOasPrzv!r5CHf9z%>~PnNH4rsNqH`n z4pgGakCCcl607LkI|i!6yqqtXKISyowVQE zWzZljTQ?A6UzeOD{d*qJpY+1ZF&$Y;Vnb$0hl8nhj*IB+(HW$`*3=>}A9T{?Y93EO!%+PiF^&gV_}v~96I);|XWVE6ZE_>e3KqdZTO z9#v=n#0$*#FT18wEk}?MG!-VDC5?x0WbJnFj4{YVt75%hVdh791{veo1cY&j_X(lR zoiKkgDm`-t8=p8KRFko{Qd366UFXy@k)#gut4e1_i)$81r+(|33JVD9(EW}@AU*U9 zzYb`p;Ad5nN07BN3WMYdkN~{+J$Qd03#{VZMYeAfJ9LP|_8N7boq%~0UQ<3@@tki94Na!P0JOh&-Bc$dozxq^@5w9)FxAX6<9!c01)g15(!bzq@XFn`B+MZ7WJLxXUU5M!j~$=l@F-oE=OJU0^!i`Kf6;KvGVxq*&QImE6YnH7o!Lr#$_Pm& zQi&f2?FT87&LIT#nNFSw2>BoI@5ByUV4On@F7n`e}`&=E*jF9lM3BXqG1t63EGvOQ7fGOZa&xR1K0YYhSI%A-+J7&7R zb>Hz!0>_8QZ%-OS*d7w;PmGBHL;8}x6Yl&ZJUgX|{TKdzaR5mg3(aK96R`_{-flzS z{!do?_6eUU8Q^H3Y>5wk=YA21aZH(U{5;uhcWs53S4G& zLVHLx4cWLc)kyl<$fu7^8N~SU{Z~>DhJ@t!f@>F-3uJK>PxvBCo~2P(rxcAjT`4aNdyk53}BbbjL;qJ_E{M!vje&z^k-S5IOkg zje)!d(!qC}h|nQn0@MJp&9xtqc|waFOj0a&e&Lqp15m;sgiN|P;?Co_mg-nw{jK|w ze+sI!9ecd51|0s(A)<`}6n!%>KDx+?zQ z1A%D2?Y5DN2q7XFe8-+(#NuqJ`_l&tJ3FjC{2vSu>&yx;;X1~T?^#ZCoFYpY5+nta)VJ zM+qdbgFg^F@~!zm`;RGgyZ_Y>zb7Pk-zy3t^9uCP=b~o?a9!QqyBuJfGpOy9AsvjG^a4;0qaP zn}K6_$QI`zf81G4a!XC5D9riZ+HJ}vsh23x@IOLXywOn`*)oX&(#5` z(I;~#i0||a+DI0Bqzrs~?w(pSW~hReCYOHA&+Rbg1h9ZUz*W8(7A*r}3>3FoMfXXz zEeF=cKZ%!r;Vs?4$~9^OxOiMUHkZ?x^pVXklmX9Nw%v|D|KT|ao_)->o~)YXf3WJ> zFlPJ9KSBCG&Ws{j>}<=P+nB|08#=KppyoQ#7*Ih=s#uU#1F;NpsqBdWQk^~H0OEZ= zS=SH>=x|UIgsF9(W#BDp4mKbyBlMF)hmH#5xd4Ct^sEeWhz^IC|8IheTj0u+?JVTo zdkC^{fhI+De0IV7vaSt~Oh7?SQl|*qVMlh{bLxOHde9<0(}8USJUYY@7(6?zmN{^W#!YySrstiw;u^ zbw@BR4vma0MRd}|LAK2l5hxcuLJ3BOZfm#9P+X*{~qM?0twdPa%xapq!jP$ zxi{;tNzYw=HbvjI;zt(&r!{Yqg+!i17?^o9dxnZHLTk;+DS@OY8@~^hOR?_|&e@=r z2d?;^u(d;2OJ)fmCZ}K<8d`w8?tb~U56)=s#lb)i6zN`SD>?rkO4Ot5V7 zE_TNHc)h%=`!}G`AE8nSvW^L7`Q&l(*PRiby8S7>8v5@_fb;?eWH|}q2J}nugP!XJ ziCAj_aK->te<3LloL(?#C5neJ^e}`L$%>EI#CqA=R6ZOOzuKd@=jJ#=FA|`>4KsJM<)}Ee9I7e!rRqx(;bYN7|1o*m?CV%9Q(_#% zkpZ*|F^!#{ASJ+cBnb5B0yi}@z*@0033444C!~Ub-@8=OAvzQMjU~A z7R$~?HO6$hzs>+SofdW?6!C*}m93(YO?_R{D;vt^o-KCDGP=J~MlkxX7DBizv<%X7 zJg-YkTFzCWb*~voX$6M3aEzup8ME{L3zehT`Zr$_X!`lAF z@Vm?P&$rHw#|(hbqIJ=i_&f|Rjem58QZWsDA$7t)>nccuzU^q=>>iq+CWmV&;rL0o zPz_>fj2S$*U3eA%Uixc|d;@VCg#|JfdPZDEEi0Bwm`p!%CT%c$tN9%O^#WP2oig^qFZ@<_tt+u)f!G3xUlQOC(u(p-vGDO`1W9Xi0Zhhz|$pbj2na{MA9Bngo ziXJ#(XetnEDDPW_=JB4tU+GYc8|yY7`OKpZprQCs1dN73bfzEfe2s`<1|oZEbB!M? zXNqVSS%5~aq+6k|&EJ^!Up5uxrs{$s5KRfd8c7`pF@W$VPm8g}iEy{f<|kF&NGgP+ z)cF?o{Iza?ZUROY;I3X+ZQ>^=#kHxD86Tx0xqoj_Lf$Qk-oSAok$&+Xu^z zqCcCI!+=t}7K|x&RY5fD#e^}nb#~tJxPTbnkl(&)R~^4rl{M20i~as#1ds@JSctjU zEf5)zRqDy;*_vMzKlJV7IX>joPPt`c&{(YAu7ec}C`xq+R3aytCwzpoegrF1gVJ3I zfQ9f=14{4LcMXQJYU}Ynp5{Me0o|k>MQf-Yf7BRnS*~8wRWh$mo7A6jg&7~#tr|E8 z!}ck*aqIMKhKp0Bhz+xC(l31H)vJ$0y^kCu|9)FrN;%9sdxrVsiXhyPPKvdseNnZd zuCV>Q3RxE&0}J1A6SL(*d^B|!z`PNMqr|6)F=$tIXskQWeX2qCl}{_*sA(#a*y-6) z<(H1%6%)%BE4=S&H5&m?(mM+?o()c+boFli1G_Q)=Fi!B+-oT2C6?TuOuct(i2}O? zLcNxN{XEN$mlyY4fxmON4n-}s$#gD5fm%8}l+u|9#1>|Tsfj1?4rgxxFia!E=mN4e$G%dD=?Z{q#@NY?|@R*<<< zBga}q850lPz0F^wO!t~x;aa2Pf0N!@uojFh(Rv}fnTswJAl*8c?d#?Bz;>60=BEwT z;_T!_5nwvU-fhGI(ZN>;%7-Vq4X;*Mw8zMaOG>sOgZ~=5ypDibqK&_68W7JEbPN7L za8UVP)uVLHOeI&I%T$#g*RY(s@#f2Xgo(z1%~dr6l+EViF*yndGnp*c<9FjkVm9bJ3$ixhan2CR!{ z^)denM|y`HgC!)xEW7i(P6u=;&-(BFlwh{CpMha^Nk^)2r>IA2oP#{Fg}UrBlcIM= zWo7qB7xD9jp%|**vcQ1aj6(WZYzSF1hK<7T|fm^?M#-DR&QyP^ z#}ZqgRO_OS*I6+96*L>~qE^);-WT0>bN~)!i%vl7l8p6VXK3WYgb9N!dS|NWjf@eK z{F7vI*b1wz^AG0DmeWR5tRyp@d8eXCgH?r)o#$tE*zo%i(hl^&EjpPF%3(4u4r7Ju zERvj`I9dGua(M)HCN}(2qZ|k4PXKkM<5cs;6wE7(QIbZ|UsMa|uqAD1`=?Hj4M3sr zh#j#%+PVTa2FA30l0WWpkuJq?k?|yVDDshK=Q7LgdItSngZkG=(ryzKZr!?sADJ#^ zQ_NY&Us%(a+bj1oW*Al-@Dm>z9Tu|6efsumL6*|y(sHKRZ4BrA*NmBxMB)UW)D^;% zkHl|o06#Z3K!!1>)sj|~OkCnayqi;wC-vmwm{O1BF>aM&H-_~B5g|*rmkfbE0Q0}r z2gs$GDOXIWvK|%R4jlX&zWKHgn8>db5`v}L?L8NOxAuntVz=1hfQtKYP)Dufv!8VA z;hZ;?O-M;;D|WMoE16!g|goOf_3`aH%s`9johx6%Jueu<$A!UJ;PNw$Df>zjCpXsry(S zjxcU3Dd=zA`!FveIx^-zhca4Hp~cbx^VmXyLv#|dMwi0rF9T!P_&@r}@6T`J2P_M@VQ#yZ-zilh4#ck}l}1bkN2 z@h1B%?jml@&ng}j{N|w|%+ekmt-ciDQ=bzT8Ir4x0v1V-o>3M_)B$)Z_PJ$G+KFkx zy3JwVoFM%H)zTjGJ->wrGschRWu8QG?FSF8m@ek5@AkrYKV*uWCQiocKi%6f9d%jj z^~PGe9oAIq989wKhV3T26nLGvBu#mQJ^ne-p+60{bx~QJ_?|w|(eqt8rQxtH&_}*2 zFAENw1lD9#zWr-M;@Ohc#^Paq8!)g!o2+dF6}s@Kz3TM7rAExFa4(4+p7-|AO%1kK z3A48nK;XgE%iX9UajoJqBw4QrT%g;d4+}OUgUpsCS-DtT&so zi~8)RrHe*wSp1-UR}4oSSC?xd!k1-y5#ts7cTwf9=aN7q^F?&^Eo?PoZshwcVzRd^ zL`Hy`Hx}Fa+Hud*Dp^p?jKJbsa9dD4F;Nm6ZL-U~$SeIt4K=9tK-aNWi*|wuyM>VE zu@GvgyEd(i??C^0*@zt~jczW=^=T-u?g`Q0TWbG$ftla|LTD4+~f1QIr*Ndxr#T(Wz=9XA#62=b29cRlPC)p(Kh>IoqX<6OC01>Kw5tR4R1vdgdq9k1p) znt^YmdcZ0u)=!E4%}x7lx+J@WNVAD<+!XDO5N(!oNu3Ub(^|`f<@cZSG(!+D^(f;}meg+pmzP0}uC#+V8!USsfTBD`Zs+G>@s<>OM;)eu&P$sXsMIXPd~m3BNh-S`>*A!~^UyPs3D_&ga;?$1)aLC z(}&#_N4#%Kf%T>x1n{WmR=ROaFMp43O?nRDdxNwm1D}M$UpWq86SuoH-odKwqX?dZ zYdR8!qXRp#X=^5T3WRKRC{?>K@Cb55MiC=6_Zu*FV<)>*ka8y{s zC(gW^ow%STDy%DS43|YZslq(*d>jL&CC0552P(5JLac8#N*%57DMm}-9kQFW%`9@< z{6;XA+MXiE4NYc3hOdeVlCQ*8zKt;h{P^&J3u0HRbLdPa>ql|$wkm}m*+Q1LnB8+OU9-4PonYqee+qPOrYg%=gEFzx)v-9+mT zs1A~uwHqm4<6@W1hZ)0v+HeVK7hT{G)`cA%HrseA{;kg?0kxg#wQgShD_`&p25@U6 zc32XVx+|YQUtx$@0dGEgpuQ#Mt%*)R(0iu7`}Js`-BzLL+#>XOBWf0gC5eTf$#KfF zJdPxnAF@NS(%iANF)p5-lbUcVm`4hZg};32QBr8ejb_OINh85Jk&1;z8{ucCCg(9w-HRrMMZOBtR&8FP0R&)Bs>j-RS4XzN2~3#LJE$~5vxG<(Cr0ggb`h?2zI z5u6asn506j=I2DWmfNuR!d1J{!A&^@)riA`#bLixTz9*c=J3{t-?A|V6qvdN(0kmd zyJCOuP;#>fXL-fCnoF^FUld5cp)xzZpzGD8LNh_MVExJ1$dkr2ySLuUeWu~uvA|4d zwwY+T-+STgayu%AsnU>y{o`pvcV*hdAJIrrwDGz@HwFB2$qQfa;osZ>d+ZlOOC2Yu ztO050+-wTkNtyTtoLwa?2D(L@+iC0SACEM8%-NfTqx!#;^c7fz;pWQMqU0YTsZY(O zTSk%LD9mA=BrhV?Lp4+;*s^$3b(SZ|h)ycV4Y zC~lynne3=~Y^4U0zF)m7R3YZ0oNCe?>}+EFBboKXe^*<`Pyp8v#nhaP2Bm9^-p=gc ziDz$Lu$49mnrmVQKV=X-?qdw0LS0X#M5KcwI(4WgZ|J1^^tQ7}HIsiZ*JbRPGDYuCy$1(hvdppZ*lMEAG`|JkX!ap<$ zN+W;v>5oThrZzG=k&Plk4{MWe*m8a0eB=GI?6IDHB#|4ICN975O^@` zV8h-wzYwhL)Q2I++9tR|{A#RBZItjbtK#|QaNMR1_vrhe- z!;0YZofX9*EL%=poFhR6m%}-hCAr!TPBff&GuSYf7K_izu`uXgd=KbdPYj}}r23Fd zpo7w={EI@PC~XJ{s}84ij0yf8>WaiZR}6j+2^AKL^RU1Ky!zgl_my0oUWMzlq|f|s zj)o|Pc0AIe-NHCud6j!r+kTRWb{S83=rbPbZJ%DIN|OHC^DsfmmIRG2=Hp$qqEtQ} zI2pt^qfFEv=)Uim$PHA6EJwI~HqA@r<;& z>gi)zAGg#oQTWKGM<$k^=$f0w@IEHr$ki8hK^3Zq=x-z^!%m>H z^4Yo&=`{AqNj!73;w~F9&Rb9%ZM;MHZIs?|A%v#~-o3}BNNe+dDyhgZ*r|F+>Q{`I4Vt5oEoBE$(59Ub z$hcR5`ma+;{Hax|jo4V%`SE;4@T}R-BQpAjKaJTV7AT^>f7LT89U3p!i{e9jn{%&8FEU%T)3TcEBf{NG{k`47?V32R zq`D{$kxkJQYDpfX#FiwBr?)xqZo4gZ+TR2mu<_d$S(~N zce|n}?Pu}QxolRA+20m*S9m8=apMVIst}v4#g=!h_0*!%u*!j zvDm}#amDgXS<#2)TjwX=s{_&A=w$a$^ko=UwD4SxA6%d~JyrNXC4oxMWC(p2{M^3Q zeTP=|nHcMzeSf^4!}Lp@zqAcACHouJ&z{x_xb)yhZzm)H=OWh)%^ObcC_ZxA9^nHD zgpf@9Rn!iT3{D>_w4Hk1n|cbTb@r$YXURb(LFZ00)YzB%XQ5Il3ruMp%w}&q$!b9e z0h7QFSn-rW23N)LSGX)?zn2+I@j{hP4A!Uq%-z=I4%1XcaG^uj{+j-AH~EK~^6gi% zC0pX|%rc}?7dbWm0os+6)t4Az^^FQpDHm4Zitbe&e=eP%hZtsqL-z~6yq3avQLu1t zg|27urnP+ke1SaT+(n?z3)!u|{63)-(RNd`*tb+Y=*C&-N zRq5fbPefnwQzR%W@KY`J1{`XEdxutER9=@@t{WP2x)h)YX@7Tv&0kaQ{xRd}11 zF!4LG_H{-Y9Br66eK!6o67)uXEf%B1x#0U-&?8#x1P(HBEy<=Njf<$aDmGQ2hRPrg zht7x5h&j^o-{UZ3sCkh}n*FCm(tfpHgnEXVbX;5g3FVy|QyWHbHAQZET}28V@ej;_IU%T{YQ|WQ!by;=kCyTBZIrYb-G($185ELx0$px!5<( zA&OMlv%^(>c(I5A{W6nG7Ik`71deG*F#Tr{OwRQ^$>JwbYGEPFj~zqnQ3gSsG+m>d zcEYf;IEJciYj3xBcw&Ufgy-~l1FLEg7Jm>VkK|{!VlM=ifAJ69In;kqlg@>MzVdd{ zpeVtWpj6$23KT|2P9|LZT0?~NT?+gH%GV>u<)}LKxFTia;3niv4_21J<~c{+lhr2p zpBoH29~E$Me`?Wq)xJG)B0pWcAm=M>OSw6{n$3}WTAS0g#Mb#FkFm_{Bw3fMGMCCV zNgXM^C_frgyT!&sja_5r<(St}PuZOeVjw`U_=(D;y)Mr|Ji4{WV;?I`cX|Zxfktpm zEQ93OT-X?7!Tv>#SkB3jM?`T?7v_PW`>uos1dl45muX}iU4uA;DE#YC@s+e|ololC zMEB}4*#P%Yo^Oq&ZwtmcqgCeu!jDa7Y|WM4iqZs${_xJCnodn-u)RI}|vsCIsZdgQ%`QQ9;=iL1+bW?@mIuoDm zijhlWzRIS&(7nI>#>f0^@Ov=7X_oL+R(llXv8e%^yD8UPhja(ck0WUH!~#`yky|;z z0ZUIDp?*4{TT1+v5oHbCrc4gxpsX;=fH1ZqQe)yla)SWFhi~eK|HJp%^xtNiTW=NuA2Dzrqn6! zck%9eq}mgcvtdOo@0*cNY~l*OQCTN4rl%nyMB=3sy07#Ze#VOoYm_KOQ55hub5nsF zvTW5T)i+xOy5;pYyVfFK_(KQbaGu4FOv;FUe%FcQWz2}Wo226tVY@~4NW0hPQjHNF zqB%6$pA#AZDtdD$uf4hO!-)VXq>;)AW&TZ;wWAqEC7wENHqW*HHVS;(+U0sQ1#R&s zrjUo|kT8aU@P0YljpR86|6W?T;h=UC*^7E-lx771*E|w`?X%ICTnUe>3S&FBZgS^+ z2Kj#a;WF)P@-BvVswILF+$N{FI@6Sa#L))cD-&GnYvHYXIO^AIyG2Zq7wTEY#eDgm zd0rrYGo#H#k{Pi(wycUYbxpU-#hJwjCKPk#yXg)Cl?0RGZ>Ov-AM5dXX46wGnz8YJ zwNQ`G#`;))j~B9(7prK;;(CuwHL}qg*(f(7HQ6WUmyU#$jwarRq*WKLk-6H`IF^r= z|B6*StMw!fS%=me9V`9fqbT}>{x$Q*k6(Y!9EH6Tx6`AllKR#dg_7;u1?% zje2*lKp-3V7+sJ*BqdQm`TfX~Z8ZF|A8ureLZ)pNHwT=fYwZ5-T@Dx`LogddHJsCu zae-Z29tCBJpW-ZYt7tG{{*Z1-ZPQ^$731d#*CksC+CIXPQ1C-fU##ovY!=j?rl$x@ zL7^7gSAxs<2JoR|rKWOs9f?TeJcLLegtB;`G)C=lCuxxjL~OL@z@jhV@0;T_&%+mF zJLTcW-ivBm`k|zTf>19dS+z62BKN{CX@v<9LVdq&`mkc;7`F4_x7qfK=zTM@C{&R@ z>!LB%RmY~FOKojq0=+o>V&;S0507&kq5N&!B}RKMW{Qz+D(|@7g#DCIGR`moG2DJkx=`DFZ%&Vi14EA*1i>2-_doNgSN;>+b`OpEnNG{(+E-LKzo z+SEb}xdq;l6P+0aJ}#5ve;XOj$3+6phd z;1Ias0!`U?kqoU8b-uMaz_Og@pfjs0lpc;q?WXwE$SxQ4cRXfuf~ZHe!XBI`f}+0r zI$1lgvpRy2ElDMc{}8jNTvwi)ZL1|aPvNbA>H9TQ22&RGwFACQsFpQnG@p6|omh@N z+i&a*=~nKY^f|m;+6DiFv&#N_EdCX*q+4=Ekeb9nj1-q6U%-Wgq9(Fc`#0vJdK_O3 zEOK=_wEGt1fvRnD;jj@LhBygq6;ZV?_7dJHFTJ0`uY>kKseH}N7p`1u;8I1RBMv?_ z#eo*+!)p;&^KeP88I&|}Lh*_G;p2l81nb}!tVE85LZ8d|Rqs#eZf}N0_q2eOf7feD zShiru-Dj$Gs{lA=jf+=DB%<<7`9=s#?W)?<6otY9y`F`|?9}YPyMLute(%$t9L<}x zUkNmXC&jPI!uuv~MI{~LVZcu2Sd&60bYPcEe(W?653YYgM;qcd|DAa@+R9(1k7Rma zAdsj2T57#*@FZJ1j(wkevz&ayfm+=0lQ<-l6CvM_D8k5WpgoL%CE(Fof+dni&Z?XM-ERE)g8KSu zFaBPqA2|BCE_MjKS1%Crk7eDQ(Kki|ewH1aD;~lFlS9DH!SS;Mt82hJq6r?5f zdW!y+&6bXyQ+f+La#TU@X4GnaT14$uz##Ou@P(4&6(E}?FiT6^9KF*+G@;uXE=Wtv zI`}rPWYj*Hy{s+Lp& zf`0AyE@^s%)$Dqqx{f)=Hc=xZ>C+U_aHEoxt&vHddATy#gB$f-2tiO&o=)m7#Kz%* z7k=;z{pfdWXQbl7nCPAiA0O8H-*_+9$~~Y5jfOTPykC2C7K9OCEOW5t?5wEG$M-n$ z5B@P@j`eE>i4H8m?xZQbenQoB%Q64ZVy%;#yXGdUKDb}u%zyKdv7{xaKnNCmX=5yxXI!`0n1qpV-=Wc6rB5IK`!jhC`g z)=1d`CsreSa=6FZK>_!t@n@ap;HQyuRyy5VzZh`5E%Snk68u8i z((N|M>wzOR?7ud<-+jufwO^<%xJ|!3{7M1cugSF&_}Rr;_w5Uu#0$xQpY4=6mK`7M zZH#r%P79+pHhyb>yA}Ad3-g*t7LY8ABi2G+GdUUBhN2SDAtITeDJS&Ui*aK=O!ScS zP)cKNXTN>$N_U{t2`DqHe)#r5DaqOPBFiz%j#+{KG^|%R(=w?9_|>AfID8SqSy(6G zr6);*(8&8Df-MeO1$r-c+5t&HYdwGHSQUdiWcdq97Np~w&mOZ|A@UQUEyUtRF828J zZiG=-n6}||cAelIIE9ZT$6tf-@@hQY&=@b{gcL()FCXVQ^`Hv#3xg@T3HG*+Z*-Tu z+IvJ2z4Ea_3FRpCsc+DQ>FtnbbYG3GsJfAwBbM|Y7JegwQoz_WSOQ%S`3Tx;aTlk* zq|Oo`)t>cT$B{u28mF1LG10(?iLrfk*PIz;#(1zhk{Hy3{eeP3;s>sTLP{=ov?X5X z2nWSVwvZ}?h~!O}Umy4zZKOY(%8rW)LS`|?0#up-T~#H@lu^dHFagZ1#(JjVaX9N~ zVEJig22v3tnQljRUiVkYH*`a#o*o)h@V(ylCJB$^6ZXo8g`2qH=C^|&uB82g+)Wx0 zuZ^1A59DkYG}ngl4vS{KT!VO&!ZdqD?C3oKvjw@667Qu);hKCaK7pz$T$7(8;pg`x5zT=7H=vO-%Hf4Cq z%;-91Vx@7_W;rMTM2`st-pqALa01s*VT7T@`oyaXR? zFcdJM1RVW@7f%=-BH@Zb3dmuD+hfr|BF$pxQ>)do)`h35zWG+#eL%T&_3a6_u9rF9 zULf*HEbQp;Rk&*4LU0_a=o^$`2jMy_t24r$7F+#!GWB8WwT;)YFogS9U3>Q=+*9pG zkF4fqgLHG@yPG0#M8JRD={vW~b|9Tm&vP?vkZI_yD8p17w!~hb_TP|KVjzTKH!fCj zXoL-|he>e+n@+A`TI~Jc7x-{g3m(@TW+koNKo)mRppj3(GHD+-xF)^4b@F8?0ZsW% z$Nt&{Y1tnhVKaa7nK#IZ-{`K`E2J?<(bDjZ@_5p_@@!*o< zRjzF&;WggD>ik`i@k1;o6=UR%_Gfjp1;e@n)pCXK5*Dc0IJM5t=2}roi6^YsW@Cpyiu`ISbryl$52cQ0nU&1zs zDj6Tj>UvTo*F8@~mKVCq(YwvViZJmDRNj_Z?4rl9MusGi>?emB;=lc)mw|K;U9--y zhK9A2Dw1nIH*JLxk>@|`XnAM$x@@gfo#H`Hf%k?emJ$9{u2T@1;O&GED3A{x+i(|tywU(}C(vlx@LgXm>D#Es2v|jnorL>{ z_szev-keO|R*TSh(yikkNW_J<1nd9gm9!wd)F+Q#kkZ}+Zt4ZiW@|+^@Qx< zEjD`~k#M$ySwj0xRQX?&$*u)(7b+uHvh4HHOoq)(bKS~0y}@pU`YPm{?4wU}EzR?$ zy;Jz58RMLce;R+vdiG2rD$Fc-1SXT-kr?l`;xU&^Eu+HsfhgYVmprSa9bW{AjHaqA z?*d83o}!TWX!Vz&v*I`YP_wM1is3q7vU6Ebw>GQ_vn4y@+6@e6jjOcV+vURw8EIqE z1v+lN|GAz#+-JOA_J80?S&M;Be{<{sCu? zpCg{>73%WykleY_0lAnQ$*XJ93CF4+pq3xFM+!&m1lB!nD zTv+NSd2Uv7UB&n@lJERu?Hs@R8q> zlsooIMr*OEQ^{uvH>pA%&0^!cyJC|1dnpCRH6&8=37M1`QZJUVZ-sk5usNqAy?Eux zv8xwJ+ab*yK0DL7AsSxTXlmF3+7idV=LT&y;b6;5uDg$3E(e1GnZkKi+l$0)o!SVj zRXxo5y?A{ThOCFcdzf;~E&kR#FM$=ZP8-UW)AmmmPb+MyiFTt%b*?a(xu@)S2g1i9 ze7nQ(k^xU)WNq7wyvObNgwTB#k@Z9dBzc$dd;X&JH{W~LglXtZJT)OICX-0H?q8hy*dLCI?c96oy;|ctP2c9h_1hRoBMZsYKOV4IC;4#gjKd`dan{>-xN70e7jAtf zFhAD^HfI=EImyR`6L5*+8-F)XUJQeAIF2~c4I*A}3}?s3+2&1Db78qoOVPrK3pDQM z_su@)f+y%R2QT`>bMV7W8?I9YYJv5sdLT&BYbBy6=VpKJ$

TH?>=>`@^jdBSK1t;DSrNUDB-vZqcO%MZRL1sXS3fQ>FqP4jP`y4sKWN zi-1Qo0|9O5!^*$WYT~jO&u=;p#tvo_G&(LjLz65&lVYRV#yV5NO?oQ5Md^sHsv<>T z{G7r*DOy`vV>TofaOrn2{xB(5L$VQe*~N`nvDYh%O0{Mw#9FG$Wm#vdxUqvAS%QS= zf(-w9BVml!YMe^>o5>1Ul!BSECTQF-UfUqB=gq&AF3&M^a6{b_4P)VecN>v@*N&ci zmRkh#r;xo=&#hZ2DL?ihp1aN zl@Iv78IBN6tC(c`gq-HrK4J!8@_YUt-c$sz(2%^K?E_F2sW~3&O7}T!0+sWrpb6l1 zD!QB^9b-A-lS+L>^(Z_CvNoaIouVMnha~-pHkQ!m)c9>-1Y< zKI9V(wdC=z1MKKd_%IrgKg@K&8KungAtl{iHN(Xv6ov7ik%^e#A2$T3zPST(YzuiD zp;vNxH`lMYXYV_M?u_V{?vgy$2h`amqmhg0Dyhb)CTk8@MwgDM&5E!8dB*oM6^PI_$NFVeCgqu zX&6s6`DO$HTp5XPKy?ufyr&;Noz4`IyO2XTx%i$?n}II=&iM7 zz4o?!X6$3sH6|u!a(zoDt?B=lf*u#vd+Z{8asid6Mv#Cy{Je4bzfQuWxZro z8fts^BoDZrUav${K8MQ~`-_KB|K?#szqv!L$lwialUjt&l1YIt_RwG2%=+7+j_<=z z{K8WhLq78mnh;xvw0!MJ+!KBuG7}raHlmo829fdJdS*ULsoRt-J}qXF(Bl-fGI)We zo?G|kz6WEIC74Jt3kRRl>W_u11I*cFJ(VX$nl1-Y{R&?3u_hP`#`4chNH>9QR1$h% zIyn-&7hmA;6h{P&Dt5&?3!77Q>IQk3N#aUyhp5oGG} zDqRxx7hb^lWbR3kR9l^`qBt>cF18$fYZ&K4Qx@wA(ff*j{^Dr&~* zwQ5Zmk+~513s;Kd_o(y6Bjw!UEA#r*lS<}iq#pWaU>gSKMuRvqnzu#dCwUd5qt^s^ z!9;`!Jf$Q(K|4N&Mw1dvWWh7rPg~P@lP_RroOYqo&Op0^F`_@$9DaG)c$Zg=XV9 zCml~n?uSgpDdc}hDeoP$j1j*^@;pXbG41Q2b)C5Q3eZ%m9&GD68zO6EjXPRbvmhHB z;U9SrDig)XRW}#B5}k}E?Ea7;xFNyf<6bQl=$tz69j-hgLI2Llr$+X|VMCTOQBUu# z=&k!LD&&Wlv~xr9gnelI7JzizehrcQS&~FD#aoX|nXU4|Gx;gQ1w}_FL3lo_AjcVN z-nSS#Q~wB>Cgk8!FT5L!_Sjw+R)s^6nk^(fK&=inGzz_beyu2Rz@l^E|G-{W4l{!U}(t)|;789nBmbbJ8-6m-PVO7wX+?>X=vh znSjbI=Q&XImi=MaG$&nCzv|l6hH8t>Zf&WcSi6y!j7q)PLh*s3M~xma-10t6d@#;& zKe6_#)HMY}lC2Ep{}gV62OR#ph%v-oaEm{^PLFz^mqrS?5SWs^I>%*sBAiE)Gsb&+ zUEeVc{WC==Li%%19L8=;r-q^vHD|rt_O*inDK>k^E?y73i(n{1 zt8FR{$a+lp!aKLB3$~p&?X~p?X4B_a6;Nx@ocHjNT7(ykT=}}a4 ztKth@f6J-=tASJXI8*&Gkq@9lNHkkYFj@0Ew8o zwj~wH5S^80k`jQSCeqANTQNrq5~417@|IBGwVI2pJhCU7sNB)Qi~BQpbIp{s-2A#! z+98}#Hn^GGxw9qgf~VVEH@_m@*SX33i2t;yWOeSVnfQlaw7A1UlHkBDm%SpX5Q^29 z{8Lc{RWB}IruLydcQZ|sQ6dQ+hBozGh4GFugqSzS$!LNi$p8m1o2{{tU+>-5Lqdc_ zvL0JFbDbwG8Q{)zYI4cN4S9X~mw&ZJ*=v6*_uU}marwTl1L!z&5Uc!#y4ipC=I>og zLa@>BJl)S79k$?etcq%S{s!ic~5c|4EygNXMaIKxL!MDb3EZbKlDiksc@5fg{l>b-<>#scy< zX)?PzYYKm;(E^&yQoy1LGS7hGIvfzQC7-(ESF`S%1EU5o&CaQs1ptJ)v~hVVhS!Hg zmk4XDvnFYDJe%Z-OH8O#Dv*qU`q>duDmqXVdoiUshyf)v}`w0iwwV26z(& zs6a&7GYWDsTY=$ZiSCC>{e{-Dw5V;qG>Hs0^LN`kA15z$0V$cS8ua-x+8cOnqOCHE ztUti72*dJdeY1f$o|bF!NUQPfd@nVcrpDWARMouxtSBecbc8?VK@G*bs%3IQY8usI z8r7woHyFMN_itbYD|rEYjZa|Dj+*rTPV*LX*n)b03HNo7Y&P#`2ET9c zP9E}sLo_-O2!cAdPQ8}(y8x_H5SPX${;_~SIfkB+u_0f zlNNmBAKF+Vw?q+XBZraV|FrhdY~UIM)$TLq2xDkpSz8h8Zk^I`*E@t-(+9uE?L;sR zIn>i7!bFzl*}N5w%5>sIk!r`3DI{jz68?BVTS>sfoaeT7@6XWAI2s7Pt&+j@&oEcX z$h#H3obIhR^6rJPsEo*{(-ai`2IoJTOb?d1-cT^<24KkUld4YNSea-~O;`u0ItctO zt#iVTxhU!6^}G}tlJLteg!>11^u4mCAvu$I9@RjYyErM`U?AA)EKDta#cL84Dq^oY zmE7Y_pK7r?MG<+2OdWO7E)autlsm{o9iw{;Z~hhehtmqW87THPUtAr)2$uXJYEjCe zv>-8ZQOPtWP&ulZ99plrE2a#)T4P?5$1}fhd?0m&&>f7@V7u>9nj9WAEabG0C^L|n z=rKyAy|(ZXGS8~k$ZK^AJ@SCRx$&r>I|OU>+GCEnA0Xh49lK}I&S#zo@%ApRTvFuD z-72a${XxCh;0zxZ^vjb5F<7^=LYoWMEm^*}TsDqoT#BS_knYIj%5r})cuw4M;iw4J zpKrqVB}gaT=qB2vs%d>|&{F^Bv!_YuBl@v&=qXX!Fyd@GQx#bSv1_3f=&fQY_Jv5z6t`|?&fTC43Pt6BE>qz zJf#KX(bGz={H89saEK+O4x^=|_iO?YsfH6W8X$$teh?XrWee<=Qz1gBJQN|MU`Y-T zWy{Wr%A`&!2&Clxu4!OkSGCv_@k%MN_xPB|gHpNCdkp@j&J+F`!)$XIO#Hoa&ogQ(kn`JxHCLkpEk*_qAB3tvV1`ZUF5$2cGD~#YQ=d%Iu@XW7>eKFCvJN4;Xuq zuhQ;JvFA$3$ooR^lZh0#gmH%uiZ7$9D%Wc1)|!E^wj}YFkLzNF>(JgYDLbWx%n`yH zqay(qF3Wu0gm*$@Ef&zQ7Fe}n3INgYy9%U7yH}gRgw*Wzpsj3OAJk=$%e9}Flb)k< z@GOI5BbDhfz+H#TZ8kwueKm}Bu{YWyVz+mi?1aZrHfG^Y1^H_(O9iXmp{3Zf?MQ}m0C%ElPhGRA1i=XpJO;T75lr+uj>9XJMd30w8iuU zAKflBaw0uC`ZXg-fmA@csw;k;5I64%T=rHR3d!w`=)zu52)G20;UG;dj9L_C>l8Ac zlMIZ{`#zTbkC^0>M!CrJ;y01*z{3r@z|vV%?e4Z9Gs>OA*JO~$*`3TWh~_p&ui|LY z9i}vIxzQ-4O-N`uoLFoQ_!dhOjuT)5(hPUrWC9FW+GtGS(srM7?fMzG=Uc`E$){(N z@Bzsy^Eu@~BG%v1!SR!F*S^P;-!$Az1voPK4lPbY3K-lT#g4%x8r8=64><9pMx7Dm z5H0zO%DocF=VNeU09=;qc}8U6Kj>J5sc-hU<}6$$uJA7NBC0;v2#KX!bI}?%CqmI1 zS?ccG(~OwH6ZU6Y;!^1&vjGkS{#EE#(g%00L#a=bLd)h$f*^s?6$w@pMONTx<_xE} zmj@wgXsdDZv+#NXV?`O}2&I~X#aZx0=*cTo#D)_U-Y z)$9y<%cPmHJO=JxS{Be6RUM?;&L+md065IwKpHl}GY>dWc*edB;4|QdPjwD0InPzD5SgIUQ7M~tM zg-F+N1T@eCj9&w9bDe%Q{k}^Z?J>{w7}vocfXZ8>|0PfKC=;J2Qf5fo)bTDSp2!Nz zH5=a3@rPobml#GrQtdwe0Qkya4m3HpyDeL4?C^l3U(E{%3`9&Y^pfHQLMp9Z9)Fil z660()-O_cj?Yr5B8t=0C6n~qd)w;S{h(f}uWw=sxemzZCtlk@=QrreRMLqrxP+LD734Ys&Lmk9lT^8*g_;c;@ ziU%%n=3*C$uFdBl`w9KggC?7jaFJ-_f%&|i*(_0{4Pfcj8uPza8L*G9QYp)IWpdP$ z4>L^mNx(23O24g&k_p;efCBDJ1ZE|tP}(@S^yp!{%0tl99nsyC`&K>J?tb&LP^*pB|dpJiRZ|GE^jYP|!1tV1*q;&4$e#Rg=c}d;SR*=Zlevmc*}D z-8+JjbrIyT7;w5VQ@Q)yT{R&=8CbT>BxGk7L$AAP^*-BsB~sYQ!HfLIs9y7vR#kC` z_$A7k9?+DHY3h=>GlYxY9zTd`xf@_o5XH60FoBiEGS58@Ce3vRMQ3OYDZtnAB+ z8{xT_P8cwq&d9L7?NgRAG2*&o+WU12)r*|dMOD>y^OxYr$Tu54%jtN(8e0q}P zCv7s%XZy{k$P$CVNaY?{vR|?f8E-CD$}LVB4D&k)j!bGh)IGB1f+Cow;KIK6r8U@v z^HtDKYZyECP2J0_o}3!-uYH{AtMTO{oz{)1N4zr+l(Q|_zG3QCDXU!FT&5w;#Ds%? zWGw|n94qdSY&->FuPdbw@vDB+=l&-Ub+Dsk4D&+IoO8gybB;mg?*t3}RRM<(vGW@m z`vnP_nb5C1K_uh={9Dbu6l{#%6IOM805Qq7mIXFjg9&f5oQWQEel)p9ftU}d0gPH6 z6CTaG^;XO(()vN+MDfYUEy{-1@4|wFo&Vg3P?z)@5eh_VX~h266H!U6)gB#&6k{_V z`p{l%oEHv6u!nygIccNUWk{$Y$9 zG6N{x1-Cc#qx6N+L@lR9@`>P87<(^?bu#rhhLpoG?@EK{SPlqHkEh<2vBD>In+QR+ zddZN)h%i0%%DEo<(%&;AO*~p0EMWsS+zAy#SL!lcdW9Zuc_&-K98kmn%IIS`wyh2# zY0sGZ2=Lb-)5*pV^HYMSAN@a9Aj|NTl20ePkG`E(WdiH}AQlFVOr{g{&gc0_xTU$$ z8f~f`A$c_yqvaPuHsP@^(UKnSeGid%TUfgX8{aScwv>?k z4gI#?+-xxrGDDk4uCyA1i=CV{rfrHX9{g*}ISP)1cTW4F?==hF{&wt3a?^M@sG2ZK z?w#gtC^qO7fO%c-XL#U`mrB7Nkohr+REclSrR-+LM6P~)Z=pdO z+5<9C4>V_(RDNliNvp4y)rRjoyc=w-Nh~L+5`~kIgv3oBjEhhx%V>MDP&<2piB8rc zS11G?pFEA6A!KWk{N-R*JZ9la;qX_MZZ{<(JjG6nhKhaigU{!c4QrPdb^X3Ask6C_ zA@H!R!aljiBcqB%w!&IHjB=IfCpw?V66HWI9$iw{L9-A=?1C;v$BZVo$UdNjdia+8 zO&7o?baeXf zR8fwo%u0jSgHu99)WcP`lkHZq9{Dqup;mA7r|^dTjRX=85*%!okhU0HxA(&2d1+X! zT~62b@2`iB7=R!lSlH3`$D>buJzfZ>pN?{q{aO!hLm0m(Td;Mah|qOwj3W}E>PIOQLgC>>H znb%g5!E&+e6ZU1s*9RJr09z#=Gv%zTkRy<-d=1jW1_AkXxN?s{^oNM|27W)s=$Z9LbPs%;hf3#5)|Ag%tr6{Vn2JODYw{!>HhB-FCUnbk z(~sZH7qg(P$QPuLhKKDE3S(eM{S&hsSsAS4x&cGRczDbBkU=xH>{q`@Qv%^}VA z#oGL6Khbe{h7V^q;_I0>sbFK%U@ni_Lf#yvMihAc;zsuB+p^j?v?A9L;9uZC7-iw25C=YcxbH_(cBU++_g?aZuZS1 z@UzM|682zky{Zi0mp1%N{?3*?#90=D03eIDDlQ2b&)mJn{_SxGnkB z0h6dHypU(|S4~k=7HC9X3cm(LFyhS_R;tYcRnI8p@2?6oz!)9uADyXb)Ws@hnVA=~ zx^}2b=B4JJ=DR5fhO;Ob))Ms#PFKwRY?`%0$*=+LD&~TN#y9doZU;-U35*&j+@n#4 zz{qhl16-7G@Fs@+u>q&DZD~X0-~qT(ipULcl%QQ`2qLvHQ`5tDO+~l&wIde^)GjFw zU=#jxquiJiZqnKx<|4qnzTrrqWfdiEr*!8yFrJFpMalFGCQurOk|#Y3o6DZ|U@W&v zlVm)i9M-1PR#HqiD2dLfP?O26dumr1DyD(%U(fDiz7Q;^c6AQ;D!*X_;D^1tRGb-* z71oI@r*i2jF_UEeP{WJ@zRwqcybQyM(LQlX#e=f#+L(|cZB(@3_!$E1%z-lEftu_k zrpI(`3}#wOY`}?d-KP5AZI9y_$@pfZ zX6zuk;VXJ+>tNloy0H&#fHYnRq)D33jAI^A##zwK(*C%jLA$(f*YbF2G9z+D_~4-e ze;hw4#`#1=CUw8pSf0oq*}ozeSFvb4?9cGDhH;g5=~yT!mi-koSfFC*)86WJCm7cP zq!RJL4e`sHrrsdoqY9sR{_46#~KCWM+?~9MQy@UaP zp8WmPd%z@#-KEUa7~|UGf$^TV$ZA0O^@EvbJ!Sz$e`|W>Knn6qClu6&=zZ{}f}Wk; znbvXAB4hIPhF@v5x;aGG+1joAyqpBaExp{Pr;?JPTF+o8D1J0&T#^qa{Gq@Wp#{5E z*Y1>S+C4jv8sT}Lk4J20Z6Pwt*hzG;;YHpn`Zzy6JGx#!^7e85h%BhJD-ik%&AB(r zmMSAAA9)kEApkE1@DNZfzK zfgGIW`ST)icyGQU?UW{v&HeDZtDTCWP3u{jLvMkF027g{j^?OcXnVy)f3RX50?LwE zWU92ea!l63)Ds`C6g=wRHu25F*C#(OYO3!R@jXW5e1ZKz#^AVPaCqA?hg;lMc0qTl zalEn8s!Q{*V>@j@>rRXt_1V8#6+UZ^ir7F~dd3GYb57DL7fEF<`1XCeO&7&Q*97bz zjYqvmHR+*u*e1Jl=BM2Yc%cDEI-=J+DgO*7(Z2{q`M8%4!p{sZuG3VqiVG{fN3_wc zG+UcEL;WO&^unX*-=Aa{lLtp>XE{7$M{X+C;Kft2MFuHmWgw8Qom0ikq(7M$`|i`y z>Gipy4p3M*(p+LKBQODfkU3lVTQgJQ1PTD&!(a<0w=N3va6~~5EH^AJ9Q*GXxcQ}Fp_Pv|G2!9wnPwj{+LhZcm1d1D zg-OP~^8q9y0H*Rkrr{$_3(*c?&pK}a7TypHiwtypU0X0XL^f4y3TC9-#;@EKEU3;? z(im0gf&|vbJ+r+J<4v<>Y=A#VEKl3}j|z@fokIPl7Y%_gqdf+vP5bX?=zp79drLTJ%&7+A+n zrBAH&NptEG=jEinbg4~9ov!I2Q0@LBx)TmX#s0vpr0t!}zGi%Ulzt_)X4z$jvC{9U zA7^enzK3)toG0MC9R(~|r^6q5kytlhin>igk?Wu{aw+8Hqi9S&fRyL?ir7%k%wI}_^QEWhytT+rgN!m&8dwUvqxv

P>jhc0urWB^ z91=jceJg9v)YQ$40CcnN^n+uiZEOt+m*Ij%Fd3l?;tW%Z(-DYO3h}~Mgd{P!l5IrE ztmS5L^Nc%Y$l0S!la_J-e~H&WZZ}*8LuK39*jeT@1MGoE{*He1 zmoF^Lb_!IM98?2GL?^$&>>Xc&kX5ZSCrs{mDt5?vr6jPCabN56{H;CiC;JLkC)FcU z)w=|_su-#VfP@R2$eOA;Eee$zZQE#N=4UpAH6Lj3^emGFx_E z7#sHR44c}(j(7^{>HhhTpc=#IkD(nP#G177*Gl$wvKlLx@fg~V+oGI(C>o`x&XuIV zo@}dh>X*5ECa#1O>P69#CI}=j`JHlInBs}BYK_doVGX}NfV-Q0TaGx_^BWN(P4tC= z>xymO+q*x(I-E-bRGcd7=atYnmk@$=C^g1(TK%tg%Cc42YihK1qz0t-;epm(NAzaoJO-T7pPIjyc{F&-m1j6i%4#O=$~33%MlHwP_n(;K=@ii*mqvbI*AfRZ~U zZT3YnHBl(hLi%Y@BQq#RcPsJr0vSOxrC{b~diJwRB#OcO>@d)iUZiY9_3^@wixiB! zo)jEJKaPJ%8UV&!lNO(-WYu?kZG&qL&vvB{q(Y=9EZ5sCe43*;9BJGhKD@hijrfg~ zS^I~szhP4l)G`gpa+Vyny^Z>w20-@J1Q6%n;*gK*{#g(Jh}LztX5zB!RRkM{UuY52 zU*VBYicFOFAW9lMRUbx7V+NHRC zY%CIOJ%QExfXbcrFADQpO%ZGH7cJI^8$U1q-1TVxRB$K3e`MX;B0!&ec#@tjssfLB5ANuUacG+hwGjqoJ4}A2M4-fQd5H&N7;c?$O{KNHESZq+GXJK+KcD(}QY z$)&e7j`KS@jyYyi@nv>`=E5MGFMBy+&(baH{*-rW;INW}9g7N) zE_|LV$RDe`?L@scLl%dwtBfGwh&q3xFcn;w_v zR?JcVBj_QUfn9*{N|I!X46@WkY*5KsSz18YXdn6UWRKLk%EXLS06;P2KuBeSpu67v46c0r*TZq|~z57K_F2H5j7IM00$loAUxc zXM{hSlWvW=-42K+e`9zNo|dnJdCGp$ok%KkZHrO3!K}~yZ#|RgXa{c=Ov5QLeLi!Se5&|4I0;G> zt9(eX9Bd@hHF}VxS_5dOQj3*A8>Ck+m$xH;)}DV*a7ON&bP^7v5dTR`-7nYTCrmA; z?9fbJQ4@C=&aLx)ZgDY%6sZ9s%D+xUa^pkBzI9lrZA`6CdkaLlLXqqw z%~?4Eu||_oYTwMLMDuyLTmRCET;V7tmj#_p z8Qy&1OeHk)n2Z&KFQ=l6pqu4p{62y=Ejes+rT+&O&i|kArIWDopODG%;fNwR*EpD> z9}@9=N`RD|_;C&9sJQu#D#0v|;m8hKykOKqR9c>?=eQGnuh(w80OT*a?R$d6&5!9c zI#HFABi+md3c(RdC=>j7YcjN(8GuFVeA!B!QUR`(bzMz3EAByKPT^+D+U z4ooR6mQ*7|l;N?XDrjvy`%}umIyV?vg`9Nz|3g+!A*5QCvLEaLjO?{Z06V@?C%{Pk zuzGIAgUnvJj^iu@|CVNBX!b|6A!b#rWMjfSrmN8W$f6usXA|a!{mh zaz32kAg9pUvI5LMK<|Hk0J~>O-`126Z3YpGVREgz-z?cJPGe7O)N~%kQreI`=mL|U zphyPC6pbB!9D=NKW)dDl#xI$pU-95Oh6VcP!+KK2mk4qHQ$_s8OVxK8ySxPbdxdx; zzLD1K+z+YAV}vzeyCH{L7nb?JLuj9q3evglm!g@ujA=@kDWEs6#iTpda3w?oWAHyT zx6pSz4WKAjDNCYqh$#I%S~_mW z;UtUZQpk#)^#K{+UU>1VYj&N})0D?ipj(b$Wx$#za40kZrAX9^^ibPE25r!`)u$GG zif@9xC{L!S1^SRN#X0C(wkgorn$^*oESxcW*il+d(}m682G^}kD`cEXn3DZe^W00e zgT^Sws&Uxa#eI)Ddv_W^K!9(Wdj!Ubxv)2Ya~z=k5(u8D;! zQPr_*SXAGaI3}x8pIBAcg)x;A6Tc$KYvF`fm>GG*9foa;TwYQaXus>;L!8M&6Z z_Of-m#RHN!op~@Xq#dB$*qt^!L);mu#`h}+Bq&afc825tR~29hGasMwsQqowdmjTd zcN1c;J{$V9g;XMyGejFkU``!+Nd_0 z;xZaD7@cTOD1{Qs(OGgeT-ib(rp_7+hVmZ5+gLjHylA?A*`|h%@=^2s!kxY+Rp-=R zt8aC`rj|y23W9OZF&Iq%ElCk9^D2aA*Zo*E!nv|!pTFO{(GdMuS(C+BPfMMMphf4p zseGGBWe$;%r^EFAcg)cJV&u`}>L)C7Q8c(krDPFnU8k#qNviL-K$IU2jo`!PNBQmA z;49Mf5oo)<4f-0i`P+Tx5OwbuUU*e{L3Ndtf5Q3c{lUAI9lB|v)l)&$Zb3B+&F8rB z8fK{xEe)9Bk+xMMk5sHPN~#m>$D4H4xgG%1gp3#QGTjB3Zc0)}TM*p0A)g|etDqp~ z2tLOI_&=I$s?p!`1V7%(;*$VvGc>A$5}?uCev6NkU;jCQE{im<4j~!8&GtJ^D(j@z zr|n?QEcnZ$M~X&_pFV1iyc=xT4DU4z&YQ{ok z7tqwdI5er^TVYW)fF3yQe^#ay4(y)`O-FOu(9%@>i*c$DqW{EdqfjOJ6W!E<{A{Sm zi~!3QTt}geAhtI5P^YP3LQg_bAFSxe~5%;07WL#>YLAvigl0EXUZfxK;V5P zqtRK}!nK*QXm47f-&jwZ6^0lz@NIf~wl3KPP_U67lLvsRfxsJ{h&)r82$<%cyx{_; z4+=hl>g5EJSes6xDSg6vRTZR5$UiZTYL5FyP4+g1>4TD=qRRY}2vL>;oQ3+1_sKm; zFnJRd$&bZ-@+;NB!?aSrjJt9e6Ps>wR!-PrVThsOPvj%j?AB-)Vx2UZDXFI&aRa^w z+TsB;>9XT%+M*uR(*g2zY7F%|CMYhQ-rl7kd3fz&goqV7U5yiWYi}z``noRY$KsQ% zGS11&`8`CC5ncesKX1MqxUPe~&1~a8*^R8yuH%0Ct;8+MU38h8bFd=(aPDxrrD7LmuN34iH z+A@N5A&bKMcoN3d8Bx@H6uXo{3DnhPG^67PB0mB}6j;2S>MAM!j?S~}%{LeUD@4pz z<)pZ#jkl9P%3gZyZpS$a=I|46Fn;yAo$dA`1iL)vITARZ(lBlCN$bJ8_eYHEpY-1W zn!JC{mqP~tL|IpE0CSRCB=AW(6Qpm;&b`4FwP_N++N)?~c3_}XqWo^thc?awK7^@B z!~EhzGwGFb?)}Js(lo_+jU4A&Rjo6cpMQheSG@7yS4=8>v@giVbaxww8ftlm|J>t% z?uTcN%;YySJC5Cn4d^FeRd(_vxY1>Ebz;5VW*DU!-l>9;!SDN3*_{3bKQ6z$DlLmA zVCNsb8i~T{r^_v+@Wp22$`=0@%*$z$%gn&+Eak)OYLNook8r}5T2)EUcs1cw4VG^x^hOT{^*2FpAby?CTr zf4qJeSn1RBk{AGLP5;YTd-mqD0(Fr8iUb*IDxH)w7Cxvbd=WXNu4v*&8Ad*q%Eg}? zHQ1RC|B_tAxzlwErfl$RyuZZ@6sPwu9Za(djXv=~y{M+E2ZrSV>Em)>fjupk8@9$< z=~1jis`<3NYe(Xro`oF+RQV3-PT3TNYvf-9LUCyzg&(P7t%tJD)_uQ@7q8=K1NeqsPov_Jttdo{H17?Z+~6MFbf!)ye~!$@ z8u`F}9xpeNW*Abt(AU)`9~IVH(@m0c!(_vT{%lV=k1B@WQ7P_dghDdXSSOb2;wWs8 z#wncjEuP@{*Q|MWuulNZ2)3~+a)+_ov#wZDT(4!-IsBJBiUxx2kY z_1E1Opbo6_n~MH#=VdJ1iivjuV^ye^c}#E)lxGlIfg_H)tubS&<}zk|RrmVVq=eP* zTU2MPoM$y!aCD2DS*4n|@~msDLd&Bh(w3lTvdRGc1SqDuKp!Xxj12o{{uyw`3M>or z4WbSK(USrw10ecpfBPjxa=tmu2j0ND@)>0wi);R$Q^T39_@DI3tv}nxhZV7_k-6W% zANjbN;(+HpX*T&M*>z&a3b$w7Z)9&hCI|6{6^J0>bir0|c_gCwg~kW~ms*a*w*5*2 z=V8eDM3U-g{RQ5FEDo-+(ZiGe5~`qX8Fm&SM5Y%HV0#oa$VOpp$zp(fleSWcZ6sgg z)AqJh+d`u`_&*;EjZ#;G5F7jqKS^o7KSQKX z+7L=L`k~SU`#vNzB-;idjBtEYTY>}rb?8Yy`5~7VD^!KO<4u%@Y?ec;$OZGLx_Bqq z50Lyq=d8=_ZKDSLjVQNi0o%}jX4!utvU<`XP&xm=8++mIF?*9_r_{tF_rQpC8V_ln z2(9@#$2q#q!F}fV`%EovT&}KT6fWjLtTrj{-0MZ8eSy!=jO;it)$MXZK^|EtJG>MN zy(NF4+2~LolMDGQbu7{_y)B%J1@Xs2U6m>sB@4jZ3HhDH!En63vl*g&p|r}YDEYYz z%dqS$dleEWXzHXp%Z6)IGcaO|T8O^8DL^U*E)i^oUAK?C1#>?f)`|jM(~#8wYNVAX zg8LrW#YOb)Vo^nId>k)b{{jod+BiObD#({9mBH&O#`!o{w+1=KQcxp^8 z)`!$;ivaL6YfLb8gcPcs(0E1=mFTiZn{pj9SayCT{rneH%wu_4J$?yfw00{a8pg!Bv;Fe`KD9yugy68BH%kIb zP2y4BmmBGz=FLjRt_CdJg<0j6hz-QnkPPtqxpvFEx|xA?o$T!*awyd*Y622EQqC1Y zNKiBZP=Pze{Kupbi*gH+?d7VzfD+qZHuRHnYvu8E5kU!IEbvj!kE`=4XGbdkmsDn{IwESAjhxoEvh*XiBC)Ds)j68hxgJTh`XPwkXi(I<=M*-3 z#@;thV_PlIljIHA2rVXXbtJzlsl*i)+pRKLA<|&WHTFNVl?86wiSx;q%9-^0odC)a!s(4i*m>wOE|pK)zs?A@k(rjGFH$5S~fLAY;`p=A`s7e zPF2auIFkoAH%Trd7yiIHPbX%{Y~@eA%cwRy2u2xuS8UZk0U?YGkU_gcgSDOeBY`Q` zZ8Sie{O>6jwpL+V+Z6WmBi;H|rDP;{^nc#F3Ahkv?GN(Fn^|>p=?7|V5ngAZ{A&I~ zn89G9j4PRmoTcJ5K){dlua*I_=QoNby9`RL91bnlLib@Jk9#Zrr~2wFzf+iYNa zpd7uOI2&CLO_U{kmYT3NN3kZaQeqWh)r6XCpzPlvfSHeYvazl^VJhk+Ap4X-6#xS| zdq}T11$|1Gu_|m1Zv1&mV#;j&KieU8DOwj3?6pT@T(O2QCItpI63=FWOuE#9}4M36PP)CTj-1CuSd#kGdNL<@9 zmmTNvjXn1F=&mnBg%ZOrOC|3A87%#_aluG%Jmp%NUAI>N$>8RqwffM_pKvhlGy;#o zYjxn)9>H^~knERkj`=n<_Rch2gAtnBS|m^y9vmFBH^-DB`*rKT-nDyjP>LX7yd(_d z+By2m!Wa8pFLwS+kS<%@yQ>wroKdY~x5Eg10h2v5$WK+cLn+1}qHNE=v7MGM_2o4q zdKyv97z^tMe8JvCx_if@)&%6uh4sBj(Q|WP(D;^(NJ{c;@p*Ihnwz%_y|?v8SoeVm z=PP|E_nBgU1?PJRM&m=ZsjCh?th(ViFmUXg7P3o_dG?I+;6p}Za$k=36fN<~@>m&& z3qH{V1k7LD5hk=V460`sA<@H%GFSOEu)}moaOl6O3={EinKW#ZSbP+gx89`?0JCG0 z2OGsV#sdM%O`xb&0LX}vXICnB&S4sf zsrAhj)E9l?_sjS9`Thy>B(2qMR8%H%n- zAJvBYHQEc5s3)OB7lqBC#Or*}KL81&_ zDCo#O(U<>Id;hDrB7M{I9%fg|^_c z^}5X&?ag}Le0!PUj39Z-_Ll#M)NEqP@6QW@(3iBl>|K~d!m$>RGvo}W6gfa5l|8Pz zF}%+VZl*gvG0?E5BC9ZX_;?ST4!$8AQP?hSQ5B{Pu_2#_?sKNwN?}U)QMb8=`B=7`vFd1G= zi6~&-Xtkc4V_vhsoC?54D47pyLbUm>%hviVOpL-EG-S zK!Jz4h^rP6(b+NE?%m>f^>NBe08U6e?TK{!d>92DVPLb5R+e?E5`lVsvJh;!Bkm|K<0i zFso4S6&z>9_=J0oU?x-dL_!ocsELV#-r2@bl5w^*2$016_I~OmgZ;ni+%ry^iv&l6 z9+_zL@yEMaeiD-zDUBmHhgN~Dq~<(Z>&xxJRPQtbvWqd$uMl0kSK_lDQ8K53xj{lS zK=Jf{tP+x&_LB(zB6iDoD{io$4qBH+sK^cI@<$_NC>j7KlNLOtW2i(@o#-U>Q=TzF z4W5pTG{hLMINxDVS6@nwydmK;-MR)r+l zDh1zYYN7XB@n|v3-nW?$;lXD)A=KwVR`qZ=P#@58D?jpAPWN8cuOP+5?-u!G-XIvWa>v zDA%R43>#^;Xvoe5Vi?KTq(KuF@V|Py!V(pmSnqiJKcc=etd5>(cn|LGZpGb-b0}`b zrC4!ycZWjp;@X3|6)5iRE~R+!LZP_xo!-y&U2lGDb}|#0nQV5mnM{JX)yE4IOZH8N zTQ!lS(;V3lv1zAj?X*9M@$D&p?qowZbBKbjA4I2Py`1UYwEcxIKjo=G#oQ@lSb0v> zNTzooon=4TvbC{w%&Wjn)?{aU^TBZ{=Ee?=ZehtW9|ogqQiU##Bdb9;?c;`qjh>Wk zDy_hU@QDRubTNI3(Ryt1;EkQyw5nZAwvt_{ts04m&1O!x?ueclj>4n*;`D=b)3%y} z0-6F#&p>%H#=Io?>Dk9xTR6hZS4(@24tQTW5&L4nRlR^g=InhI4RO6v8EL8e32Z^ObqpnZ_lzorKTrvu6tui9ROOx-P9+`Z~ z1`5_>@7lT@kyV_O*s%%Cai%Z+RhgRUs$hOu)AA+=psMz#lS7<8S2 zMZbSWWN@X65l;>^wERi-qUZZ5Oqujs+oBLru%lVev=|1slf=6;X?^F(FX5(HxcC`nh4o}V8a{u z>dFS2{C6ExRXix<%e4j}RotyCPg#ENnJfhw2~QiN-+I}e zw^pbr{oKE)qeL@)XTq;3kqQ(l#QhTX#VJLJS-KM}Rc@gH=)X`xDKnK%(}uvOAiCJ4 zkZ8~Ag+J1~u-r+e^6Tu|4h7i;MaRhSiF-&354~^1O;zg6a%F$h2}oR!olDF;5~qB0 zR;00XX#m5M^<(mjNt?Sia#6KSBMXKM8jFNXG!`h<>jw^}G5?aLPvGKJT!4c=F^HfE zDR?Db+w&(<-919LTGw}OpU^gc6(aFqX8H0|yl?5htT*O-82gni8J^TSayYolg8Y=T z2q|h+GSAjvHGhxNfh(0LeymDCFU{z2$%}YZ)g%8P(tbwXd|sdS1HJ!|l`P4m0R16V zYt_d9outuDiK885Wmj7Bdof0MwHnyJoNH{#+p5DDB+mKiZC`kg@9K&dg%);;qlK@( zw)(lNcXFJXEhbqGQ4GMG$2i*GY`nC(9D9W;y9>u=AStF{62s*^um2uJ5Q*Tk!S3Wx z^Nf*?#`jclq~7tse~M#y9rH}-G()zhoz2tggf)(-d59xV%$U~rBcJ3fC|Q$%*LOo7 z^32egPL>Oj$TG4<-s|6+uatck5WQeKy8Wh3P#uD)KCjr6(`rr%i+I2&>yjR&;-6Ja(1e;!1^!GP5kBk*;oYr>b5naI>)=c-Jq4fKz z>uq7ne6w(kUy4ykp$ed^LZ$VA9~E~gYU5g|#du2SGD|Lfpjm?G{IgRQx;c#iAWe!y9+uW>sNX(w%=`obO%DhI#%opI^PX96~ zxG3$5Bmqh`qhIWN9iq{*^xdy`VhlSO=t2(!tC88$Wfwz7n?O?0lse`VMlBSi2u}*|k@?Ua^68?Tu)4HvpR3K75!Tdwe zm(WE_>Pawk=O@^g+vPQ7;+F$VZFD#bO{iV^;2aZX9}Xq$#QCc-=lc5R83eOdjq2l3 z$GdCP+w1xYbFbAxLBcKWB5yiLf@a_Fr;%s=rszhQZz3>sX#3YW5FE))IrzL&F{b1? zZ8#R3oEDt0w-m|01)_u&(R(RW`H3pQ@D~EB8c@%EU-KGOEd;z*=q(qc5BJ@1`WuFk z9)&F{Z6bCAYci#s$l5lj+71N@)7RFFIM@OKw_l=J->uO8{98cx=`I@7Z{oo*ZO5+eYn_C!hd}ut+x@9KXhxb#CQ!3vgjWj;p+d8{+uCX=k!6W9$`LLX? zaoLfxX~-X0L&eGp zF2{}|$wbPs2X9&II?FIQ+eL9|zBzsW!I!!N5slthd;BdzHwLe<_I!e>>-0BoW|CXL zO;n9Sn4mJo^}~{_R{wS#x;zKe4gUkBo~0(s<#2`U+Lv(S4V+LcA`rscfIoyo$ zNOrA@lZ7W?^Fb_Ay1&sTLf$Bb_uda?4Twjm_`Dbn%fQ$oXKo z!@^S+J1B)XO_t-Yg_q!4_=+0Jh_*Vh=n$;fY4}TeGT0}KCXN_HwRCdEVE)xu?d$o>*VzBsEhByuEBi`BR}l0ehU|lw{nMUOWosAw@k&t ztb*`#>e@@~UW|(GodRB-)+!y&OT+04imBHC;q8N|<99r_C{l6?K`WYpUy*$jkpaj& zs%K&tffeuU#v`mKTPzcz?>gDc48hLOQ!GVsUd2SA->@Wq?Ca+Q!@^!i#wds-R3+m5Ix7X(Lo3YH3QF-ci`o_6O{<`q^bS+h_xP-NdEwFE z-wB9%#}`}eBwJeL>S~Mba_vuJqgVdX~6RHJwupP9@Q4$cG5x7Y0FuwcJISzC`cBV+I*`YU6Zn7!H%R$7Cw-(X+6PQ z(oSjX7dt-yI}2IP+3i5o$oANNM`^ly-Ur4(t^f_ktdj)Qw!92#bo0-YxB_ftL~a30 zj_tVAoi&;(-;R9|b_<4fj2tyNC8W2In^~xpWez!JYLdS}ool|j9TlbSrC|F^P@{lO zH_l`5Jrq+XUNzqN+#I|0!NtmoBwij~#l8^F9q?}^0R%rSq#Oos4`$&&16L~kLZ zIX%tjQ@dhg#<|O$^&o{0rj`ungj~xE)i?yK7FizQD%lvB2t&`#{%!&wP%=~T>3Dxb zg0s&uTp}&Z{F`LD57Ov*C}9hf^{_C}{>k=H0tLx>q!Zl^r(g+8bl>;-0~ufkMTy!CNB<;Nr^8^4UD>9SSRIjt>2T#`J-Q2IXH$*x#>& zjRP9<8JA0G3(i_e;4kiO=>y(i?0-h7b0$racHcf$!8NOsVYoC-89lw{e4gFz7-L&e zI6(~j_-Zw07(UcpDvUxAf*mJEHT|u8beq$oOW)Kkyav_iQtz~@NxpNDJ6 z1!<-?L#ARAe&oV(J*lZa>nJp5vsZH3HY^oAmD2rZa-~WgebV#1OmUgU`KZsD!uV9nM1i-wo#W|X(a1y63otu^ zl!}DK!Z9YDMOib5xp4yNSIcu_?zP6tBowN=N44+;xb@2|yALB0F4>p!9iA07tz+!; zJ|qrOd3GgMvwN592qF%D66pb$2)rYBZiY?B2$4P)%nZ+ACmX$LIRwFVyx~|V`hcuR zeocNhfV6Q}WPYG>n+o!(I$Dh6!HSfIZ1O^+L>m2nZC1g#ezzv$>0h(JacTY)D}O}< zM<0OT7Pw@Sv_4?zHpf_GqHK`p<>HG`3DF~KV7QCyu~t4L!_g_XzDF(%F?;`;nbQq#b{{kY=%`@2;Ln*zjpdTUz^ z2UZ8aH{!i4WSxgEk`AMb1il?2OEajphk>#UZb+T%5ViHmEhS@sIq{cVfS#2Wk3|#Q zNB0<~?K*FYE{~opM!1{J&JR<0ijN2<%UVq)+fJ@s)mBz#Orpm(0|SvaJg&!F*IB%< zH)T7ep+DXdYQ#_Y^Fda%1{^E-*jo4Hvia=zm%)T4dvq*@G2~UHHU*!V<`F}=} z-El;!&hUg-Dz7hGE+5<2&0kYG{_N@-E!SzOOWCG?Gkj?KB#K+HP@36Tb5T8kq=MLy zs7$5TGE}GoD_mypzK$5?cq2DaLy0@7|}?2+BswrRx_pHnTs&s*^uL~Nx4RUJsU=`X-P~myxYcC)|&b2??Ng& zde(PR{(z@~w(0Pfs8c48p%ZuMPyB~qlNUErYaSD|pR4O{dLvYMAcGN3w>OBchSBAu zY!igGrJS>ue)~6(#gAFDpwj*Vl&)*H3&cReH+tNCf91OuKy>kM32GMnW5`9cRGko| zp9o5)5sW7~kW5ZGxC5$?e>(A5F0am9o!%buTTosck^-E|RYc=mR7vu#@FPz;~OH1 zF`VDENAW$j9+jd>;fafBIEO7AvUq(zPT<#1kM;3^R3^GC_&k@J@m%Y~f2q}DduAPu zv*_V7tLgg*>X|M!`HA0JdKbH#dn!(x=f5|aVLq?Lw(G#lHF25*vRSHUMSMiD1_&c< zNpc+qWJ~y^SnLT!)MEWKY6nJ+r|no~d+fCQ2|rioxkF|%MZ0+|rxKq}y7Rm0BDX)S zrmz?ISZAsEXG0E-$w9BU@q&2qLrSQ<;P9?LK_}?>EgC5(sPak!hG}USdJE1G2pHKy zvm64|vrz;@%!@w)rATMXFQ}UG=_ghtK>05-0HAk`EscOBqeNN(Oj8v{)k%L1>12&5$U% z$j+&yu(%ZRb*$x^u{qWr??%<2wt6|AS&@L0_{`6RvZQVEU^aHCYOzA@)ToZsv~?+U z^3~2q!*Rmj#IU!ya(vc(I6To66AOl)H*E4%7ZxC_%w_RoMX*men?{CWOi&3>L5KyzyGYN zG|Zo2O(;cwOufx3LG#-XJuG=>9p4`jjpzq3`mrSK9l?YcI!!5;$%We~JeX#C=va+J zz+$C)3jNgTeLx&7yZ@4ufFiB}y=n|NyuBv>Ff!KL-ABm;ORTk@PB6=`FjuA6Lt{ni z>1;O)gNcY$^nh>UQq~T*c3oF9D05(m;KUxkq+aq2M1xq~jz!fdV!AJ}NCD6YNxknHzQ-O?rYz;MXoh637p0v z1d%n445$#(NGQ_uwXq!ybe}gSYhq7sY=h|FaZ4_#W_Q;ON_`{!IOva3!S!#F5G3Jd zQoo#c55uZAUlObAEDR8Swew0}+{L2(72Bghh7;lTz_H#%$r(qXIQ@nm<@Ro{e13X0 z5rP&rM=obR&08abLbR4Lrm0XVlYQIs2ot%#i0@m*coMRmQ$)(-oz3BujJ3hMSPhSQDpR?xtbZThfL`Ma5u`TLr5&{bxB+EmkFqXS+vGh zK>YRer1N5&Rxx~7b<+h+H1i6X$}V%c8Ht%&9EgcYsU)$uU$q!G5niDtE{anOKg|ff zb!rOZ@M{!0)c+OIik1Yi$QoS1oBT?naiW~13`!#tLD$3Pi;EW6LiI#4aNDA2kk#ca z*v#EWm_aUxIXSlXOdpqe)ZldSTie*Q!=bTzh$mZZFtDU;O>fn+PWWMVn;MJJXmLVd z+z&hUD_kEj=t2kVgc0ZFAUYw8gyyVok>zPuANytkwi?!S@5~25WY3tek5?iZ%^@Qx z0wcz{d<2dUh=pOJe3TJf&XZ!B8w?Ec7(i0u9RiKTT`)ryW!JgTIh5h|-M?iK=MJI> z*jr%T>Da61-;F$z`88Gw63Oiu-NP3b!z}ft5V$DtAne*O$Ys6lKXEGJmPX8ZJM9&u z5H*DRhD_(E)0yPG^q+E;W4_suVrMd62>R7BTb&8RU*r@tIahX0iclQ?b7? zehSCM5XJ*|h)pg|^$Eir3+L=%+hA|L;!rTryoVhnFyBy&&Vh^9efZ@hHZj^_t4f0e z@1l~RsBU){a14M^=}#&U&FSIn-RNth1Ij*)M6s1GY)9S@cJP$c2uPKJ>+>FyMO0P_ zB!vvg8ZLl8uM{qvVp(c1Hn%=$1l8Y<-j4`BXV9o6hx#3~7k&>fLPnZU`X*do;@C!! zT2*A<67kiuWrTo?q*kK%1}@D3G>mQ=_r+K1odPS1A=<5bkh?QVfj*HH$L3K?YtO(G zv-$4YeqMyf98=D7z7|{^Sj~?N!Y&TCGC6b%R;(qv1vlzZ3pUQYX)hO~rJ2)CV)$c{ zZp~msK0PQ&)g&7vH5-LzQQn^zUKn@W!PpuH^C#Ec$hK1 zC$bFf*}sK3s+WIcM*ltg@$8 zy2mQWtBXc*xyyKp#aGp5Y~uSzn~aRFu$ftyj>LiSSUfEpKdi}d`E8j`!zp7KZ3e|T zoDG3V5#V9?B&*zK@MfHMuf*)-}f@ zkW!*6BUsweo+Ybyx<YkUL%1kKuJd2^i+IZPW4s>5GsBxrBzgrT# zM!}Jk=DMWqp>*8uYb6vpQ{jnaia$n_7|hX8FK>-8+JKEAsAnR-InMGcJDLSDaMz@e zz{73ng_Lt`ptT*}PN5(6lb5>=#;R)IFZ`jXwE^{Bko8->c9h@Rk`!+c!x2e0+Y2&t z%ij)6Ns}@YkDZIS7-%4LwQjol?nm2OeiKB%H_|vQD3qlUYh;|`v%OC92;lyEHAP{6 zP*Y#95Mr^^(#N-?Bl{>EDZ(@Z;Y`|=9=wSPg^TGOzppCY!9=1ix{I7@z};{({1Rjn zdKr?xRi&*&?YHVG+$Duz?8ur&t3B+`)n7BP*UG@v#@N+=sVZ%wM3QwOg6En9FXT#~ zvn+S;{Qx!zTL3BA0Zn6@$8-?WUQsZ;c0_^tj}}3OvNxMj=3t^T?smNCuS)u8wn6@WsDDE3;o;0%goEt(2s9dkQ13L)%WvcLJ2|&9*Q32epck z(d+~89@zb z`GT+82^&Ru4FTZeJ0}fWOFtFZXP6n?{7gfOXa+T7_#I|U*|r@jL)fVWf$y}x?;Vxd z<=MWa2#zu9U8f)`jG%@TZdA%i59RC^h+frFBujO}dA2UTKQK(+QT`kSJwVCt(Wz*7 zZ%I3inh>yj{(vv-;aB`{p>Oktb6KdJI`hvpI*a^im!lptSCeJdY4bjRRgftwg$Dg!9Q5pN-RTJz3z{X zBL!>ejyi6Cg-cK4i}>mZoczF_L4G8hOtS{%cux z9F`Z=hCUQ=8lwR%v0)>qrQ?|smngA*$D1O4-6x+pQ&lnDmg8@b?t4Us!G6ZdedQkr ziGouG7u-3lPZOVxPqHuu{4GEwL~p*Dsr}F`i*Fm})LfE5sO^Q_MA@Hp7uy&e44+NS zys9@XO0-45t~E3D4&#wMl>w^~70^Us-7LNGTzgjk1ZBD$HZ%I2ci~WGz!;=1++{Y7 zB{1qR;h!2VOBj19Z&UPCgOwwWGA&goS`Cs|-3H;^Q>qH8tp@(v^ zzdYC|M{{&C6hf!!XN}lzTt{JXzQooE=u)D#qaTA3Z zR@A+ms4pLST!9;wJ3BVqewb1{om*D48Fx#pP@BZ@rwznN+NevT`D{+>um$<=gNna= zu{AGzTW^YwtsT=$xq`AUy2{l$Z^HV zso|)&Ok9=g!Zs&N0x?k`4@1#kZjRqeQnDkLrOf$V6vkV*ptM>`WI7k!X6ht-)~AL~ zJ)&c}j3u;i?Rje7*!=n;$1$Jt~{8vJi|U zha31{J4o&G5vQJK@~f*nX}NmBb_ikGG)}gu5dkY|&u<#8HZP_+W)Wqo0Xl1HZ;p79 zlUEu1x@3G!yH? z=kFGBgg4(fb&F#6wIWy08gS?alw(g39XetUbkjdvaB<0rP{Xsy=cpK(Os#MX;vkY> z6JhthE5f%-BvD|@e$iN?m^7OEv~nC$dG+^*sK59a`AqjVQjbA(G%#6afYWS|aQ5?O zIi|9R&gvMS!Yh)q%98=#P1}~kzh!?Y`J#WA`H9a=v{SS%G^Nh?HA$r_t0#l;kb2*3 zTugG->8zomP1wBUkAF8#A9hMO+CF%tBn*duq2w>0qbj^(p$_*~xILp4LSrAM_K8%1 z`IvC;kMW;h@KN!OE(a%~i5qFv`&BrWBmOlNMfgW!INX2$KUw7D9g;RRuu~{_5b=m&)BIDz@E{ZZ&_J*DN(3*r*(Xe#zRI|JRRFA-_)jggU$@}@@s^{2KmVR zfDIqDI|4B2yE0|UFe5ub|0L#-hGcyzM&wV_rinBw&AQJwcF}meKg*s#*%PquW%w0j z$$WE^6}C;_VcIy9di_`tpH><^-Hs&%lLCZ0hY#+(LFRRg3b1{iaT{xyl$o*?DJ{Lm zY0}+F{Zj`Gv1+uRjjim`=5*p|8a88h+BHTgJQGxMD;IhCvh__FqSAZ)>fsOrshi%b zqP0^H97x`Pl3~8KD1W8E%SFyGUt}Rqp)h)f*`*HM1pGbeQ!Ej-%%*iuqs^FVZBmo6 z-j%9bk#@l3npe|@LG{QWMQm5oZr0!s((T&P--VF`*0 z{8>&(r&Tk+RZwjH6N(@dP6e==ixq=#H~Em1uWbljN$n578$X z67hLPp))^|Mp4cwNl!&%&kag2f+w&Pb4sdza`ylI)}N*7*=9sBW1cDEm(Kg^xl_LQ zdsJvX82hL7)_2Uatc278SyDL57D$Vkfpmi6(y!p9t0>GkY2wDxu`k}uRJg>RmbQ@; z@DlUc;34;PStlB1p_tr36mWepRG+7*e+yMdZ`s~fn`wJgfd!@%)e)N>Q=+wnyPFBCxu%sTk*)wGXhrV)Kail(&vew7|DTAX6 z5^esvyU=ZnZ6uLY807cq=)|0M8yg1U@XlroYLJR879q4kzb|8=Y%O+UR016YM@;zV zsysh4^aVmy`M-VI(F`WzNy4HJdpl;Zd!49LODcnZhDLD?Z$#6CbfP&vD;OcZ#&L28 zQlQv;jRaKjSUC@tx3hBvsc|AI*;LEU*XWF~4R!iom$N=kM*Vq3Ri)<86`RhtEKIWZ z)=MU+v&b$G`#yA9GLZ78HA)^bFk?^Xih*v8eBkPN?Y^3Q9x~4PVs;&fcx6VUg{W9y zXqLTSPZA?(#mUp4WDzpMQ6hn9-`#RMPW}xZzH0+XSlP((OZF|&0SeBOsB19n1z#e#$#dcr+%3^x1>9}uz zsk?UsgOVQDi@+l&@y-2|y4Pi8C4qrl zh3rn4j)jZm&0eCqeNroG{(9AJjCoa{J|S`);|ZBkj7icf2@-(M|Cxu~OXSJxgc^#q zhJuvG7^*n|&qBQ{HmfysHr+%Yt@d0M`GdZ}q?{;ZVmdPa!?4Eh#FSV9iaP=VWMlVO z&G`Gm9Mbi`?ed?sH{5g}dd^D+p71Nh>z;48k|%4wYC^aaEI${EO(~rw8px0+`b_D;%+FmNlh~nKufyy^^Ot)2F!}QRd*a5 z9PrTZ`R5EN9eiT~i#j{`!SR9rvzeH&)IuN5VPJhNFxqCc+*O(PMfgl%P4dUi#MPp? zn87h0M@kLw+F;U0Ahv%|AABSqeW}A6p_B_T7TFa6eABkqjcT@mt7o8S^ zxaOmTWz+j6;{9Hem;7_zv`v2x)SP8TQ&ZY4Zns$2eNJoVp71J_)y|ir+6>9u8(I{P zqJ#l;OiI_qW8~DVe$p8q86k2rI4Z)`eJvN1G*4PVIN7b z6e3cUn9pj=3B&mNj{~I*_#Z^!5bSDTe?hn4O1syQHGeG2PZ5z;7Gmq{==p02!CV>kft9|}sN_jRE%(Yq_Z)yToS!)T4Yoy-mH1(9-2Sxdi^DNV zv0GX?U9WeuW_wBYLH%{-v-%qe7%5zg+o1I9NuxWA{*RXtiN18F>pxgoZEkMIZb_e` z^l1EVt{w}$#}eGt|5W}RB#|-@(VOOi+}Q;qW`@htrLtKpIEKxne-y3|G1C#rQc|n# zO_`S`e22iyw=8F7SioM41cDJAbQT|}U!x+PZ?1*`F)5{{+1aSFp0MkA8V0QXP2juy z^;&@X_D%jf`tD`sBGmK#*t%1r9{NGc-$HI~fwIMmM3B;q{&eCz$#QZU^eGG(2k$K2 zJT}}H_a9rf=F(~PK2-(1uEn;R?)S1W@)vh9ns0x6pRRId z6Q+(&Ra9d!J2YtvDNOK1i1>EXhbO7w0hY3B61Np3IwkqAOM6^&ESRQcIlonWvL>G) zF}z~|B%UZLir%qZeGn*}{83E?>d;Oa)?jWi*p8hX#&{Q;H&J(+|I_tl=?YiS^M{;{ zZw&`_YT1n_$EmrAfJUI9BStyfr&avzz%p_wEYZEdQlda+Pt-h3b7hmD-QT%#u;+#C zS}ik~<#mt73?Hv1r6d-674;KJEuC(A^W9+kbAmB^i{I~(In$rkj#7()D? z4fVDEX(!TOYxrb@P)KbtZ~7(s7cSOw`AH#P=sY#*3A9wMwYuGowmr5{*U= z_-?oq^%w%ck&dmhXm2xV(_0i){cRsn#!LEuUb*RFyt7wrhZqsyl+#8SW&dW7y@cAA4 z=RtrI$wsXT-6+4#q0{Qg2Az&orX-C(XrxK}bIlg@TUF|@>FR`g0s4@7f!QtFv`9_6 zIflC5^@;Pr8HUEmraB&(@k)1&*+>^nu$}OhD2kJZF8m*c%q+-IP|9N`suB!9=jE<0 zIvSK_W)Y8-U4J=cw#K!tNY5I0DOUS>OAvj6ZRv%Wq;refPyEw9e$l-lUG^X$jb{RK#o>Dh>JBS^JF8Z4+ z#i*O=r$6{?EhbsL=b;aYiY?6W{jyxIkb8vN>m7lebEuBw=(xc1$M;9fJ(^ozH)&s+ z3x$2dLfFDn?np0 zD}g`r0b!%}NQ{ z2^kq~bUMl6+Y1dn@Xem9*VrZb!2z>JxtYvHar3M)u+cfw-wW;p zb(=!%-4|m>f4Y}s$pD?w4D1gb;3#%ZkX=o3kPPegDTjA8-TgfD*zijpvL}VE^CmT0 z16gbww@{u`UKA4vVIGr+wHI-$)l{oKz8Duj-N}Flwx3IRMn4s<+LE@Aq)g4{4+rY- z*&)3K?(b)?yRP|8;l_|lb)X7{fXCYyH@TV;?``h&pJ)gFq zNSkA4E$y#)!u03FOgpWbN`?L=_hCD*aBd?(N`x;NqaK2SN){60%#>GG-yHl15r-aj z+gQJ(#I`W})QiUH+adz7(+?)jY<~{Gta0u>nfryj!9GMBIuQIJxFE7ydzBl{YM;Xv z%ni{_YHVoFpeL2nwM(=a0FJ&k<++i?7Y618Ymx24{O*m^5aqK`MoYz`ajzq|O!|Sf z-DE2eXq^J4`bz*oRmJ(vg4ajU*DE!Vf-{|iyn465D2H&2%+6i6NJ(Zw$5FGQ=JccA z5cE07M4?VysLfkbp{!UDi!O_XLR$Txu|_=d5$E1&5pS#aiIupQ)Sx~@uklE(v9Ny# zlw{IQi+gyv8}o+yPQ`8npYN}xgz|T3S(rY{UQ-m=m0*Omx2nUz)ZSUr!@JytwqL)b z%r0pE@tZC}#F$#)ytE+-p=cc)`Lw`lw;lF@sK0EW7^e_Uvb46lC~IdfEOD8^Mf^pI zrGouVM0%{(KJ)LaU-mmOw4*twDlPA$EE<92z2-kNWD~j!>=8kAz zuq75!6M$uD(~q2XC1dX5F|$~IORMCq4L=?;qf7<7-0W{W`tvYwZ6GZ0!nn%l;!^>z z&j659*9~^3Vqn$3Jk%=Cr4dn6%jX>Fv7e3+Xv%y$VsQ9jD%tL9(dxlrw8;TQ^~%(= z!2JQG$hG(G5t6^epI`vc3K!0Mb|g}YBl8guOdjo>$a{}re&PI)YF~u`J{owH0)Q61 zI{;ugdW+poEVa9k`U*Gyt1!ji-7j584aaErXNDaFFNT9u#2*9+29PTO0H)47xW*d* zIH7srlHBNCj}S}_D$MHMA#b)&h-A0Q_y|b4^FV?@Gtl~>LAirV4nUAoI~5Buq_V2f zC(uF{S*(bpcQ~$01q!7=qk3@V%s)k+r~97)S^z)}JlZ1XcZBAp!>R@VqF)CuTusDT zem0IUWP%r2Jq4p25Ky-OWb+*L3R*fQt<^`se5a?1)Gs;@+M=aYJPxirSf|Kf0CTH? z6Nq5WO)&3q>H$Cv+)^-t!yl-ineY`2u>nvZPa?cq56tUbFvJ$(enr)q$_d2*fHn~V zBRMn%(ItY6E;#dPU1?;ekfb%%|Do}%dH|RNWeA)WY^`6g`Bsl7{*_tRc{HpZFm_a( z6CO+}9T+S#^NT(YDCtkbHU>m`(X1|uYZ;Mpeic}XbpxcFSqf4;5q!bW3L?${L^;lH za=;t($yw{HpchgAR4zm4koqkPfQjBB+k*Mawnep`OW4qx(Sij4NYDltzyt$tw>mXmAe(E)SuL5}aQFqOX9+u9Pt+&bx>$ zwC!&|PE+$w^IuT)IY8;CgTu3_;O56(6e{Q%U6as`GO1x8sRv6`0BD(sCnb691GGGt ziSTVIH~`cSz-rh!k3|%$FkYF?eJ>? z08s$|1M2CjO3$y zN1SS*Bzu4z1g574%D3^6u|Gh2c^2$hmIu`(fSy*)T0E!|2z*Fr7!|pS0G+Pxk2iSIYl_0)XZeEdIZ)15H7eFgE5fPWcaqZN69sH?nhtZwVkhQd8bh z0zkHRs5VKhX7K;=0xeSB%#-+t+|E##VXGjFAF7ajz|{XgG_5tldjJr%p?&~h5pU7! zYJ>YXgj4~x7XY5j7fK->3{WG%RQ3Ev4AmN#xe?mY;Xn2G1Vh;+d-yM12nzt9kMp;` zTmOM@N_UGH|K0s}fqxUCYiu*hiuBGS7@FV{>=yj#|F8gn7!Sa7ZUKeU6+Ix6bEtOD zPx6fakANI~={gDk^~jb60{|5?z3wUE?X5UE93TXSLZBQ8vvbiN+di#WiRF-|Tv2EV z2vAlTl^LnXxWDv(m<|4ssmh2!Qtt*(g(d%*B2=vOK!wOij0M2*1F)hTPXI{L7*H31 z(g7%P`CvFL+->8;e-Oyx9ER()2g>o}!tgh$e@XuZ6h(cg{EF(IK;gjv@CZ%wfj}?+ zKkR~G=#$f+5Q04b7fwb50K@|Sgv2fO|0({9;mZC8(trUKF(UB)fPYt*Qvg2VV`Zn; zv&lK?CFtXSC|sxiBY?_Y;ve+Z=)mDs>YQfM`u}jUGXP9k4*&<%6XF;XD~uFs0tG!4 za4FaaZ3i%ns0jcHu+XOqAO=GaX+)9reTcyTjBzkDMRT6K2O6QRz_|X4p#ix7zzU@s zfnfy*Gy%00s35eH0QiF*C~M&Wlp|;L*7VG>D9x*u*Z10 zULM$p27GQ&-f^C25Zd`MfN}B{F#nf-9{_#)t)cs`jFLJ4&y#4d4gg-DRi1qqotpo_ z`~6g#7Xsg5$(d>t`Zt5-4{g>wVVMaHzDopn_wJ$^>pL4ltS8z1c`PP7%00&|c~c zl?@|Qr2%kEV2}%53H>Rj=K7bJo7AIv4vqZsgZfoN&)c5((mstu!+u8(3{c`Ui^W9_kGCH4#-JT|s}v8tyZ~17uJ8*MzX> zV{|JUWuUX!-+r5i*^MQ`gPiC_?V&v`)qETKq;D&WhwXP)9dl#e(oj3BSYLdettdhS zDn3gnzWKmTY?p3SAu>5YC=tFB8EU=?(1Odt?r%f@m<9@q%@E1Q{n(;jU$02E=~^L$ zX7Exe(sY{dz)%ft({~(fY?(c(r+JFWzLp} zD_VkbM~7M%@JB{R-aXbMk-ERiY%H1M!dR*X3L;aW7hnEGpiVHjwdct46et7BcXC>&I;yd@Ls69j* z7)eZ90iX4@&aE<@vk>q_roriN0f=@?Hi2=KA?U@e16XhZ@kD~9IJ`L&bJRcIWUz^q z3CVVUh;pX_^k)D;EPxC8fB?qj0J^KTUbsrO=uZlZLd|?%$92i^Q5T^eE3`-IwOG@l zAaT|K&$c=7f-G(SFP{fC%{R@Ed*ByK<$WggaFrh>S{!uJVm-X7QR1=;pKmhUmOl9` z+Qt-h)Kq=^W=mRs+8*`2vvL*E!}0HvL(_vvuGl)G=uC_WD`5*ZEdalGssm6=1f*ts zo?t4ld7%;tI0w-8-m#8k*7nprtW)_??s(izsEXfWr5S5%4qJ_Sdpo_=K$nvC=h~Sl z;Qpm@(_8s9>+l^_Fv4`Z@Ixjijxh0$Hs&HqT}&yO11dmF6@g-~2gpeEh8yqs_et;z zSG>*qglvdUD$uynPJ9!HpG4Bv*x+iZ-21$r_2w2cAjf7b$KHO9W95*&YP4-Vy3|7y zgj4zI;l`2Bop1g3&({~n!%Y=?i5g_z26i>o!>fkyI5){j@AL0cOE`NSss+b-fnq(Q z?nty&*E-XdgrDm!)Z;$?m~7r;p!R2r9`~Oi@UB*AMzC|@|FM%poqnH^Eat5n*AU#L zr%5l00x_0OL6E5=*5H5l^A6y`J!GH8q&L9t&WKW50MvDnp>m`(xY~ohXJCSgR_;&} zf}x6(is*d(WEPUCq^0t$Tdva7n(O0LQ%n3DyGe@pY|#4|u88Niss%CEtv-s|NHO+EHCVxH5Z|JfYbmF*+Lu&odzkHP-($P7=hlBOg0}+?WK+o)SV0%G}{(&!5 z+$+&u{~ax+i)bXM=sEo`JVb^HI-h_5prCVTqXB~RDKaF(Y>cW=N_0)!PMVaOqDVV} zIX)w9D_wDkr43uzE`MAX$H3DDSn|r2xJi-96@6Ej5{WhWU=V`+T0^4<0b48qnn8C8 zG42P594ZNBip&gv<_v%+pry|{Xx$nqUYuDT_TS-Hy*3yN%J)J46Jdp=UNy;aqw8y~h7}oy+R;6yV$sbBhmuv|MeW+R60dWzZtJ&j{IPulO3ngFd+tus z=UYdTxONv{-8a8*XQe->(kI3GB9^oM97tqr?*)jMt7eMG{=KK+wu5>Ak)u(w#n0U8 zGlPBMbqW(}TD-Wza!DIz{q^YjdXXLG%dI{(K3$>AF|yx5+BOpZ4@^L_zfAl99&68! zAO%*N7i3r(j_#2t03J91004c|p<<{3iSUVCTS!0v3TGnLudMPI^CP6R7s&V7Oyl^m z?`BM-fus+5V6!d+pt9J#di{pfED~MCrry3*?k{u=K~M>YK!_D*E; z00b=!vkMR_Nyn{GXb89>afpKepoItk74Ho)R)zHPTd?CI2(hGY(Gqr^`@!Z|7?cc+ zqzDTe{_-WB;NaGwoSVN)vc`SP^z-WA6AP3E*OY!SHu^T(9o(EAgtWM4_vzbW=H$Md9|@iDmQ)nq_|U1iG)OrZb( zAc8*fsYlr3%mAk(3Qb#`*?sT;1*~Gk!a|bA+5lsHo_;@be%1zOz-&#{?kpFrX_8}- zYq#0vU^TlZY+8-jb-kBHxl+L7&^eA@(&OOCj-MwZCL2kcDwDnXem#Q_42B$_*7ugv zt1g;8>*(L6LljCik{4%M)U2GTUq(jCccotspzucFJneUj!z!2+&7|=03)Y%9s|jhV z;mFfQb~1o=RgW7ejWe76qCeWQU&hGw>F67h-Gx*bOnPAjei@by0O1kT z1rFizz>$GhFdCd|7lWtpg8IzE)0xuURFyG(kIz z_ETkoN(YZ76ti-?<6f@RLDS^+AC9C-T!vjV7!nkK&L4Z=dj8n6|Ftwj1r;Emj|96z zZMeFj>yP8l@MYuWTY#8rAO#XO(qxEAkf zYv|k5J_$@-R-wB3*`TOV$GLzww_7r0&x`JT%D3{7yGmU9W9&(Ecvo1O2GexCUZVD? zo9w6quS>;C)i;f}Bg8o+Goms+!x%{Ya&8_g{9pduN~66=%|&qN3eYV!Y0v_6S|YFB z7Xo-#go#sX3XGCW)b7+CbPW}~!7yOO0eo>t(_K}pBme*a09cu*5lvcn2@on{m8O{U zJpJaC&3|lN&}uq-X>A_iw1rgBFCK0a()kQy^8B-5rq_`Ma#Z0W*d|YB4MXb=u+jMG z3Qs9>z>pocvR=J(X-v>VtA9oaXyWwP`A*V`3^{$qK1Lcl^Gwd}*@Y4?w$AzM0khsKlPEpmMV)W>&0G0~UA# z>x-!1fI}_&x*+S{d)2ZsD7<7)S8s57<%bQ78<8F?&9!SYAC)$OzfqPM^Qn-U5G%Ss zzRS;W%??*hO~m)RiuOQTS;gKCjI48{m%p`XKZb6!xnTGe5It!5n7*u{Zdw+=_>!^r zsq$CXo$Q1-mt$v2%KNf_jXnMvHGG~{kN(2+9lp`obS2-L`;uuJVI@NMnYfzWi}^DX zA^hM~Ou>GDJ=T%wxfb|RkE*PB=cKTi zyc*{jvYU5H{sR%m)-pE}AO04i<49k8J0TWT3NH2cxG6=xJ&|*)D}Tg%Srbhvnj;*vjm6X_S8P7N+HRdl~;|jS98U2>0phFiCjoy^+hnc1g)S_yP25KEum?jkA9r?KS zI43RS_Db9QwzkhrxgHhD|D6;xOJ(|wn3rk`X-lPgBZt?=^x5W?H28MN2brFJ9yOtH}?()%aoO{0L2VCp}o zKbDLanEM`w2_-G>%i^H$5yX{#th)i}t~+Y=zAH|I{wARWKkLU`irsHE4F#I#Z@=8z zGI_Map7z@|EN4yRt_oq1Djh1h&Y1D1`5KW|* z&jtN?`q9VtQrTa4D}xGuo+dH{+Vhx#u9}`PG)Kj@Wz(pC3HUzXG|~U}>pOR1A%j_B zC!%91s3xW&LOom5BA2II1?tx;fQeDv#zS}DKaNfOgF(zKGKE$mD%VJzh*9`S zRo_UP>F&B}+xBAF%}f;9I*ih~-Kx1!KN|wWSrGjuAjRjvSurZQ)Wt{S{WS)!K;L>E_o}d{OIQ< ztB#ZhxUk%Ar2pG5mI11nzEb+*duCVUBq(-E7869&_k(H-bSVA7K#;*e6QZ~J@u0Q?8F6-3)wo1R5zR^M)4S z-*mmsF!QbGi^95+wExDma8PHF2Q`4?xg_q+I4;?IJQqc;N_o zH!yCk3u2oRZw3!{cm?o0M@Ge>K4MLl!;iSiOWixHC{y=@q@x5;=~tc)oPqWCU83x# zn&Y@07`?OmGc+$e+Y@;R6|N_591i|F6qT6tFk<<3J@WiPe6KPwg!(R7RZ4b7u!Oik z$Dk*!_mXwD?xdN)lBNz~P!Eu9v7mi%2m$;71_44I%5KN)Hb54#obB~)Q(nv_R3l0| zUWz>O4g=?-y34o~NEo5#;uI8P(A=}b2`}ot|B1}xBAZ!&of>cs6Rfy>#s6Uz@8q&t z2Wy5FA2~N);oH!Q4_}LHpFJMAPiH?8?}C|YMP?qi8sekVYnc^b>wSD&vSnr>7xF5s zCu)?+HyjEJ+=L(&k$D5{+R9LEdU5*Ode1au^Z*}$5SGYghEaHseyU>oIBl{%o$f}P z93|GvpTJm?ws|a27ZoEMMIM;0xls^Om0jhDhb7D9REJm~t(Fx*-{VnQq@9^YF=gzQ zznShM3izC40@cu$M43JDJ_$3j7;z)`$zy8t;$`s)5K7fUGty-);)w2`q2|xtyZBq= zCm2-~G`mQ9zUv}6?yJ6p=HbZcgNZic?Hy@nas1Wd1==s&Px7G&Z7zxs?!6*C=NBDT z579su$3l^!{?#)mM`+8~b~LIOqYV5B=v!Tq!4&La&4=^=>_|T)mHYc}T>9<_j8Ehv zXhh@9;CDE2(!`a1R(2F`^!J}VCh?F#v&tSUYwfR=G3F%1Uq;3}6Be8lOINX;wAfs4 zImu4pf()%N& z*%)Y&fZSPk+pseCyLWhwJJ(wZ*SGcPg4%C7(K&Y>XKbq{n+~c=w!u+M zT5Uu|N}efXbS34c?1BuNtol-D6cD}F7!n>)`RCfMD){fV>qe;9xT)ctROs-=i7L*$ zh2Qw&5#{(v?6KQC)Rp49*xm$sDFO3oy80LP>f#&4_UmLEyX4&1DU1rnss*Mt`YH>z zu?g-4rwWZF?awTTuO4d$??4=69qw!7Av~_;8MHfFpi)YIPh2I~Xt=S3dis>@kzkE%wi1gL4XFaDhYs003IBU`cz_`@sP6uCXzp)Y!oBB|n%o73_4T z`9@%CUkQ<%N_ExPNjm#kKeCLZAv47AGObEaJZWkildylfh;udW&0zi}dah7s3R-;_ z?mMqh72M*OdXz6mi7~Nws2QU*7P~(uS~O!7IeR|vHyRbZzGHmWo~m7N{0~AIi?vI! zX+A8*dSuM-ffCf2;HT*n>!MooU5E?BVYuX6K2~EvyP}SozA(oOZJNjDCCMQiofs2o zr-Q}*Ysp8Tkx!IZR^d1fH>XGs`mp|nexFuoJ*hq3AGmvT9$*X|IM0LNMBBTyG@h4) zimQ}6dJi?8Pj~5Xe*%Wm=+0C-fMjBJx2OZ<`*}_uj5*b^RtqiBt{)HP>n<_9yl_Jv zR3yaEp&$Ik0z1F2A-j%+ zZ#fY}h}l})ABZ+~f2vIs=Aapr`xcAzt3@-ybunQz6b4k4c>_OXp*H?UZpCj+V zUIPB_Jgn(0CBxDFkmiGssC@jB#H?zMAReV}4i@R6(;t_A-_T}aU*)3s-u^wUGYwnG zTD#xs9tA54KKwHGbGY}5r7kR_C))e(ghHi$4e)**;;_^dU^X@M*f2aNrATdR_*yN_ z7hzJ4{r?1l={-X?4FjF-95jq(MjSY6MSreCExm!S(TSOD`hR#*oeB^T?)Wmh3WFtW z%cq>RN9;T%J0^{{diX9OC^dzgImKNs4BX%_TpwuevDZ)p$1lW{|M7FO>1A2GoIJuoz-Ii)>=>a>%bMLJN?F z{`Wcqs+E1Tp7t1Ry6NGo)zT`blJf5vP#B#k#e3gz<2(kFd6v3g4DsUjIQhl}j@_OC z1%i5qn&&;?mDJbm1syd5O~ryK$kU;P zOFZDq(vRQHTj1UdZlT%%|M0%!B9?cl0&{@1THSe6l^L1Hmsdn+VgeG*Kst)%@X@-2ic6r1CaPj9+^!ErMxK&+?uO1CN2`W7YAh>0;N?9wm)MA2CxHYX69J(Z#?LjBO?2UeawxH+1fen<^g_5lRMkyJ zE!&M5B(TIv6QrhTZMXewA3=9Tm-olT<{|>pk~z3<4r#Why@D0iZelRk?4bzxnP6Mf z?!LH;iGh7wrGY3;o?`RqPk&$=&wDcXcVV^~W!ycIh)tQ%;-$qBu9eOT-bi_KHdk{d z`c>p}US&6rmi-!v-N2k%CoEc=2+@8=Vsr_b${Sidw!)22>~Q7VXJ1-%Y?&wVc5OTx zzffW1e2OwR1oN?nG;D6)_rmPDkFLS~QLX%`T>h;F3ORMR+z13H0M!n3=3^q_aE`U_ zzlpycwR1k-h^sR*P+vHhRN1_=-+h3(@B%SzbBle-PqpjmEbmR;?Tc?DDY15%FU47j z!9`?9ZL8z#`)Xr9{*E_B@q}JM{~v)Pw(JAi8~&qsR;X=; zlPNEbAvdY-jePkRpFX7HmR*iHIP@gIyr z+hCCgs*0{JI>g=1ieM)2Mya79B<@}g9i2YaJ(s#))pzad_r=s1ub$ zGypp5i(qaRwl7o8d*_QkK5lqFi(P|HS!!2i1g!#406(*m{sSy%@O$suRc2GXIJEdY zFfu5hrQ9C4NIH^Oa}7?>y+v4JPr{*Gcu!<|1aG)wyHJf&C)hV-S56FKh0F^Hhkzac zk{pOurfDr+24HTro-}p?Mbe8h|l#7;vWP@g4Js{{gMO>#Rglc8`beY+cOHK zX$PTCAC>r#Yr}7|5o4>6xaw`u=DDiOabMNzOeCy^@tJoO+69eSj3Ldh=W#50i-vbi zk7#U~7ju!nZz_OoMDyCMpX6y=btXzteBuD!k42TfXQMR?k z#M{%+x%eC9-Xa6mr@ET$+CusnTwj(f)MvOgh^+0sQAoF9qfE`8Jkzw%3G$jRwIt9$@${ZCAi(v?s1nHL zWFrk@%@tC7nX}?5^UtB%JQjImEME6!5psVc)d+|joR7}3eokRCM@3U2c zXt_?w*VhS?EsQ|tm~$ik4d+aDMc4QKI~^i+dbH;Ku#NNaWbNo!`Mi}kD$I6(S5qhb zdX$CZ3^op~=_9#n=gIW4#>Dh?PGRlQEo+@M^)(+V!9-Z{?=YX-e6L`F1KRW_yO?rqAF~FI+R8Wla&4I%zrB znPvclY~sxoXa(s#3lXy+ZDFrOciqg(>0g(FX_CkC&ntCEp<53A--yU$X4IhJ2V3^F zS?y9;i5uCDGQ^BnhOR z+dI>GpCB1VwnQ^-~#+23!x|& zx<|BAlLcvUAcgK9 zNHiCo%8|Gc2>GM5;@;mE{10w)Glf?)O-a3cWj|IA{+!;7Mk0v=yZIGgn zq?I*#9mrMc6a~imuky(Q#9c{m{&GzQ<5;Hsh7wB+oE+OCKA(XY5h1lWwV|=(sreizcE%_1HkXC*~Cg#X^_bZICJ$GqZ zX?qfj7_6OOcso*VT4P#>$i71dTg1ZZbb@GEQvq2;6F2%S(8H@Q!1yvC z4@n3JzMo}Uk!$EUf@;L5SY-GD?Q$-O-r{H}FbFo&@^GDPkN^f`%O|J!-^g)X0w94> z1txhv?-c0J02YScc49JaXH5N!CcUJp$2vK7e$JWG-1AnT%rqUK8c#B<3cwQiBcn)C zthIBEBG#!lzSYK8x4uF9m0A9jU!Jv$90*? z^|QEgH?2&t6$vmQKfCF_`d2Udh!FXzA=~vjRv;i7QQU3ot z#5p1gM8r}Su~mg?Je#i-|BxLPpYan9XhL{^<=1qh!&w|0#C2Id(ea}FhNEo^Aseb!w4 z4WJ?~x9xL2ihZcj01s&NX@s-Ts-L7$2%k*-=UnQ`<*oHUZliM#v4=(3m4n8KdhpRG z_cNx2>W!CjsRGOSc174=a|>KFroa4_Y}c$(FD)-42!7WRM{rbM3`x=LkLq#VpIMf$ zL=n7AVZHaQN;ACAj81jmCq|M?BJ>RNH)Sco2EC*rc~@7H>co=r7gSHLc{7+wS@g|*PF)?ot-4h6toUA^OxTlzcrme* zG)OcEpI%(`3jd`D%VC=bX!YdT@D}e)oUm_7i{$uWjnnDArsbp9K}n633_4Vl$*4zq z(!EaLAf&>yHrX|clf|t$3^zvZ?`ic$bxGG^M9y zMzhW~)Z<6kL4BsMaXAy#S?&W7g{8r>0q^N4J|yL5A2P_^`XFyBn)hSy>RBpqpPD?d z*nV_{c*_k{4{Nbjk(xH?BI!3;^1MemZNE9o_X2 zj8Dfp;=ce{t}uI)^LNO!siPy&LUj$-rtCD>@ViZQ#NKxks8-hLJT*8dck~a5pU$q; zTqx}x%$AfC{0=?ezA-Gt5?EYm&kXi)4&>cB+B~ zIc)9X(VR*+zF@84YTad7K{?w&00j8`cFIYVP_yKK19lHLSam!8{Zk zsE6^%{Xz>LcWZ1m+B)ib)gfcq7-W4FF81YM#3~N8gFPjiq4nuI;| z!NQfsBQKK-HLxc8+8xN^E(M7-UvvNO$=73l=I2hgH8x@LZBdcb)}AgPq{02-)Ri zvrX@ZoFgEEVpP_TxZ@;fy@L)(d&cR2Q%W*E3g0EfeaC-HT41o@rmfn505S}EG!upX z(2w`;2RK1VPFjp98pA2j7ZKBibHXU8d8-5QrLpG6_ zz(55ctb3bQn>gRoQ@Z`PoG_jQEq^n-DOrlTk)`b_Rcln8l2j$AM`LFzKKLI8qxjHM zfn#w5>{;dVciF(egg|T%(XLPcA_hfKt$R|1E4*oYCe#i+x;O<{ruTv6ocG1~lgu9` z6$l%YHz8*l1XwCBp1jp1op1PTiB}?8+`!ApVNH7}oDjBdP%`iExm(^?2t#BLz^ApN z0cWxj^WnTHOwU-yVhYy+($*en-Pk*G;s{GcX2{@9yr4ay(^EfLWmfLrC!s_--6IhB zw+pqrF_+b&Z)IfXFja4+jsScdAtZjGGkgwR#n5qzQ5EAzysqWYl~n`1&x}}-j}wMK z{}BJJmcJKozBA_%N^@SrA%^po`v{Ox@H7@5178V)Tv5H8`@G+9qck$n&`60<08KI9 zlH>S;FPXa@k~^onWt39MZHzxMbXO{))R%Tp*l0OYwC@cUthK&w z4^Nu|8S#rd8YQ%51^mjR#}hsmC`BJms-OL3t2Qhh(iwDp^J4KbA)fr_4KrT}NMSe< zS9{sw7uOWdTnbH;t`YtZ`wHpbmkeT5_bo^ildp(b2?g@<=^OOjv}qwpB6}JZ+uV9D zdazm`HV&px9^J!2@9+z(>oT;}KZyp0n3X+?Dy{1G{=}($?(>btGT^vi=0$BBClALZ zO=)Km_&IHH3hBP{+CY#q7{6xDIcMl3d`oY@UX&JBD?iq-pVy!r+_QtrHDrT@Ax8m~Bj-0tv83 z?j>$%DEK}*mX(Zq3a3<`!26_=H0A~0%YC^vU0TSxi3=LRR0ihFPZ<-5e$er=1qc|?NT1QO>fJ~3Fqeyr2?}@mdjy!$plOm= zZ<`m*`Rv!+`gw=j_lA{no|kCc$CRegLh*pt>hI?*srS}gdx;x%2Bza|s(N7_8jI|$ z31uqv(Ow~4<*w;N>(LQoo)7c;?!S8p@4|xlGOvS-*9b2zI7h+}^B}8WX9>y5U{i zNw5&DHQdx(hm$A&}!tkdk3K`e4bmhN%FLX!R25^5735b-AhMaz0B;?*R z9nnyOgj06~mS}z>+~i72H8C%=(ZnB~+mX2V)va-zv#K{)$P&a?k3wqz&CB>gWrRqP zlrrk$tEDd+@DV_nHb~V~y@)|^d|0fSF%F{)8APICfz^3M?hWz!tY0}# zEoHZxz}{#1lTgJ=;E7KTKZbK5F7dEm;2Euxb>`xjK3woYhz8G!8_WZw&FCYby10A%1T zeYCtBW&h-cu&Jxve zT@*BHQ`U#TyfGc8ux7|kEdv4W)q#!q#ajUqT!T7WXX3tyRW^wF2jHQQfzP-ihh>V2 ze_PD2o9|vX;V-=uNKoIJ#7!8wnToyMKR z61wQrt4TrdIoMKZ zluZ9qZ4ZSFmB5g+O~UN4AW*=;1uV)}CV6d14LU%i@yd(`L`YL_$o|C0r_WpIEC9!v zw+nYf$iPAAU0C1@FJ0q@F@|?RaLi37B^HB;Zz1B?tQr7nZCxyqlJHCwY!xJ_m9}UM>kv!g#40W zju^J%xLgS&ZSH?|sk*X#!2k+7!Rzl_Y{w_O|I3*HEF4w8BM|W|fEOa9KdzG@Y&QPc zpUOeq7kTnFnvm9fn@_H0=K6+^1pS1HF4Yzh*BS03?C-q>Ra2ip6aLTMA`nTs?YAtw z7W?CA5nJVlkJ1~Mo z9+^;wS*4|}EumIJK>`L$HySE2fhvj&`6I$@uI>|CHCq#^xkGEmc@q5KI9}HEaOC0&8(%t|wosaqd?i&oflab_6jcm1jT1 zw#ai(a@)U{-R!IS*k@$D!bT;#4M>A#dD)d4D0qPq+RP$}SEc58_&0}>3~RYcz;k3t zbI-cxk=51TosF6S1{=80Fm1Q&3c=c~Ronh0skj}+>K;k1yF_F&-aB;@tT?47lp$Q} z#q1p)HbOnSkG&xH-aQy4PPVi>6oll_8;Ij65?2|4$>gT^+VAY{d2?bP{4Yt2C`hFQ zgNbuy79AhKQXWGHd+X;^*(=fYJ03mUxf--FG|*T1N(+w9K!WuTYPw;9oeL&>Rd2q7 zMCHI`rzFor*z9#HRB%>WGa(^8;dIGfhd#B)!S}n~EJ&K^H|=XFz%Pf+s)=$ zz?41H_IL&9lc49;B^$ZI&y6~23mya{x5r<hA6Pn1JKq@PveP`NezOI<5C`t{q4c55j+M0bIQhP-D1K9fzI1g$un0Kh?Gfc`Y zx3bdg$*e+r}h3CiN3gh2vNnJ*{sRfKOIJn5}(y2rZp;c?Mh8AbCiDg0Gy$M zRKm7VHU5HhV^n+>v8+qgA{=ur3Nc`N@TGx5>KpdexTi!j@euG83 z7cqvW^4-^2$rfta_QfhbfCDRwxE>k<%t*sTb0}#t$I^R)soVg=>VtB7SO8tuhWuy? z+_+rwiuCf_$ci8`9tME7E^kLFn(MDv6MT$Bthq%P9G>mLclm97;Y%UmjN1Wf0HNfC zKPx8OcF+tVaMC=c3MwvPj@JV5$HT?V#=m;7@FL_i=B6%Qr9j@YUC~e!?OHQ+un}Pv^A*h2@D&G77@Erz^)+VHY0g4$OOxGA^OrB9WyAI@se0?Ia8ZQ&{{svoWSXd{FzPBOUgW& zgp{G27j_2I-G-;b30lX&1CI$tYq33k&|hzufga#tUB%zqzqi%gc4lPH?X4ptcu?;> zH5W7wxG(lAqEmXFG-?943G@*42BN&qFK29sY(8lrvwA9=1Q#E>Bt#JSDc(R1G|k?R z%3+cyqMO7}#ox})(JA_uNT+c2|9t6!F{*mjVR8nYj!w=i!YACPGH`t*l3*OG`taby zvei>far&M|`io6vn>MlI2oOXs7R0vsCY0r{-fW#ga$3U&EMw>lfc^~uwi+cM7oQGVq=GZzN+(P1sE1Fj)`1~C? zU?GQ!AKW@q?(_EsJ|dECDQG4Ab%X$%!(y})m`;PvKI1oq(^6IfInKKqNvJ0wDVU)8 zEKTX4*}+UzdGT-han_9|T7W7n(q!y|tl(WZc1+8&pnnEVtVKRg>eKg^G50dcqOSlg zRO|tpg1>BEPP8Nt0oGuQC1GJ*zSecp!>lOpvM#~^-+*Ox2$xDTRl@JhHq^G|B=-1c zo~1g_4#K#-+DNM(Tu8?;``v2$ON^$1_&G?g5H-?9mnf=rkHQ%7HNOm*^e)H^fJQZ? z(oFR{JpT@FB;I9YhiUI)hO(OQfjqH(7;iqCqUfHoA|*K*IIT)K#cT=te^ zX2wtq8><_c<}oW1B7AZHSJ!OnW*GQD#(KuW2MU1$!i;k5&EUIP(PCt|Jz{PFr1`X= z2=uqR$GoAVIYl=B4jYVD_XB=Pjpe2`E&@Kj2RvvkR4-{$iWH`nlOsRbFO!zPFoxiy ziDb`wj$J8n?Wi3SW!fPyBp#v6ogBq7>)n|wK$`iXR*&tf&MWA#R|I+QFj+^7>YrIR z)sOk~rJ}r>Q+G8cI(fX&$#a&sjcWmJBki#B4Kl?P*$F5KH*?DN8FkJMhpED{0hA2M zO1j7eO<-DCtGYlRgYhzO@0DmKi!yJlK<33S2_Upw>_=YlQ96uwPHx$&f9x`Fb`1)Edu(t~Bcv$WH~8260&$Rm~0_A{V#1(%ZEAYKCTiaVMLOsk=FNMuS}8)M{_w2F92&10>{+ zS+`(pEmikAt7lbx5frP|Ln(v;MmDKDaX8PFkZF->^T)=Mqap(SmgBWRwVl5oDZSXsYxC)~&~E*?;rq1MZUh3T&I*I_F8EOaQuYeF}*+O+Jq`4uLYVyG8^? zKgR1HloaaJ$ZPE>Q8Ffo$j3Hwd?x?+a9L1~KdV)SdH7&3I+UTJ?%+)`d&9TPvE~@W z49KO5DrK*(@NPL4`zc+4HV3~%AR9caZXq+RX%*Wl?9%|K8x1GM=YELQl30q7(ZWwg zEQqDUUtL;m%NgnO>Y`*7o>FVjg}F%QxC)M4PpQ%F-Ork({)+VYdGe zHSc(v0aFYr>SvI0;8b^bCO3R1Ly4gv(h0pt*ux_j@E<}*l zk0>r{oNI5=_rLN8I!ZStjhp~zu7HOVyDF-)xgiA?9Z3tzzF433IY;565ZP5`Z&wlY zX!knX@a|ME;mVVGXptT;>2R&=fQ*Tyek&qVG6+N1jX)a^sr3(aT&sH^Zs2RZFm`#} z{FNb6^QrU5V9P5r67e}cfpT+Z`FDgp&a+Om>D8}MyUDXADAs*c+gu1FzMwMQ9?>DK z_fk+;VAmq~r7lDVFN)?_MQD|6ejM2?-a<7o;W}O!|4VKf8TckfbfYN$2lTW6yy*r8 zzy=sE798OeP*7ylVA2;`G3merqSR1+<=_Jed6LsecIg)^=kg7K#diF<8HGaJvk?0W zuO52eZ8c@Br$5i`{){(!S0dG`5#;XgXM%8~Ae?k(g36XsNt>swBPFIcPQ67FBdK_Y zC#>hCmlP6G>pDjeUam)qAUT6{k?z5plRhZQJKs79$kGy(N|*Yvj&`QUjv`=g+BILW z$g3TPBxGPpAqm^kfJaeV`2!F_r4#RQ#tBIvvV(%$liLM^ zJjGxnM_?!qd=tK<$KDaXH5xBAZMSg9KY^ISC29IY&Epkzll^LV45;T0OThu)wr=~S zK7{#tyGr=cT;qhLRDm&b8+DR74gZyqN z11NS;bym8YUReM}IxYp6Ly!)yFFx(dq+9!D{}Y?wSIll4L5-BwcRVtmF4BoV-%eTh z3g!(r-t~zW7@wTHN_6bha>ZOO`^RC19gCn;uE7mBES(HzFy#h?ec$!?)cF)jOj+pI z5PQi{4k1e?Ncd)Tyn_%pp(0?AES{0GIoxwmhuR=iJco2J73Tp;#V^e$8MA(dFg zH4vUJ5gtnX)k1}O*ZY2Za8(cDlD)m%6ZTm2l>gR#AmXC9i|qE#ak?JV{$DOTj7X8L zT`Gw`4P|&sC7n~sC++poqx)fQ6ayYev`jSW!n$@qU#kO201|WEFFv7I$!$6u>O_RW zbJqw58jpkDaBuwVeu4mBQOZ+G5a~Wjh5MN~F=lGR-0ETvW`eFFz+2=*QUa4mktD5M zw>UQvG(Bqpsp8f(wv&%8JoVX&1?=T+m3%Vxs-Uu3y8(oXVWNVK+P|Ra7OnhXf ztv2<3T4Pk&70+pT{{7k~R~l4L=33MmWOhDIedG7bWA{A#CiR!bI&_G-7)#LD!==g- zj#}#NExXzAX=FUPsOO#M1CjFuyXT4)g$aztJs~j^QMz%1%0Xer|3c^DmZwX7KdM=b zJ$k)ul&5ai=k9Y&5Ir?t#~EPP&f1I zrngPdA}k~psR7Y~z?uE*G(D3H5X}u#BO7R~ZKyr*DtR^M7-to5Ytq{V(5zAtz!P*l z@B@h$3m#m$jOQg!2;ayMPS~(A(V4}{u1pklu&ZV#^?xiY&PJRuEGCvxs~lSNidnhC z081~wWJ-JO?m_YEH7lCRUK{c5O%4o+3Tohk4lp~&sPkN7{dLm!POT{#y-yYIq+ap+3KI9GSR5Y?{J3s%TRes$z8 z)W)c2{{eKNKYqAuD=FmncvG!u5SG0CqgYPr{UZ5>I73Aic5uupgBNz;|7Z@ypq)@wWC|hZuU_Jdcg_VEpEI{DPNO&~Yl90-6oR zvi^g31^>S>Gr{$z1bVx#V@X;!;MVOs^P~)2l278PnTD_2Kd1x?gDxY@w%>3?Xdaen z7^h!Zvh%n5j}(_DNa&ywvML_@|8rbsPOQg$-hXi{Yh#Nm!uTVx0RinU^SbB;rcok^ zS62O`h+rSMm$S6w9o7=jWZ#|Mbw2Cts{(ylTOQ>+{~QUQBD3LkWcT21OKGt4tEoK5 zaSnB;TS8izb@6(KlyqQl?h2v=w>hyc)y2p3ehU^PXzD{#EZT8Vut%jobtSsQ9vq;{ zig&A6|D4gnQEbaUnF4qu^EPbegzBsrI@uTA8Uqaq2n^I<1NMmw^Dqj6#nV{$Dkyu5 zi?QR4v^)Y=PzgmMOvN?Wl#o$yXA=dePJ<(t^xy}o<>bqA)iP}I=ya4_9vamb9*jTk zc{5SmAu_J|=rIr3PX_w-sMr!FI?cy)G=qi-P}Y8iB*afF9Jfx_PXx%CpSZ9zX@7u% zLovhJrfLuq%Gysx#UMz+e3Zf8Z6VQ6E7a>I%|ZI#FD zAO8-_B&aQ_1K9*Y_f%cM(G)};_2$#m+e*ngPSZn9grX@fVDRct<5JEAAea9GUOiQ^ z6+O{8!$m+y_SyWZ$d}SBRRY+)uD|L(<%-&MIj43|evjTPrT?-8(q?k*UQQ#a7f`9i za)Pa>Beai_tyZN

+HWL$>1LWd}3>Sg5ueR*TF0HTp80VAu8~mp2#2T5x~IckA@$ zCIXbm&nspNb&xZHU2dfGJ?aN;t*W9z>YCJZGY zqMQ7-q#SrLWw|A)^ct*7b=@wcM}2sOLC<=Q^Y6lMm5qss0}=77ec$`FAs|Cjzi5{e z1(F}>3JWn@D9bB(=wXuH`mtWt(4Jqnzg7+`HEZ<$#n**y~+y)|!sIoIFMA#Y6eO3A0@ zDp2UDh%(NY`ezBroX=^`8A5}uVR-AB;vkXe5u4ui>NJ}ykCNcwTj$_QC7;!lsGCxm zXodXX#twX;^cYJp&r}kw1@ciMLw zUPfza^$#Sx$Dl{t8ZDvN_<|lJJ?d%yg7j6m-H|{i_!@Yadb>^_;g+d|;zL(hQR&vg zdT=D%I*>%0z^&s9ExBjt<1`C+9l3*ucv8IpmeMb+Lv_GqGChX!4SJq~&Ri2TXn&b!Z3wLZBprsk#dJF2tmK;V)>hKRayde!-_!UNay7o2 z^fHa?*$NI4kmt3v%6?W|_3rhW`yJwJhel|wDUK%H`F}h((pzi!onI+Z!!hJ&Z;^-> z!fZkSalTL1uQK%kKW@}GZhpcv1(+ro$RK@IMQ9E#lH$gVZe-GV%^Q|h|7*=~7Eer| zZXuI#uOtMRIG&;x^4Ys|T!bMaNzu-@0jpjg$f}aDgN_w{+X7PYBSQ&~K~zN_Z6`)v zpu*?VNKWG>q5xVLatGmP{V~wlBDk1}40BG10qg$;vzkY#wHV^KVI6BdZCTIw_Cf-f zf%)P-B2g5K5qht>iC05kr-Wd@;`XPmo{0pE!7*!~)9#KvqfcyZdAW-)?A#&>uqy2U zr~0Wlt%*J^un}6Zd>9MtxiXP?_w~>jzpKm;9+hx!$0{qsXq>aC0{-r;UYEM|D}yD0 zakkY=FY$_68#9z-#8bQJp8nwdDVPZPFi*0`6av#h{t%~AU@To(bFDZ6_`_H^(M!R= zDn?C0B=iVJ1vqQf{`jk~^KfcPw6V0@yvbbl+=R&+(6W^@3h)m-J8(Jq&8#L!%*? zH7S*99F0w#+yn5T4p}Wy;HV{Yn5*+y-9;cs71t+Ch7+NJlGES!I2!n=e%1frmKQ}^ zp)}Z69Ip~7N%N=d_5AoQqA!>}eQ{~^Qvu17agej;tlSMXxgMqDL0|rzl^Aquq5bEs zrHId-P9-mrjSoz561yaDTiTdqcfGbyRvQ?m|MY+$tRU-S+w2@2P^6Tcv{x}(=qzL` zYV(^a%E-Ai<18noMF&GfpJ^KzHByU6Ph6U?PS>mhqV^KT>BRd9pk!q$$ z_c%mDao6v{lu61HAZf7!}w0I%2B9=wcxwGE~P; zD+@>_b;*UtDQpZM1Wu~~eQm+KD~g<*w1c4VKAl$ua><1i7svZz;RpZ|ZhVIq8lm~% zu-#KCeed5hBblw`w|@a6j-?|T0KOyB6-ikHe|Fe%dgN4VJ}D4VK@cOE2{(nLqSSUt zy*Wu^47!%=f+L_Y-;k|Si-lqbzf8lRe%>j@c)mOuu|)>PLQk&ikryoG2r?eMgrwkQ z=eTk6bCVWGwV0J+j8Zh5BUJfF?F1>pg0+`l)2sT6ZcM~?kZuq8PaP}GW1e`9oD#Yj zU}w4@uo@uUH_~C>p`vjg39`@9>d^6W@vf*|^=oEIzFzWSCYFG$nn*rKi12 z=jCpsSAQ_iX?R2_d&+(5m^Ngxo??0}QN>%kw4^zGLrP`!_4iSn99i$`*RdO{U6XKH zJsD&-Tim;UENH`3J{||Zq8HY(r1f3mXK(E5@uti^TWh2 zI_%wHUn}$O2)#zc8r6?Mq3i#4RmE_%cIB@^sXCKGkT3>ufPJq1Lg}b< z7Y#&(J&gzW1$Ut)#VPoq%jAQ5|?kK=6&k z)jT>ew+u8?Ph6dZ=#&K?xC51(+nl5(>jp+1Ts}>wK1tZ4?}TAJgd5v89(AzHH*I^+ zfw9O{GV^mzm^!e%uVJC!7l$d2^xjC6{nfF`bXdTYgOO0kv-7m!`p5k!rVfR4=08z; zpj)Oi&5=ijA;YJF?|f#5`pZ2%#G%su?RU2eB79hcb*_+VGBW&m_0ET7fs(VD$VaRK zBuDj%x1@q|07E3jmgPOH=}mZR&2XjU&?yqBH@61`K1ulu$FsK$vMtIL&9y-p^AOID zFPY$8MEdrb`#4)3+I1*+kEuqO<73At()Wxt=fkDbp?nl;4$Q&4!uqKifzA6QJOwWa zwbvAEP)2b!dq!H`6mmGP+XopY0}i<*s;B00)taU9wk-anVZ{dn5jN0RvxX@RrEVMrrx7%N-VCD$6Dj_q1VDq%qdH9tH7 z{bqx~1f}!<){IE!#d<@w9y>NlF4L2uO!P-@N3IB8W7>)(00~1Nju%&A3Va`>7Z*i5 z=u3OH}PKzJxD7jwuZ%e*fPoy!zlWdQo|nPzaYJMAXw@xxQc?Y z1GW3~f!aZ8x))pfUnIci^IrU~RUG^iLCZQ6blH8i6 zI9&ogmJj|=^?EdOLko%jY?2~Bat7=Cq@45`KtuJkNEsN|ae65}X1SH|*mIAcWM;6e zCnW;-SkvPo7)$ekY>s6#FqiXRjDU0q0DQB|UX&!1J;+Z&&b!8ydjNBoZWLNtTogk% zP9f*321%HKlh?|KV5PD0rFX|w*9_($w-5;G;m24Q4`V%@oYr5XtsDt7-@5-SpOC92OugR`eE4NG1QkEpE z;6P;-b$;-W-mkP#9Cp&4OmcRx$5v>yrV*)dCB+n>F&vHFf^kLTgF!?X2o+K+B_!lb zsbrnw3C5XPAm9>VFE8X$YBhzOdgSo|T)GNiQ(;f@ia&-WQBsLy=3!d%UnRTY44)B& zaUVmupv}IKS`poM1FJuDuul9&zb_hkb1joqE>ps3I;BT35y~u&rk?+PxFB^# z=D+F+zShQ^@wjEMIN)qwT-w&9rG#P|%`^BRL*Dddhv2H7I5fEvDxyNoaRuV-*KEgc zsgS!Oc}sz?{!9m;-O_2bX7f*qHr`G+X+B{w0Vk9)DG8q9k@S#eY#QA;|B%=y&=o0PLs+lNqf5FE-RM(lKer~C1w3+s0?Bgim?8)w zdyAvwe3I8#d)%;xpH05XgmCEu{idS3SDSI>@=a3?e>tp&1txtaJJ`q(sKAC$E(vGF69SZ3g|`+;F6wiZFE!uxU(dROA{dpl zfU22pK{5x0VE>>vdIA|jvhofB)8f7N{+Xn8GFfR3qqTvNnUzUgX7=He)}W_oLyHQ~ zWC2~`H8X_IAFqy10=Tn1aL#9pZDv{SD1v%>B1w3(u%r&Hn;#+QXf;23Eh`H)``#ZH z-h4Z`)U>HgW0m!$@R(tWYr`xM1NRE6v+Dm3o4riZqQjCmjhW4k#q7n7YVUJ@h6JsP zt6r1!5JVwH{nMTt!vVaSHLm=>iMk}uM6Aq1_)4*hIn%W!QuQVW3@kp0Qum#0n$+u7efY4v%Zj@ z!a--@dk7t#mGxZagq61$j*%T6h$*3tPY&ww_^2+HX&v;B{u57qZY`k=8wqC5MM1GQ zE<0_6+(+cV@WVX%JgIdv$74gs?kQO%WH@cFZ<&=79^CJITZw}-pGbCpS?k+;8_Ibg z*OdNL(RLCCyNC4pBz#CQAqt*Kv_nfq#nvT**?G#<-k_tqdc6qZD=Bal;sq2s&!cnW z2LEl9l-+( zB%NL7`ZTNjh_ta=rNB=~=H-MWz5n&QK|{2$9#;p%C}_y_Ln3sOz;I=oG19Jl_^!T9 zcjJbkO<%hMPs^wJMk57&H}ZmZ?lZJ(vqtZ34MaNiMUdQT_gA8FamV5-N{Qp2-%~*7 zS-=ctDwYLi1UMeVY7)RQ)uX3o@I{Y7Q*;sw14o~sy z^Sipn!2<2hTpm=ru!e8mT)1WU7^#`6H{E4|iToPQo(IJ_ljXh0@~)?V$jGr?t`c3* zK9B#JYB;W_G*k2#A7&k&dCr;ALtF(i0@g|p&SO+P_Y8%h$Br6>I|CviK!KF%9Wtzcqa9gQ z=C}>tn=JNa6G%Hhv1u_VN?}5|gV8vtA{(Mfy&BWNV)rRzSha!>)ByfQ{9kO48l zAXv%?oYoeOQG-eDx4z|Syc^F!$pH$h?yy!`JrG=9nfD%1@X^>YP$HUKRUM72(AWoJ z!Q4xo@+*FFNE#(Y;9T9HsOrLQf$3XjUSw6}l4~9vj-NM?=em|TUDLRVgCrrseKA5s z+~6bW!4g^EFSvb;Ab9nn^BXrt|a^NHc9Jf{Eyv-!IZ%*!bIBzLG2lq9WG*6 zQ<*PXPT>`n8jS|8yoUH4z1kmj>6b}My6k(Y44_>EuEb|1yb=_m4 z90Clr;{Hn$F*45F#!Sxiy2u1xRfN?;v>h*qn0f!`*&YdZ>sbitl`C4lnhQ?3UcH#E z?*I~BajO)bUH0|UBIC@yJX$eee1PY%GTdH#QZ!V!O?4kndBo5tP~nlv?1{wFH-%`z zjtEn2P8e|Z_IL3T3ePIrxr<45fK?w+&g0A*NLh^k_ETbiXq#x=RP8kkz$xdQNfqO~ zoc&>qtG0r~H~fx`p-d=^N;xIj!#>Lo1=#@E;GBBy zX-zAmK*Qi0Ufw%-8nN1JQ@BG>QN|@;usBQ?{IC$+v@wH;ircw;>1IuCerNLU+dg^a z1e&1~!+_YV%f;BCbV+x?Gx56##_6HWm5>3|3XKW?j~2$L8HE(AY0oUN1p!sF?>=5^ z<_0E7x9`abNZuiT+AnJ;BC9LrjFwrZIC1`ed? zJP(g4*688fZp~LvKHB^tOf~G%B2J3)UlhDBB+??CA>nv_F~UZBx>@jFJkL6i<+w1yS{{CW3g+kO%%>9 z+OTxl;vA-4=lD2iCy(NRO5*bvKbXYnP~ncZfZ3yUpdi3ffZkhv99vB_3ZWW-z}_3wy1SjSD=xTa{rsg{a$ z0GZGM_GaP#KEw3yViBK4Yjc8A1nj<=_g#D%w#P&*cpMcq z%fk$W8YMeYem%k!Za7p5>SkD6bC8pI7YRI!YA!1BM&9@?^7;V)L#a;!|6`@KSAFx* z6}=7S^%I(WHi62blEU(ZrB(c+d2(%jiQf3gZ)7`Kbq8*~uv?wj0(tI0wE;IAWRooB28Fu-tiJyqOMG8R?!(7%AcM~^wRy8=UQCRB(f^(VT1X^kbhk(vOfK%clX04LVS;_-(TeAB zJ!k`RrU|Rx@A|i4Cq~wxA4GM1V}0xd6BTpDzKVhh_vo+i${I>QPV8lD#Z9TZtxU)_KZ%OtOJbcA ztSot)Ze@s?@s;!^7ps0+yl2{!8&wwys_AEj~FC;8&bTQ`S8??oBc z&&b!d;xj*G6N-7xuBg^ap&Lwpf{CE&NFr(z`X~Erd{vgVMPyszTadV6u6?2CXx(f2 zEg7W~l|HzN6AZS&=DF5LF9pcmt$v>Gx3|nRy=Hef?=QYwpZ&OC3~j01UgnLh6YY~A z0oKBnLS_B9^u<&G-9*}4(Zvt1NzPY!(~H?YsSqrX_LttJ8Ql*vF-l9#P?Fhtfy_T^W%b5&pL~TsrFF6Zj8Ua(g(Sf zG5LhcJb3{Hntjnr63B1P0r%0M1vDp5kc8>%NNcd-yQ(?Ri_t``!vCT>NuaRs`e7`P zJ9048$JpA;xK+&i=pj*?;IMomQdn;Q(hvdC1Xut75`#Y49s$3%&iTXbJrzGTFgrS- z_slR5N#ydJk{NVX51`e*7pf{cP=>;SZUODrhwp9>r~|ec8g@!Ac3nZ;c`PjmhB(Je zT3~k%kYn0FTG+lijd%ZfweYT?242Ii$GOIQWeSzAIKlp@0}o2Z*V1YH?j7wCN{8?{ z%{Hx-Pf(IetAZD=NX#e*pIsVxilc5hs&U(!SI7c-AqiAp-$uFiG{=yBA`pMU&!k1M zl{a5S-^?5BfeoHES&jZ))?@`e&)~x=N$?Q6;Igm&?tGyZU@s(6=qn?8%krPJEElD> zDj&j;{05YP5;Wt!I?LB!k^~R+LqU(NMA{_{{GMV@7}p)a?L8WSaQN0&polw>!s=LMq5_JMrOj zPAO^!mNot`N0^}n=7(3^a-}S3lVH3CDWZ5m7~T6Q0!Sk% z=Udi`c;j%YMf3nk3W5=TC6!HxW0i`A6EelDU!yhn>$0D9xpxf|cN~$+Z z!9IYTWW8P<3#Q2+tKbmN&+VFL$1^BzH;}A4kOUJmpN8zzp*VddQ}JnSkOmQ)0fr?g z(2gof`a?o0bIe+~nAq@a^0@nHoAFS&T`l+KBu95fN$7g&TL%aCH2ZHxFINGM%~nQ@ zOKHeU!Nfp;S`&2u3lejc7&ne44E%@DHm7?7zOdm`AGjqk{~(gwyxw|A85#h4ni*L^ z0c|25Fro$kFfndZ9anb)SOx8p;LIqO42uVEz?_Avc&zfA)`UAJ``~J|!|q;*YNsS;SBE-OK(kNack1rhesUnaNXjuBAhn<+5JqSjBQC#(`s+V&bTosUG-rFyo3p^*m*@4)yu1kw$FTr z#18BfolJ<{^_@{&)0&3BXavEb+=Qsh+$shl`m;$5nGKK>=b4V4$rf3mPs_3sGDGHC z%#0v6vQX#MnQrms-#lr_RfZ|Sy$PYDbsn0N-+EsrK>bq^10diUf5AkPe=X&?Xtv5klz7p_hI+n02284B7BRbI0{lBA zVpau@vm%rHKdR8$q^(PjULU}5bAkx-#Tx=34US*{01H~y=-nbjVqKq8_PK6r1(G}LLH>@N>(Q6PU~%~hmn0w&u>h_Y zx23s7!Qoh2Fg>tKV1a7%Apvk3#jn43m=E&5^H5^E_*OTjtT$<3^8=7&kKl~KG+#}9 z%hZS=;SIzIE^x!HEnV|)x+CJX}Y3Ay28a(aKA8lxQY%OzK%R^ydWg+LuABjN)Cy z<0rqdz@x6(qD;*K^H`!kJeqv{gb(jf>206)Et4xm2Yh4nlJ%+JIc@hYrBy>SBQq^| zY1F7=UsSiouQ6~(fdP@DOA6^ND(fOire`{b?1FHU)If8m!9ff5=Lhq}v+OpP#LM12 zJEnA5Lj_yWhI`YXT<9gybN~hflERtI0VV-Z$v6KjmT#2tfg}COWTbv+Q-WG{-VXmJ5*f{XrFtG@Rw$f&={pjq5a=$bOq}Bby0V+}@VBq`C%X zVamb6u9V6W?8Q%bQSwv6;c4v&`=*^65N8%i<>J;w3`rXazQ-ijKPI(?vYiym1^SkX z=7UwRC1JdKWl^#>{D}O@fQ_!T$BnCkO<*ig>Av{YcZ9@I9>_a1l@a96^2FlzQF=K> z3a{#}^3T@L*>5eY(OY`kQo8gqTgzF)``8Z;Ii!6t@QeXnNjtoo=-f8r7k~%#oc5m$ zAGAGe6o%5H5o+1T+m=_y;g%c?H$#a~025P^oVL>(^H01&0~W5&yy8wWpwW9K z)ObmyRmR`m8gT+4OpSiWhnqL^Gd>OtqXcO#H7|Vg7Ad465%g6Rq$Y+;0*=pfWqZ-z z;i$sxIS^3z;S`;>$zZ)?QTz2AYdIYdf4P7At58V(sY_t<75f^l=P=?g+r`khO=Z1_ zT}D@>%WiMz-uVY3Bw^=P75CC2kc9Q-i&sm`!mBCtSyI2KJPDC7fvuZ5HOyiDdP3== ziT3ko3QO~S3Sl6W&S8vpne;7K&RP2?R8-k|xb2F&Xom{YkD?B$*=y9D&vW3CZqc;7 zaDuTWvG$RiR2;Q`9~7BIy!Xz%;gnLw3NME$52n$Bgw2ID9o zO(jv3Z(G`b6ydtgoE`@3^?%$SxZJfvsdPi`r`*GmCP?%XO9IQ4tyT;W-%}ZP#aD*r zl*2_Gd@#LYmu!3&GV|RDwebYRU64k4xDePGN9XB=XJNF~NHSBv!5OQsmr-2a{kmf# z+EYBATZ^o=*>eR8_&~&D=#8=EG&!LWG@j`Pi=lH&1Mo1H*tpybEb36^`@>ebC`fNO z3eUk{&2;uniFya>Wt;Q1a5_Nn^bs4j5|KfiMAs|%izTzZ)8$-*^o7TC#kl5_C_Y|R zf1lj?+k$o{Uj!zI_0M6aWJm{HXmOnw^#D#*4u+&ZN1$)R)43ls=jpGUhTm(J$I}aB zs7ojJ9=EvGfB+YFdsWFhMkO-=0UGnJ3*-?(n8!@iisiL3^`h8I)DQbkq_E8f*@-}# zSAK3|;CrxJ5{hRtLIl8J&}<}@F*BYz-FLa6ehvS_|0b|6$QTW@#j29dvjHnE9|yd=d`{p;R-y=n?dR(!qX&Sr1yr%%0Y$H7(R9% zcE5qT=3cgyXFSe%2i;8}(xZE3QIF%X6U8V&@ri_;pv*-U1#N?TuQh{tiwUWwF8CHn z@f6U(wk5hQ(pofao2e9&Sk+O?+_`}i8u3M~K$)HHXW5aAod!cazM;Uy(k4fi06}92 znsV?C)V;Zs8I9`m<;E~Uxt7xv-~3_qqe{lpn4o z+sZdy;VHgXk$4Zlk@zq9*A_>|BlNMBYDWMd!E?%A{*4|&@`vnaeWq6XYusZuTN1eDS(S5o%Mbf`$lX53Ddi|9_H%}4HE!idYQQQxcn&(y!ENwR<=8-dGY-S+T zxqeecJ7H5)AL6|D;TEZ}8>!oSwLKjuhdKfS8B9o*d|B7k8KlD#gXgQ|I)DfHx+Xpk z;Vt@)?9mcy?=4V|5AQ<`%Em4FDzqlG!=YBYa`X~}Wy3OKQ}oZ*85AA_^hy&?1Cs$J zt;r0{0009^xi4=G5var-`1-8UQ{|z9CJi^s1}!B|6nNr&%HoCdmu<1Iz&O)$Y27I`CM;JoY?@h-J;kAme`=47uK7I0A53vf#|3ERu~MO?~ipH_zGU_f62pVMj%+FdGxqR0v5V>qQ2?e_QBxJqPXUK)Um`CAS4KrKw&jHemGMe zA4nsQdgH}f5EH(0h}3G88QU_@wA>|NgYjM9H_N`0t@y(#4O>2OHIsq()@s2u_aY6@ zjFl8N@9c~_>ojAA8&JRG)k}9Uy@^73lBc}QzDrja?U~->1SUERl_WIJ+wgEys(Oy z^buhi>=%6d)B4@b8-bsg8&i8-U?@?mGe%_ zZHnf=TJmI=a!{fuXvsdD=9Qzwc7-b3{y38gJoA{oL}>RuWPv9kLMIC`%#Z_fJ*j-k}&Ppp=qO; zroT4#k1hKR_Wl39V14s~2hCr_NK2odgY#m*KgM`O)1zMQq%FsDGaBd&4pX4M=DF>H z=kuWSfG5SIp4sLsoN&`huR62YvBo*a5ntA=_~1nCOV}se&wYnYg)b7n!O0PJp8=lJ z3S-Ek8SJdv9*B`i7;1EufE+2=Wz0(`h3`vqd5P zm6gCrIAl69IXh{C8hTIbod9#2@wvzRURGnMP9*E6iYxEEQ5y2Vr@u}l`{41(@vT)d z^-$6)!TO9&18RB>2v-cHO9LyA)^o_!_|^Vm7Gcd{!yF*2Wn+$BsPYJFSrB3ssPf7Q(E{`ssIk7v>Po?e8}jn)Pp7dSw@j&?S#qmvJUkP$cqt!4I{VbZG7 z@#B3Xdu%JT{r+tH_p6PpiM_-N9R&Ve9$OXVKsDioX%8RGq{P< zF8MQS{|eRz37lUKC}pS@b9-jz9ZMkx{(Tqydi?F&|#sRy=FT`c@~qqy@r@E;f4nmJ@@Gt@10K{y$@Aa#r|0dAC-ZsR&F^WF&}3voQSc3uDk zVX;k#4_lSh{Q_QB9Q-&_Vg5I=M)mB}xCSjad^+k-EA@~LsWcR~O9GPVwZA*jDlN0U z{!|lP9rS~CQHJIK3D^?4iIf z{hNL8mNL>Nd~V|HQfW1=20&*WB5g1Z7v0S$g;7rx;Wg8 zeNIdTt4hoY#$@CRqc}cmHl&|eGD>kRS=8aNazlDjPohyFIfHLZdD}Xv)3=>6LkJT2 zb@X0Te0~Ob#{*tXC#G!qceY(`yi1FJoaiwopcNiHf`y|rMe3EK?u3TQY$wrmyNVcY z&U~&K?R8-&Zks7m(BLlxDVRrO80`gfqGWz2dNzY>weLh_D}s&j+W~IQ(!}JWzR021 zfw?vyQ&hCj%bezd$J-AvY-JL38qcjww8sobv=Gct#lfhYo4>QBthrfPtg)yQH_ZGk zA@{R9W}$t3xagf>@Z?UflD2}CVTpn6rWo`d!L`USC&kL#6p@W*5F(CL0J31ePV13p zMOb60A{%D))KV^T7iu|6r}Hl1*dl<5t3I@b`y0&v!b;`l1kD?~>p=b-o`T;0U{*=$ zJ#?X$^Pf-Q&M{zsUlWPNWD1oM0=4S?+orDYpM7(50Q?~%(GC%~xM9G+x=$|;8V*BFaXKaPmHQzN3{``jOWG1F z{DKibpjKoj%Wa`Zs1!PN1FVJdYjk|#ko0JOb6mwCH1~-*1`T&MuzXTI0dGD%&vStT zr{C9^EUqAWEV*?9Igh}v(e~xa$z91T_m_>F&3elATUX14#47SSObsPF0Ah#c+CURZ zl;_vp!z-MBvcW9l^feWBFw;|5YQkK{)#E)hvi%d@+%9pnq9S*yjG!}}2PC0E0`0_Wq zv1@bKQ>jd4@dWTwF}?9iBcLLiROh!JvD-F#R7Zj8tK$87?Q1Bb6pCfAgk;=+3w(^g zj++aR2+YOo2s7KoSfhRnoN7YQ&U49Rdj2|_Lh9;~pk|aD5SnNL-jITAcX1`+BxKY( zD;xLB{Joe}?toR7ouMRHF*QM?aGTrf4F4PH@4*7p-LerhbpX4;B@&r;0%%-4! z$Bw)8;5~Nip#!<_yWBKw(pRagSNW@7(G`*-J%m4ndknZ;9ooWbkUYR`-V!eVN8}^y z1oN=FhFMzj5Dq4JW_EQA3oE)t4?dfb?2m#6DB+23X@VTCkL~!x_L38ARNi-$n4n;> zu<>bDu_~LP5m;@9Pg6(WK!JpNvkRn!HfY4bssJRUq%Ah{>6rz%E=H3bmdr+rts0C$ zgm9H+!-5KZ4KTsQueHB`y$EXKSfuAAt&JG~mfTp9Th57xUqpN{)iV)>pi2KuwdjaD ze-$cT9|$}?gK6t(>@^CJxIx! zlNxNMms$mA<4Xn%#5I*cyBU2!pguH?%LdrW{~zPASdn8}ki5ZwQJ^%~PXCxy_;}es z$?W0XvM?eLg!wn<3j9_)xX>@6$<-!_@kzF+b9k=rR;lmqa*J#_02Zc@yKnTdiDLkuYJONeE9&jaWaI9=H(2Z$CCr_JTN z;G3J1A^!y6>)X~imkBF30KGD?$pK6C@)h*fGDDf?_9_({4OHmM zqBjNCby-4daSkCb32%k3?FIlcn~X+m-#0QfshATPux}- z-z+F^i0#>Bl_lTg$lWv|^*_II7&{9_inXonc$^-TREGNfJ8O>V06{56R2?R>C1W=r zb1duMFk)1cJw9l40N|2sYoUhqXFymQ0r=bBllxS$e|}2bA!?{5v0ANr#EsVS%9=b1 zls5qy>yj7C)X=lt(^d^%)buJXYNqKk;`BM$nXNCmi6{hU-Isufc!uv|JOqIB4Ay10+4WX0Vk);G}WjilF#nkvb8cFsvoz~}&%=@~fS0v}_f zw9HTU2Q2)J#o5nCUvd(zzXi;xsBfatb|6dpjb3^`vPhE)N~Y0XYEX0D|Dkj_U!w z_!KmD2XF|rw~&&d9|#`Pud3SGNicfHvC>t)kk*=ec zQpw7HWUWErLhyL}@#q|J?)1{}4l_9?t;@ETik!*Y9h}>egg@COYH>>;(hg}Dy=Q}k zc-7*0H*MLNG@v#oLR*IfI{TZvX5C)^a+mzdmvrrd@!oK6E!B1J?A^)yL?xN_;sG0Q z-{iixT7IR**}DTx;j>!CfVKvJJ{S~_D7REFA&mK0!VnGhW0ry3&F@J8T{yRSr3Ivs z{6`MuA#i|N+D`9uz;VgqxjFXM`*%Yx+m0+aPpyS4@Om6#HhXU*%UU(y;%906$M82B zjZHO1i+G-mZ;OQvzmkCJSS@9A+q7)et;KBaElj7n3j(fAao%tmC6lIFT4v>S$I~8{ zrdY}lLAEqyOTyWqv=%KVLl$k%K;P3xJ?9s!G9(@ITqock+9HmKr@8*j4WvbEu$7j!!W()zzr}=R?j+$)oG>&1cPQuIq$pOFOjR;Kc z|D=vezLSFprZz~MlP%To{+*dBQbrN|d}^9t6@n8{q3885=7(yA z_>tvTsVPVdo!fWlB0Xgjz^}tz&AIg3R;QkC{o-&z%J~G@oLlbi(-7VP$;2l!|4ZGQ zSPt0)=FH%(Aag%ltUF!1P_8fKeOJ&Pii@Dlq~&(HIW>A~Xmj;@*p!v~ec_jnIfITZ z<-d;NNky7yXBdaiecjM1%H(O9Jj#In#vfH$4!?D7tNAt--(Uv?K|L zpP;Mp7tC3L9ndZQ1)sxbj11C*bLAaV*e@z9#%GTmwzBIB0+2?}z)R3uaJoMGiE9Jm zef=qf;v1qSEY(FBmF>QDu3;eVT{Dk7qXXwBE8|Z81h`00wS@gbF$o>!sl~BMVOjtH zIFRZoV`RKW`rYg^S{S8%4SbUxg|yM1Ce887=eB|R9lu?x_E6s_edZZf%*gMr9-B2r z&cU-5bOJWHrWTos=Fo=0_!HzU4*(0I8Mqt%rL}rJz^Y9oj-hEtdFv$# zZ>wyguwRDuVc63Kluz(!(EVih^M0(s^Dcaj;b(zBc+p@^yZ`_Q2SZF}OnCbYHC$a_ zND$&e^=VaHe1CON@c9Y~TX`;kkJ!)O8J^&UfSrSw&<0g}q)6$Q9Da^T>jE$$K>nU# z+51bdGS8;}Mz1*@05LwY@(iV2Au>Os^st^=W>W1}Y=hr<+5$bu$_liASDm%x5UG1& zN~dr3OQ!BEt27CGU5gAUHQ?(xm}79Xgz(8~<{9#DJ{eMqiwz-DL=r0!k(Ce?~o_C$p4TcpDV9J>GJO^lic36hqX! z0B#evfwh4D83rQIA>dPc7i|Pc%iGJ^dAs}I#FpkehtE6<;*S7W9eerb7wrUGCSw9} zs&nk{ghp4Ccp@jEFW`98KHRTDcXB@{r>WqORl7jd;P(NZXh|qwh}{IR zXnoRv001?d0rwBWu0b}oxy&Aq3UlJ_@`-Rv53&49h!6&G`b<4AlmS;d$>Z!SsUVKx z07bpfX*}u)g6ENvYK!`oX!yq~z%lhGK74@^01bGa)k!Jwyhfxkcf)Czduf2kL?PXH z{cnvTaIfXf8%8jvO}n!&Gb0(a{~Eo1+R$PESI@iBWk!;dTwP=W-Q@zI7u;(g0jURK zd4JW9P~9ad&z@CuUCjj|W8hk|1V|T0`ZmCkl6UD?W0LN@s1iE`CQrVc0CrHEsxJw# z0fmFbWouo15n*@(&i9p0hmnb!bo{PbKmbfUlH`B|NGLZC+7#qGHzfhrnd?vFjr-X3=On*WjMbuV3Ghna+l*y zvm54nhxibK5m8dNsWsfqEwk^O{LaMgqls$L)(}TmB4#j|q$>A-0Lj1re-;gSPYJNX z33!(_^V67$N)rs0=)uf@UR+Vo`LVLID;c9|^%?8OT^5)-;AE(IfY;&~x*5Zs zZK8%#=lpvTGYD0@001^M5H~FN8-8_w^QAg=W^06Ogrhia>jV^P}&A;U;l=wR2U*Al);5u5_bc`IfCOUNQDa0IJ8U71iVJgX9k;7_Jnf2y#P zzDV(p_VSmNTE-4j%@UhDZ3_Bv%t+DEQx1?kNhEnvNFtWy5PUCmi0?PDLxm$pZAn0~ znd`W3FmUvMd_g7@06-e8nl^z=Yb$~glK41#BA+)wS>yffTh*q2U&q3K%zkN?$*&6yqjUSZ^E(_88vrG^EmHGs<=E+z6Q<`L?zqp zW`^MB*)#QWnjqQW7a32iCb+sFDJGUBo2y_?kA60fkgV7^P;A`CEAxb$Pryv zc*xsVkboBS9V5IdFilf&jh78MBphG`vMV&o)#OxBqiUg19%p`qY_Zy)=JYl3qYg>7coU}hh#&5n^-yvZ}T!jeSX08+Z+@RJ8v+56yDu7nu%#8Gr=im2VuGpaGdy@G6 z!_E$<-UKC?N#etsq@)?(y*_t0m;QVKuRQaL`LV8NBsP*c)ZxrSu>>u?UQuE zHJ0+p@tc(e9IrLhDHbD!i*G(pl_5pMR4^(WZ#LEr?rdj$w=|e6jkTJ;oQqE;0Qw#v z0LD?}A|Fn|Ky=B)paibzMnI(0dU)OZQX*KubocYj&iB`MOL21Dqv#~E7!kgO69Efm zAxO*C*bf-Epoc{d4OAtIpyI>GmOf##vC_}jxTKbywOK0pV_~b-F#8QD)1lXXgSMoh z9mO|yJ0Ol&??dny6(u?KJtaJxGP8$p#Jhp04D%MUi`%lWciP(KqqUu2C+^ade!QZI z@Vc;_g+daoz*O>J%oU(N8o6;Hf$d<6kW`2{r(&D*J4mS|kHKOu*M4~9LVY9vpBw#z2+$<*kee zM|8QVEN}VF)}OlWLkw0bPq3r^F#^*8$_URy9A$^NfEb_$tWyL82EhGPKXv0n_$6-i zr&Fg>#$x9IGlclK{=+>#<*6(fO?hzKExWx7?w5ep2aG!-aZE^yr{~P;gt(TRqk4u3 zxk#t(f4gsNR}33A>Vz@sHl(FFDpI(+XIx+a0oB=XLq=5s00sWJ98)#7n)~`;IwN(~ zdH|%UgBdo8EOT0pai<~LwhrT`B#ctr&}p9xoti^IE+)63%~j1;8LaE@oRF9V&Op64t% z%ScM2QF~>Rn^d$s%|knJ*@2+*z>?IcLO5QIRKO?h2MQl+U-W==PL{v~C>3jvCAFjl zl#EA!D)(ph%D$er^gKz0b}rVyBtRuXh2;mak#<$4Vowb@J%Bvq z{TZP0Gg`;Q#`hQ{K84FD4~0p}l4b&yuPb{JKc}&=76qf>bF^Mw@?{j~0hUY=vf#M` zs;oI^H)6;DOEjePsJQ#_wdEQ}u7mYqy6+u}cd%)YkRDUd61XU){vOfjUxs+U&`_C6 zBQ46Do>S|cLmG)LYPaS_682ue4$f#YPxdhfFQ0KbhAAk z)@bH`C9LfU3b_x%O6-CfuWVF_d@`P72%QnDv)4G@bNhz3*0xDBTj*Ry5xZn*uP57< zBK~T}zL?>?Oj#4U+w`y)q4p6CPJAn?$TURnx+q0P72t7c91p>LM#Mpsm?mx5sJd67V+4c7^a- zUY9})uSdAKKA9Yp8#rqbi|mLjHONx6NHQO)*BG@0Q9zhi)=WAm7L+r&r7p4z2dv`& z9_xrf9pD63k>I@62~M`BNuH&VW0lhIvjh!5IC1>U7?kI$!LV1t+6kQ8G+7YnRW8oY~Yp<+<#=2IS0@s>A+BpPCKMi$)bWF5OxF83+VHU@7@16c%x z*HeW@39ja2F6trl2$FoZ%YgM>W-|~w!JU`QLMn(hhG$w`K<+Fir@Ku|B0A#4Q z0&j(9$+zIKE-oYrRu6ECa+JdbcR@wJWH15D3!vjhEZI={Y;_`EGlLOfx)exb6Q*uM zA6ESlt=(|%#Oz*R9=`9iE`2H-->DJZNE60Y_4%Yoo)2SNulN(ENSpxO+mYKH8+IkB zfX%K|M|U*i{7Z$#18knEK%{o`66Og|fxi zk~!L;V0}6_Rf88Hy}9{LV#DkOgomA&sNv=vAC9XHd4L%qKmzNy0TQIVpy5YmBt3e zD(2ius9J)ov7|%k>H+wr4MSF`n={QC2pIeurA) ztnvp_<8aht0iI%rTElv0R!T~~oTP&F+GF|Al48DYZ;$G|$bY;@@cC23wj;rxvZD>b z#ooE0iBY8DtGjcN0zHlBSsfxs)WlE2V}!uL22pnkHp>BLM(n@@eyrC0T#s$&#zwbL zoGsdePDn{S=mXq`dr$xgEL1%sZ0yK9Og#enT4h$E<DaWf$6B+XkWTh2c&u}Unf`~}rV=m55?QX|n*y24Phk%&2JAxaUrM%-^Lzx4Mg-J49bQ6}#gbf^+#)OrgdA z)_@EalL3&Qun%qXC|I8WTF56K3?iJ_5_*};lJILnY)mR9pYQ+(N~g}?aCiU>sl$ZD zQkiI#IG&L0dWU;No*A-h|H0E0)WKC130+c-wX}FH-cT8Wphp&J=T8%%jS|K9-IggQ z`f-X8L%S) zJ?` z9Sw1B?U}>0cohsVF_k@Lerf3a&IFmoC6Adtm=t51oyoG01jy)tXQkXwT^;g1h_r1r z`C3_*+l&2#bAfh4#guTzGD?~DNN~-I(Ss-E3bw%SB3@v04ju|K=YC$OW&g_ zHUg}`r%>$N8Q2*qnlZuvD&7DAOF)c{3aC4`#OTmTR6p}HprtTB;RQp_073?%k!ulA zy2h&_r=JE}V)nquyaR%nar;B436BHrYRLsW|7bQ_N4&vRu+)m)8(#zE%IVJyjSjCY z%Xf(;xnlew^GL?0avp7}0J%tEj!88kuUsqUcxN@lZlLd;<8O+M|j)#poQ;>qVa<3b+O5RoOctdGCc0N^urg)3Nq76)+* zs}Yz30rS8e37Y_rkufJ>`tE7a5W%r%Z~y=lD95ha`u0z7X3@L$5|!6b3_V&_w3xVp ze}#mntPgqQQ~>O4)Lp)_Ix+JbZjT68($i92lTMA6bZ_rE(bDtM?c%a+c%Uq;2Goy} ztBZgyue0Q9s#6oW$O3r%f`{@N;@wnu;rt<@cmYhP?CdO(>yMfOJx%|bOke;21BO$h z6uK+%(IeWskak9?O}uk}i2$B6RMT>2hVYqVz0kgei&}_67Xn16b()rmWU7^L#U)Z4 z8iXL9+W#3l^Cr!Cm{0_JV*nvY#Y~IzOy#k%mBivrltD$YUt`k`eZrZ(2O7>FF5{{Q zZ+^AR&c^1|bsbWSOyMmJrD#7__-FzZ*`%lj$93%0EBD5$?8lY-!*wIFBApyp>zWDT zHL`gU^|AfRebeFk?X!u}==__V4$s5dS29rr|1Zc%Etkuy!i$GGq=UUcHBoZ9GDo6x z4ZsNZ0008-k;WtUtk^sRGWS0T2N({247La+PEZhQ$#w=Zr{QcY>0h!+; zUH}U7RY^e-h74`WSicVL&-+Y0mTb>r{!4?Ok@mVLOd}56wmz)Fq6{5UpN-B zuydB|g`Hr*02T|~%j?_H8VrSlRr7pm9}F3Bf7YNZ5dAA+AnV!z6`6AA&~QRtuiKt4 zMqn--z8Xr*u|AcGIO8jW0Ad`&YgW^v-K4qA3Og0kpEBH21~M%SzIO_)w79Ez!)q4i z9hC!gUuTaa+L#2F!{sYzuv<8ySy_<6;&`Fz)Y%fKr&U zCV9=g_d_Di6)7|(s31HsVN8dh{|LT2vG(MwXPtR<1lK`3ipi-~1bj~d(f#%KO=y!; zOEqMGDl=8$At3Hn-YN4ky_5*s_ap8AZ`dL&{Ge5Qe-#iqkO2ZgAxCd

AGd@4)W< z0aTfaRm7JqH*WQgbCs(uw*=vYTb-rE_rGUeY(P~EjIh6z z+tUPC5|hF;d30Y_V~1#klQnY{FMnSaxftyPwVn-;QzgO3imBpgXdlF!UI6H1ER+Z z!o2W&gX4sHc2teED{W`|(lNm71eFevuQvIL|ZK5wAu&a zXn`eW>o*)UFfRb^73*nKSk=|sU|86>tpET3DUGFHv(ZF%A6O!!Wxx|p|M-LN-A3*1 zbHOYDlELT0NlANl%1+M1ga8LH003AR z06Znoo$SPUHKmCQVhdAuAfEb{F;!QtasjFGhwR&iO`93g^pq%_#;qBYBi}$*r(lmK zg>gQ=0RtwV&FkFU(~K)s7g0t7*CH`c8A@N;aCON2GxO6^`RTha{{M~5aqxu*+0dX4 zP>)Wwamp;Na~ha5ZS+0h53yF)FEA1Cam+L(RUb zKjO4(DiO$B0Hbhs9lX+k3A9BlhS>b0{gVGlwojLy9wt<14`JEGN((`dwh@tRLtd#j zZw*>Xs8cF{8!`}!N$_H$R*(_u1!GC-k7KN;A&|J_GOEo~SAtCud>Eys^fty8`lvz+ zOOrLS&(4?2KU$DZ*%CmH>HVq! zJO!OW6o4}mD9{X?NYW4^BwE3$r=4WVpost_d1eTUYXy4(u%GitEN)b*NFyT2foIxVD6?q? zi&8S;3%AI`E2=}F6MglsJ0?*j=5>y<(IKE;>Se5tOE?$EIHzU7hqB2$uqOA8F-|^j z9dY|kkg)ccKhcS5=)Xfms=U%2cCp!8o)^_ZfThv^0NlI400Ni=C;$y1iIWCm$MbM& zQ5GNI09A`Aa6FopY{+&wS%DKdp-*gYYY^#`YbSk{VCQ+7N1oPM$-=4_(}({9@^?*p zKgf38AJ>%2qkFEC(X)vx+;3=L0HIYNi?QOBhfD5j6FO+2n~-f9vwO)e76W9cltG<$$M~*3D zD1Zfgt{`xA04t0G4*&oF223a6kYg#bl^NUsivT>p300l2cg$q^O}zrRTET84A}CJh zJ6D8#3`brZ8eXtOB!`(%AQO`_LiG8_F0b-hR82nC?9tE` zYrE+ll1>9-e%&a9qZ1H|^E11f_ zBacg&&x%Qi#!7GU|>H#z64|gby~1^D=m8N8`{m< zd5scNSTbb7xkBw-hIV0&r8mL|&C?Z;CKcTWPdr9Pjjw3i$nY&ZKvGfcv|W#8Tj!y) zvwdHXayAPA=JH7q4id?1B%Za<0W#FIv^0T)hQ&JM73^Dq z$y{GXA)I3+PdW7?1idRj<_o5231Kc>pz~CPie}^kn|q;@7l(M?>?ihDG+B{U0D?Q~ z&Hufq@$uTBB8y-o43Kg_x&55amG-d(#Uz*Z2+d{f%H_xegHU9-E*wqg5R9BP=>B0L zOaAf%{*-(xNHk1H?7K+MQ0;P;`;#kqO37fZbYY`SWEE8)4jfm5WU&4zN*1xLK4N!1 z75*GI*o1($YQof=qba8P#W+#U znRw=N1w0B^TLgRX92k&C$H%32<~1ijN5h^p4D8JKy@dMi#GEWC!o&ZNO0;t|S>88? zmq))O!sV=38CDn#qF|ON`F+u%iq29I;{V$vwKBl-0Zv&PvuR%gE)=FOn+u=Bkjv); ze%XPIKtqpTa-ceHP@}2tg1V5vWP(Me$aWo_Kf97=rxK4Mw;vP>gmtB-K53M-Owwn3 z?D#(u7c!h^%Y8ixXku8(%^l@dg>HXNa0HVo(o>F-TXwHGksMe^D9caB(Ga>j)R5u9 zR@juzL`zo18cSE|GWKByXrI763ARCr1}}-&iV^>iBgHPmq5Ffc8~m%ztFZrLF(1oZ z1rW&s+ECLbKlZMLE4_z^EpeOuy`=)ULU_Kw0002%6Q~Z}5?f8>aevn>-5QYyDX{Gz z01bX7vPY?0R~pYAAD|7dPY#7X;Hx{^(iC?{a7H^Um{~zf%uui8tdyBpmOZS`L+`94 z@XP%vfk^%Vv5jtCf`1h5=ln!Ui=CE|k6OK>lM-6AkXCP5TqLT@XAw5p3Dz^S! z)nDUz*E&{b*IIYyxVvvDD~oELv>_7yy=Nd9uz@%U?X=Q(=_VTAzs#*^JGg?+lFhP`Vq5uI{U@hnq`0Gy3 zy*oq;8RM3s@9haTCGdpmV*vR;M7m~0;6JSk_$O`k;vT$lZnrIh3X*k!PHKE)1CnK} z8zfRa)9o8DMzI+yL$Bq-Cg2+YjTM}y*;EPM{!+xVZa#5+%dm`B&^z!2%)FS^lCBpd zXn+Co?NG`+WcWbu;)GMY$*sz&(jyi{Ax^uKJ~3(U7{sNd5f4Z(pe=HGW{Mwrl846q z-c0-pIPx};34=Y~EICDNB5B}7hP?5cbtxXYY%@jUQ@ zU7IEYCQpt3QMqyOQXI{;c4t>tSOui|L79!QsEcK)_4%{?&F7jQ6Qj4dQD0w^;ED(| za=4!#MqE^;UNNQOtiS*OBWM9P$sY5Zg=v=tiUdKIfC7Jf__Wye68W#$sbyD}&m;CK zQgiFt^T^Hs8IyX^oL{gqu_YBR_h1Zzlt~Nz1`*GbaiN2hZ^uAY(9;OI2Kw!rsxC8p zn}Gcd_hg5!#@vvve5~B$eG)^`je&Y5CJjj~J!_ zaLqv>{WiVRaY&yy^M^MyeBo^kOmljsV1&W57C=*e=dX~RLE`)KuRxgT$&i}NntXz< zaJ|lscCCcj*67RwAfkJqL%Tl#UWQajMN?j;^*x2SR}e+VAGm$9+67FL+Xlt9igW!o zaBd9eY{4bPV==Mu62LD*`T!JQaKJ!oahi{3&&Wufz*~uiC;$qh=QK@8Umgk_hzVdp z^;U#{U0AZFe3uOR|F0pi!Ju|S&P>yLIDjWYRx$~c;%)O{BFkc!?PXJ;2n5{}8qX~~ znRT})EB+#TH%agQLFSedJ%89AGnB!wL1=x}v|Zz5@1hk|Em)vnCoV#wWM7Y@L;4(X z0DCCFaZWMPtpmB?q>)&0DkKPMak5W6(*4*L5XUBmynO|yLZNm!NEog>fkI459RtNQC@ahvil)w-Dw38D3mr=vNk(qu4b%v9q!ZxEPC6hYq96cD271o+{7IFp3Q%{$PPU_QW!3BPZn6H)#o9F3TGc;lwul_u&tm(M zdcs2mY*F_^R@R476BDRW(?RrdQj(Xm*#KLFCq1JJ4c2VD%Ey_6i1Ad>jClR%z2uKd zTUJ5X4G-AFkw_EW9qIKCYTfNNk&FkNkt~t)$v!7uNuV$~#0*~XpN<%7%S}$7cuUm0 zP3Y(4XeB&0+QoI>3^aJ9KX1APe%$mEB>PYVd6@mK{rI;xE7SK-PC9FVs&P|`2^N!* za=_T~|1F=&`f>AfO(^Mpr+z$#eb?H{r zAo+hqUTrbpwEF^WVg11g|LCypu{?f)c$ATcf-ilrAhwdIXDR_U6~djM|H0|ftS+k_ zVvlC%Zh9Yb?3$S0(&&J+-Y`_A8^2UNG zPAn}x00RFIZz>Dp$Oyp;62zVFJg6NRliI3EJpM_yeTx1!FKmzfq$<#&0A4#QZc?Ba zBxxA=#I#`rre_2T0Jx~pe3#;7sK%$+0vF(``L&L;6lq^McfOo@e_?MSX>r?ADj}!~ zV!yZgdzaFr^QEfBU^U8p5J!kc#l=lW@bHArVodc1P|?8J6Mo-^>OB61Y+PmmD-hH> z`W!fC^AtSfq|E_V*fuF)7bU2*Qc1iwfmM6)A1P4;2-rdVMvt}vaP7e6LYz9jV%c{3 zf%U4w&)I#itV1(QgBLUxbm^#qP-V7^2xRNuABU>BBXkZ|iPHFfjwqv@OpX*@VoT>O zBx>=&s;9MkG<`OGz+%S4VzQR2K`<@Gh5w-W4gjk#3cCbO=c0F=SIXbM*ZAPR{_6Z( zj^V%ulR>t$k&+Jf$~H-4_RD?AmDt1m7LNqyFWeT`q6gk-DX|(M+-QI zGZ|=#XW?LFNx()7%6v@j1~7+xfe#Y~h|z`;8&4cwo*Kwz6({_%gk`3@k=t_`>0m1< z6Clpd@5+!^;56j*4ZmQ$0g2Y%SHRbdGvl34E)p|vgra>CW4JPQ7=(Q!ikPmC!TqYQ z&fva;aKo08702E|&~e0n+I`wHvs56}vS8J0aBRPuk)vXZQ@bwlUr(FqMSXYfvmjkP zJnH-Hg2Ts2yO&OFC!8s5kr!=+jW#13%A~yba~~AfXea-mouQLZ8(Xc_>QZ&{jLj>@ z)`CiqT-1=bjSp#s?qib3E20!G!YI`S6inb2M1fRi5rn6~R%hMBeH+5&f5nPx9_@3o zaA4Pi#H3LKNDpJi>%zcw7;E%G-b_L)<$7u;jBd3S9t>fKYnh%sveJHa_Tk;hs!~Ry z{7W+t;^*h1-r1RBvrg8FeCLk@5*bTno|tz&eh|=IM|>xBh3U%#eUe|HnG`EXZD$nw zI#_FT#U=r}@^ckJ)yBDr&DvpRH0croKZOwdSkMRdkJE_yFC?u5Uy$sKqE4$iJz-)5 z-*cm_W{bvnB|bfP)W!!;3^;;D&0ivv!iIRhd?`ZTwJgaz_|E%tB#IKHOMsd~iVRR| zYyQX6X4NPv7`>S0r>lZd$CrbBDo}+9tGMB3u^k>)#{hY&pK_dL@FKtxf%_F_-616d zC4SZwLhxG|HZI0FoiOkH>X%Re2VR}XMblnv-KG$QgD$jVqGi^T4??7Cc+JD7TX=CJ^6xF90h04ImGHJs7I$RKRU|cS9okk zr5LiJV|&a9H_l{=ue%;-9f zQ?ceP*A=8A@2R;uxf0_F=bRCX-(;?<55AW#|z6c}Tdo;Dk}?(K$HDcR5dDqD3asG%nIV2+7~EW6b#3VpB<&x%B(oMCPR} zX?-O|!i6p4}W~zj2{Y8 zp0nvbmx|2UTVXh=>?K0GySiZ_zF|pOFUW`CiFI<&HoBUAO5OFMy*0Iz$p0*>4x#TpKc+dOQarSVfTe;FV!U{TIKhV z8^N(YWe3ZxqeU(uUrOqLjH!+4!;M16bN$|*k>+eG&u|AXj7+xFAA+;PTGjcnwk%Yi z-3%(%vP5#MZ|*hBm?7>Ay|ie;9|#^R8>xhD=O8MR8)o)S)n3&Ob}3F7 zL!Tz)>}?1InSFVjI{yE8x}Wb_DndH6_WOM(r%+mUAr|YPE#Dh%A@QGefVC<9pLXLE z;01u=RCSy?84D>`OyG8nWb{zm2b-j=iw&-&=jf%>f$2eGLD@+Az~-U<0#Y09aw^IU zR_J=6K}XjCpXKcL8TF65#Nnf?l~BonyY9D)s1_rOJalk2X>KOnUGoD#BI(+~wRAO#~7Y3V~8)AJ5|Gf*Z8W z3eoZvEan$vmSCkrDO}ubryv0B06_ECwc0Wrb{*W-U3rWvVv>dM*fN5AZ5_QlQscTl zBS&@d!0}tm+?bCCWnu!cDLC6m-m*FeW2N`1@{gX(DE9aF_k4?gOG@6*G@f_ug_aKH z&hrKOXBVb8qp!#`@(CP6gFq9X!ucx{X1YMZ#4pHg1s@-4lUKg~zxE_xdboqLAsFBn zHB@@z<6>spn<__Sia>}d5{=B>&2mGtY;k5^tI@rR+g0b#n6$(l<#MxGr6qJ)y3?Xg zcmpeBMO}*xU`X!B(dy~4^hx*Sbe>#n8$^AGQqT_Nv|%KjvVDHMT6Wd!P~nk^sTjYD z@zle!`-A4iK`2lUIev8|khzx*GFQK!iat0vHs=jlY(r-#rOlwRQ|FEMJT+@`3&|>?)vWqjpeRAe z;Z@2vb@di^vHccpR4A?o#Ktv5h$u}YchXp#E4d_bj(jTPo+B7~22ueN?dH>ZRpngg zecB)-Iu*%|S?JQZ@3XB+Ej$ZGz`81jjxbR&vy|Dxm85NfG2go8AGic!AEqjpi&mcQ ztZhkkh=oQ3*A4R-(&ouu9>=7S9}2Koa6y9EIRNBg8j`g3fS~qi1}P9|tnl#z7e_Dy z{v8?v!w52-Jw5XyqmfE2fDi4nVm}bZ?m&P5(BK09>_2jBXxltAw>p?@ z^*rwrLcO-Bkc-C~DZp=GVGqC+x{ykpOfS$5!WTlgAZeu`!8#@Is(EKCCj7Q5yTt#U zMk!2sy&?IQ+r*jGxupY!+yhy3@8;!MLF=z3CPUOsJH93M?0%Eg=c{iRZw@c+W6SfDk@9BUBVH9S$DFj;h!1#FZ)b^wuq^O1sQU5F>%x#pmG2$w)_&REF( zmeEQHb^=Z7NI{;HHTb-bC5t_q1IMN=G?uMWpEoNw1a1vGa{y}2d{??PKrz(ic;SgF_PsRO9FoJT zf7RR1-!ypQ6?Pl^NuwtESIz>Gx{P$T<^<{+=Zo&|#rJ4}z^EmkX3W1%+T7j{oOaw= z|L%B1#2mR`N7lxljvzUqbDAeoGe#DGI1e{6xGwve9k3BB_PR$qD=v6287~_j<6o`YM5Dl}kN`9on=PSEm}UUe}h( z&58zqQpY3OIN#+F62SnyaJ`fHAEj<*+toA0fLKpSNX5j8A-_~I9PeDUG#DOEWP4wg zT-myOLoqqLSEv9DNzO5peQl=(z^o5KO{V!t8#BwxNG9Yy{9?|psYNlFejrU4t76p( zi7Xk{n%qEnVWzrt0goE$#>=81ax%Ca>>4g-)rmQkej;g6Ld#EdM08F~DDe#46!s~5 zNXEMrV{nOk?;Z}qNNSP-P-(ZpMNdx=K)_k=a>+@PotLsSDF&IciU{@(w`>yPYUd-o zO=%Nkok*XyjQBIdAecPf8tAvf;b$8o_AkgYHQ!U%}WlDwl0a2#YhA`|*)vGbi0s>w42yk=@BAjRd?J9Ta># zA>nHd-4fw+_}pmI6zO>M7Q@Rvcaw6Jx>7a9jG$8?7f(xUvQe)4A?;PY>x$RMRh+T= zVMxU#&YBd`;n73=A8SbN7&S!q%8l-tqZd2X+~mM1tVgiMy5$PDLa<0zq+^r_Kk4w* zyS7+r8jPT479HHRl@$xB9X!(p0kwt8C-a#b+W=+7k}g5e7H}x)QrIXg`~L2PkEl%E zYAqdVi?fR6(dQKBfgI?G;A3TKjd z+ChSN_)MD%y7>EUH8+j+X$CiQz?M$ej(hy`CXB1%CqBlZGVF)d7TQfP(L$u;S8mMS zq?0UseOiBTH(A+0fWp78t^LLq?~>Rz%7+l^7!a%pkijI2{_&5yq4(V5@ragJ5)5Ie^jA^r5E2lR((Q zA{^GFe~Yjn*t7H?dAkoR-h!FK^mHVHjoNSv+ajSDxMOwp&cim-2#LHrKHt<=hZi1D zGDQjM`D909)+p+(b=7EdIaSF_7Ak$;PVI73yLq#{3x$bJE`QLkGfH>tr9)YYy zyl@ttYHvEh7VPCGeS13h)}Nj>;Yj!pqK>OP2nQY;h6Camf2FYgk@Sir{77J{ z_kmPa7JUPpe`0xg$+Y#4)%elyN%f&x=SKQCZ@tu6bg`TS z2!W!Ev;EvOySJUts$qNM(NHqkSTP_`8^i$`^~`TzI?1XZ{pIq0~=Fyq#)}^W( zA~lK3mrOrufC(@GiJsRmAK%)Cvk9!lYhWp0HK*tOA)hf*roWc-)_o_TYl)#~72 zba+NTzkRkNT>K=12p7jM&}qw$b?+Bc_k^sh{Gp3P+?^3mV>JH(`Q8w8fAR1V+kstQ z{n7;~K?rgT=B1oLA&}o$BE$&xS9T&Lswo(l9uR1#l*+;Tl>}jinQZYQMhZ-Hw4P<0@;1bK?v5<~ryKHvXH$W; z*aTQC3Y2fbq|BNY7M9{p%!Ly>i?9rUUCy6SpKpU^Tf=A-KUg~Q3InOP5D7FaBES>U z>EZq6Mm6l}LyOctC9YHiY?%)(R6pBwP*MnlJ}HZz3s0NlB;&~f+UvMIn34ON)~}xn z4!hwwum+W)Sz$7U6y&j|k#+(pyyZdw;nKMZ+M*ns&udfPEYPJ_D5WM!1CD{!A_~w3 ze-4r>Uu4G?6Nn^UR5Ri$O4$l;NpZOb? zZK66IdFLhzl~Tgpy4WYM^_|2qE?4u6L1#^dW_>!f${JM(FXGq|Z@kB=I-? ze?jP@h#ysvrf#VBogv$M%AdNRlFKRO|zxapVH8Fxq4>)e| z6#{@kdYW=HEM_1gs>zb|V0tg`e7AHX$-5J~{DF1CJJ=wB@9k!`UR)2p9KOjEh-y8f zw#89^r8>dGETnBin?JRdVO7mL-AW!kW?gv-JJwXFv74Y@1(HxL!5bL$F}bIkJR2Pj zE?iR-R&r5FA-&<5c}V~RXt873Gw92@8{5xATZ>8I?DkVALSrma_qp5KcR;5_4OC5i zYsQR{fGD)XrH>u3IMy3EQ+s}ZyKf30tk3;?h+KF&w7@_S zHLt06yiU%~<&+PQ2{QS6{b?%3xv)c5aVvopAGO(M19@z2ZWRhbBjQ++f}$cHL&$Am zDe&~Tev^}@6G5E3iso501_J1xu$R#i8-z8L<^yMO>ea)i*~k^%HqF8)xNW1W6%*}m zO{iYXVTS$=7hbL_^`rvStp)??ie`{5#VSUK9GdzP5Avcs)4ceBMvwp^^|R0bA@4}S z!9$b%JN$~YZM_9p7D3lPy!TCacZYO`bcb|HN_UqaAT8Y@T_WAx4bojoBOr*BfFLb= zi_fFad;PC(Z+7RmXU;iu=FFLyz1Z2^ff5QwqUsTWr1ONl#k^ScpO)A&=qZ_Kf}fbS z>y>t_+H`Q@drYqOCmlC&4A9830am2rmmm84q^_FqRu=nc6DatH1o5%rPT}NlG3Ca# zXog3JtrxdOj?uL))FT{>%|a@pO`H_3%@ILfWvN&2zuXnVo7Q zUvcH0eFPISFG!DFGC(a!iX|zaopNxm!B2ipk5Fw=8x305(aYWhnGsK$pu#y0pnuuyh0N6a z+K)9fjf)1NPjY#mPSu5Vs#O%6GP^cPh#AvkYPCdq)Vcz)sFL;|tk%DR4ym1iFtp*kk1JvTe?e`(+yV(MHNwz$XjfXqV4 z6!D^1`)esmyR4j^FduDts{*5gz{So?ODa0t8YOS?XX9z}iGF@GE0%EvTFTEWN5{Gh)=nAWgdN+ctyf+7`5xAcWnw5^@yw3^G&dFoF0J|O_l8p~1d z*YOS68S$xg1>Mk)U`Ou(Up&Ulfnh=BdhZ_DCf>eQ2*UQ0y(CT15rW8*B-YD!>KBKyW?ArE{^`CY@1eNJ6N^RSj=(#w`9 z+ay}ijBaK-nSd!C(8l`U!GU2w)Hh@Mqxn>Ec!v#sq7W6&q^oO5lNxnP`p2hH72jTb zM;9IHn75^a>Ns9}{(1-!MQfi!*MYr{VG?smmQfAD>MYbMbWp7|YyO`zuw*B8%A$4C zn*LKPW(E3T`e(=Wn3o(j;>nZjj>Sf z-*aYW$&dBEE*PWdm^VrHkyp|M7inU&u)2LE724s-xaMj#dXC~TXOpCm#yU;lThNQ? zJlM@JM*ub3l?fiX{8DbUDzAZD63|mzyg}ZF~#;yFw5N|90t#veaZQ zMv6$Z{Gs19^pUDmJ)SrvizI;sYbh0QNF1c^Fipp;b-y{VvmEX@er_ZB`2w4{bkwt) z+2{ijl?AlSlFp#;prEsg(Fejs|%lgwDM(}IyH%E z@0b&(3#5-`ps^J?5mY9l;nA7OF}}yX5P*S8M`FB+TtVIpIm1I{Ros~|A;4k_*4R*p zkg$x{+!MF__$F}L;Y@59+UAl^rIw`4C zqGWM>Z$}XkcAIw}QO?3|b&X$p!F3??b{ei|p6RzTCDnF4Op_LTGf-;5x%R0jXQKn#UGZAk(+w9x3LfQuxJ*~GNX=h#r$alMuUolMv;lw-!^=^!q2mc zv|}#&wPt3~oxx9VMefVWnvwRtKONn;*GhuO?*y?;7=I<5k7J3s(&TO;H1D>FZjl5= z8~1^>-8g`qS6Tyqhj}P+MY=lgRqz07)aRVw(*`WJK!=d&xYA7WH6IrNc|MY{+75tq zPycFvGrQ^YMGxM=6Uw{qMJD3L+5~Una}dnY>hUd*%P?C?VOS}l${Y^v%~kZ_c%SNK zt93HXtgqjdt;*oSf9paN^Z3k`La&L(%3QBfiB`y$RaQAZjLjh{H!ZZ7>N#p}Imv6& zx>99c$Xij#`ip*W%8n*7)TdW^5ZC65$jVTrWaPtI|b-xjdqzn65 zAXF>JI5oeA`3R2Kv6WTX_RL5J#_=3xGFU2?G?*#F7GvK>JkdKZdH%!^t3*zXZ^kDB z@;ZT=0UCO`^KFF!_l?r#K#K4aS%GOQZ*cL)S_JC#YOCG%PG@cBh=INk_*++=667Uv;D-iyS2>V zk=tm%s$IsUp!i5@V}y#6elv~vC^z$d5#LH(2<1*`uP~ultQj!T8p*Ve-+f*ehW+hzE&3~O1X*Xa9zlhe zvWs~*vcUw?V2{0YYc@tc57%E4p>%6a_kfh`5E@D5K<}L>4}B>pHER zBSH443R@YLeBSZsyM0XA3w8lk+TvQ)QVV|T$Uu=^Y;gf{=y+Vfi)W)MYAy!zblRHf z-V0297)4w%c~M!KP_6AADskKaS&9Z3!;>3*-s%{q9?D{A3$F|>m{zot{;LzBt{Bnj zRF{sW;lNieuVY+mu6^GtdFeI7Q)m3>fFP(Ki|75w%#wb3_F4RMX?9T9$)N(eha%d& z((o~*wJmMko94Y)-ZS;yUq!NY1iS#Kqep_A{*`1)O97gkLO?GBocRK;#YRuA8l3W(621u|RDffkcP_L$ChK~|a$}%(qFdsrM}5k^=GNf( zsv3ZsXAD7|4fw5#nVH2<9nNy}8LeG{M6+aD_6CI}`oy&hT#X8#d%Q;p8C17lGe)bV z!;j4{C~%srBE?VHJG)`^GcUC7LxV*?!#iR!%i+bXFFXcc8Yuh&v3i+s1&

+T3TxN488{Q(d39)}8&2!R!Aj#2a)M*NLkFhks{?7N<@I^Q24pbL8g7o9c5=vnk&1%b_)y7b+$5Or zmY_sLog!?4`SsG2!)YP0!aoky!h8o7xt z7ceMYB@eTWB<2=^vwr6H)8ufx@#!`?yr}7&7ImDtQ^ILPC^bs674Uhg=j)lwBsfM!K>OX z3y*w`YF|!e^OTzw>hM}lJX5^Bz-F($d&DMGE0#+b!HB~^iTCMqH)pJR9EwCg5(t}d ztYO|H#}v|Gyb^Wb{GBWwgkA=3SM59Tytwr#vBTKgC=S!PG2GOzzJ7Cu+ZS>dI#cTG zgn3o25S@tgEl**Kkd2Fedg|9&{<+M)Sie8xuAhk=xRqdNhmE4oSxJ`T%TgSfe0F{= zv$f#;lI?m;!g(3xYn_SiojseRdfIBvL`rzVA)bN{tRZp-A#H=PJhz}$*XIvSd~w&)j2Ohf{T~WW;6OWg0dYgR*@9Q zsTJS3CrwmUQC*Esy-Kx>rbO-usR(l#bN`1Z92_IR1We+x?$^mApu7bxJ@ zEqp~=cWohEF;bE}B`>W9Z|eNcK>o~g8%Nk%pXQJu3hQ`Psk&&7GvtLf6;NXgQ&Roy zd*`cPlb?ECFUa9GAITLi2tIky>8?_%niL)K^^3pGSpTtTBnH}VCT16hyQDLJ=?KUu z)~m*t3gvs`$bp$5#OuX5krrjX1)UPqkqajt+B4#rK>xfjEH@rO*v~$CBi>7^Ri5bU zT%qG4soNjeG$>Nr2ZlCpA_l%J>e-0dxAz0>RHM%1?Jn+@hO4Ioa^{lt+x0#}T(afI zsS!B@jAdS#?*2kQ@;ha(FFs91@0!I<>{}1e5396@MZLi#UD7xuIIC&gZhZe_&&69u zWV9>Neo2xt+&+}W9&ggJJ+{MM{NRX}pNn0w`l%c|f;;gjF;Az)Z}*uStkEE5s%G`l zyU!d_=>8+$Tz%t?Spp!Qqp`g(arCZRTB;oCxG$|q7_-F8It67__jX&7_o4c&e%+$l z1UW}vX&7Lbs@FQAYg5j@lF4!LWxFfk+Vm!kR9{$DxiH^kXKrBTvZQ!^e)mku0>~be z54>|az4{_^MVh#`aBVwL0W6M2rRN|1Zcg8RBFLPD0OKgeou^kTO#l(*6SERlkW6+) z|B=3l%u;grD;*>Ck`n3OT05t63N2u8WxFmS&+8YA7|UDwqtmvzPef zYgC5LR8Ko~RRzzAxOgW~&V~4?SNIRC1^oiJ0!xyjg1 zVH{h55|v+Tumx-Fr@@SpY<9?HOoq%AOxLxL?Vs%Vcn(aWnAml7{UYdSjb-#Um)~D= zUuU{Ib(Lwm?sP01)&XRJ_?gj96( zs_<3Xp8J+2Hx!dutmK#lxjAiGG5UHIp(J^|%O!22IIQt`sqpS$aM!SX!;Hgf3PoaJ zA%NykpI#uB&0 z(+^Ca6R*dF-8es4^-No|Md9cpJ!?n}2rqRP(c!|mDhlU&J#DA+3xSIAA_5VPZ?B7S z9kVi5OzAFaQC;e)Frx1wzqJuHfCmHM`%Yl~1?j*qM(L#7BWm%>K%K_PYsiT&A@ZTC zU)wMwe%8{Pq?^tGW*nCisqTlk&vC5#c5?f`ov4T80(N83t6KW`i8cPlgH2Jc_(nk@ z?k?UZu!9D5@;4#v-XSgjC}`KIZdjY*Muo%EEGZ|oFdlzU2a&@?bqqes+gDcjp{ZcbiH4= zc8bo8omOO-18R3fzN+F!(ODpTtl;jUes`kbPb|)JpHn~>2Z8c-|5(v@bxp^FaP@tU zDSsBWtIGPh+nEX<5kuBPM~4uK#r3wf#bA6l6C))f7Nv6*GQ_rBfVxt_>l@x{@j#k2 zS}Axc5j3+9u}%dHuRsx1wbL0E-xEKw_Xb}IvdxeXRYL`Q+?Oiahpr)>OaT zC*Cc%?z}bO5}|-W3?Bck^KpR@FAUb#UMgEMq?Jo7+r0!OymE9g`s0oZ-}xdN)g67} z@)Wj2;xgMn4t_|mfj%sJ>`y1yoo}ql$hoA+$?A-NaBqX@29LcT{c{Q4JdHqJ*(|Gw z&$a5cTG6#>20K2P$ucl3=En3wrAwOQtc$fz@aHV&>@i_r9YVIZ#ST4u?A(H;*p`mk&JXIvgB;>Qio#`Vg zp-X{^+aI5sV3k64!swpgoPKP}Q>PznJG)`o&f@brayjU7XVLGROr_8iXEA&pc#dv+ zdq8R_7K`|9E1rSgyiIWIB1qWlm&M)){K+r4R+)wA1OG&#ib=_$9K2}$!J5!|#FBA& zXMZ2L4W4=!>OOZ-ZuY~vi`kDseDxOavBnqDwygY|77{!=eze_@6Hl64w$5RnQUcTf zmMXU0yD&1))p|oBmi5>6P8WTsD=R@v7;Br}UFpK#F>yU8J$J7)y&Q6OB;g0u`L$nl z8j%gbwaCBA_@x`*%H~z>k25%l&hC2qZ4JLpVQLsJA|qC#qnu0Ez1D$rc#va=b*Yot zO&BpGn%-QJL(i}FJGGhOEf1$R&u+6q@3tX@sYWe_o0m{V6hj{JikVBEDgGAWG~CIm zP&0ZDDku3~{0e~uhLKe9(4BMTG4qv8k>5gWHaqY3NIw%!bqO#~X7_wBB;cl8z7x^v z>#r5Wre}f}-7`5A?|;7go(!d|xcsM zD3}_5=nGXyjZZ$`b9)lvxx&8w7}NkZY5bcxK75_JmfDci+Bc}_LU*krxMN>t0r*9S zo^jZ#Z+6@&IaA@t_XI5FA;)mGZzG>u4keHAzv)ddqX?WvyL}QMnWI_VK}L-J1Ou>a0;;COE;OL4J09D>?Xg`@Q)MSU(!)2+ilKb8eXih7gzE5xky;} zKR5SRn|X5;yl;cw7@#Um79tvM;D>MiR)D6FUOO7z$v1#?9%tg+`7`ncPomCW5)Ygk z;a$vdNx~y=k?XeKT&Q4|-U;DgV2mVBe~M3l6*LaEB+buS6pG5fu7|1FTD_HKfGoLL z{4(Lgp^E7oYz}~z*(UQo?NJZgTq3+DmO$TvWRe?#PaxBtU1a}gd-<761Ng`ou_itI zQPk09KtG^Ak*-+IJg^KE{#8F6)LAZLtdVWPJH0d`VtXV_r&PxiD|_*h0hXo#AoMd#4jm$^$;WeQ37*{B{?;}&Qus_A4zzU>zk^7xUWQ^Y`;w`&wY+a; z`zdz(m1f8Y*MHoch*0v&dusiwI$v112At1%3T?~rqI7fvdHQQ&tZ8@+qu`>CTGW{( zYhqg2?SYR^dMJo}_iD>uyEpj*xv9(8v<%_j-*g5j9-=vXAZ^CpJ`)MYex`iKLKVk= zbTa08@d=5o=k@k69UOQ)RhsPw%|?eUeDNC=zBF4$p-9?$!`}*MiG?Y_)2?I^0cMZLIDS8M7%jUMUpEcA|2MGvzlk&XE@; zo(&lEcBjbm(r`O?N(b5v1jI-zEMFg;2E#@f9HSUfQ)ouff0lrM$L>yu)Obp^J0V@nB9-G4 zvpl|InFY+V-(V{C*crSCOkc59GwZ5GPvfpRGTG%3w1Rhf(<=QWD;xa-rN=)1WgBz< z`=;n32Ty|v4#O1+s)=UF>z_0kzw5;t)-DVCF!Endx@v3Vclof-)QHKwdH8^nFn3qz zUpS|s}JOp!jn zwi|lqBx(-cjo5Dew1F@U^)sOjZSK@@_rID5AC6hCed&qC(uxJYIHHY&am4gRnBzv% zRSd(;Kfr5AZagKeoHSP6`gbUfmZ29cmH{bQMF3sPhTNd^*lT|)y#N8Au<3T~tHqQj z8?f(mYrR=n)@S@A%Fpb`)fe>FWMo)h;2o*H zCjQn|MplRY6;I4CuY1UWN8L)6>GGF@q@YB(b?=!~b0Cs4HT?dEFj|o$Rg-tG0<4w7j6Vv;@BN3i(ey<^QO|GeX{#&bHzCL-+tWIT$hu@3|Pov zqLsDSjW)_eU{9+2fSQ!AB(_l@PK>maRW?^^_AHJn^!L#$|15^d08zk?YFXsBwPkPF z5stsRFob%<1I?tk>vs;=Qlj48Mg`hv#P$>dYRWAKXvgJ@$~}jTjH|jYc;i?kNi->t zRExh-8GQaxWq+1rb)>?9A@S`CrYo*zDGZamZPrXgobTI->9dDtxxc^#fAsB~<1N#H zX+vXsFkh3YnfVnj38NW|saN%MPT39hxkFQLFlr}lu46hmizDyte7D=d6=Ses8|2` z!)S?DpkLC|9ObDbRYV_wQ1$>a8$u9c`U8)=;BCb=v;CX_FA~}-PyE)w?*XOhm|Wsg zQf3cU6-0Movp z6Ec&Bu!vaf$`G?_;*@~ffC5yF^u3+NyYT&sDGg1+lf^+8t!Ffrdbf1Yx&FRaudKVc zq+;z7!Y1ha7P)gWi3EaJB9jHk!{^_@($aso5sOU(ta}})3RmOXY)s%7RirugIIpEL zWMI~DF(O#g-+#y4M9DFB4ZAs_&3g*olR==uI%?>-xSJnT4=8gxe)r3VGfgkYP!l^t zx=*ub*KW=Zxfw-^qb7i4(nLQN*O*HbQJ(V#`&EC{U!A^?QPC}K(Ffm^kdlyfjIQLx0yQsKexT#EV=K2dxj^6Uv znPzxIHVdO-$tOet%Ta4N%7cw#iUjZRb(l*oeB|g_>vw08$bFG_v3Fmun_lc?zC&16 zYYK3Rf{x)Aw$+vLbJ02!6sB*Ee;8xMujVl;?@Dc~vNNgYO?ZLDS|$*|_2EftAK?J4 zH_q1>Kg%~GQb9>}yxMO}v-gf}5T*C7hy9WlR=48K5U<4MJWfwE)P+KE=6Btv@g6}ra^1U+pgwCvRm6TX!|DOGnS!TnR>ia zvN|410=Id2IEhu6Vdb}3kT*YS${+L^ri!~Lz) zp#?_;iDs^|EJ`p@U$;qhAoHN2#%1i2pPv_I>g?c?;>F%(&+T7Doa17RY@3W@z#>nU z5DIfB#>3!$?H@{6)8Bio*Mx+vtA*M}o%})R3EfAb*1j6)o~ZZgrg6JiwC^QsXzi2T zoM(UUCU>KC%x^i*_*h^&&VCn6n)0CX^9SN~lsgGno?hI9+a(_v6(2S={tnZp;r+gA z#->ut{`peV7+-lW9b$b>8MBt=JV73;9US%=JqLxa)(kSO;%{ku-t|!QqIY=C(7p!= z-vjnbyvzwp@H04s#r8ed&h9n-(zOo8rRhBu)uyHAwUR8Ec>!Y{6l*8&xDyP5CTT|% zIV3CTxsa3_so;n(JqkXO8U`LNCgo$B?gg*JXx2#!aN&vn; zJTlYi!bm`ISE;gbkzIof{p{5TNQiaA}w<#XiFUI70w&SJ`%OXw-Og7M=QL91)oyIQ4`O+7C0gBsY_mlRJ-~Ry_brcGqiaB^jz(8>0d{5g@ z@MHpg!PoiIVg8mgx4e=OwN9t~6lT-%t<6>L8xf7syR;{&$Lg*>SHxJUF?>+Tn-6=E z-CiNyN5|PWAoFX^vjso*nkWm2!w)!6a?*AYCNW1p7567n^AO+9ws+SXrCNWDoHrpP zM!_0~^}Eyzf)L117EF|Nif^{}!>h6aUPSSkJc^w*fj@*x+Lv!&;i6JUKv4}Q_a!l< zRcmtJ(jorobn9EAhiLuLwcD&T*{eNogaD@mDATgsz3uDmihjE`57zo9YB*}5No?|K zhVM?qGntWfUnL0z;XZoeMcqLgt!9(_*!$UM7)N7zg`|63YrzMoL+nUYMJ3By&afbi&*k2*1{wWJJ;*}W+ zEB}GeykG}GNxw-e^=$8R65&?M89@?d64G=Q@XOp{S4vyZxpm`_E zASU&*CA@=5me{v)a5Y02#f;6R#ZV?BHMk&T)L|H*`=Tp)aGV(U<>CvAHAk9BNElEI zo%e3LN@-~)J@CZVfh>^yhS$^6o#_=6D(xT;2S$J(4 zq{931r%XLpq^EKH-r3ZbaQc$o>beH&7NX~5-nB|0@C!M@rawtkiV(XNxI(@8sb%66 zTi_@B1f;pB1Zo$TW4rPgl2D4-L* zn3{j0qki&0kcvjhbcwzorW*oa{$SxW{QP0-6(&a_Qu6@pu*y*qrdwb>&iu?ix3Kj8X>7*CWpubDNT&zZNy7F zcI{^fyeMx&G0JD&9gEg$ake(kd)OT2C~q<8GRd}aQ}(gx$)583c*z{7tEt_v4QZABf zXi5ls`vr_@4lpn=IbqDi4v2=6>yv|CUm|^H`#zkDSpORR!KXi2H0JG$B9KA;dAkK+ zIK-4Q6?q!9kYOW}Mu1`cAweS4NvtL0zAP^m$l9sn@zjql?y_5SZDXMw@>pn533#_QIBZNOU7yd>V%;t4p&l{5>~3?4U+a;ra}p5jU(gcX#A;d`q!|O%V6z zu-AM0bl5bqPJeMqT>2AaZ-zg@p+Uj@HcErObS1n9g%r5P85RUR^Kcz2 zwwwIaOTQ))5#A)V$C^4GTyva^G`}~;C!U-o7fraFV#x4Vbo_?UP{Ox-u(LotiiG*9 zWUrgjv!%!v^#MEQDC=p@ud!2$eWmJ@1`C;%(h6qoqAw_<_v`!J@=5d~Yu}_u3RUr& zg`7}Q*O-Ky?0I@rOYl@%Xf-XLJ99~8Pq%>ur_dO( z)qNb9u2Q6xgsD9cU87|pm@7hoAqaIT;m;APljVTmUKMmF)0ua^yr*$~EsH2CEIWby14!B?2&Rjm!IL+!#KsH-EpLbA$~DNH8yb(T6uPuR#(03 z>K{p2+E;0qp{JMRP&&3ctS@_)NJklj>Nc$MbK+7PKVOm7Gh6j{kp{`8Jbx~tx1jLw zz;#fFNY)g=N35vVPwZM-KVAETprMY9DE~gJ?+OAx&Pk#X5IflFr|-8;i{5qF78b+e+F%LO8yh2&X`1eneBZaU!q4g?>hOgjyDv6D>n{u?D`i;C`5N(N`oZ{H5k83TMrsgoYmRY73{e8&maJ@z&XR{gP@v^oHk|#v$A7G2eo5V33`W~>w>Ua((uH_ zY__j*Ttknd*0cmvh|DSB??o`Yzm%B#g5@?U59H)TUb8CaR6nOO zi9hYU-Yx8mG|&&<%|-Q03*2^hOx)qj8_7jgE7^g6eRV)*S9*+y=RA5G{}KMf{%y}w zr^WsmLL&*P<@q#GEm%OwQUE>CX~d{Y(!p5Jy(OM-62aP#Knu35Cz3I~&0CObW;E?g z*j&pAAs*+f>Of*LXr>9Oem!B*G!^3!8wOxhyCB}dl)`Z^x|q3zhUoVOQ@N}U7ELu? zjhdxadek{r<6I%fMoB&+wlEc)xxR!W6B*(r#+c!FYTaom{`1M{q(N^_Sf8kPuic(^ z(uYsK;MQNVhgW8XJGw?atn+xaXVBN#(LrXd9Tzrf-ytT41{s@{3h%=a!&Y32+;R+? zCYK#~=+p`4q9<#TtNoEE? zEv|G8YE}Vj(0F2{_{WzOqAy{^0YFAqUe*g40F;#hCU7YhB7g$H0H7cOU#t%#LNNbe zFds;RU;{8<3ITrrgcyMPg8?89Lh=unK^Xqa18RV9{*grh`RX8Ce=shH+aSXKbWVob z0^j`ZmtBFzji}? z5@7$~xP<@s1>}R~C1CxbKjN|k?0>i}5$w(Xu@~Bw2!8$Ozql_E<{y1D5%wRRO+@&w z4IpPC(tj}~h>`!vE+^vtp@TkyZYBCY+6fPGL-!Nk{wWu5mxZ|6sWPVq%ca^~W~Q9>kLZ?my*% zaf5_e!1D*QfEd5PRgc@F`o{)E1b4XqzxMn8qcL-E337lB75u*`0DKz(0EQj# zYo*TMo2;|JTD%1S16fe_;hDO;|vZJp!vfC+5?9RJo&2=jufE#Ckq46|Kq0xnE&d5V*yzI@}Ly~Y=1H6 zJNAFr7~uFPs}6AgrGpK}^B032N z;U9(q%KvQ8162OBqc>PzQ$Y0(W(M&xpz(kBHUHtqH~{jYScm_5W8yFCtzK>ffoP+MCwmI3&=qN24M;` z2-MI5S}G253xdrg3Ld$^+Hrwlj{y`x6F?8~gQ2AgS}g*GfFP)y8VqYXu)E*_P0(DZ zBa{csQwMW!KnfP9SqMDm2kV0ie1uj)C7>c;s3`&tfHhceF|dAuVEqUm7YYC~&<^Mn zL>mla0l*maD>LW;9xz`RnkOoY_d?COHw2Ke4Q5ftrL}0#|i-WEE zOAd~C2oweu4juvVxs`*dwfl2VQwI-Ay_dF*mhR@J4wla?U7XErFd;Yq{DU?F9^)Lg zP{t_OqY$wO$mm(w`9&UM3GA|eVhRM0{r&%LVh;~zQvigf@Zq7A3;>k$A09?z0N`yX zD1-B#AqkLrOnId^qKQmow4GSaL(e4M9?2Gz(sW#yLTmSp9Tl#*cOmz3dVmF1M>m*SP+q98u8VwkE)ZCuZ!o$>o@|CTHC8fEkqotcEB@Y{yqa&pi zJ0~0HehknB;HU~fRloy?;J_m|10daj$3JwLM>_0ZIx;SZ9u51CaqxfWAVy{Z$Eg3x zBJ+UO{E=0Bltuf;qXb6TAG+2f9qS)m3!EkXM<@J8e*uvFp`(EMEx-=?sQ!`{|O6pp}f?i9ADr+cnYodZcAX?ye3=PzV1(FdH zQ+^B!yamBNHga&Vfd`Ik?OdExr9{azwY15QHbF4Jf6yNz6K4kzWo3EDo4>CQfBF0G z`Rv2FQ;d*n?cL=@ale=9vaM-R^7!_c`R`f(mseC%GiMXvZ@0iNi;07i3kU?m030j7 zb8&zidjZGzPQajm;~2=X#lvwPwq1^A8#@CoD!X27uw$PQ!zVgfM$$7~=L;Fk?zXW+ZQ&-u(B`!W3US>Or? zB+v#1gPZ>OOtuXKs^kKJP#gdGjFuY&!a)Op`WqdLoQ$BCg9HABH8%%=jtfB`3@s1{ zZyflJjcN5z zjh|$|yckDo#}W!{pD}I&ehS&2h#j(`SlKxXZKZ?HWwu5xNUv&qd2U>P#e)+o zHO!Y;4_3~>?Hfy(o=W#ZEnxrMu{7VWn`5g&`|fF7TpL2i_qXT5>q&uGx9)fMx%RV3 zS@)MJ;H&psb!I`3gDw<^PJ`k4-ss%3@P%H?^R+#5y%!3x3c`EXG%9>h!i(7RTWK zoZtV>S5cufn_~zME`EQ}7zznM{4jvfV z^uwbYqMu)tO@?91ARvPn5tW-`FG(XZxAvQa)>V@0AWR|POl^sQ_xUH#+foWDTEYmc zK?Xh`eR9IEYgDvKE8%07ryJW3$MMp{6mrdhV5*z@k*pL8-E4?gJ@N&WNFXNs>;7N< zf_+c&U}_gqfYE2fLx;CU+&?9ZQt2iB_Xf@s3Lt9h1Sm3q8)Wd30~msgMr&&QXnw2a z!KwF7-vU!lqj}MDOrQYT$O_|@CD9&DkL|Zq3i!`WKd$|dFQg0^#G~cOJ04cS*#fST zLm4IfNNNmK!L&72rQhuh{$0I$Cis`Y-U6jDEJ$@)vcJBdLbW~D@m~W~| z*_pBD-@wG+qe@J%qPbA2>{NEv2kc2jF*aNi{!bu11XkyR<7r?t*Ro7P7aqb#1OOl~ zlX5y}+UnQ4}mkz|M4B*!vn*C!RiwR2xvJV6B1B`UIiE|fU5jRX`T+VRf>2qz!VTSz)@j- zhB|&izkw;2;J^vQ2O_3UNFUt?L`8VREu2 zaQ_5wvi0A{MpS$SK&uQDLK>t8kN#W&GcqNq8G=fH4**XOj68rxCi>fhAE|1QD@MT2 zZ~=C53isz^f)Y}y_^M{Mvv1$~M5ssq?TiQ3FmmCxaY$GsqU9f}+G z?|qvM80P<=E2CNbhM3-!{6COnscE%@f%=W+1z>Rql=?Rw!TJFp1}^O$S8^hZl5iOU z&>s0flP7e-O|J!^oCxu!HpHL*aSg;pZ6r~ifYC~U_?OIoa0dh6IAF3tuYqyKClylu zU@^^ezl!+<0KdyN3!p;5J`}NLN3I~i1BZEt4)jnoq!Q6_1eEMA#wP;)`CsN!MkQ30 z@>TS4 z_#Pq_!kvirf6?(UZ^(V5BXQSnfcdbEjSoQ_E0p{IVgSsd4A!$Q+o6yc0Z1*2CaMn@ zCxjBHf$s$jbxJ{Ev`C$JY%|0J$?%6s!*2k^0{(az1xGy{m;$xTUljU571B{vX+O&(=zk{%M8LnDE6gSz8wY65 z9|S<1Bq!&5JPhGQfF6?5I{(Q%03g_3LL-l2Y$H_?BAPr&YZ*Kcry*DTC60$zh%o%M z_up4WbmDPX^I`yja1bqt#f8Y(U$S$OhpJ*6&k5usGjj-sKHwK(afs#%{Ru9*XMim5 zP^3Ho7^L9If7B5GHzcHm-n*tO+Rj73H}fxNDLMktE;4+M1LzV!X|X`Y^ML0E`2&#f zz(`P^{q@H`!6MJdE8d|ylMUgLI3A=EXuLc?8jE3c*ck8(6lZI}wa^$aTStcqAj5CT zNADnLqvfyuE4BY6Uw;xk2&vKERu{4ms*6LYjbau^OLiu3jjX)>nC#zyV4f1HTHN8dL9hqvd*2MM$c9Ei20&!7P$?FEJWUyD%0 zAW3KzLK%Z}7+`amEVj|%T!{8$ZyLA#zup8w6_7*(k|(b`&^9#jA`ZNYfQ-upIyvOJ zlQS{9f13eG;(-GwG_Lc#-% z3!32gv1zFUTFz8*B?B@YKiRqA>%BR1X-M9zoJlu6sqTX}8@Fe!zc! zxeXGGu9jL79nZu9mulj>l`5xOA8Mw1lmCnzpr=Z{Eg(Gu`4jkP7LFh>BTqxQN37Wf zaL1a{RY5v1uLoFD_ClgEx%-BgBEj+zhKT&%TnvzUnuHbQ>sJZ7C<*_`Wq^2rI^sY6 zhvrIHK^I`-8%`ewEl5&WcUjL`0IqhgX8cx7W@08ovIj6o%#TfDX9_`7ZbMa$6lfI! zDF|d)9@5_jf($u^BoKJkBEunn(0h;XN39l*CI_uiAh35*7uu9yZrfY9>af4EP?Tv) z=`)VP9UMMu&ykOkiD=J*alb8QgW!Zthuav+xmcT!pn#M;kj&3DC1G_Ygyqo)ND4yd z6wx&g1rT8RX&}>wA|0wyl6hRhe@u!ytd)(hb!GLa8&GklIVdAT^nD9cA7BWdvwPKl z$+t|q;eg1d_rDmufBFTcSzgu>K+2E;YzGKWpcGD|K3L0xQfr0Kvk@5ds~3Pkyz7Iw z|4EWbDyQaj;E+VPkNs7NU~q2G|4JL=ebQ^7>~PQCQU{C?3#zRXZSo_f7Y2 zI9wY+;;}#Ssy2p{HEqBoSe#8fgWB+rJ}%$9kmb9`48iC9xGNiO*BFRE-Sp1=!-M*k zq{{-8$3JTK$94}q{*YXN%r1fC=RbuEK(pOjFcpAA3$5yY1B!-x%bG8X0-#8d6U5VU za9=V|cR?z%Q95ju&RboyreU!dsYr;RZ;XU zjk3V{kYV^kR_M@XsspTz0X9%V0v^KO>7Nche2}FF=75wRimyHc_0eQk`if|zY!i1K9-~d4W;FLiSIn0_rM5=Df3_Iu=X1`_+!wkmC@K3l z(}U!7)sF!pxs8a83(1rlr9QhD;qwy znR;wM`BYS$h$iI;G0%Hd!i(;UrD6^277;Bm^zV%P{0o;%zgX-;%2`_q_#OFU*EulQ z=xqDWWJl51DL4kI2G|_vNo$DvwSOWTi~@}nCn+B>NT>}Phi0V%p|<>Dr!fE{Jb&dtzRTaoBA;K2S#i%#d3>9;CRhHX z=#oE=gwa-$>t-G^_=fhzlmP_kEkO$Yhd7^zPrJwj6eLfVH=G63f>h`72j`I2Bx9ha zhr}u*o}OQEa;hG^7JUQ{k-ycwpjiJT8P72>$U7K`DP+z@O2aSoovrqGs+ zBtPL9LIUQu97`CP)0;G>inXspn=b2VS0o=iU`&!I=AJMKi+XJkC|D1kmTdbs{p9=x zTDW-ZOLxLKXHV7C&>@76>`dbiG_Mrm`uGE8f}Nk=rZQ%&bBhq)Zo9v&4zH(oLY3Ba^&_(-?A5xpkuI*zjV9k%zh4^ zMj$;N#35v?V$@qOZ1hscd@Mne@2+Y=`YG54LM1R6KvL|Ogk=MSl%mrPq)im{oFr-Z z2Xb;DLi^nw&jyg`%CNRe<_Z0+sPYu?G<-}MasZ8e>I>Sr+bH8NiknkIu6bEtM-)oq z3-+FikmBnYy7m7wVWRl2F%CiDDe~rQJUR}`( z4t8c{k(=aSf|07ua7yF^iC9OI{1pY06*t&lW)`PPzGLz{ojS@U7RV!Bg#+qno>`-m zWuv@5Iachz@;2_){wh#o;}HY70FZ+NJakb1(@0-ys%-c_)feXUcST1|2Je8KnDxev zC0b3gQWZ#Fjqt8hQ}`+QbZNwd=PaXnt!#UZzZl$d$oS07zMfl~% zjh0G$u+Ln zBya1TLmPm9nOQF&w~3zozOc|$xHi~4G92BouPQ}m#!a7EeG)Lxh6rg&4WiQN0|^kM zYU%q%rl5?9uhJgQ4!$S6^4vKkLn%SQliT$kZ@XpM@DjyHH_8$Y*fDPFMnTBvxJ%?{ zZ)@;pN70p2IuBPryT!q%T#m%J@!uq{rX}%ug7dvvr$K~j1%K*5`g=5>(DfF5L6Dxr z?0(?t4__>}OSfkWQ@==E9#W1hT88%Yx6sxhBrByN{>8j0kcgco#5PJg#QQa`qsV@d zOzXUT)0Wl=#3H@OXLwB^<>i!6YvI1SMCNjiJjEe(DnFCpTetqMa5+=0Q|p#2MW(54 z7c*~F_ji01tZ*PwZl# zFe1|Dhe1^8Ie^yGOR2-<) zLNuN}WNnd@C%%2kM?X&rlYV9cjiSD2x;i9QQ@zxHEVuN^0poZy9h(myttsGW^>Dc- zWibUW6rVM9>z3`SZoEbeW;lPO!y#_4Sk8Nu@LLGLL?gvz2zV<{3eHI@)tfkRS1nsuMcZZOH)vVn!-3?>6y}+Gyw82khMBd+BNok< z6uwxR$R)f&`qtEf-b!=RBK9N=6l{B7G^I4w;;Y=ONra>EtC-(+M#Tiv!)sGcubDFT zrtJ{7GA{O7Ck-Nz7$w4kssObLDr@6Qn=ilwJW;jXP`2U1|a92k+c}`hw}_V#?_8W8ixAOV2}Wm;E)( zc$3^Ug|K%YoS2L$O9NdAZTSocX5eaAe{Fo%xUn)Xg+)8Q&M_Q#-ESaTNIZ89*F5uq zu;g4*{W>@!Iv{FN>XcD0A|pxi%;Uv6Rg`ukC5bMu6sOoW_=^=FLue4%?*j`9;=PcZ z8=7eWm4zW>S&Kvy=&%!y0q3)?CG%um`Hbr9DXibzJeL`(5h*~lR&tx_MH7g4dvBGXho>+Y=ixL zqXiQRQx(=b+CHCO1jp{Hdc=%f(tN~EfEhs3D7M~Ru>SZGmH9L5jCHqhM>YCNy%O6_ zcRGvxi?oewSkQll3P^9j(7n?eI%#O+0;?@jI2N0bGTx#W1CkcVU?Fb9Q6%V+GKqpQ zkbh>26Rd<%6@L|y3lsTyQ*X?4@#F_jgXC*5MWxGj&aVNl_Xs2>bBxe~lBiP`dSIVP z?a3UhxX-9h^=rH}LYB)WwGYd56@opEm^M9^#WT5(tkH8cL z?w@#VBgVYBZ<{sBXW#dB(6d+ra_{s)9z3V8V$8^^{zy>|Dg1nJhHnqyXEQhxJ zOYT<%Osa2d72YH&0ps6r$SHmuhD|PMel0V8!fKZ`5c{55`i*&HU@&|_?ssA3kT4%c zva3KUL>8Mnq|U#sr}pwn;Z5Btfb|B^n6DsRpp0VNh3of-_r%7NkJ zfotPc{o5Mnp8LVz2rApD_J{!glOk-Er|GmxBOUZXcm8(K^s7p40LjRv=mW=@#xN?zy9r4u9FS} z1r{WIy(7cC5GsFD5HaEFe$<FjW*BdI@0lF9 z=T0TeR_?7~ZQ9t`qWulY?Jsifk2vF7EzAZxWa?i+F9hvqy*45(H_>EKqXjT30IxVM<1d|#QOIrD@E9UMJhfX(bh*;&C}%d)k@63lkiV5D)auw;;7_NY1hj-VRf zPQF$`8ncUIK^CkyNqIb4Al3EInF>WJ@*Kcb-i5w3?zox1e#$WJ%#MwBWF8(GUYLSE zibn@+R7raoyUTn0^8Gd#pLJtanuRQYmQgKSu)Bgo4Cf*ppJE`r>1(!~EFDhKeGKQ0 zreK&Lw?#y$VOgXtdLvQMGtCfYmW-t)=*vps){WGC@SgPzQgex;{Y1GO3(y3m^iipu(->u~k{Uug38?VW~7-(N17Uve`4j_O6NssW5BMewEmOI*Mxg!Rj8x( z#TZFv==LuBZX;)r>cqa_U*@X$?OwJTnOOIf_wwm5ev-*M{`zt{6Y{7IBH}4Ss^RUP zu>^``9U_D)ttqFWlp06vkUsWZ_7=j&_aD{z;qD1$X?bfOI?>7aA;q-T2;g&#Nc-5hJBm~|KkHv_ia=p*^Tnm{tqs)h(RTiGTWkewcTpq;8WJv z@j;UuAs)Kr=a)7=1te}NG!a{pe7i7jpnU>bF1u*vbU)})0&Em?c`dnjF!=5S(ke*O zkPVS}4Cx|utlod=3Q7u#bNsNDSc^oZANS$zv6yq(XMAI?gucS;)6p>jJ1Ru#g=!Kw z;wN(7`-rzMul=9t!1@}#F1KU1bU$4EwG!aN6fCE)SeJBry<{$T8bQ)UG5j{P+*Ne2 zl1V|q$_4ArGMF74 z#YS+4;V$1jG|~pdnpanjp`EI@z{l)O4!Ki;lD)-rqpxe8F8UBGDF}O|*Gudxjdl?xvh|DLWb2hX49PY*wH8?bU zox+9U24_PORwkO;IS#|eqV%S}imFpNvEEai%%mi}x?B<8O|XW_go=8yro$G2(7lqW zLLh9k9ro^En?48`=jSaa^P-mc9)(h67uFShdisttS1Zs%zI9K)R~cK??K6p26_E(rMnJRpm-ZrSoNz$YJhGc$Q%Yk^c>hI^00D*S*A*Qy%^XZCT{g4{VFNe zPq`|%nI+&Q8k)plH+SpH@NvDMYp(t%kDm6O}@H< zvqM17rks&9!8?JC^y2%OS~c_SZDzUlg3Dxple1*KL4N7n>qC5(Hw5VIqF;!l3-li0 zJyPP=25sszWS;Xg+^Tf%0Uc^Kpsx74IfB*B57+GMMYO@jS79|$OG7&Aez(nS*%zXl zkDeS>PJo{4B1WfJ56UMMZH~pO>eG+VXIik+qMf}MSV=m<2}HTkhtpakh+-IiW#E_^ zeOFqs(KjzimJ;sO>ON;5NBP2d=GbXZ1G-6#}0dw~+cuweq1#dz)BrH^?^g(TKz>@w<{S=+AobVnvU zlbTNHTXV+;EMf_77DG_N0?B)M{tHsr-2(n<^0E&gpAbQjC@VtKh<4F8jV|uxJ*72? z6m=(3Q#y+ZNDADG@D%5Vy+6m{MwV7no#q~IS9On|^9f#> z;@t^1fdp<`glll#C1fP{PDn!M-Y6e$`9GHE2u80_EfE3nBzdxuw8)4?!ApQSOwau8+N#&Q zsQe;m8`DSRn8Pw)R5%EjYNu$+< BcICxdm)P_pqfwlP7|EHSFYxV%A4 zw=BI|ETF4^K3;AO=_gP+$|9%(iyUf)@>hMD3rr;2Jh~xcXpSDGar3FfUeV3_E+cmz z*+L}pK2lu!lWfJ@=7d@zyAk3BzE5dvjNZc67LL;v*e7P2MF)N=s~fs=}CxtsW(kRa;8aN*T?5 z68nxH)x_JM^*b741NZyyUz)5L@2ED>Hn`k&ZEw2`qDAN7&!2qlcLG-4c^_8G9dxl) ze*i6F%*GsGfdNu>Q>Z@I%HW|PM<@llnp!>NC@bO^%=bv$jyP_u{D^9ZIOajAUIxLL z#SVviM_~h>sUN4v=X@RAdbKhYkC&ox`fvgrECY_`&KN+ z%ulagYl#RVa(DSle{Edfl&x zB;$9t)I{kD&tZJK_Ca{}7v)@TE?-YMu*!Z!Llo z(k9AOz|kBKIq2#VL0J-ptWp5rTNnO{X#~rbHu%W%nNMNxS}$Xr{QCqw68$X6>B?kX z6u&*&lmYa_pTFti!SqkGQA&S!+z1ijQ`6#+2*B+SOqk0FNu6Xe+?Ud=W?Br?m5r!d zAiSr0{O(72HjdUX`Any7 zrEJHJ-NGlVJfVK&2&~-H%q{u{k{#^t?PQHEUrB`(Ls$CHa1CB7e2*@C- z$25yVvpOj%(;d2PM=vG){Vi7$(1>=oRJ#2!f}G?>!7MP%*H6f#w@6ebh!D zx_U8rAx*rw^@||d33QRlc{8X}oK7S4_G#Dgr*tbmF%i`3`O?PX4}BVJw}v*XaX#ej za5{>!?jCHGWIJ9?AqTypGP^pZNcV#YB-?kYB5+O2T71?K{L0y9$wqNbbK-c%Nt}E7 zn;qbMH-g_`xO+9FRu2BWw~R}r?^zO)h27DI3$!W3nk2hx8A}!gTHj=9(xcl^S(f!f zHh1d7|33aYoZu$~?KmUvWh9cgYah3;QO%#B(qgObP`?uP1S4p@plU}D&4r^32Ix5d;IdWrIoAYM0P3+9fTM9V5 z2Bs_{>t2ouM%Uu!M8lp2eM$BWuN+P!T_BrZvD+y_S0tJ&llJC z(1b>WV#Rq{GAP&yI&DxD(e}=XB#AS3CVjGx(ZhX1Mk@2lv#%rb@>E%b^!=**V~SoY zx-K;g$#N}OB&J?(N7XDi%0&^*ZgUv6oLx%TiXxK@*Y}aYY?8gF_=#O4bhl3B`H0{t z{XJy2E)@;15aR>qKN<+^{P~XR0<6EASLhw-K=uHB^rCLCZ<-*ecW1caX>o7TVoLQC z+L+hyB_KpTjEz~JTZHS^EXXbbf9#IQ`LT>Ua@4hU&=s`bHk$SuYi`gpe?~djlG5$# z6udjk*L-=!HY-kgu{uzUfGabXKPo*rm*b>6&WvCndBmraD$2;Q!K67R;mlj|B3gf2 zxb+758M=KvE-SC)m#}<9{stDW7~&10BAGBZe1*QWkU9{(8#(2E7ZHeOVW)N;To<}W-nKLD}8ECYkv2L z%TE6KMrPYEI0Qy)k`8u~tWQX5ksPv5lNS4I%Ccf){CJfuZEcm{b)YQPyG^>rtTf%u zt}_fio8NEIvQnckn2YMI4t;V>g$IpmToA7^`J*Y-bdnSekCoX7dXr5f#O;nre{ztS zZy6&!dj6g93v~x4b~6T(7w)SVA0~q4aTC!oW`eEHEN-TPFuP zo0OZ9NJXr-Fn0&uX?#`*QLa9});VA5Rf;ru>hXJzNS-8ouwqE=gQ;~L?qYQ-$5LP! zzxkxofRfhY0VFcyY3xxw#8kZS^7ww(a3e^*L(+|uoisp`Sl+XIY*?F5Rd5f6ag(@5 zTOjva7Oaukr6Py;ST?T7d`(_lewAg3Q zd(>Sc1xXAG?{af-AC=)#RckRnW8HfhJX+-?AeAsgr_JPV48upq=;VOf(y_yXZ!)f% z?G*2Dcl4f9&dpy;>w?DB?}_oowRR&_*m>2+IPVnBXSa`~XJ0}uK|=NsJYtWV^IzzM zG+Uh-`ae&;Y)O>7c)`VJ7AYY$E5e9L)tosS;FRlpLRU^26l4W+K}~=8l?KS_g56&x zV48CCB++eZ7U=-nCu4!`IgAcWp6FNVO3$JfPFvlUc?9NdNq9nI!oyhn!C4ooJh_8y zUwo(FVxtz5w%NPqURR~r4g?PqJ>w6u!yWo0-cTt}YC)*&j!z+Uofs>|dkNw(_^>)$EMp|hS#jeMVNJ>1h2ivE+Wj)sjVOl-@6_uWz?ObmQP8i8Qc zsZYXXPZQBqWl~aj;^m?5PvpTkIx;FImpFHcvTBUo$Gdn-)N!@BbnoApTK)72ndafd z3wR&g|7B33(F_-nW;PZ3Bn)Qz%Uz8JU0Vkgu#xJM4dxM?j15|1@o!`L%B9uQC%Q;7 zja4l@-+)rNTWc3R(JZth2Mg~Jb)D>H+3h5`E=p#w7NlRVei&hz!xn<}=CUY2I$PUY zlJsaH>GBF4Pi*MfO?;(%)oz#w41v_(742b6SA(dzoYKcv)iZ2Tg1_DhN?YW3b2V4{ z3_9~3DjyC_#*^XBoV{`XUA8~-9ItNM?K0#if_t$=twfB`T0aH-kJd@MO3dCloBSe^ zN1LH8d`~r63)c}yRII@TT>8~N?$5(MHEWY~zTimAdMkT@W5m?JvhgN?E0p)luLSnd z{uC-N;4XQVH+ zPtOk&U<2B69}Bgbm~0N{8Es~Aru^8=<=n7)(wOy}hfkIB7r&I^W83|=JtgyC^ZFiM zKSM6Pca*Q=QTCdq8!SGcb{;4eb|&OijVma+v)on zH!!VJ7`hj)wKQbw^Q0MtZ zTZiC1M7mQF<8jF%8)mxCFr*cie$e+#S+~GWB>a{PL=g$L-V!492d6X9e8+ym_a#w$ zU$lBE<6P>&DKd2Z~b3KG@@d)OvF8baP(s*1o{jTj{&eZEIZ+=8f7 zR0{bFX>S@{vMLXo(&y1*mA+Ea6^Z)rG~Nw&)M;psmDej0Gi6M*1Wib!b^fP2X=$;v z5_q){@3g|K*!79CXW?1cN1%;xZePmxkrLkcQ^t(sYTqcs3=_%4R~%M{QW~M>wk49a znBW_1EM5tb`SS0ZIfCmKDN9y)G~c1A5{j*Fnq$PP zWOeR*3r6#I!xg&-576+M5vdm@;n2&-?)%^=hABqHE|uRm?(e%oEA#lf%ULT0yH04s zWCbi}R#3$9n(GrnV#g8f9MLaoU4^|m`yR(#*dh{~Prnz`n|Ir?t9)gi9Yx}WkY_rc zhs0L8q2QjDj^8g#wey4w^(hMalONdwi`uK^)XzE9lcg0BxopmlDzDUEy=aPJPwM~t zW1-0ZRRPmc#dh+Yb07ZIYXN4NDFJWEs(8V=fC~JHWmw04&rk1FOs>aK*`I$hxF}G# z)-T9x>Ef9R3)G7KSSa==`1j`};t4J7XL5@2k&GDmy<=BGcq#iLLZJr-rBqAELYE!S z51TRfl~HkG6w@@*c;8AUU5J5O&{w{_y2wE20IzRL;MqqA zF00XZQP%`R3LYnUTNV16&0j-x#9H{Ijv$HRiBz>$FKm=OyAYSl1sM2c)CV+2g2q|A zYpH(-IBGo^M$y30w+lDPNM2<#(B9YxUFm$mv^w(M>3cr`I=Tr0TaKVdu1z4T!ySJn zK?=##F22l1CD%?})(<5uCG9P5nu>`-UVb-C(HB@tnqT#>9!DUKYQW$PR51to8b%+14O~$KA+@pZiBljLh(Z9aL{hUda z@nb`0gL`K>mYS=&v9!3Et`msttBoFlPT%DGLSQM0EN@wWs#c~Oj_0;bz< z1rsv8KpCcWC&gZKl-{QQX3(_oq%GeRH#+|-zCTlnTEjDeltbh30olN!ZqmU2*f} z4Wp#dc2@2My$!DAw_khFiEY&sGwGGe?{8=Z!W{D+Tc%OG5sXe(hdCj%4K8mDL5WQn-g)oC-1Cc&y_*k%`R?0h;UGIC$jPW8t~_ARS1 zeUJR5<{M>j@w*zH=+g^=b1$>8Zt+%pzWz2#4mx0q9w2Re>Ssj%&<%GR_j> zW5bWu<1B)fO5=FXZ=+aZwEPpCU6(W*!`P(f+$|?}>Gcev5c}tCdIW4{luBX5E5Ns` z-&Cx=yc(nqF2AoUQ5%96z`A`)QlM=n7XK#4ymT)dr*F7`{DK6%3Hw=~EW73sX>orZ zl^1c)I0+RRLFPtr5!2>xmtvlCJPwVUDE?<2^kf=~UpUMAoE#RWXAo2;qK>md=!DEL zE^|q7<7UI-$L)-H#)v<2lvyD%Hlp__^3uW$xG2ZHZfsC|lhel5!w+n-lL%dCd0usC zi~2|x^m3TFUn--d6~22JH>lRqpELpM<{&iBb<9*os-jgF9?y>|jl757nf7ZP=G^=GHdljjMzl(r*{7;E>kXOa4J%Fce zp7^sgQaa+?@0bw%jFF^3>nX8`f~-no>e9E*AP;=SeIJ-(IA=TP%MjwsxRinU62}??+12(0F?^L?l>uX?u#n0i zx%(;hEi&iZ(vL=@3Q1x3uSh-^FXgG->f>6{aI$^vpPU`l&g@p*qaAEO2)%@j974i8 z0QQ`$m5*1G4h9{u2sxI(C0R44mmzi6^HYj`x-hEhefFk@XrkE|lh|WW(?)jIJD|=b zk#KS@BE7(|^tBBJryJ!(f3#i*jfII9_05JJ7Zznl2&K?#67uzyjVu+6la#N@uCw6@ zR>HLn{Xff{Jh)ePtEkMBtxhUQIV!l?Mc&;sQ3$d`_Pq{BzCvSF)Rn#x>!&|4VWMpy zu3NoC?k&x4-ZQD6jN#jxz~d`*sf_Y9aUP`-^wxDi9ve=s>ad`Wj3Q_pBh}&fD7k~Y z;)?yAkZt;9nb@UfBe3mR_eTk;@=aQz9z5;O)kcN)?J@iVq?DWH*3fsTm=(`m2rA+-YvQAjlwI+z!gewMSYSCzymYBHt z=--^l-};%2J2eR5MO-)c&kWIts%a~UMx7TI6Lr6>2Bf9^nSQHl?+)QEG_z7kygb;+ zZFxbwNmBUgeY2JT@d|jSAn7cbW=l_TTK=oB0V}X&!@}Z-@0@B{_KNTw}VgD zRLK0E`}Ct!lh?ICOq>IwMDwvRl?)dbj#&%Or zFwyU#;NT=(r2{`RT;zI(*%GJl009G^0lCGq>*4Uv$w`b_uY8KPAUu>68Tz!%!eYxVQ8XV4^Ig#QJD;l$08+;cQXaI$=$Lpd(O^D?=iiz_{H zC79>%flIKq9n!Ei5u9!!&2AP5H8mSpyKLX{)6dd2{fLAHcS)UHDWZrze3C)g<`(+k z=|~ivyV`WbKj-IkS+-u3mhUpLYC=%}+% za)rQS*Myd}l8OS?x?joWVOl1~D#poAc<^F{8`q`>Wzu&^lW)9XE=1!Fc^c>8xk!;S zFYech><+qJlN#Ss5AE8=UtGzsE4Fpt93pR2Gz1Y@JyRL+a~rEdHwi%ACKC>{mx=uH zsc%B+ZP(JB8Pmq*qo2p-N*{>A(BhiwWIQURQXF!7s5(_hyLmS@&II%5tP=gx>9va~ zZ52MVEv2G;L5luNo=B}+@!p2G&Sr{XWRLqXzFn|LxA9spx3Al5azb}B`1xY#>Ae@9eNg6|+f$rncog9az!3ZlqW7xgM}@LPra7nSgRGiyYJ;?L@1Y$@|@kI z!>4KUnEa^^1@PXJ??u+Cj2I;~t4TY5ku2|cxHW$98D3Yg;kh;Z&R(+{i-_J)cGtOl zXO;1kipMB-uaIH|m%&Xnk8VuEBD6RvTWUfn9CnM|yJ+Q%S9HQNz$;{~uvSmHzY>fDNk^Oy^uNrZsz-#0iL)?mfa}Lc$WVt=BHTI#*24-4(1SB!z1}W%ou1ASsWa8-ncpOB|{!E;B~mZe?-kl=jOyDOkg|fmb}J? zg)BsYbVqZL_~={$2A!$|3n?UVHWK3p`QElrF3eZyZxcP=uu_VrsvUxGImF!~XNi&@ zl`qQW$9~`~*t0WXC8vQs6&sIQIx~SBl zNFQO3b0?oVcdHy2j-U#MW;us8CYA+j;le8!>R+uf=H!Lr$gI1=hH6z0_ZPO;4LGa$oV0@<~2gUDk-ow0cB* zNfEOeE+^;KKtn657}cY7alr&N;>AbSAKk}Pouy*kkbA#2vR7sHM*GmEv1Y$Q6+%o@ zNo`SwU6NqiI}~*#_C1Yaz8A3E%}zP(=whssRnY1adgGMdlF(sjv`_i@wdJ$fkGtF) z9%9Vh-o9=NL%O(CmqbIh9FaiG53q<_p~OjWgv4Ij2j^*JROcw0AjlNP8B1unrG~^S zIL^a4L=e#(q(Qds04){mgsBuupU}8!yign-HHP1(X31K;q9}dbTyiAVQ`yzNRa2ve za%*1t{h=QHIloVsroC%?b@f>E6lF+84N};Oq%W_TjN1_LLn9&u)S_Ked`+nh>$73( zFPFbLxExtuH+t;f597SGyQF@*AVD(!`7uKRc1k#D4gsUKe%9eKF1K}PT17^X`sU1< zMxrtfU!?J-pc9+rd%?)n{)DQ57~J^WGr>pwTc6GZ6&}OjF1(})Xo@qLsVW-hA4*&j z!rQY%mqS&2%Ae#TyMrEw=VgR$18@Er>oy(bvRa~>=1W5;`;ZXVMdBiNo`@7ozd|5Y ze&hLGSua@I%^Ue`)2JrOvfPT!V8mdXe{fQir+i+W3r2oOlQVvi(>FNEVWr$xi9dPM z;-A5oaag)PO{g+4_aBWuEzIo-T17R9G}eKRu}eIh$~h35bwQXk-soTw>!s7ed@o} zCsMs-PCk3P)^Us#K*40md-e3Yp;98eu(I};0!63oSlwQi@D`^YLa3$8Wrc1T#$$NQ z$re?_KJ@yai)$C+@ONqz%(zpexH!o_ua0&*j^*QzTD?t|PaLi$^#Sz z^fdc)%+_b_ipRnp=X>5KJ?DexLtQYES~>HZqsTDO)(eZn5F7ARyxq7*+_ZD!dpqi; z)w0r7xgr=n{@@v{*~DJ)CtF8SMV)B!WwU*)tJf|&1J7KZEcpkfSNL(@%oKxDrPRdo ztG#J3J^OX7ZBQ%zADZsLJI?0q1Ng?aZQC{)n~lxJYHZs^;|7gw+i7gu*1LUv=luuv z+`DJy-nnM3?`K#?WMP_pCv9KlT5gO-yU54hvx2^-#GZ2SAh`X|GG3~>&O-0LZlA;9 zTCHbevtGHDO+&IX@c#QI5WLW6Ds2Ak!hGQ1>qEou)AabW*z=_p>)90V1*}A4pYGnq zYOecPZg7)j)DE|cb#)jyZn`%*uV?`Dep{O zLsw>I67ToCJ)r2Sc+LJMU0Oh*q-bZZm=CRlA8My#)GcM;FIQ%;71F{!QEkw{&3FXG zWS$V~9sR-Qz!ZfTlq_zYEb0sgguA)#ye>lruf>+bRMf#`FS z?hY2xk<0jW?H=ii-l&>t*UVcE)f}fjXEPh^&Aq#m?VjoT zdW`#X!oF_Rnzrow-P+KN=hyf4AsKjs8t1f!*>^DW!RAKi$I$p5p?es6n+f9Yhs_$d zgTEwmx1kB21#cTE5;Zs(zDt*6b>HkzfdI=p3Vgk*_pVh5<6pK|U`NF;n*X0r1Tsm$ z9ODQIH87ORLk4wwCB&Wocti+2T4zqrOoy5O^h}ocP(N#VIZhavM16qMxBFgZOl6-q zz59%7?2XJY+ku><^<$bJEEKtA*bw>Z-HO`%R0IOirc$GJS7PSQKD%G7P{s0>n zfQPIkzS1^2<_3rRz26#>T%^A*$rP4KA!cWfuH zgfBcF$KdY;4*z?f9)BIGL(6R_*7-mJr&;gHHk;bSpl0PhmQz#7e^iEKk%%k)$HtIm z#YGMe=~Q`_AVO^P%3F^35BA<@;Hey~{7Y}57nBFH1Zf+&Cl#i}5UOctPCQT)Kor1W z3Kq~cF(WoI4oL6IFqW+@dMd_>6cc-1%OWMnl6d$&9BIL9L#}a>wq!ZafswMNii(Os zSg$c~L|9hE_}HaGK#K72#qgp04Hb`Tk}ts)q*Db{U^(^cIRNBsumt=z82oVO$!o^0 zyRv9;eslDPQ%Sapj^vApm$R}S9mXZ7;C^b?ldUa682G7xOoZo`Aw25>Ti-n|cOa1xk7-g!9t z%DO^}tI1q;NUjS7gF<(SiX~`b1Wr&1XB97w*ZqCFu}?kVf?9{2Ma(Ogcy-Givf|90 zqIS!@yhnuZ^DXpm_VN)T`=eYnm39fStZh(Ew(fMtR20T$sUa1P|C99wW@mG&&{eH4 zI0Ubq-uVdu47?PyhR&$AkLIqW`>ST7S`Ci{kfb^Q$8LxrXlRI4zlqJ~=VD(3rr?={5Uyr1c3pTrvCDebZW56i?$RA=bip&Lx#>c5_-kKFx4@Y(< zTi{k?%BXpDB{J^O)L%v)-;L!qMA}}z!OVF%K9*t5Lf6S#?T@FO7N>&J1`9544%#47 z#rE(T3gjinQg?x$HkF?s87BSTuO?5&4_|~2E`u0zJ@#YYb)G19$;sZH%Ct$K{&qJ( zV#=%Jd~taU1)JOu5_rr0rLxLWB=}7uXiS7#zL*X6OnQqPQW;A{hjCtSGc(|z zM{co`AeiYpCryO{)aduFy)^^-hu|M1mV~~Jqkbpw-vzJh27*k1#uc}R0`MGKzU(4> zp%k$eVm^=x)2TLOiWz3VD0U(~O*?hs$(@npA6aBvb5lLT+iy}qpW+k|&{K_41X;8t zoicYaUG(eC?VACV9UDB95ncR?NN)SO$oKpoHWijj#5YTpBQ9|CD7L3= zrS+blFctgPVZ+ykkzh!36f3b;l-irB3GoV6u$=7fk0kqhI;oY;3?^s(jDNV^J~tz9EaE)ul4$(l~}CfIu=Yl4z1= zpmvXC%!{v)Jzf1Ceo-W{G~4qzD26Cmx}=2?5*@2I32@Q>MYp9m|JuUZ!FuY{(HOTW z*=6IRUWyoDpC&LM-IAY;Z;EvK;+T;5;8;X~xZY;tgC+@mRCcE^G&y$ z?lEUBzApByI2JRN<4xD(q8Y)1?ehA!aLdT%jkBml%Rzl@oo>KDr5YoW>qC<1q$NFj!)!^O+zIRzF>8-(x`-@KoA)~f!I7~la)7xLNVb_)a6ybEEP zX3a=$7#%$v*-aXUmj><3(foN&R~HgZoeERQx^PJ-x{9^ONmo4!W7{}fGcBOQMt;v8L@yK(L+4k=o5-k=+~8W+CkM4Jq*9pSg5u!%%ie3nWCiB8Vl5vE69q8a5y+lIMg8OKp4@)usKuInl~R(NoFnv zXG>s-ewM)X)DV9Ag~$njQPVjF`iRC#`qC{UKcfR@KmV$OCX|6GoncV24*m3i`S)(j zfkIl>wjfn@42;q7+Ue86n#3n6h%rLEAeKlpumi!JTktTkxqgdglZ>ykWJAwV`g zxDyt`im9MBmhnc>SKG_24O( zs2_IP0&Xl@QD)Gt=Oh^yrP}fp z>wDJ&bZ3ay7GvB+5NIWZDseJ!RJ3clMi`!+-ou`vzo&{YSa*prU6Y&-k^k_|9R~Tk zSX@k?jW;7y!e8Ac==;$gdN#0yk!ump`VALb`9^yx6g|Hz&$QlcDmy7Y%L+c#VDQ!l z?bPos!8?)h8%y)RKT~RF0iL*bR>P&{MqMz#1c1*vQA#HGCa$MdI?h%~iJ3Ohj?*P0 zs7X>-IndPZgP05CF8c~xCw==olo1p7olz)$y;oYMH_-S^RlLf^2!B=2{S2`S>0e7n z%Gt_?7y#k#80OjX<{Iv=z(rd8`nxKWPt;k2WyNqwTjlZMbH&PPm*2#9oS_(pybqEP z8WidUr+CzL9*>`Y>$-+(II8tWo`S1%oOXYT1|BBA#~xDK>-&lcab(gT{FNRfPP{!W zgZm($9O`u`3f|t-ypwH&ki;fz)R?b*kB^hJ&Bc=S#(` zuDgCweLnV_n=3xweMJ7W)*vX`PP7bqu#T^d(t57;8K~5Mtdjw=$ho{{&bq^ zq~MhaMk7kqhkR`ChgpYW!4@~0>F%exs83NIME_jjIJbJWT-&ElO#{h%iGmCh2^e(4 zU~zj^=oYo;U8$FVGY|*dPim)I4ayRx==m28FbNHDjfC6(l5a4o?N>adidM7TMs5bu zd;Jv%Kt838iUNVMvy3PEH?pIR`6De#+)A}JDErl$8Yzyy%(RglWSp>P!rz5#t7qogMi*3r_C_6tDL+}kGep_YMzbckWP@#R2 z3BUFhVa>*aEH_JNBW*Fb6{IR;4dP91m^4bJ2vBIP+Yq9hEDKa6@6vM|xbupY3|!zV zeguKWBs%dQ420(EL9rx;uW!En&(TZoB<%K6RP&g>%{uS`=8s%Xzvs%|bEN(wOjZ9O zwZPu`BJmci92P-dp~#KkL`tr#G+KJV&?jV_GA~=e2MBespw2e(Z+GU?Hx*1?`#W}b zV~Cy>Ec8P&nfaFe-Vvnp0X8Rnh;xZj>Uia*uLA3=+ax`=CtBuX07zeENSD)fLxzvMpEUrKGlt7WobK zWnjUf$0^xY(J{2eiHc`#E}Y8?DY(V-GE~TKS&vD4c{r;U_|iPY$UU1*2YQvs%DqV~ zk_{&g_PUABg$m=Ls9!;l1_hL#-@|Zwwu3AVj5m%FV@No=Y&qGXUwAT5raV-u?z92p z56Jv8PIpwPUsJ-SnfL!BH%NKEV4TF}e5`o_z3emPvdC19sTOm()-s&W3g% zsx?Y*E_T&yB<{0EZ3OapwGI1Zn4uQKKJ_7xVh2#W7~U;*`r^;&k{TJVbHR{JV;Nol zQ$G+fcs3`k_+xKzxu86sbI5lSMIu!N=a1GXFxz8|T8ke`Y?g5d9@595O>^u)YFU2v3j%-=yn~SK+z*z{^oiaW zJ~ep(wNW{x$OXmHrm&$Rxs}3nfOh}L=_|4!RvQsF};DV;9Sis zzArr%J14M-C?J#M$VUx025vZzDMsm2z9DwZHG`WSWMS@BDPsSrZ-wD zA524CKvM;+f+c8hRvn79`&b{=%M^3#FeVnI^3Tgw{HQYr4_Q7Mrm3n`tHO3J6LK1i zh`T%ako1ny;(6`dIMBTKZBBXfpMnWAX_*(+Gejn8xe#%##bx!EYEjbTw?h85YHaT+ z{kk8bCjMLUO?FfY3})~R#LL2M%SHP0L+xsG9J@&2S4_gb{y^n+*)LCtfHhHQ?M3iT z=P8qPMiO`X8M}ULv6Et&DXM?N-qP3?vPvVxj;fI67A@vu*eUeXC+6!A(LQm`x-O6s z0qzD!SG&*Ga6Ao`RHb$>INrA{r&hBx)wtiX$Xo$ww83ri_z@{_2;gS>kx}rIyRB6RD-25)el5$6fz;Y&&mX zzoD_}L6QM!nCw{Q^B|*>!jId`+KZ?GySEK^x zJq@~rzsq{|UQaO?%_#n+?6Ix|{)Rt{_SWb|I#JtjRyO}sE~bkM_~MY?xsoLY6hink zB++j}f2tFslNn>W*AZ;icgz1M$d+=Z$d9TzArsPVIbYHrkQ{|ODcubYPQF$_MPBO|$$}fhEKAU47 zf6@I*UG~@Uvk8^Uum&D>7}JsXv7=NbU0_W9!WXfM;1?iTm$Co#(!0eyv zyU*rU_Px`EDb%{TnQK=yk+%U+6z7!8=J<}ZLM=Q)JC&sDE7(K7FtWwIKIJ&rngYz< z{Qao*=w;yOU;h4|aV9GO9H)w0?;hIvAer7XJi>h8SJ2MaI;GEhs z3I&y9z}d;D_K!2+)`J@@k(w|1YfIq3LyxnuX$1_mufU!!c?|1{tE8lhVWN zL|%#~j6#&sWKcnRwWw5I>i;Cp#h;upr8DgTYw~{xIuK$ryklqG)LfJ17cQKl=>F&NY)+^iBhp9e^H-Ky zTLBogJgheQA$RMaX%Od4p7u&$4*zVwU+^(TbkmqKyU_Oh7#_QGFUHLDn`&*z_`7?N zG2q{fDcFpTtKx$PQ(>aM+{Q8YG`MR*7G{CQcJVwAU`V=oWQrR(@=nQC` zn_`C(>(ajiYi;2A0DCNPZ`}>$v3U5S6YJSFzDXhK{t_N(0@1C1+th5)541skhqAUe zApJb*R49|FDya%66nrJTIfZ@&ZzvzLfD*-@c`NqsCp*o-%F5r%XN-MQT|piVXm)xn-C2S6rq3avVvP zs2XEJ`cl#z%ug2vsw)5PkYLThygZpY+lS4RwML?!eAW$$s(kMlgR8|3bkf*dTT6~k zs?XUpqx(}p2vo`SK&-@IZ|+6wxec$5d4%}m#72xm{n6xp+d7aQ{OOlj5%wA{H?_)%#vP$ZxL#ZDrDSfZs}GBfJwk~v(9&wXGP|0&7u53d@C)wmoi64c zF?cDWT#O+$7y46ByLbKQu$8&)0Hk#5?*tt5$ReCEF0gtjJG`p}MS59R9!c5QPVkT5 zoX@Ax(Vgb}G9o(rR~?`#N+}D7C|_@>iP~w0WJr>3fbQ(rnCU~qrIySn%jb;)rPzyA zcjzw?S2+%{+l>|@*n^C_zN}x6R|skk28LW48QeUH`11)CD*24(U6JK*xE1b&Jlj4a z0lggFMZFPK)Gy$Hh31N>5`$Co2Gx1EsZ66sijs8bgJ$%Vwzls;5!1z~TXJYdaf&$2 zv?}lG!k;TVfj|}cOZ!K3MkSS?0pR!tDj{;E+Ry7V)T9~4su#QQ=y_KXSHDJCy)YOY zd7TU^CKz#jfjF38joii`=I@NP5z~YM5A39DWEH}<6I&MGF|;I{G1>}LGtYf2P+q(O zp~@kw-kr%TuXC5WOIl52ieEn)qT{9D;}m#WZR&)B41Vm(B#|PE@QVWxiS$;bh*}FD z7t61wE}}5o#bQ)}17GY%!n_d$tDWdyojh@b!S4uOXb%4-QT;QO%xL5sCLggr>k!{CD- z^STcWul*zvX_NU`jDfSTPz4GN!Y&6Kvs~l{Ah3vQ<;EfS=8SB+FeDbCoTIt(BVc3^ zmIod~LZ6wFI<0hj&*=N4O3|#D;yt#I)gLk1Fc{cbQCD?g5fyQpun_9dL79I{0dO=S zL*Hl%Mx|MuIVf?{>o>!uTVKPCfln$Fy0wPElS1uc!VHc#!}tsPGDb#^G> z5fg<1>?eJAkK2HsZrF1|_6{liECS*6ZM^en+$x*6XxI`5cn z-Oj9J{6YY?_5d&{VT<5-U2>5A>b8P@Ec)HL{aARNk<|Pg`bGRZ@NfMN$CW`^#0K#u9n>vfbUWzNeDtT*PP5pLxyBCHiu4aR7od|53q!q}do6*Z~DPUFr2e}g} z877R(+2t1=A7`40LDb^%Nlc`HG31if9cSPAlS4_LKV}fwsS;f-UiW1%LLYXkcY$N3 zQaVQ@6*_y7ZZKmi4Em7@w8nR`92qcB!uMRNq0(AHrER4CcD3uqD{v+-qFg95Q*!y? ztQA)%SM&T1oC_=FkGC2TMs%77Bm~@YoqFF&3GctgPQ9aiw2OS5UoaHH+&Y&s=o9Gv zqZvN>&0C;YFL8wCMTOEV26OE!NYf0F+Bt17W8}wh^C?Tmmb=xwQ;?ziql$`+;;|bC z@hahI=?h(d$ose`O292+60Kj}T0y}s0Sm8J_49&$Po1IXM;31`W>&`I`M*L7F1grJ z7zi%g2`BZG0!O6AqCkc0YJYy|W;RYND87h1L)+Bm!(w$;1PMpQ(I#}7y|~@h;^2az zb>Wl1j(68~$N?`^kfCf(|BnSD&=|z^e!0-Rx(NJK(O||!b=_kWtrR<|LwvVwOj?DUVD) zEcuP-V=p;^Z%(-auf?I0yXu5He&k?R^i_Vi{v2ECNi?+Ps65xg%eC!r1xHO?dd==8 z7yhx{xnyHV4*|z!_RS6R+_G4-?tKQ-l&|9JJo5y3@{*Ouy-QYz;{;)}_c0N&vl|3`b{+)<{v{qvzA|?CI2Q8*E%#Dyw4<=h)oJghy_q}lz zO__4ouO+0!z#_Bi)wzQiM3S!!s?%7+C?)j%2kt%Evi%c zEE=TiDBZU$Fiz-G>Q)nTO}sy|%HK;@P~CXx{c7CSHuD!TPkg)uFW9P&A;*>$0KmN} zr!hVr>bBF)rHo+yil}7V6SrQFLEeP+3y;7MnO~sYWkkJsCfp8CS%anoc^~w%+>fto z1to`Xe-0|PE2IzreQo9cl=MnT!6$7`q{wX zW5u6zQN$#pp>j>u?wN%7z#^D>klT=QU2QCqdYoSVHl}XFyg{O{e!AOk(%&4|aYBj^ zDhdv6Rv0l8>u45=@vpv9xMf&_@lYyAq|_Xd{?X( zQpO=mvcAdu??(qd--kvklPzHZD2^J4@71ABTWX{}o^!Ok$0@&V*G&D5@s3u5_1gUN zqNxWZ(x+B^H9|n%E8#^2DJ{Ohf;0a%@DexQfMrrxcb+Z4aDAaaXo2M`3S_K{2tjB7 zBAHi(!-k2Fj+eUyOh5qNIP*0j545vO)UJaRC8z=r$0P4g#vQQh_Fl`6Pl2&GPL3=) zL9BIR?Z4>Rn5wj~_DVOxJi`AG#r3N?T~ zY_(F6IAm@|-1Z3BZRi7wZ7HBfFdq1(@mpZ8;lz{#<0gXVMa@ub)qg=_E0F$TT1#(` zm!Lo;zlz!{`*hEi?TI6VyyBx+sGlM;=&^|-*n~jrER9TuzU>X|8jY>hIh0-t>d>jf z9|4giz13*mG5xp$0M>q2$2N95q?{(Tx>U^*elLVW|74g;YAkWOQ?h--bq>}`)Y=6- z{ypv3DXM|=LMJ5nHXKU^L&G*WqUU+|+^~a@zB3uTVIjU7M~vrkLWB&PX^e2Jx!8}Y zCy{@#YvT%C^*MK)Z)c6ggI_3BrP0FcefVd?DpS$vv-%qIZ#YDF0`xZ!JI^FR)bSDn z0i-*j?0HZ<`cEGXrBUN|CbCq*NF`zshl;7P3a*vgh3|~4!z5imUT~yO)hQjFcEgp(6kH_EEX%__T)ZT zD@Ln@c7INr^mw^-_n+<`SO4^hNW&u|nGN8R2944jxF&}$&q0x9QS8`Y5*b8z)Cjp; zqmpZz4gD(`J!6%Tl1gdmMY&GRYCJwt?FmbdBw|#iweRW7k?m8~ zO#*mHf4jROPB@R)WsDp;F}*@}_$%-G5Fw;APQ<8-P$b=I?rfRd;145@5+WY%$6bSk za5YjSLB7Z!VV7~-jAEI8VzX9HLda&yxwo2B(@WKs|MDZI1GA2!NGf4{50ZXYBpg5< z43a-F^MOm)l<+n}_*&4HO{G07^Ty_=5Vf@&jFfn}fxcud(av#5jy8bzZ5xqmKp~Je zC3k&pXlLs_`%5_!MygXUqKciW$`qf_2cF4FL1(W0fPQ+dCgu;Vx4r{p8*yQ!7g;P5 zw=c3Xxc7$T$R+&f&7s<~znZ4+kS*z7@$E-ei8#F{CN-&*WCHwAG!l965{Z(r!pSUf zJ@Xr1$YC2sw_Ns58Ff|A;I{yJIp){&>&S*hO$X?vv1yDfJGnD5#Ah?GCH{U99I>Oo z27wNPb# z_juAwpEy$dlIVRgVfY@nB^8LrUSC~;lQZENeqmyjXoC+N@dLz|wMNN_bFy3*5HGeJ zVNN}{!|c-M=M6X}FX{TR${AT5w>wUS%k=LXM#0)|kSAD>>4jvW9w!zpIXoLxg>EbWHOWEH5P z$N9R5&9M5j+`1g~Z=OeW&w>_?zgyL#Y!r<(Nt5Z$79QDMuR8|36jHhqRlkcY(2aqu zsIeEwp466ikTx9}qK7|^;b&5H9Xxuca8BWDw?Tk>w&Bc}3zFyD_%7(wizH;2c67-z zXWhh)*u}65HM1Ki1Lpx)nrKcL0NNKTm&uL$o74g6ND%1UGxDX5r+?$^9^<23U4sd- z#vsN-Ux1gqGzLY5T}CI^{DbbKv^=Zr{7N`H{)E3u5twaw82;Ko>Z!4(T)11!tk#G( zI6X2RS!j)e}9E= zg-eWbEx^x+(N^1GuI?UW6$$K0OhXlk)k4zbAcq`CV%wdW)8h1Kmy1Sr1T!&Q2p!LkZV(zNZ zJUrl%7{H%fY#rlIju>#-kJ9C5l3Sq!f_mp66d+aGx&bt~3LnpnE3Z>}15uTh>gm%+ zFz`tx`*`P@?SCVe;MtB zt~yiZA)_!kp=cIWglCMF(-v^{qwcP>bYbTWH!)jk>*m*jD2wfMZ`_x85zmnTT{g#Z zHUNY|X&BTM53gkaWpu<$@o~Uxmy4y$iZbe)m9QA~jkob9oSw==Q&z&aZJtU}HYf1P z$69pG%SkbDxPh{Sk9H3F`0z~Jmapl8!6$R1vw~q+1ki&ApH;;}{OpHNt=oc6QBwWm z$x3Gzh}R<_h%X0S#cjKeE;F7sq;PBLTcOP0So4WgvSZA#Wqs_JvaR0e&6JT~*jSlB zWO0-h8bczK&QC$9CT29>X+KD6 za!+%%-;SVA*@ychn5MC!7$e~;AzIKw(KD)ghul-c@p806FTFme7?4b0;|~0_UCeV5 z+iBXo!y{lCDC>sr#%sPsxzAtHrQ-q&r!KHOya($)eum>(CYvr(OSDlu|0=vv3=h!m z#l{)z{F9xYW4B)}pZb`FUb5o)0GHCy_5d2G+p>;X8&-v)EKX8xgF+aZUQpxT@3z~X zFS7urfE5h93HO@IECt%%F7~6f4K-M9C>^h(XvP>KCJaqrzkVysA;viHiPQXyUt#2! zX-r6`w-15q*L;$+4Vs}Zp9r3O#c^>=!4m^MdDQwoY#gpBnxZ0?Y!T9qUJ8?0#D`?lL zc9Jc%4grYMTJHA>*eXt0y~A+A6X&mHr`4xhyb|gi75D+yZOOrxWv=4;O14DzBNDfd ztDM>?Xztysv8u$dC3EL?s?#jwFNpB~xE3pzTiWf<+LLHu=bOH2eJR&eX)OPG{-ENa za(U!j2L`b8w}-qXvX{N)s1+syP?qW;eHbsN7+xMABW9mv3*csSY`d3WATzEq;4FK{)e?vuNrO5~WMZ`S*iJ?_W*m?o1Qh z!tzfxoe~a+7W+MT2a-{{ z;m;FEt5~=V^c~$IYm~4YdR)lN4yPnAGi{7TiNw+g7G_rBlzB%}l3fC_*8RrBJY9~$ zyy8Z6iO_QS$rWQ@yotZx7T3;nQwln#`*17X&c#)R?FPWcda$fEfP>a7*5^2{3*fBwMza@oUBq<1j>Zn>;7HA`AY-H2_9x;AIi;F|6 zoB3^}`oi}j`6n5&&>T^c%LS(9W`fq>?Kdje*y9|ZncJa5%a84l(MdLpGuEh$DMT`F zpo^RzJiVzE-y6R%hmZrc`o&0>bt@yM&JUFm$Q)c;RAD3b4dWXEq%6e-FSY{i!Bd@y zp}{x3qsl)AV|}|iAb*x~r=+djox$xXWu*ExvmBVo)In5{b}XnPTCwrpO6KeXBj; zmBM_ikv>I6BEjfGBeYA>aZ}`&7VtL$RXv~lOA7PH=H*wO+w0l-A=9dnEl8pB&$sI3 zQw9kWZNdX2FvX^ERmN_+7^gZ%It8|{NU)1g=Y=*}x{E(4_@Ewj{a$O9^8mtM;+l%~ z15n(gJbb(TfChlh#mcs$9p1&5ZMNRT3*9*UcrNMNN{S!%;rLp zM8m4+GE0SsnZV7iS`*5JQXc-4gI{Y+)CLDYg-@wL*>Zf7TR~kx1GE{+|G{r0={`KF zWn`$oa);K_-lq4icL%@ob7L>$=IsPq35%eO$ZO}CJ6uvh+sH7i$3KxmR=NCaQ^20ypvoRcLs1ubUYCN0NEb)xhEq|SQsE0&!fkzJV~bq z%8C-I6*F`y&csH_Jp6@MA4BEbrUG8oX#<1Th4UhMgJhPz!Ez1_=OA9iF zS1j|xDT^irH@GZsbux#~ZfX>G(11tfj}ETzw+>uZu>viSqplsGQ(^tk0aov(O~qn> zMOrt0XHTewM%}n~1IuZzqkEsK6U$!bFGOWnF7h+*C{WT=+jSxZwr6B`OuHLe)7B|0 z+_Np&x4O_+jVl)32On!a(s@045}#=pF;J!6BTKzLMpG%xW-5;vC9#i`JfGbGFFp?5 zBR+sIJ;$`dzeKk_WIi%{EneTy3N=|nz+VzVW2O1b?p_nh_DSpSwY{|RfP_V5&3-=x z-;dw?MAI4H^7F@#VK?7V`YBE2l)U&Re-ObCGx@kS?;0i9uf>Ch3S$~?3jv_YDG=mL zY_mm&cpNK1Tm~-6z-p!XLGmt^UkO$A(rNqTK6rtzZ0ESs7(W(_;G%pGQhr;SgCBiP zREqoYdxP?7v>I?Gr3NE78Ob1$p7D&Pv&8=lw-t@Gi#R3%uf|WC)lJ2GpH8WD$0^UjmPdY(_6G{)nxcw! z8+)PBo&Jz+f*4OdHxPRW)|ITcX_Zc0Wn`bU<$cU76SpP!l%L+(Cv=u)aO1%Zhu>&} zf@>));O-W$3Lm}Q7a=K&iz z4B=IW!lo{&ML7%-z{yv!V|~%Emh$94PtqMY0=k$)x zxZ|^m8QwghT)xb?kB@7KT*%HaJeuV)6hKh09<7jzRg=q6^N(mc;n`#A%rxjW>7(!C zzYle*>xq8pne|q5D~Bsym=R$y^7SxR48rE}QTm%$)v1Ux`cJz}UUse#m?M|TWS^1E zL?GBu1u*6^=X@=TvV`QbB{_R2DS zyG6rc*@_ot_?-J&Fv}xK3;<^WO~FD|L|h{wBMsO88%dKc$P{?)kPuUkUhWYkKn{Qu z#$NhyH^q>z!1~fj(_P%vKFfGsxiz^Uru8R5i`ygLkqM;5obnPbcS^&~`yRD1 zK%Jv}mOn6MlAY|xnhc{t@`AqqXQ?2BCG9uSw7-w*&O+4P8j&e~^a^x)tLIzzUyw6% z;%ip=)u^pZerKN5ad!jY*SMv6NYjgpF?3?bhf9s6F;sgqQbPq9Ker~x>iE<~8r`uDJYQe8pbt1N;XXGi6%ZPi zb0iC={lr&2A-i_0zac+60FW~^ga6>0vGak!Ie93{#cXGcwi_Y0>-eyoJQydgDdQd@ z1(*|zjc6bRvF#2QcPeFt zBdW>Tu)_1Cgxz@_%dt1@HlUa_Qb`@>3Qr2~XBp>M)m{8OH}68L$a(i5rw0$Xbz9A^ z-Y5Ega#>N#5!$L`Biol@ltf$@9v=#Z?U~3VEKQz?pmJAi{nG>^CK@`HSS>Q|iXXMq zT^L!9>u{q6H2P9dopqkq0r%@;e1i}`SxCEmLd80W#zGz=+^(w(VhRY+`MnE(Tdk2} zhed|CQOtW~EfrR7K7?syRzqEuo|-CDY=OdsQ`u`=!7qpolW#;V!j{#h5}N`^uz2IN zO~|50pNSiY9nCyixI?rv2GK|T4XvD_6DiHPmF+(l9%)x>W^0B2O7Z)$KlQ}9x*$H$ z0N(7*iBiiQUG=BN zPQMu*E*d&wDN9qt_gB%oQEV?6eg!~!McMB=s&0$g>tDJN1%VOEm<<*kbgrv|zq?RNIZ`fJCN41ik%+g@E!g@VTgwkaGe`xP z&!@Md5{B+~gU+!lAU(eQ$pV1=-NGjWB8^0{voQnuT^nEp8{{R~_BI3eob7SKQq0HH zt1dzmJqr&e))>j2M;kt`tfHwkEQO3w?Kx?F~)?I@e+a_e`!W?V%Kbym4rH4&L8WMqe=HXEM72~3f2uaJfdy303#;pm z0_-?dKQ+}N{F->GPPfZZldW8V_^yC6OZP#MtBhUn69TtA@A|C~Uoe;Q?7V5yUBZOL z_Hg`$WJm`-vMv|R5_;(LEtPNYWQr$P!7u{vgZWm;LJs;RWf?ui?fKX=odBj{M%a7}1b7Q1cWNJa+dD`f&Pyq^W@`F3X`1wO{KNOE>7Z>|z$49c zL5}XobSCez?@7=gJe17-5)MEo)_T-yCqd(^Qkc3{gjRppD5G(8neV_t$vcpCwJbC^ zR~)y>o{-W8H{vEG%t1J-Djx!ZClOInbhpy`lR`XsvF`_KM!a1Z(P|SMOh*z1v3Vkf zp@VXUP(Z-1028oThlsww(wVK2Zq+K9BJ>;-Z=TvSj7fU%T`yN|mwGL0IuD)L zdCE0_71QIc&6#-0vnoIaw0|T_Yi>~kOrse^B5u70k~0+Wql{H0MMdbT22W}^;(jgz z490|+7Ky|~i`G%kg62e9?)(AZIC3GtEQQk!Qo2I~3Z(!vU`&*zckKuHJ6Mh6q{WVI z1%wn|3+y&$k6e85gGLBQA%mhj2Xe~^ES(n-E4nuafyAGqZ;WD z*m&tlHB=F25AtDg9REC$z6g;GVo_=^si7DDpsz-$&=-!-LI#X{p5t0Xha{RDv<`rA z9Gckd>K*0opRa%TMM(G_I>>)aiglp*ZJf|@Ww zVwf+BcW1AHMDsqb6|JjURD6RI6;u&q%|oSZM71({xs{V`vz|Q$fQa7e%03zvdL5F5 zL%C7{0O(R^Wa$nPQoLTNIuczIP2!Y&G_7b`P~DF2k?OtvfT#e!MVu$4Wo2x2zFc40mPRC|K0J~3 znAJkCBhRiQxlELCu_a3hm^)_6Jy`Qo1MuHL(3qtyN5@ckv)M|2a%55$O5@`YBs~;p zaRU5B5Pb9^u*y#_`U(RS5;pJ>aX|+R5+i>H9W$&B$KehOK%Ze#qF|jBcssXjsil{l zh^>+>iUkF+poTSS9UYkqXQH=7qdBDbb9XTXvA3I6?Z#i0>LzP_mF=i&VwWjt{h(B9 z#t^EuJy27sn5_=}^etEZEP;lKvw9t}IV3UJ_-5czh|ZGMnUboA?99L_04}#77nG=E zYA?f_2r1X8bR%P>>zUrCKKra3ztYgE969dq-&c@Vw~7pS9A>O_=l+uB8%9Tel{6EE zR%#bobtYTXcfs1|0c+KFPqGA=Q!=d@gDePU2iJgF2Z6~LYte`~tb6Axf-A?j93C%Q z^#UC1>E*#1Fu1SHTgf9q{Ji3@9d4Puw=7mc)99v?s|J;V!F8w_(Zj+?v=btlZ6%t- zt5RJuSG3C(oCB(<$ZdINlbv8}RV?T)NNZpN1@oUV6|~lI8(raE z#FhbJD%H7NVs@Jqr_ zB6*BKg9h%lS?|1p0@G8TR<#`%$OFXcL5LL+8gyGyNrZ+0|OjcDUa;u>BNH2m@Lb4RVw@Fk+Hc_A>G!KtQ{LH?Z#JB{K zg9|H2>1|8*;cc+h;l3=s;f$r13l%R|^6!Rc$$621zjTv^cqj}9J@f6Ywp(8}un=x< zy%qt)XgYzZ5$j3BEccUnT)usLbAl=u6R6qV^6I13i{j!ZOM z2C(2oibXGKvZbZ-`7S2hi+b^GkGr|UN_74m_&)$mK(fD)zp=GY8JO+35FlDN!NzWY zGlIc_HqDeEghYjkk?lF0;G#2RxJ(aUl+iD`i9*}y{s<5HQa3ldAr1!i8J?Kk&bb5y zW%DEe52$ahUGV8Xa3J&0p&;JsfgTkBCT>8!dl;+=B>Bz(_!1f58j=SQ#aQq0tmKFS za0vBYeRfS1fV&R6Qh_1#widq7A4^W&7xz>HIymOG! zwBhTMulW?Z?VcXj6K{iKzPKAUUie!8M8Fd1)u@2Hby}`=8`iz?4yfWyviLwEhr&p1 zZSoXIPgxHh)XS9y^N|yRbJT&jTv|4gQPvMWaxA&u&`h={15OpBFWLK5!jXCFh^(cB zU@D!waT9`@vGzrmOa}_P`$l9<+GM6 zhG|?Of~-VI41DW-_3^NC(6ktdBgwD;6b}qmyEG5KqW&pCQ;OP>P0aKoc|ov2cuN{pio*8MkuacVN2>#p zo2lt)>acOm#c-hVLF8%mAXib;ZWH+$Atj{pnpmxLr+ z+(H?2G{oQ5H&p{kQQ`}NvF5Bn*l9LIbg2P20ItIzKY##4FB&Taz=UBmrnTitQEC^fbm1q6=vuQR;Lif5>dsycSImhCAv;!C>`;E|u0 zMPk4-WN70Kts>33#3HR!fiZ4qFu7m=nlvgv)S5kJC}&S&0&f3qgp!&e7Ru!Vtmny` z%9t^=ZnVocf@pLJm|QYsLxjMw1Z6$DMZ| zT=(q>pZ)Bs0=?Q{3!QO~VDSxL0G){F8F^A@h!|?Qq5uE_lhSW&5@P`ted6B4 z005PNe&_%ci4u4K02r-t4OZc?5~vJNz|1DNvM5nZfg8LeyLx8rs!(t00zLEV(&;2NywI<$jBa;G62E^uAp-%Jxk=w{bnlGXj@~w_KBGy8$FM@ksEm4 zpL>hYKYmGTOL^Y|`4_BugQTAz1-=bs6mjDCMZE~V$!(q=^O1+26wKCLO#Gw*0Pd=~ zwK>$E2`~BeE;B6Ti1w?+gu9=DEunkAF`qT-%ZFON^yU61Y ztB*3>sRFuh{0jVGExP~;!9imnEypqPpj?8r+^~3;e__}ICr8Lc0Lec3*C+k$X z?NN46gU2oukfv0+iBeODc6M+84#xmZ%v59>Df|$#fcaO&D0rF1RA)(e*h-88vA_$) zt)B&>k5f^Fl!uNa07({D2HH=@DFrx0{L_}Rq#IlCNv78{?6yD`Dh5#i{Q#MP<8Q^o zwfRZcl_;dc4o-H>XjSQm1H64qWw33ywXi&Dtk8&}@}otZH!RU{DbbVG5QPC2a+-rw%$_OV%(XBldl|230?a^f(A=o4sTYARp$y=yazURdxg1<%;(;m zId?Q1)K-8Ck}5VqSCmp4d*iHVeD77W-PKlP3DBt-;TqGHRtyk%NP@E`$p|D{Z|k#e zISvaWC8+}{M0seFRzcuv!V!3_mOZp_@hG1~pzdm_zG$Q4*Z=?&*mvHhyd|CIZ}0=F z_L>s;7!UD&+-!npF4R;o+FAern5$imfq)4gx*@076ZMmvF|?qr~Sdr5m?+ zFm1=zevt{BvZ2r)o|!SA9VCp-=s|%y1~A=Dt1yCuUgBpGrO27bp!?^*JT$22n470`&H|(7vMe11yd+*XexEPQ8kMm?*^d9OI+WW z(?&R-PCOd%0;L~=&>&P!BUA@cCa@Hr1Elq)K`tHFMRiQ({n_`($n!=)DJeVFRB|fIBY3 zK$k|0;ppjsGyEZj#(Vvri*hA*JoD8gq=Or|e2MyEV1sjDkXCpBIu>VC($o88zC9nK^#0zI|${cWkv29NWc(c>JH;2eZQCks{}&FY!a8a4e6IXZm|XgduW7zFr8op7 zvO(Xm%0_WA06>2z7u_E*WX`3-vXW3lzPLX&84AG|YV2qb>@=^7vK8IFY3MhfWQlIr z$h6tFQ3K6Yc<4P0e1K*Si3Z2pT#ScLMZVc>{PZ}^z-gA}W380?Mln=D^l7*taF;%> zuzO1aT&C0j`w2_kN`bvU$3+B{f?vEgw5)gGLMH}Ct>ZK3I4k<`QmFr7hGKIr8hZ|1 zHQT|sb=B_uAE??{H!dd8p?Vg0LVk7|pA0QPhQd@Lypt)VNKxe;bO{1j*3m!!6yWbA zPrzEnOZeGJY7Edt#aPp&&ETW4W<5fer3$=4&~WjwvnE7ctG02Jf(i78oY z=1xV(KO8%mFCt{k{5M5mm<9xTLz?pMKF0IuNH1(t33L&tkO114CrZ(JjSP$vw%gdD zxQPc2kS0buN7gZUYsd-PCjdkc*NRZH0AL>pGfJ)?U&|u(+5jFBFiumFymH6}SWg!m z$VNC1M#8MI1O+gVk2aZnt*xSK?9aiEXvk=|d2UKV*=7LX6KA)E<`3MA$2Ea2G_5%e zys&i<1;Da~*3yFn*4pY08GJFydY8$pNVaTV%UBZ6W#h^GV3h9Bm*5tq)2XHAQ5`VV z)>SmM{3U!Z$3thccndaV7oi@T=xpLOfiDqc0DdOTcJnl%B!V$-5E}fNq-B9L9Y3adG;!b`7)R&G^^22= zf&g(27I0)0q(J&Em>0g53jhGNHWrAVkVrHT59$O4K^%R?=qX-V5Mt+m0CFj^g(eb^ zr}~?2SVtdNL=;A~^K1NR_4UOZR%(ZUL&oe#Bae#^nvI}<_wY> z8;}T*4Md_G4vGhHIm>sITekc2xm^&AM(IETr*Hni*DZ$!%M&cCG zic4nyabBYKostKK%f;>M?hqz695%RP!C9?hGJ2a)J;x0Wapqv|nnI-sJ|}vg@{uQu z;wkpN2Z`CK@el&Ba1AOGGIdjSNLT`E9b`w409A}&Ds3YOa>PsK#T7MlVM~y%&OoeD zYp4e`Ln2`n4?cs40aV-%GQn`get84Xi6Q}EBd^j+n&`GIt z1$Z0?c0Rgak^}A8WI%7Z;TQ?WLJv!5Knh-THO+|mfy2YqR*dAbj?dUS-9bN2BFr2@ zH#`D`Rgb}f5{=_18nPXSWQXH`oo9CM;w*fAQ543Q81yE^m6rtxVGXUwQOOXtmaj)( zU<5}))$jV7OO@@w00-?)|&tq zJAqLcCu}bGPrERl&&B{0rnrMf06Zps;6DuH0q8hHNPIA4(s*Rf}AHZ5mJT|X8P7_64Ygv^w`9m!t5IunLmfkg#PMHALIl)x=P z-s7}g>enP|JVMa$XpvHH*^CeY(Jr>%qb+5)t>vbDsVHncf-|Wh)6C|9NH{0!h1(0~ zK5e!v{kkQR{x3`opfG@Zzz)Y~gg3wePUHuH*T}C|)~v~09%j8vhWJ%?!4A00ajBce zQFl5ejIxRn2z77TmzEsC061D2jHr1dhvS*R`MMK8>|N49=d2FAg5Sejp!qr)?o>zt zsY$ha!VoE*OmZ+qQdQm^u;KNnBs%HG*iN(>1)y5)oLat)TKRw*LEgdUX+dgqC&GJ% z30)!rse;Cirl6m;=(@j&PqAdtZS$`!YQRNKtLdc6Y@7xK7FQCLf54R7I9NI*rq>w2VW3ryxa` z@oZK|0RRAd2wiU2w{$o zumUX)1ell+JyXz{ymr^IPM-sCH3sLYBSakmcnCXYLZqIbFWfaDFN#;liOYptK7!H2_BRCYiqw{==5iW>iBe!*()e+(nWSry z`!EZqJF)gKQJ-!faiwvjERcppWHfYZ=;7pM$0<-_E~WomO+-mP=F}$eM74qSR~d4@ z9E*SuEx`+@F#IsWHAOuBPXpyRO{5nc@)dhMYmyU3eOl{Lm0ZUjh2Ls1-pfl!EfH;R zzyVk4=4berhR`+zp?=lwY2fn7p~=c{BM!nDGf)7Rlg)4zG$FeSoq-Z{u;Ks!K4HwS z&b!jkrVL`Vf&c&kJ@;ZQXXRKJ;Xlj;-CyL0cV;d;2i`ymX>q(OHR8iKJ9#?h6<(0q z)psOsq=oQbk+-LEVgv{N5;2O4heFJ39v{;c73?!v3 z>f2DorImonirYMv$b#5O+U<6h>xi1Xp`6j{?h4Htkjce7xUNaRK%=frt-^~q_5-^w z!VMkzL@Q}5^Fu0;0U<+aGrxs`!%OK5dly(M5hnJfS8aTGsLsb_o6lV!!LO*gtOD6o zd3{X7B#(_^V0z1+W=#pv@!ri(A8?ZN34^e(+(&Mjo5~^yCp$Ym<|V)+zUxc)!9PhA z3%~)io^-pV(p4U~%|j^EbL2V!SelvOjWTqs$EyGcW94liMgco}!p(p)d_<5 zB@zG#uv=RLRujYvh3YV`z;HRKaw93}AkfyW%c7@Sh-}EWtiSpJ2+F)35Mf7>wwKYW zWHb!JRH55W3vJBeul92{HkH}KaMgC{Ubr~8U(o{zGXMqV1;qXv!XOl{0ptvODWtou z@c;vvp}qBN{?Uu$AON+TWW)8+-~b8d+9hpJmzEh5N3@`+y+79emAN-mU~)pwBkxp` zBA(io1>~V>;)rJ^e#ZI#D8pMzWnf|MuAYs6-bGrj`Z>Qpz8IuJ6J;AmNRQ!{Kr6UW zN!Vm!ULs{EFs~Vq>hrb9HB|E}>5L4@eBa3u7e1x$pe!5-+orAl0k!0UD$e)&A(z(4 zN%od+b)U24*m|4@S09k1u1B5yfWrVpbr~22TQoa500KdI6FRh!C`8Br0{=xej{y=4 zWVQgE?0^o}z?$l!b}~wWSOgaUo{a6^obm+GstW{UCDb?IY6vGAvDDJL!+k<3Kt8|# z2(Ew%h4x4u2~oq{2}G;5=Y~ofQIJgNU1N@ZG^e28XAsj`tQCN)P$S9EK-GYjNV~`Y zgtClsemem1j{RsUKNDIHKX7gsk@B8EU5C0@bjl7;(UCcM1-Brxr~3dzvxF940;*Br z?a*?yTj^|Is^Th*_2n;Iz_g%~1P77R*0|%T+DexcLhze~4J6#kPRJpm31+{(VSYTeXAXBw?~d!>$)tJKrfi15a70Fd zaHI%eF1HMd`-kT#mvja$GQtX)dvIE=Vi!gBFCYY~|ID0wwq5}>4gd&1o1lUJb7v(0 z70aKUClCWZCE4%5899Lm7DENe^Z_|`s{wvbAT*#F2pI%0#^cJ}+>pM=91e)!1cXSC z&M;b@1P$58paY$GMcTiz0CHUxcCSbP38sjC`hpe_PwJqqg-?=;im422hQ)ykhWK0- z!n0n&y-(m$qb6~|7gQ8ICU|kVTBVjRJW?}XY?LX!Er@s{Fr3*-0r#abCOUg0M{Lb_Rnt}Jmg6x%kNB<(F=b@K&Gc9n3j{xrN)GO|%BHqK>cknPG#q4doy5VGzSzjprppuF4Qqi2 zNBt$j8!`4R^V5zeQb9=q?yK`2AbR=_lZQLt!_A{vPtcOK^+#Tg%YzDRiF52PCkNb~ zLlbHbQ%E8rg-AAR7rU3JkbZCsU@EuB!Hqnr&IlNuA%Ike7dE^ zTpV1t6q@p!E9gZzr&d`9M*jkdNS$w!#RGGK$_joqZfJ4|tupn34=M zd&ReM+*Cen7#s8S@vAc6@oB)5HLn4{Fqd9fm=n{bi&EHUw^iUDLa{L`w2SpaFL{Y`Dc7SW-!-NTpNf z3Scm-=h`kd^mFCNXYVYKH}3WD1Hn*-G*dqdKN@%;#Z~G%;3Cs5{|io^K`>KGQc>A@TZRp zB5;7wto1Xfw;`$Qj^fe}5c@5y`*jmpbqZ7iNQa}r={Ts(Hr4%!8&9buWwc+! zshtO`WP=Jf<|uJq04b~i5OL4i~SqzikrDA@b}1501to>i)X zyJ@`pdt3}0Xx4|u(@jQbhZ`ZFlN1dqx$0Ofdve9Q&{Gc#xKKAhfB8M-pYH-uX~14{ zfLTsF>~72%Q>q}7giq+X z9kt5F8s(fbLBPwQtF9+0$q{kwb|=kX7mhDL``glI=?F+r>L%2SA6z>w41G*E6BeQ! z<^8syKv+Qm?_}{GnOz_Vbf#TfH7XatEyrEsb z+DLOEJ%oTEd&OFt$A9psD8FCCs=iP3!aFj3!naAtz&aWb=i808Y4Qs~18~MHD||E* zU9r0064*fk^@~83fh9gnC1uFz?4>x44}y#5y1*dX65*Nc?=##!Jz$$=MEK9xy_!rLR(ga2 zY1rh40agfukqo?-qV8Ulg(E_uemX-#3Nn=rReSeuVcH|wZnWaHFSz3In&zv$h#X0d z01QZaoUg`3g@OYd^$<#A@fxj(EJ-Q)bXz(!Wf@fgB^PD^P(Gb6qVwa~K3qU2Lg|3LAknx3>H()iTahebu@Xy3x(8Qfp03EX}Zl1A6>!I?!vx0yp){Ydzhu=HGkH{2PWK%jcZ8+{N5zouTGa5%5JbJ=abEc6WrShOasU;CT8^E)0C$RR zPk}e7iKiX?-#c)yRF@4%v+RIXmV?@F)T)+xiF{+-dctE`m>VyrsR*DVBUmrB5qxx7 zf=54y$*s#|uh3Ai?S{()p(E&^YTdxSnJoQjw{#>$VLxDEP{bbPV$6wVK6Xutk(|#d z02eS*OlprYURft0Foe&>yqBIkt~}f_Grq=R@OpCAY&pV88tPQ}8cXx$cH!KrWD1|< zy4f&Elaq7T>oXmLa}`KR22^piwPd^L*^oP|-Du)jFU}>0_?RIn_2dK>^KB{Ya(rTZZcq z`yj9KD9&3vX7;I7xk3I{-4yQG27wG=V9!y)w?a(X;*tm0KBuKud}JE;%7(tN;>!!k#3n%%96W7S`3CT_AOAa6u!c}r>f0;Nc{_RRASfaN6cr(#vm+Ys7PUdR3%;c0)OcMBQ^YFDAW@c&@*JA z@AHREk7zxZiCX|WCVtH(1CC_H)xoTDODn=DblWpsXxNwvm}j<_4Kd6jMZE|mS&+GcyjmGX%cI$%8clGKC*t1DFJzHFB zpj95VqQ)>Lqd^^@42Od*Sf4~5=^sHN%wUMS5_|xWyIUPW=o1ku1T`YN01Z>KT_d45 z9;zko;T_L+KhoLSdec%p2Np7@k)&2t$vqul<~Iaf|Q;l7_sIjtoFS>XyDN_6I`av-NmVZU6(Z7-WJe z#$3US41cePvA7O27O|-}#kEgFm(3PLLFkU3b#j;*5RQWXlf%5!`hy8Es)5p7jJe58 zTYwKsin#STrhNy(tP zfS{)#*uIFjJLh8XV6Xb)p{}MchLjGsC_vwl{$W54n2OB2&u_#MZY{|8$4tG1RJ+QH3*m{{KekLPaMQhG@vh?I2y# zSLPYsPC7^(#W9};o4)xLd~i~yJBTLS{VW$;6p(-RDx`p!klodX>|YD_b^#gE0NDr0 zwT%KwRlQIbG1?`7dF51WOc&mmuerr2nSvo6?u935e<>M6#zs?yx_I!NI<(Wfn3fBO zOsHv{l%;7~@$*fCRxLmQRJto7jx;ZUpkC#yT&M5GowOS5MF#ffk0}ie4){DJ>H=0_ z2v6tQC{SUgm2_ zz?`tZ6#7WTh1`tzSQYOBsD8`~3$400t512%vftc^c;+=@ec1kU`>j#pdYIcI-A@>8 zY?xADQw|Qe8*%(RiU$08P5xybL_AJSmEJ^jGijEN#yi7FwTQF#ST* z_-K7^)=H17EXNhcI7{sTh~~r-;y+;_2NK6U!$$<6A^;OX;7{|`#SkQX*gN^0 z*x?9DF*Z=4Qa&-YsyNt(h&K!MzBXg=iHm)U_66mNKpjv6JvBrI>p%|#vtJ-%?h-We zV$2yE{cXhObNI-Mw{Am#owt(X5)4sr=TuQ^2h_#u+(+P6e34#KZ%~@8U`Y)6^@}uV zaqyX?`x(XouHKJe_`%Q*T^fxgn!8Bqq%}kcS$xr^!M!m8#ATA~`eXoAHcBjLC_^cs zer0Jm@`fGQzPq}ObW6bd@FZQ2lUA?f`9g0cg-6as#3-R`ng zFjobltZjLBV~n;Gi@0Zi6#6h)icuI3x0@LTn2_+qxQ8vA7uWz;nQPQ*Sk08ehum!c z&I9n7x0r7AYa^YN*G1@2)ZtrM+=^?x^z7M{^3pt>&MwcgGQK?NkzVjq#$orVZE5p5 zC>ks=Yt7i?7G2Y@@O*f?2xbV=2HZ|Z57OUwU-g*5i6n^KFeYQrHRnROmF!l2iW-L; zAJ=?v$8ATnMxc)Xx|&uU*Dx)wOmg0o%Tk9O);}jcOSBwn9I?Ij)N_$Dx#0StRfF|Y zq#!eU6e@iD8o=3^4$hCh%aeY7jFr?^=t0ysF<>X#H)KLsr5_aI1jZH4YX2ae?C=fq zus%Ub3%`s@B%y3(Qmuncc3A=679atpLtGtUx;}-A11ki2{0Z1)BM6yxD2s>Q0|;+G zk=4KheFShMK0p9efl=>qpvGXXGK>0ml7fT@%+%*`K7ul4+ ziD$tPGjlkckq}lu^$7xkd~rJ6ocv(s+OcS;Xk;<3#Xgd!lq;O{g$d5VuAa_+Fo9p; zZYeIOzxWfF5mG)}PhMXU;wL$f>zkUdHh$+V1x7?ORR{p+GKu~Ls)f>rb7y*b! zyX?doxDDaDr5%E#s;1UpA;c8riQ~^V>49HfHfKCee^U^kBWF5}tV^lj= z`p8$I!eCT0Q)9K^4(LDtLJC~Hvr=!M5WK4lV3eOA#lb_qO=ig2`xR*jr~rg3)?anP z%SckyTas`%13&^8&P+H#Km{vf`~;s#Tt3w1nR^8lIX6w&EED1e%PZ)ZHlI48T8_xj z$7jJ4d3V*@JE z>ox)4OTGpGgxgO%T?r;RMu|m|0w)&_%%xQgq+u3tO+r6=6JfyMVnQZh3_-pBwNu|N0^%en8RFa|CbzzL-H+=Qr#Qe!o|J+V#$2utA!d?7b^ zq}?C@l*_<=PKzAk$l@hH5BG*3Q&{ET3o0f5m%f0e0aUR_Hl}Dw1GP~r@LC!mQq_be zAxdv?0|AwgLm(lfUWOa(ZUWXMKF8qaB$1Yv)*jPxwD&UHw(`hg8wogP%JCblnp zI)|q2Civ{e4== z2~Y{;_vmH#&o3H8m3|zvqbW8R^?FerC%s5~aA8MZR(}kzUoC;?kYki<*hK`gTj1%H zj7QKYAjN-no{_b(_#1;x12_*WvSqhZ*E^dl6?>;LINtKe%r)JTmL*zQJb)0`$qNKl zS*RE!W#=bJnxS@1)Eq#V2APJ2JRphI>An;I{z=WH1yS6DBx37wRj7HjHp!@#TIew4 zP4#pn9;gk@Vq0BYlRS4`4ypem1T(o7-i7@oN3D4XjH2D}{TR9%ShnhRi2ch;dz5P< zJ&#tjbI%i}VjQ|yZm<96B9ag!Frr!&y*hYS9`zy-YIV)OT_%vyLZU?BiO`k=Y5NCB z3|g3>a(NWtSLK>C{I|*aRGdN)m9GuBlkjw|4fx4oKJy{z^cBU(P%c7Ww*4toRH#(j zudPF01o?r{Bs62C<(X|Kr(~`XYIOr5-WBF$5!j{4(YU^@NY84yz6A}#=}O&UgbUmN zYz0YzhK!0RcR~~-=lHAZOkRXR;GJc}bxF|MkCY6igiyIc%`iQ(ZJy}A8 zTMFZCXVoNgt{K3UQAyi2u;XF??(%m zEE4EhfM5|K1@ud{(B0y&DBp@s`#%6<3SU(2A3f_C`Oq2N6v|%pzUNcR8UAVm1A+=i zJ>Y0s^0wqt)*ft+1CW={bLvv_CGMMWj^e#L@F6Y&T7*Vu!0LAeZ`7JEqLJ1eIpuJh-_49I zu3ZJ9q}++`Z+Z`TUL8)eX#gOK&Er87%40{z%%=}pzY=xmiY>zRnphSiR=P&#WO&d= z#aNZ52spsN8F7MUg^$V0DVCu-(k0PUX){ylx0%pT)rP#rkaZegDvpFTZD!-r^$4x? zsJJm~-jjan3)b4%J$`N%LHq4K+LClvu^LYVFa66!AU#GC2?u!w$i$Gfrq)gOFDse4 zid)hRU^HK#Dy1|xfN`WlP)j7{D&=(zFCzCZ}&iwv1Msv4w%*RB^Y z%A0-_kc+1@k~h~G)xuv0_za^tm2E)A$3%=F(@@bjJ_wG_0%;a*BPyn6aH-F|8}?B* z9UolT#4%(8%9qL?M5$1zyd{LR0t>TD`=LTs&Hng^(y^Mt)zP6#bC|yx6QYQe$w1lz zrHEi_zKbp%-D5d`#_A@tqOVe5oz&eVAj)i=Ly^AL}uoSQEHPQ)Rux zUfWgxbHkssNJt*_vz>|DTA)wmaO{XfLgg_XvB$I>icc6M+bwK4nH-^G;9Flo!BpBt z8{93y4{{;C{@+8>Ct7Me)-^;<>aO#wgD{ewEqbQ^FW1i!p+(&QaA%1Jg zKTXlf0K9DZc-qpO1B7DVw%VOv=eu5*G85@#LN=rQ^#_in8C}z_SxB#j7(KNsQnm<{0@? zR1?dmNu@2tA>JQ}qImWq)^P~EXJh?w;>edmBlK+|z`9<}+wdq#fbg_QF%;}K*IUeK zRM(M~r%n4%$S0@b0Qj#BFDL88CqtM9KvMuVsKuuoe+bRf3K8X?I?#pg&Vf_AWw(wr z%yYBz+mgKhPs_hE_9POx3PfJMJ+c5beis|@Vt{QU*$vGT z8YTQ}-%)O%xkH4)Q6O`I4WZ(ZzFj8XT68!OVXOPJ6eJZ4`Q6g()zidBNkQ9bC#y~# zgt~}t8>=Zrp_F_>b;#Wa%u#NNK0nZpkObmNrMLlTvKqGl|Kzw7>44FAU7Pw`)V*LG zCO2kt{a((9e!V}qF1Ydu-#4B;jQIA98_J-IE)s7@rCk(X2R$2L>IjwF&(+*^Nk%Xm zah|a&FRMsPbhXlw((T0(2=&OM;pXozTDRbU9PP-Z3*UL$oO4gOdW5!HfO=M3tnQc8 z<%x%&-yS@z>4#cPPM3m(_Jo#(Ny$m0SjBeHe7vr*kZVUbD4993Ck=U$49#1ADJE^y z?RoMC7B`<^JwvNy^v!`spdIL}W^{=B2c3)(l~I|> zhYkc$;)2!oafx_^qa=&d?PTs6yhwr~knd+U*0>WVC>s-`^RIjTE-Fv_oR)ICl71_!S;}m1t#Vn70W(Exk5Cq6$H@fbE zH%UOyEqP06etWs-h?Y2)2i14IFL~dGXEwy^o0ICwtGCL(ALcdxTdUy?YtlNj4rBOZq6ZfO!*pRP zO#h~>`6w*^9+!`rmXBu+CwVe#@+aC{7FK4sv9wC)iG9b9;tiWN_TVmZ|8a*E;C z?5Dz5hq3Z`6Wqo7k3`0e;BbwowU}jC7%rC)h`|nc&}YZCc-`1+IL%Q-bOWqGWr<}S zwrn8~jl!}hz=;e-cMeSLHkvlWhA(`IY(25RHy}9#9Yg;sq`Z={R$U}ZT3Gbbt>i

+Z6O)SF5UVyX4#E~G88m_2e?MdK zA0yX!x6Kc_o=DszWHuXy{ZiVvo>Zd3QKU>do$|T*WHz^HzZFU;L1OJyA2NO3Z%SKE z9ISmD@g5NDt@|0^qi~mxtPwk3Im_SC#>obech3NaOww5UyBw4kJg(TtIg}ic(erp@ zx3g_}n~ObjJTH{g#;IZek#!6*z_26}dOTJY4#0E&=I~iDBEBx`nO#(_N7V zAfaP&04?GNqyD@>OW)w%bLwOu1fkn}b@FP31Jj3XCcaKdI0c?i&-#Y2wyNEs79zFUuYTtEwou1^>NIR4wxZ=^!0(kNv>UoKBsHgk1TpVxXZ-F z7^)jMj^%|FThSjIBsn)kHE%)&5gpj;wkQm_O$_jxzQu(8ICd@f6C&&~R%`4oRe%FZ zL$x53V=#OsgbwBVBuDBTS)fR>mX zcS-W*HrVi*hocS*G%GXrf%x(;R@h1x@=A@are)<6wP`nHUqP z_=io+34Gkp{X!NmO0{t2AzkMwA|(WfY)4B5I2NgqSk7osUl{$mz8j9>G+;k2lcs3) zEPQWMWW=_8hcS(cF#`t%My61OADz31fa4iad+C8|`abk6wFhh#Ax8bME$PiKQV79qQ*^&6{y>73iMAa~8klTIkSo>m&jp2c-Qot%q7* zKzdW&I5a}UN#X%oEnPO;Umhdyt=u`8lZaE3^S@BxI4$kD;QfCRF% zgoQqg{85&h5e~d0@%Jy!Q35vp5ZD2G7zn-*O!kIB=3~k?+oZz_Rt@a9V7v6}jdt|? z{I3CW>#^J}j*~jPh|H)dE-J8opx96b!Z>Vfkl`=~KTZI1OXX2Ea+NKCfe2-;3hLf^U~u`N_I8U%+O)DYXZRnq-MR52##U->{p3t+BE)=Ke+ z#-<$_6oBNMOfX>Ph_s%RvQ89Zd}m|;(F_rxFN8ZIF;?iLJPfHSG> z&y1T2%($=kO%1FJR)rI#ixOmfcTT`)R)$0*NR zk~CJ3nH@BVb=)3v?zh^Caz8D0?0CnFZuaGO70~B%OQguL8+sqo$KZUpGzwduQSMBy zpc6Okr0Uwd0z37d0tX~*aG(?zdqSihZar4@^K7D&XWy<4t3|lQ(OeOwjZo}{z^4#E zSn!g{i|y+94n|C3!?5J(cbuoH)lzaF1jT|ss`>m1M>+s8oT7a%Yp_LsEQhwt%Me;2|_7Rh3nwa zrWNG)e-GFf%)eT6G<|hIR8R2uJMMs^ySpT$8wrn+knZj->5iit>5vZTZWZAO>F!cO zIs}zekl%g2-|z4J@!q|?-PxJh+1c57JG(Z|*>+1k6G7DQJCWljo__CgiIDfNzAY)s z-KDGRhfFhnT4L`uKc~dYyou1==PWYk4LjH5_B#GI=fevTG&OM`X&y}+qrmi^x3lI* z68_OrgysVpzGG4x4baKyFZC)Ytsjr!ONpC_WRT|xGl*h?Ne&cME4T;8r!S(OUg-bSnY6BC0XzB(~c!s`Vzh{Q#n)(_w%lSM%~x<*!oXp7@} z+Dbr&j>aqp%J?V8^`*~r+Z3lm0V+Y^7r;FJ{xddZqUsO#C9hw?*c*3CQZn;!SrM|7DSIBL;7p{k1Nw35x{XmIGkCYm za*UtLZ&1x=53CJ zsz>&hCNn)?rbgi-H1Nl{j0p{=hS#6z@X+S!jPO|0Mwx=h*lzbdnQ)Ga5cIuzy9>9G zC9KhQPVMGbC9KCJ_%G#+#UzzI%Xk*@%amEBy(&|}cF%7_u{a5LeS5Q}_6jw2&gNg4^h8~OFVp~E8n3T z&pb9${x;k(eG*9!g8!<21o*%MGXW2Da4&7sH*~4)mYb|qA7+<644(NKqv^uVZPy1e zH;8FJaMM+jT77LruT!OdaYYy@RtbCUN8uecyKd?DZ;@d;^$qeo8bhxZT%O^I&NQ<$ zkq#kipO4B#L+H$^t*WvrO9YVLF!V+ia#X&xP{UGSlK~qF*j19T8-wFE2vZTAYse+=e^byTgm)A2VWNZRZ=2{eeLiMTv#C9{SI&n~!XqN_GOR z35&C8y)C6Q8KIm(mbjkQWc~iW)X!Ygqf9H9m53Yr@`nU~A0(`vpIIpX}K)zjF?j&%@r0H%MFlladcR3^V1{ztFZH1KO6wL2=COlg0z4Ly6% zP7_u0q0Uyy71pFyZi(Y&BNk(4i}6rP)fNpoqo&+y#*zvyorq>YIuqvKs7-Yes*WWU zoQ-XU?QEIF3CU;}me6M+le&>So_c#+x8c>J;!?4{hJ;=E1yR!vMuBW2ov>I+gNq%C z+iLUxE5uD&umT^?O=n6aUY3YnJx=>N=a#a}biK)hwu;cbgX6=$bW8nagw?fM(ksUiC>c+h zM?9TrGne^Iryqxd%P9Ltlpjet8={H^)5oSc#wpK1`>LZhCLecBU&FpHRIPnO{v$Ue zqLg#*vQIy2us^2|t8^GY4;d>tT(9YnK`rfiNlf@$nZ!F=Dk7`mF_tXyTH%U+8a9g@ zs-4M$#CYKx?yCjJV?VBVuI|nhsbJYd^HITI~w%#hQoww0rW~k4Earw zA?lrV7PWMGwUS#Ug|77znbRby5cRMjEJeNZ7p2d>jjC$X;`g!fL2}nq3t-haryI+= z)@hp+0Pydot1jl3vTwh?1ADvhnK3ty+-D*R^7gW;{;Os-?b%VDkHd_9WbeN_6Zg1U z72-7~eUmwf_h0|QL#4SCPl_h$+ESyJF%%?mApZZ;4c>pBH(IGIGmBExnOp93O0TiU z))`uZBhLo_07gON&3Su5VTIG411(bfHSE7sX zYB-ej=XElbU?5W^6AFF=w)-L}LsT0YhP&fCOF$e44xGXN2LKX;;t(kfpD>U zagf;rMBK4U)L}Gz+sJ~o0BDfX0@Chl6cL96^uHHBj{XV&4jpi!i%F_AuRElX0O79V z;G+aaVr>8aJgCtCfR+wq095zAfL~s-UdS{a_N?5q|G~dUp4kkaiq|nb1yu*gi4Y`W zs)VEE0?_Rg&yl^rI21gG62@x<8)TFeCDynFTM1MHhNJ_D3@*J~IuM${N7O0>@WVkr z^f)ja05yaz41lKI+(VfaZR>eVkmZ0{Bv&Pp-eW;28E~SgUMqGt4r##n%?C%u$#l9) zFG0R$J(<_9nJ?)uP4B-nD8kW|Kk(rLnAHFX7Ycwy$1s#wi^Sn*;Tm|=fbb9;2@xFj z0FvAUoQe$Bw-U;N3G6OVZ71aHZ1scBrR$II*WqNgEvi~iII(h>uU|V%sX%uSSnO4H ze}MmZibbXYEJ@-a03Z?z&WV~qa@ zLs`Aln$77Pcnb$u9Gz-0#kT8)-tlvy;^N;-8XXs}La9*ix-s1{?&t;aAv~$u01zD= zaRCRrs3ajN1Qq!L|Bj*HlR1AVQ{q^%imGc71~$$<8&^nabp*b{IO^x0&#@uB>)yz` zo|N>!YwbKvqzIHix|?OE0l|p?cI*WJos!N10L;6XW^IwDx#*(Go&n>}EDr&`0o1Yd zclhh}06?J?Be3)CsMnjhEHO3}4&vdUdM*HyaLF>Bi3Qyc;6qkXWN-|f-~gZ)ErS5C zS!*hIzXShOCk7t|(4g{zXHjaV_lTub=uZ`_SGJ+GNbJ!=d;#FO8~`{u)bC;DB2xg| z360TMW@)o}N;21d34920ClCx#Ep5^gZ)5FPUDj<$&+7uDlp^z$SzrzJlUxFj z0stie!n&pd;Qk%=RSX88yfDBNzQ8rHuK@tp2qb;S6eYE>jo2B3wYeRD2tCT#XMdDz zw(}`k;l;heR2Ycx5^k7+KznC5Pyqu-Nz|ddkH`uD;1g=r>)*+vAVI48?p0WM0zN4P zGvEtDsvkI-!UPNea#E)qs{z!tz(!~bD!z6<0On(j0m$rqkX;0TxC2NHfJ6l_dl|ch z`e7T6QrJ^H&!~(4eQq%s!cyRg6j!A7VyQJRUOd)G&-!JxB8~$CnBaiFuVXwpfL5BO zZNX6rXe(_Dz=PmbQ^@#f8_=h6#fY~D2>MhuWD;bbCihyJ*d!qZ0}OCb54-2C5z2M>Y; zE&cBo0QwAiH}~wdh$}B4E{fV1KG$YK@~kff?CGqj^>ySC?fE; zDm}?DcoUbPsN00Im=mBbsa=S!%YwfK?0?H3Tdq@5lF#{KkKT;4tdX=DhUsLr2&$e| zkmAWj3Oou@n!zr6PzlWr`fKA+l>cNKnOdNfZ|*RH;fMl7f&ov9_GG6b@%w-W$E;Nb zKmyJee*hFW4xT-FfO%H}0B9}oDTkEiO5gxF(n~Q32au|kf>dA{f%2~OuP=>~qNSg6 z5kVs~Y>ZI;006QN7`f?<;{epWr^w4m!Eu2yFp^yELCeJ?0K!HOjMCr(*jGy46!IJ$ zqrd=A67kOBc}!Bx18H3VQVOxf5lBu*`&^z4L{^S>8&x(h`(PpwMQL|J-4I0M1&R4T zCq{ur&~U);L`m_Xk->rC4}@*78Xy4@G0;SQi|~62&UNY z0NlF`Tx2!Kib6>C2K^3OT;s|`Qi)X)8fFCucUFgVMm#pUF^Knr`%1pl^dc0H}9GJV`WHvewF>3(LkS^ZAa z#QnQhkYIj?rg2ie~$z^evvdjiDxbx}}2Za3E`Z_ENYerzML0#|NF#}a2}Zc_>2bVeLCQsWK{ z?03_IzonsQiI2jvy)4aNWQ#q+?a>4kh)DVua$O82E-Mr7zo{QX-IuN7ti8uk^xwKO zU1((e({Va^%v2P=vu&5hR&Oj-);LcN2Y}XiCtvIvB%?9nN`ajOq^5x6BBjbD6KTen zxzk0y-9DdYo&-14z!M*B5*f9(05d?P_tfdL=o5(mI{wZmjSdg3CMJ$S|C-`VoeXcm zccx3B8*U*2!DeNB-*Iv}1JCPXCt2S`#7fekm<+U8m6swTw?s?&KpVH|3mkC&N^6!; zqvv=IfNF7s)MSw((8fz}cvc)e*k*AQ1&c$VylYfuR~T}jo||O7m*NR6OG0}aF72wZ z<$Rlu?~h){6Y3O|BV-^#(lvkF!nAv8uZ?zRGpALCx~CwPL1uqMiaLU0*4w4vqzh)f zWhOT_lIyai7Zn>gKCH{fa@vM_894L^0F|a*5Y`w

Bv+;%Hzg!6_ybQUMUi!V5Nw z7AvYj;*ko;uEZ37Mr~2bjL~I~Z3BRi_CsWIs(o1$VOqE=IRN;r+amQCKz9Fbdolp^ zf-gF%MO+mIGzLxew1|G6eD6fC-XWCoSo|2>xh0mhvgB6r)EkDIC|+@^$|TK#haKLg zKbG;t|4oytsfO$dqCaMdTJ~mw=bh*K>zp9O3b;~L=Vn$;>nSi>w5hE66}I1;qej^m znV;;c_4Gp+8j&&uK#1z;)>TL&M{nx2TFhGf9<1e9!$MWZJX=tU$qS?$v2SEw@rzF= zLKJ@vB|jpyOr*Cj%elR}5WRR7_6?pLZ5x49Jk0$&dpZD7D#-XhGQleU-LVV!Q6%Dp zf41FyWZe`35b-$7D9vW&qGIk@Y;F>ozB&l@x>nxxm=ACgR_aYJLyy0+vn$M2MXf}u z!|D^#S&`!^`*v-(xpfu7S_B^0bkf4%TlI0)a? zi~f}p)^W2h)xLmwxjyjsV9dcy?>u?ZE%3?owtGIB^k`NoLeS_yR_vS|p+Hn4rhypq z^a1TsH8n?M=F4h~;h@^7e-}kSxTfw?0l1DR5+%@ZeQ8fM{wfRre2rt0_V_lc*&P7T zkl18J{K*Sg4dPi{{E=rT02vhyT#|n7V=QJS&c3SAP3mZ`xCM{FABv1JZBfAMkchEc z`)0?jUgLl@+rpJ<_L8zm6uV?A?~d@Cz)6d+X_v=#BCk$ZJK)GVa23+70W5&!OYLS? zr{B3htH{|m`-CTtqoFZ{6H={l21g|(1XAuO->~q>0dw!4S4EzV-2pbm9!L%%FZ9*# z4Jdh)L&QKAE~td7XJ_BS>HV~S>!hgo&}6){M&DO=&7WIIc%z#%IWM@P|Hi`Y=0_|s zFs(pi8i_wPzb84WTWl_!{|LdQeEw4AmdUu`7V-)X)foL5d4763Gw}wS&aUX#naZ8& zKFIFokXTc;<-thi<)(*;O8N(*PvQSOxtF1=r6#ZgbQ6#cJWhjT!07EGKm0%3q$5DG z><9qW0S+<}m$HLP{d{}HnAm#Ikgc4PCdMe7>aV*EzN3>pPlSc8@=SDic=0NJ$8;Mr z>-hPXEpQ!NsO1gpnQm>FVJ<>HbOWHhopMfYULmUYF47Sw21XV7_#UJQ&giM({w|jh z2skfyfslwJj3DXncj|lUEfQPLvSh>nL}5PYM(+fx8$e-g=1T{IpJkvBqOqYA3__s1 z(rc7E0P!xseXNJ+omKqV2~SU!&{PLdOvDdY&BPkEeo8I zuK3O7UC5q0*xB2ec)S)(5I>k6;F&#&!BSaN{|`jrrSuhIAFf^zzIlvzOl#Cg*6 zbN3j|r$WA;S+ItbuG*W8y=EAGnP!haxy65c%7u1IP&j~ii0M&@L3$j{%}7bKWr#}A zn-Sl*ubi4|`w3*!Q)cXoo6G)wTZm{P*zs69Lp7j#4>vsIz66xx0lePPDs2kT-w0HB zx^h~oeRZn^w)f$Ta~7FCr#d9Z|3+cEV)XS0GWNKAHO9qfLRFfkts;}Nv1*D%h=?D- ztM#s(Mmj$=Y^9&%i`>V*sC)3GKV}qJ0G%b-v5QD-UIR`Qrc4@QDC{ELQUOy+an{@V zl&yQy__=7Gq`3S7W;6yoY4j1 zpka}%r?z_6#Nzx}qsg4iz@m~elnR8}|1x$8}@oDjAGpnR97F^%y1ExB*=4q$67QP+r5s1+rNVET5#V1eX? zuF7wYoE=>p`&SiTEI-Cjb;k+{EEd#5dQL}NF7Xh2d-lt5sjqRLer;0`Y8%Q(DU>q& z$hmq(1^&ayLuJFX$94x?ERf*}TLw;F0!)s!{Pnv}W8Yx%A+$Ps;3B%@(CYD8f1W{K>6Vvj_Mcxy z_8t1FTb$a>P)UE;x7k?|i1Mr((LHBs(VP)SVqZsyAb_AN_w->qt=Fp7OVxJX z{(xkhu(nx^CZjWW1|xs0$tS!EVBuUD=B_M}3>D z(+TieMKacA9fd=F5<|^+pHAWSLTe690?~H4`yz!;ZGXjg^Qr$C0Od9 zp0QFzVuwM{fsPFbXfi;I6YOkF(!q_!pB@O~Ewluj=E(voaV3 ztxBtK+pm(7ovPZwp_aTNzM;`s@(wLtGesgIw=FltZ&QCufV$-`aX-{`O;YH8lwRKr z)~!y?43RC=ebf%QySU3|d)4%MoTFlNUGU!t9y*PmcaCGkwO^ON8b}v}r%YBSF?-KU%fRo&4UN-*z{k-oQP~TqW*4h1vv4v?_QfKsEY5YB@ zsct0^{MnCz5>=WBp82sKv%-gD6n9Vay*NF{l|~uOs~!zk>Y+j()_yHFUuUI98997c z(OE{vGc+IIO@#&61nH*+EK^21c?cBzV7*epJ!e#{a_r(9d?7P;uVMR8=o7MZ;A0W+ zee7Cxz1Dtmc+?V9j5cgyak=%=dtI5v8~8|!{_RJZlbjqXC~{RoC{N^Z89cjC;7}nF zE(*E$jIv#}fB5s&cL}K({s&>{c9~@ z_eRcis%ls52rtTB;#9b{woUmhGO*!Q{Tm&Vk+-tJi&$CKEqW^S3kYx#x`YdCKi=KZ z$fj+p&48I+Q7F+rfhJJoFy#&7>{59Uqo7??S+2KB=NjdN<2j@;k9{A8|B8OR>b1Mp zI`H^dvs@Qub&}Y($#h1r5Lq$y7M`u}B;sVPbW}&9ICa@2W0Y>-qqNZU=iDBBUo}Pk zVD8;l;rF$ebB}+PtjdtqrZW#xge`to*nCX!=59bxykCg34n00%wR}VQEsKZebgm67 z2sKMX0H$h0F#ysd1-fYIzx3@|Li)0h(*A`_U9EO@tlArhfCTfc=%ZPoYbI7PjFrh= zdrAn=TvqQ}?PGvsOFPrcTZo^j1pVyAE^FQ`oXs?c1;6DgmuAE;{K{$MLlnID#{SOW z?;pN}0w<&UL@K%D>b>86X9V52DBPc8rC-qBGCoS5UC3RQD`bQ4+l``Ek&`;93Htp7`!#iVo_Dkx6YE)-@L!7^cO4TtfAI>0qdnVa>S?nllpQ}lrp*A`ipU4-x!UlYt2@uhQvg{S3!!YXhBB}v>Hj+vlE$@ zj`CKE<`lTn<9ME+qG-BaFKn-l2(*-~kH_C*qQ;()rZ>ualhym}o3e!u^U1J0q*sY( z)ChxwyjQH()KRS50=KS;u@0F0tcD~Jq8#JH+LOPr@R*a|GnEB+M_;uhZllMazVLq& z(4(!<6HU4o9`F1iU#vlsZ;T&_HKfk~0NRexZN`x=TRn-Xjj1f|`w66+2j&ti1*3-IcfBDO%K6Q&{<;>SYxlLi zNf1LsG1pn+z(pbldR>cReMo*RH-f0VZmiVd} z6EqBu_MB4_NU-XPn4{^ry-QurK<`4o<0t0DYS*D6oxl?>-NbC&Zm_}IF{OWzX(Gl! zSMU|F+Pg+Ox#hibBxAu;o&z_K{|rYSHlo6i@<$v_^FVKuzQN{z?%E+G*;U?gjMcf8yw4)#eFN&Z zq#8C{G9!K0hGvx^s??#nX4uncXl*)KlbiTYr$}q9_t^<3vCL$JP?TneH3mCK zWTr<7JvY1&O@AeT%WMC-&?5}9CO@eDL;J6`XIK{ovWtU0U&2WyxQ*Nt$t{sBhP>FU zi6OY}BL{^5lGN8j4u;tG_tM1lq0!B$R?O1)|I~}(O*1&N&OM9raGL0TbnDU+S-iqd z*tfpI6qH3wkE9KC;VRS`S5MOifu~fF{r&d(GX~D9$TVEPN|q`9hS3XauUX*099S0l zL;F*Z94D$YFhKa@o`rwagV?F*$<~Cz`#~q_00o?08aqkhxM6~d-sIRJmDU$cYmc_D zw=5nvZ>46o)(<>1k;jgnaQN{DJ8fg@=$o;gN3*mMo96us4l&wCWMJ~fPL)r+$;f(i z_0?1n;|kICLw{TL@AXnVd)qH=U1vp(@sqMP9!NoYgf=m{)HC8=X1~hEF1*yiM>8$$e2dS!Sq52-d-{zd}$g1jKT87R7ThaiX25=Uhk`54Vqsd3oYVg3cBqIBo za|6_PoF_5X9^1?lRC}Y{$@`2);Qa&OCzrs|(vfX0ETYm8uw&ei^ZM=tV08u_<-$_m zqx&T3#fPA+o?tF$>(9*4%1sV$ftJ*6?!H=!I(00k*Zd7L{Hqd|TzcA(Zsc>5peeE3nYZmymjPYE972aI28&By`IfKR zF3fm|>rr`DGy}qX9-wq)H8E6EsPUqqW5Rh&iuKhgnfS#KYBm}Cosb`K`I<4r{ zt%wPwAVQbr#yu%^KC7*)eW3jHS};HO=F^cr8o&1Wc#_o6q<^iXCK+t+NRjD6*P!#C zAO;1Lx~BzT!O)p;6J0T;r1}?#66v@%lRsppaYJP}Q2+~!Bh$i+>XDGz5@5Ab~^W^Y7g+TQ85}Nj(nz8r;e8X#Oz~66sa9{GK;`u)=al5pgFy>F$o>s*YF0 zV6Sg?V^{42hTB&dbLtJDV&pSEMz@qwDz9d-VBp38?V{I2Y+hMOD6x-MoVJa%N}tGU z@0)!mtzT3V8Z^CnM)+XT-bk^OJwt-g7(S4T4nK4zy@J=Vpct`F0Zt zD8r0rvOJ?&wVv0#yZKe2NrkV$m)wtc|Mh^;&cn3)id}yz=Fw3Ar^XFs`r)?3D1HZ#q<|MR%jyFve4tzFThH{;0S8ZsU-JLJv|UlRt?P+F}8sA37>e4v*1d zTG<$rl6Ns{RjY9&5Eu#h(T}&j(K7Qt_E{v7%YE4%2XM$`M&6{8F^|UR8ln=@X{OLq zHlB%ARr=8AMtK<7ILu8X))})M2`IZPwb+@nMde%Brsg^>?th?QxsuMUpNX4d9MLWO ze9p---}Wu_bD(*zUQ1eMNnBs@c}&lu(aX6+6}12_`vGIh75wP0`up`Rw}g4`)_7UK zA6;OQ${z0_=z;(t(p8We&b$u8D(Ng22SP~!*%O36kip2LRgi#<+>#ffGQkN!d4ND^^EB#+`J<@%_~S}KKOKB$Tvdg9=F5GoplA{4TOuw( z_7D2jbDjpG?Nr0%Y1}N zMlK|Tkoh4|3`_FLhL z&75(~)uXWT?sDcvCwH)}%cBql8{uAe|0~_xgJT7)lh`4H#$rE`0?TUKF|p2bP&n6X zb4Oj3qK8c>7Hm$CQGnymuSE~^GF`Y(vv9J2*<;HndK?QJ6={JeIdPn83vqT&E)aW& z@X?pZ;y+L{1cTpbN`e@n_GcE;TvyarlYpNT6fly9f>^;_*rMAl{^FY`t4Mbn;Zkmx zD}$jYb5Vginr*^sfeMMShooA>VZlQ5A4Zx~sCirSdnU4C=!T2MPQ0h5cY0>Bwt3CR>t^9+?kqzqRnk(JR>G^lwWuNAW6hEA-HJEm z*H)pEK;jpMQDc$_^N{8jKV^m(oT8dGq&t5QsrrN#2cj;K&-HQSdl=Sa>uIreYm9$q zZASl5bm9GiI#8p;l8-m>*)D2WY>xI(5YB_qw~;^g#1bRD1DGb_kj?pR$xbWArtrFG zN$qrL`=^cVgS*SSPo7N)qHk(RU7LHh^Y{24CQ|`wGBI6Q03dW1m)S%f1wQbQ;EC*oCf#h~&y1ckJJC>>#oP!PS**A-%o2q#M^qDv#8pT6c>V6srvdO)8d>GbY z+KvBi`ivib>1kNE#jjDnN>kAON|qK05u<7JNloU%KPu7_wMa%w>+##h(P*)k8;KZ{ z*jwCo^r5ANZ@dvBB|2&6r||5ds|4V+u0#xrr%!az_Zjn_0^Itz2G5z*@<)4w+iK8QZJ|`2t4YOA4EsDY zJfeM}C^~P3jp@o|w}dOcqesqU9M(F=P^BEfSpTqdra2Y!g}ZwCVu{{U7}8O_^fhI z#>(=x=WqMhEC|bI)LJG)!QYUMnsagKPhRdmp>g=aT6u4zBQ|X2J^wwX*h^C_ zuZEHmeWPeo1W|soi>*lt#<+ zsLelPpbWk;0EmtJ2g{$5^aWZC?ZkYHxEi;s#eOy!c`J7UlkJRS*e6N`R5f zkYk&Ee-qYKg01-TOtovc+`4PHXAxm{ay+NqH1RD?$(eXiq^Z(AxS21`Ad`3PdnFiE zq-2`+U$E)p-+qz8V}~{h?3d6iJahrFWvQ-Af_FN_MRF`O$!LTbiuCowXEZOx1lUSl zJkWPGA;pjc=xqo;hbAV$xLjO?+N(2e~6pE%pm++=Q*>V#Kyyj0?YkV zD~?#aSn^C~7(IJYskoP|ScVXOKI3WX<)>%T2IdlU4W^pr+J4^nMwqC8z=w;;>tYlC z?0}Sn^LH^HYU52!_&Z9b7ELM()5ri?gtZGuE5+}IaHOwB!#uo*QJExP-Wt&Y2l*P~ zDpmbfRE&&szK!e_U1se;U;Ey&jg_W$#FHH;YG;^4C~Mok@1iZs;+NNT7#=izQobWL zYyf}Ed$w=(n@c7AIE*u^Q)oJ7=i5Z@;FsEXF_7mOy zvco^k`MUsr-abx=W$fN6jcbcn)F}1Ry{vEEJ=jOGX!$Rko2rUYoT06$>EoqFp=kuj zV0gRylr{LabMlwCs&1B5yGL6gI?yZSaG*D}ceAWr<$Tpkv_>E=T7YYbI>slPV0W)N zj|$_9$}%#>e#UPX?^k8+b$?rfLDKk}&>U_n*&8~^C<G!{BV{6l^MdMFUeBy# zF#5>rsaPTL2b;@;H`Gvp)Bc!E3j_qj)#^sOw|Cn&f!;>YSDu*YyOX=1cljF4H3R(* z+)DgWc2im_um^2%b%D}5eNevpZjqBt$xo7;Xp5t|E>-h0`e4D|`W764# z=wWv20x{!c{e&f-SlyYF$$pI!$JnTWtZ>#s6!*1*Ev{ZCNUTyXafbAIH#f6IBl3JiZatRB+rE=`XfK-k4(C_*m)&InH_vrTvWH&3%sb>k8U5!Hm+^3 z1vKF7Xl`@!XNlG!WbX+bOorLE$kB})BEMn&bdneCthe)uQJ&6TlC!IPE@_mvbdZh1 zE1flZO=$u*wwDEu(UeS-*^#y=?rgBS#z~%hk-+BkS$ifXxZ%R>YA40+>5m3qZ?Won zg9j4k|6z-xCVPPP>gu9bP`GakP;TLW=25OHQsp@D&c|KOzOcw&wVz+7r~SOEe<#FT zst6268B2F9LUQe=h(H=58uA;X)}PVBCyy!B`Y|Q>8_ElU8ons)Fr^ zxh&F1O`dwD^zD0Z`AcsBZJDoP$wIij-l`aEDKa)QXV1I`2N41w*aaIxdK73s# z4$;V^I<4<5;9nT}0Mwcxit8(tXZCs;llGxP6>xQb7 z0C_cigq|z>ByO;QM(kD<^77`(QsJkqNm7evJr>dXuzo2qVqd&hIB1epixrCg@GCQE z#E4$@zlf}H`V*gC6(uc$U)YB{n^4R|d^i_X6+4fB3kjam7rr+4qS?|KH)%{>wq_L$(hECe0x zwBo{F#U_U_MnTqZwcn?!3+9!X{svV5br3e#r6hX|FMV?RN*VDdv|+h=pu>l_v<@AcGGFnCijQN~lbzl7F2%e>0y041-%d_Kwp( z)6h+hBu=p05(-@@UuO)A5Otyz!^CwAAQ?*KI%O739;-bj9)#PZ=t$Yc^X8dT+B!tG-P;TYx2dN zOd|X`OeB>*CxAQ!@vo6r>~oG|)9;`Suso;8d;b}&s88#8lRZ*Bbt?l`1YA+oij<_~ zVh0tXzFpsY$f@Fd`b_-z1Osl1Ku>+p=z6J#SEjZpvBt$JiJQq&h2;Vq9{b(*7*niu zSS~d+(uy1-_3ErNC#FVbdxTP=;_kS);)!mwb!IcSNMFAz7OUK1lF{L3g4bW*BAHQa z^xEJ?wB6u)3_YK0W+EHNoYxk8*gY?tN6;^&?YGh zuKba?swCgIU%w5N`Nl$}ZwA$m+c0y+p9kSlt^1xZL=pFP=0WIqcR#bQuammq*!ERx(@f{Zpl0McRa+!`g#|&tv5iNqRVU7%04#xZG~Em z%1ObDkZAaF>f~Hkbb5;45w<>)89H?ZZx>lcLu#qRU%A~Y%9&){S zP&}nz=>GTdl~#ZY8&Sc%HbH5OPPktoWrI2LQylUjbv`@iIaP#kf=7LmzGv}mMXa7~3>ipHdtg9XIRkV0DsO9ls z>xF}T1HtKu1N#6*wEX0dAe(hPMw!YLIkj;#GS(S?jQbq^kb#{wJ?=1sigG;y=WFY< zr;TBL#AhRYo42O`a16K0vv%teOLj7EZ|~F`Wb326$TzIQMic18{O~o#P`^@7Gd1s_ zHCDA`*sp}9IOt!N90ix-X=VZ29et_xz7TUr<`n2Arh2ptZQ+{oXQQLqw%90re02Mt zWbp9ls|pXPidK}VfoA28L4QM4sZ|`!%0nmsa@z#CZ@0W{>2CcKqhC$;GWH%NEbwvJ zJw8>gquyB1{H_&9ico*4x?7|c7JPk+pUYOv)mn8Isw*}YmMJX%rJ2m-@`6u?N<7{d zj%>YhdeNqh4c#ssY{)sx6M>nAUf?O`pN#Ir=6xzG_6@E{div zxQ9{o<#ZhWS*!`U%J&+R=?VHirqC4t!ghS!LTQ|69n-9$gjMULr;e*3FN@0t3H-#8 zCp$fHD&2jSjhst}i7p~j$KTeHGGw}g^w!^7=W@!-#Rl6v>ROS6VRrTRlhXjIJkUCSRC8jlEYNS;^ow0 zIjyFMW~o3}C9D;kA%`}vDk@}O;DZk2my5i3UI5j2~C(FOYlNqt~XE zz*$-(vPs$+-o!F_MgNR)+0m^vU*Iw15e z(x-Yr-nsxB*Bay1_vdOf)3SrLeuq(uReantyn&@*M*b$hLo#uCWWjCZ((xyE#Mc%u zT6nkfyh$8`q}H2F)thF~w5-3HU0#mHo&no*KuK8NMp;3|EzwU!13-Nu-}!uA=&z zCi$+yafBcpf&a7pzE}3-yVLLy_pcl=>sfrZB$r(38=d;R(YCL7SMsPY8 zU#{ymNVk9amqnt+B2s9o@kVM63ioiZ!Kidh6+$|u2!70ckl@5c46&gl6@c<|RPKiq zp8F!k1(5N5tlT|X)mhN)BTN7s8ax zb4DKs8U2^;$me^CDt`lCrPZu%d`#@b19JT>4ls(p=&Jpr zm0d~WU)#?<&fd3%y`GY@`!^ymRwY>SNCw?qh_ek>NnB`p`W1#=|GbhoL-mqW!!Kr< zUDd{*_><}fDsJU7C8B})eWonA=SjfG;C-Wsi;gP9h@alatS_?3NIcs5Pj2y~1~9#$ z3HnYVp4rTayEBjq*uwP^t_VIGpwh{kE%j|8Jk?#AEn0V~rIl@sEPtti--=y%{aK{?} z)c7hjY%=%oFB-vChiUkAS!|?lhei1X9<|KlctQOkW{P+mInAT>Z>rg zdFg@BQloVYPYUrN-0m@+5hK!gWCZvB541o_zn2)bUw;)+R7ZKz)RW;)TtFt!jZY<;wvJX?oYx$0=QMBU$oL@U<3QjKTVWnRHN94nizx8=g~$ zV?gi3EEel5Vhn;Er`vUrQ4{x5Gn5y{%+I&Vk&LNv*Mpk0EBYasDMytRz+RG7zI*D+ z1|8tP5CS2=*S7dqHnN@p+dk0dbkbhG$_2@i2idnw5{>^D7n}#6QjG&}adOGU(y1mO z02VQ&%%BX=4b6bnP2`Ket7y6b+3}SWUX0| z-mw_rTwo#Q-u$L$VNipiel<}Eug&!a+0 z(Lvdwvf50r5}P!zf`rxmnNG6&h|n6wd7vKfPm>&)%q`GoZrTc;o5_|+MYwfwVU(u< zQ{=s9=OIFXjKre(9{)UJGgAW&bR5IAvc)JbuSdk1Ko$%#u>hjP&IIkUJMtxFO-<+t zlv^oQ_wjU2WY;4ixdG;EKSZv~4Dt=PK6Hssh<>IF^9CN&0Jl<(tP4&;=VdO5dR+i@ ziXwgmdgX$Jpf~9Ipl@{~4Y|+uxmuf!8JEM+BYy>SAI~y$RtoX%huec|wJcdP+#>B7 zIr~9Zrdymzj_Om<_R>OOOr&|D{6t8;iAHr&vtCjs2~B^#U~t>?KLR)~QtjH&9PA^l zpyCdrl>YX#*W^J9gpAKAm~wnQ0>V!pOcJbKAq1%{l^eqRGYCkTA*@Kb_907ZZZ|e2 z>hDO}bx_4oIWTI(^0^={8vdMFQ`s1{ngQL**`spvtoJwEd`I6vks;c(D25?DdKn*D z21G_q`RsfcQu*ExQ(f)9Rm(~X#UoOPNjchtyPna&&l3PX0Cs6hR*n-5pA}oG3ZtpX zj>h$@>IQ*ff9g!qDkd3~+Rd8#9qoLW_GM|H;Jaer{V9V=BTG+OZ;;vj87mUh*@S^b zCyLjhTSv-VKXQRF0Y5`dHtj6k-s%@HYS_lxrD}h@4|KR13C*Bm`LGf6UOc4NMws)8 zEK4Elm}s?0%NZFKbDM*Fm`m2P1$84FWK`KmRycA9byv@Eixa7*1mKw_Mvzy;0X-Rw zvFvE58wN)bDDHrhp6ue)oRAj#ZYa%~m4@Z!?$ThgC2&cPr?;#N(n$`+;4pYoy!YTv zLu#M^v=iMOCZIl|(+PkEB%gNcaJHwSb}k*Agq9*H69W<#P&>DVUc$j}EiHIpj`l@m zKUr)!LhvLy#FQFj~R?yyARfUZ5a4T2Kgk8!o zgm>}FI_ij;S~FR!_G-X~p*iS+6VK6WChUmeGXMv!k=c;NZVe^v>&bk>uLD;Zh(L(& zzTYw?g9t^^^a4tSs#y=*rx7|IlNC_iL``miQn>EiNkX`+^IwSh8Ww*9V(x+T7i7a8 z{+Ye)8oB9Vb=``qXmUiYn3GUWl@-o+AYFkS`05Ks!=wmx0O*EM!nt zUBbo2sZO(MrrytF83SZG&2e!sf8eZ2`p+V~%q3?I*lea3#6LF>hh}(hyGZBvwZwp_ z^n8-f?V$b%s2nTlvB-Wk?OBUG&4(ex847nv>hx8nma*vNr3(#=#(db?t2!}+){v^E97{C zvZXA*^y;T+H=V%{7b3B?N$a2BdPtL^O1JRek*!L=1Th+Yu5Iqk0b%kODF6X>00tbK zjxh%s@fjeMfG)xgQmg>y9=2fx^DH-Mm6coM-B3d@4bpqcem&xS>o0}RWz_grsx~Lk zRjXV+bEQZ|*$l8_3kb0+R;q&F2`9|a7@2-a{#6}BFY3+^)@;6CZWjR6(kTi60QU*) zG$R>mJmK$5V8i6IpG|2O`(k?xV3keFhu$q`3%+qQ@(XGC8|8<;U!56Rsud&vh-Z}T z{v06J~4mFL$%nlrVez38S)RIen@+! zeE$gq_3&BYU4$7PdFHtToB#j`_LQWe1s-aJ-F2OWa>Rm+ke`kY`f>XBI{MdjNU2ud zqBu*+Dw8|ewUFB1Z~rCLbPiq4sHep{O%b<1l7|9?9ZcqH`k;Q^zt4zV;#ZgE25<5` zN^SVP>n7qvn}Ai#YhK%7Y)2hC!29TfCX@)!wlV!h6@Q(chZCOMw34*@C5V^__( zfvFO4F8KdO{ePsq2vMmcg82leT9b9Ty8ij~nb@)p1ZpV)F+y}{1gJjO^ooBxuv)!L zH^FRjDRMMts@_+N@l^r)eU!84rMV(@ShOthPK#@+K1Xo(N^OpS6GfLs*icmGP1ary z^*yRw8GT@kj5n~d_G%X80L$&bL*eUQQ%hokM7$%T6ureswy48*GT%N-0Ht$ z3rGDMW)rJ=o@i5#HA%i+%C`xD4h&ZT2#1ve0y#Q+B7FaQ~dtFLH#MG%AOsH)4=ryaf`-z#qaa1I5)oxxNFy%9nUoZyH zaoZTUD>WvI2=8i}OLbaG11x=LqIE}^D9g|UehW=Mr?0y)_EM)SoK5Uvnc)q(FQ-~f z{MS+!3DH_V-yIW1Xzj8NE=*p+lAqY`nA31`ZP=H8%{S4*K!%W5criz6!5ug;@7prU z#CSeY*4Y)Uz%)&&fB*m&tI}6c7jsWbls=FE01p)fVLb6>dv0z4%G&SXXzZJa@7Nd` zcI%)&mI(3sh@XJqya#>PPA5t8!OwkfO)G+Cp{+uHAw;6z{PdF5%3N3*|1!uWKz-RR zXJi6P*t8$t9B3}_q30Y4)lrTR4BoM6JgkR>M>fl|CW?hk#dr_+_WAHf@%;_7t|3Mw zP+y{MFSh%H93grwZ0nz)m1!4D9d^Tz?Rc2NGi_Oh?uub3u94jIr@U@@CaMvL&}J1i z-~9jH`!+U07-`Gz$f#F|!bXflps2VFp#uKnxxIfmHC*eM%;ZyAc{#%C&1W0#^*N#Z zA%5fXBwtWKlCCVzt%czLZ&q`lro>Xsv++}>380Q`m0&af)T8AqjUmJE=@Gu&Njzvb zZGl86+VB$+4kT#KVi;1{BEEOK zd8Bfy&rVk~1Z6BYaDjCh+g0ws6QX$rnOwd3f1;jy)*o%3qH^-9#!l^X*pwzMqvl@= z_&k3WWSh8;(VuC)rNAcmb z84YU%^FF*3cMKE{oi?iBQOKZk*ts;sjR>59aI<6eHF@ADCL#!l7eo%qCDxcjP6|gpLv|)CD181WhN)tM*LVereh|ZvNsZ(3Ub~R5`v|lFI}m%E4*%yV`(cwachSdq6;WFavG$nN2-$ERy4 z0}*khJCY&MA1%y%`E0{Ba+Y`xEvl^Mbh7&7GWC0FGmN#vMvzZKO4-qthPQ>8j=u{m z{`#eR7E($7Zp5s&@o$G9Hn6dS=^^Xg_?9Or8!lu8HP&KbNqX@eCv?FV#{pG(gIqGi z3NVTe=Na>->h94|hQS&ML$fUTR1iKsb5fb4O=)<6-GDf`Y{<>wsF#fcqiCG?mNL9h zV__15en_kJ!>no$?mWMpe|nWPYrSmmuL_g(5V+{d5;O?2)lW7R`^wNCNB{s0){7R; z&pQx1nAihtKreMDAQtuB6T~9)Q|-wnCT8`b?44H`1rY36C~Kj+&mAo?LLJa}-4ap=+&*XI0x6W}2+;v5DWe99JD5%GTagFM zet*g_+AVpO&naY;N}$6Z5OE9i}_q}+UV%CF<0Q&VqTGr>knKtZ;v{o5m(ME92_X$ zt2kEBE)mrz_Y{LpAh(x0p*?Xivs(FI($53$l7pw7?)KAV{Z+Inci4T~3oU4N4KiPe zrXG4?D3_Q325Q{%Ly=n(i0-FsiYWj(QvVI(OpVq^gy)nPo;#Ak86vX=z)G2%#4?}p z92P!Uaba6SS=|ae79NyP~v(!zihApLNje| z5eO{zvihuHw%91Ra@4#JuYyrw#RMth?$(SDwnBiVb*7n^3|zDe>r}Dy*oQVhTyL_> zq7av_$J-ZZ9@a|4_8b#6@@&`Z1s+zieH5pgX?uvck{wT+*H}h8c~~r9hprNP{Yz6E zqA>_ZN%F&0o4J;kl=4L?!_+C57d@R?)1Ii!rz}R^A34czkE#x3Kbvc-6@hw8MKB4!L2}99Hv*EE4rudybArJ>q z>e<9`Ybz6!{GIClVsdd0z-=l@h-3y$Bh@Eq<03IM24u{=;nA4Y6#8hYt&Cgg1>A~) zJc!XZ{1AaR#FWykemHOVRs2^pX$r_ywj(PhtR13@9#Ab}wR^3l@0DUALLFX?+#hBK zobQvi_C^y}Ny+*h-rP|gk8U6We7Wd0f0#Bftn;K002}&K4-4@BMp#j7%fiaX5ml!} zY+v1u!eBgVNfA0!CRJ^p>Ce2c zHYU&9i2Z<+S7_8!xEMAH?Fl}DOs})8zEkoisl)b1O3l%vg2Gi@;s-qpCi3ZXmwxG>MJak?}V2iA)K_R)!}Zb@@lV1KuYs`9dwE8Jcb9v{;y%snEj4 z?BFd~oJ^ZY8zsOw(9-^9!5j1d+10_cf^3{peM{^L<#SNZ|7ZM5^9bWNo64|Ttik#gW=xDD|lNhpFlY9w9MUjvPV>z8Xv8!Lk3 z{Bt2`^1d|Et2>?IUWs`B{Tp?{n3&}kQoKmY_MG(r(UWSM0^ z_600kqSw+Lo~Mt;xN@rj|Mvj~BKPH`RRKN!>i5fe;u41{Ge`V*M)lN4lsa78WEqu+ zC&DPzkBeomda=4Rp0MO&V~Pi%NG$!PQ)6HZk3oLf#8$Qc3W6c94KYmP6#h59>IKK) z^tCD`eeQnC!9SIUK4Nb4xreg%puY34gWYz}-wP~Gkj%+qJDw8Q^T4-f;&_nnXM^*1^ibv+uGAt!if zvWzhkzgUwim~gL}m1LQ=J}TrUOkS*kI@u0+wb~B{fl@VkY(~QWy|Cd ze^Dc!i0hhwZmKXPDe?c0XX_Q-qg_9bW;IUf_j>(@b)4}yk98%Jf!>xqN!FGX{nI}% zfOo2=H0igmf!bo|FD<&hW(JqiG%H)H;lI+v0+91hX!wTxm$)NpWkc0Cp;ik>hX5!U zL2QDb5a_agBCvnf+ene{?4L`1X~aV{?iJSjzJ6ed4{U?cSnf4KZja_x0+Uu{&e1C! z_YiJ7WZWuAN&z!G8WX@v@mYpS0U4535hOB1szZNE3O?d)Ug;<+Jo{)y>{YUi*GVQ- z3b7Ju{}AZLjSkx|fGUO~;mW=w!`YdoEkSp4IM15?J{Bpny(p1~^{}~4}6FTv<~IDm*~gF&H%w@0ph4B@R#-9 zcj2TZY%DlM56r1nYF4S13BpZeU%bnMN_iIM* z0KtbvZc_Wq{Ef4=VW9#zAeGG6V!Gl+ppiqQ3?UvA0#fzPM{ zHCqiv@5Sqe+j<-pz`j#}fyiayqgmMXSyzgD>ejAHT~r)MieN_WQ9Cb`05|f=G7vDJ zb-n3aNl*z6yGEj2o0tKhL#v$3eLuA46rKtFQlu}VKmrbirC>5eB@Y*}{pZKc4zEL; z2LMCChYu7}@rEqff)-k3Z8}v`JO&ft{|Bt%dweA)vBIIlHOh;3Y|s(9KnLwRI2hn1 zShd#dg(YcjH^#jLes$g`2-VP@8C5t>tt%XjX1UrqD(@0GYN_bjK+=Uo4?mq_J^_Bz zdltX|6@*!unt%WVp{H9X00G$?7IKtVWX1Ur1W;S@=4q2X3E+EOdsQM)gKGyJ)4zquio^O0(Ru&?0PL4f{6zi% zql8bfq_v53+tGb*BUu)9;x0gA^zKwc{pZV-4f$^aNTZMM z-X=h3P!Wq5YR)keSdwFjsR&}i>y^&(JrQWvM{@Kj8q@qWe<>~U?>eOg(mlGQx-sM= z?qVJvn`ji+9i-q9v3em>zR%Nejh!5O+K(DST#Y-B@<`HL>;FN!J$mzC0%fE0fFTk9 z6t)R5zqSrw)BpfxSO8ZkuKB51ywFls^9(EqV*A2MvWF;peO~{JKtrV!QqL-{PK)IL zSoX&a!YmA!>MDM{^`HO%tD4D-eQ3eSPimeMf>mH9(5RFMU=Yz=)H$96enf*rl|033 zvTC?UtT&<~q4FLgHz>)Rz{mgrIwxJ+Vq<>mR`Hce0p zLqU&#M_>Z;ho{i&&Q=jA>f8n+b?ilaA0W!X%OKR!M1gMgR^f3dN!L)bN}OcYl_ttK zLG;O8y{8g>D)iDcJpEzFdjWSN*{QNDuGX)s007_x#s0Kwv+w`_LB2(Rnup$R*a^Tm z($iOsN3`{5acw5kI@=YgC^hj`#8=xKIj3hZfE=EquVFL3&<&CP%XATfH&;Q<<1+P^ zi+3lsZ|;t?a@Y>bXf1lhhWVgTwQew!c(D_uN8QwIa;iKx7rnrWPj`&y_qEK5@G5>N zO;905hF3UkPlORGPN8}X=MqE*W~VIYH-@LNDKaZj^Jqf1-(K#N!EFY(z(=H~ZvEXe z2%AHryN+aL;J2kk>u9J&xvVDu&Wt($BbnHAPAq?L6&zQ$_Xl%*Jb&(l*AnHTom4Fd zRn{)ubZL(k&NX}azjlKC({`h>iCekgA~!74x*HEzMJ-{QojeL#P{+L~PIeE!Q5T(n zM+84bf`0~$g5xg%jq;U@MU(#cT0z`{?d_P~VBsAc@IzME4L9)goQ+j)I3_Fw{~ojw zP>uo{TnSMZA%Fk_-#tw9426nYFh>IBV#%{ zcj@GcqX7LMVb5!^$?r?y$VnW|@ZjvfR6~e4y=X(_CK*ZKN8)G1ipdX(dL3I+wye!b zs?#BvxN!(~9E9^Y^UZQui={5%#Dc~gT*fvlMK(+69Le&ToDo?glgU|95&d6 zke10+QsY`Om6uSevz1M#O#nZt&Y$Qm1b;kwuMPYkhOAnPFecJ50CfhJtXbZG{t6U14M2%;z!|nsv!@7T z&!=a_A|3{S_UMD;NOys;dT+#m=T;9U04=BEtSJ?5?>_ixR6)ejyE0B|ui za+&dpsu-EVgZD_mV5o41@{jfaG`-bV!zP!lW+LKhRjT@skKow<6Vt@eEKp@RoA%FwJ*~csbaI3UXq zo)Sm(a)1Xjg23aBbTsXMIOfcwP#MO-@{$Uh(6m&6=z4QCKR|Ym!OY&9QhGka2BPAM z^l!Eou#k7h!QA`CECg8ij`cM7y=op5c!s19%DsV)9eEhc99v}A_J>I7R%%tbsnx~t z&<**<`Ehp!=Gl9%&6O0j(qiral9v$h5U-}-I>{%*4|=UnmK^*RUWe38(&jkXKJ7zF zoXc<97}rl5*P;4;Ly15kl>A>QvE$NxNqbrnXj&Un1@Ae!jpM7mxGo3c@;2sTlEMYWYj1arV1@GVUU#=83~(Mz}5a9kPhk5oG^;v4YT?v zAgBQsj36%J2FsEmIjU$r4Ck|kVfQa0m_Y0Rmv;pvy8xYuy6jJ+cButUyL>TfaStXR zKz;IeXiJM%7q!2r3k*C+4O0MX;~_JF0*(Lx5nr3_(e9MPWCQQX!}W6jo^x10*!;ju zkTj11c6$e^_i?yiNCM9F08NlxHr=cN>eN{ODuh!!>v&EVGjW@3H4p6Fc#RaHH=-jl ztxQU{g;M#@Utap{K;2}r@tAWiI;ReNbF05Uz0GHjm={|?x>*qxke#xVA6|LNIyfJ| z`!jfUwL9<3)f^t=5y-eugS$1nn)(eZx2VKnarh?O%m}lYJy_#5BAa=zMZ4Ab-Mf)d zn={?*v>W*1*!bcOuqO2EmxZV^VLzKJiC`V0j0iCRV>NI;uTFJy4Tyq1l!4ch?_P~o zMNW1sIe!JZ#AS;)h<@1E!)!oVPjCzn@QLc8rsFg9 z5fCEK027b{GVlVvFhl?WR0#jb002mF<{T-{jdAuE8lIK^3?25aTgvs*ULHbYiq3a% z1O3QSr_laU00ZCCV@C3HSp|Xt{5J^qk{8@r=3bc!*a1@Gs@+`#qtxK~6(?66=gJ?w zzHnhTto1ZmDWGp)6?ni01?SQrp&Erq{-}3t;VY#H_lZiYKX3Xl@ZjaGD$#+5d3e{R z@v)V=yk6Uh19pGtZLzqV9oy-L0CM2*>AwW=#<-nbW4@~#lQtxc=KL!>Q+o$7ifFiJ zUkeI2QSs#&yqjc6ZO3-%CUxY=jXpLM$+U^_h{!&Sej)8UA zROqdu91s(;``(YrjZC4`wgMV}KemogbkNOgAanX zsPgq;un|)(aZ9^PS1&6^uVxoo@lnfGjBd5%P=7Uu7$XkX!@XA*(TKtO7EIp>^-K=3 zzNVj9I@2>2M8y%5-UbOL(q=n_n8H&-ypyYuSR+$XrE{=_8R&C*XUc(QkTkxr)pVe2 z37#{JQqr*bQgnmK$v!koB2S7uIbic+JWBC(!^R|c=P@qWn%?tXFj29gVn>!h$OR-& zl)n0y>KrlqH)@{T_5znSr|#9Jm%mk};n*;7jOEF#^j1V=oqEoHjc;dvTsRLnP|sib ztX}Mu+tFK&!;x8JiQD5uRJ7y3QeDac0ZDGf5i7_&PomMx^h{b;!E{nZ*v!=Oa1WEe zE~8$01xqz=fFyVNjINc_P9)9 zr;C}Dg7CI$garXAWTPxNoGfdXV5diO!)W@|p3WzchA>vdG!dnc;TR%f$8>{A06HKz z&9$8kfz1F@)$jn8iLn(Pkew6w000du07!2b001DZ_krawE4b(a39k(k-voQhwOD|M z2M96Y)m4NK49jA?0AW_Q^!~WGo7Z`r!mTv*3w&~R>~J%0CS$(}FM@$c)<|xUKOCjH zUjjsA{lLU<+2}uVAVJ;1MP%gy|e7=Y%?iHl9}z4O0$81W#5o8e1+a zR*Oc|LbX3fR(R7EX=u3iwpw$>i@Kit^A|BcmoG#F@+ixtBL;BuHsMqYYa=`W3Si-{ z5e&&-mO7_?k59bAfC;iM0|z24LEE_{5>ap(TRHE znxVAYSsLXV+RU%`$e$i8WEek@Fu5GHiwO(}6vRtWKp$JVikF=hOR2c#m*SqO>iZob zvm-4)l=AY@Pcrbbt%@_ngr9C=vh*FCL{P3sB9?#v03<^PnA32dm`=C=XaE84m!tpy zTCM@N)SF;{ZhB-b*}7(``UQQare7&m?VlOfnL8aa)#C#;>OjO|v%{*UvudxAzNyvS zCnOVuyE0F6(((Sd0XCAN+64`rY49hH{3yF1l{)rwzj}BWTcuL?3r=}w)FWX=rPFoyFz<1$T!&g6+V<(s0Y81O_maUe5K$&h}OkW9P+zLP%U$=O2>OHPfdt|#7i7)BTjYolC4UK+w z$WvtJytW>#f396xgy1#jdN(&#I`l0L01O}jkRKr2>Uu{hGxH`_*p_9g_13oWH-x7L zYzZuRkAhA(LVn{PG~Hl)iAEyeI#=jAnkbzC{Vm_a?1OybNylT7Av_Hwxzc18zvWC2aF&{(_g zRX);81KMJu*h+8$tz0ra3u+#a^t*u=PYS>i0mi=u2nd$|000aJi%ff<1HmB{hVDLqCgY+eE%a<2A94Oms`NB-n49izaCzeCJ&3suKPT3k&*A7OmlOtaZq3@3AlOAo1_plf3pL>#yqTjkHgt7EVk z&zXQ8(`r-T8Mc;+JHtP?ITS4th5!L!cjsyV05t#r4f_BDtt>+i2{%mh7eUFJ5q{usueq10|74Bd-NM~}nSBQ7X&&;XJ zEI9@TZPpQ4EcgIAoo|LrRr=u|xzVe~%oo4_C(Y)M@7?FCkUR_1RT>I|^Fsjdg9wWW z1{KnMvnq~_Fu1@0Sc4GDnBE_Kf2aa6>wnaw&Z?)Pi5nqzY9528Apq@w013&1@bJfk zEM`Eo+v4pl|2XxD97SU%))xKenh1@z`p1xsQV&D)L2ule?t+kNy&*5%fdz&H5=(T z>+q5-HoZMy0wdOB(pXh*6-*O4`V1gP8_tEBXKV?^kdNLTs2TJV-O-!%2d*9_8)&;h zIf#l-T%ZcVj6g_>4|;nir@-NCmojvt5Nfhu2;7oFi+o7Ta$4gE0068t4-Z7ihXGjt z9TEw^01a?}1=s*GQNR$PRsy9)JM|?z6pzP;VXcwrO3mo~fu)0e;2fr8%1gX80CGBU z11J56;>Dr2Wx;PJ|BDgGBwxqrz6Lv>Ip42l0Ik+Q@iqvnkh`>7I6BYzX?*6lS&C|t zI}~@V$@HHAnttHVZ-Fv+IP6_hVOXHE0Gq~WSX2`67 z`SPYx0&y7I5_e%K0vf%(ZIxUXFAO{;3?vKav1S>pB2H9{2zTC?#U_T>t<8 z02Y)004~4)J5T@s3B3w2hb$)!Xx|yg>EK&Rf6m)>Lv$W^C8TgS3V(n}6T@$aImA|2 z9;bz%#=2SKq|87C2bu>W{{nS0?gQ#g*clJD*w{m@dvN>#bWVXnZ5HfDutVtf3o0=? zVedA_@FH4@p$S&Kg(qpys)mTHdyfW@`M03lB-CZ2vompYOlw3oHnr7`OpXmnIXlL} z3H_|OV|?VGS=Kb#P{w-VrUryGP5;>UDz^w(zyVDad8FN`k=g>ffqImvt@r)aMa62X z+kkrHPkpIs+D%mMVgB}6EJy&LpuV^=FBF2FJePcR=-plSdVoEk2p`ibUzai19D*bT zm83yoKm#Jc02t~oud%(*ZWoG=+s*E=F=octGJf&ShrZQW=H+R@eyOv;Npbp(VLD); z_yVSgB3J?>0mK8-D?mqT1IKO8iUQ0J-&S_tGVL`=MC9F2A>JMu8p+ivG0hr!1O)I= zu&(V;6~@nVOjsq^ddo}GBWWLmu7+=C8J)hey;ArqNhAkss7Wy3MjxngqS zPEYr~hD>BSN2>JE zs}-mX*J&2goQgfUD4!YtYuj7!0aVu8K6_V9=;x%jph3i&*5C>mCR$*h+Vo4SY+Xy)`|J&9_^P+TU#(+CWRa$ zmGb67sNPUvvkgY`y8Ct=cH!6m<$!x&$U!!Zzq@>dNJ*PU_!EV&Z-s%cfuLy1&H*HD zPw2AKq8v)psT;FYp|n*bFN=cPDiP<8F)hR)kJjh_G50K6>%ag57PyvFf!*_302bg7 zVFABkvvT2M6ht|sfwu?u{GQ3wlPt{u01K?mk*%we%d=Z=1UwR}2k4>Ci{DyXGI$Lc z6x861%@y1~P7=yF&weSh`|arE#(PLzXfq|O0a=UacOiO8s&06G%+2+b98w@Vh6{EZ z#^v_v>PdrC)r3?kf$fQ>_U9%fH*3~csh;^T?flm%%goE_kpii7tITMds(41ehYSPQ z`BpvQfx*sht82#C7WWVt--N~rEfoLkew^lnP1NhR_goq3@IS?TE?=hGQ!pJ604JKp z?g?FuXc6ym!GXY^IJ^#HC=fcK7p&tR*BeruDyA)cpnF8+zv)%{K?Ah{#MkbH%xTa9 zMgi0hIHd7<0~$kD_iv=E+c3T40eKK5GRiwBaFtHg6l_XH%_LcuLW&$>FnH3!O>d+* zY9QU?yEtOtx9&tIOjji(#E{XN37|A6E%|Pu5pz>lk^Od-!AIjn z8hJf5(FbZ#(4?YUpZ_z!2j}ZfvZ7!>0{8k7Wjc}Bl~PzuzyK)y0~ayLnepiy0gM4! zF+G7_(i-6fdzEyPN8Uleh+LtMMn0m{3xI$CF2J9F03r7<5^eqP1-s&QfqGWq{)dw* zS0mV_7z*eQ%Brr!%wC5QTyd8_)!LD-?f)>p!og642_Svpw z#F*yAN4|a8;)dQkoBvqs*dYudW>u8*`*1(7uO@BUs69807ScR4w za|l-+#Zn=;yUMy{$z`Y4moT-Rh8i@hr(CH)DFb-XwMFkY0*JhnXDpAH02GLb(H{0; zGX~|C7^X|X#eE@1%p85h14_WKs?zU(%^U&>L%jv@fuNEhU1VXu=ld#wBLEHkn1Kg1 z7ULq{+ie`%Obe^{QG0*nLa;r_A@?Fa(Ia1vn|JdcDOde`3PEfafw3+=f-i!mbHWKs zw)9o50bLdfW=bp+*Ls(8wW=z7P35-a006=n`z&EBmv9s33b6tj990Fh_nt@nJi@%%&Nr~P- zPD@mX1sAdu00Njm1?dlSk8e4Pbf~wJH$yau_e#dI8i)e!^%E30I;o8t@5aanZrSWV zd0k?p?4e75EDg|PO^e7HM>t1L=C?9J!t^q_Kw51GvH6*VAt-6iBdh|FTPSISkY6L6 zA`axB306-gxEg>YNSi3ZGkD~}K1Q;T?f|V217}$R`O|1?x~iQarTz3WMLpCuSSuRS`yB-xSam&1Lw)3jg#X$ zVKf-AJ&MHf8%Ad#AuOC{#qu{04t9tGwGBno000W9oPcBH^v-4uYXI40K_ul2i+jZI z5nta&05H|NKD7~255xcf0p|b!0LOr<_yG+?93ub#ZSJ4;t5cycbDU#C@PEIr3JE&y z1$J_6hH-WxK1m{-3Xy|{-Afd5K)P<4}mk7@PvFd)NYU$UVxisA9|ubx!l#x&snT*smx8lB`8Cs1D>nyYCm$^ykpt)XRe z4QF>|GZZQa$#x7X2D@{aDbsyb(k@S%r?<<9Z`Yd_`&5!JwE$gPtGOZ0kjcWe93m|R z9_~C_o(f8nlvzyLO~q=KE!B3H-=}ZEV-wMI01kM&{7*1I02MF*26iGESt_Tlvx*9C z!XA-MFA%5xKK8{tyN3e(mfpjTNxg7>_EOYr=NplO88AauFa?DG8XyOWqcV63Xd25a zf|bKQ=t`vkF@r;A)wPX#RF>sF9w1S?gPYZUJJ#~1xDpSzbCzLRcPhh!JBqA|D6_JG z)7l!mESrQl0;E&^asZyyIv+p0pKWa&T-eblO#+RKxO>7wfGR52?)L*3a!qcMmcSE? zz_ykzD|N;P(6Uw<)ehKoV$7t*&5hdauY?MMCNAKGUx%iq<8`)$AfNa8$)J9)5*8RF zQ&-3kV3e_2762T95CUUi(G5b{PqKg~A}5N>4ErcSDrd;H02A=i!ax%{+;qHOjLODh z7S^A2i(J*SDK9`AG!CmzKjCyPzp+|l%>MQS-A%MaruTK}%0}=a<`Z~i$l1;hQozPX z00>I2j}^{3-#(CKO$%3)u1WwUs_O5pGH0ugStP~0v2~D&y zP*##d09K$vQZPmS0HZz?oUP~sQ1qt?%0kTA5rR<9Pg%rOXIBp>Snxn;h7hfd#29dJ zOEd;(P}iiP!9-U^=W^mD>yI;RL-8I-(0WK6ZpYs!za_W^6!r(7io)x`sZRq^f3-A1 zna@*5P&A{S1KEeo^fEDBec9VQU!tZ`+(kpMfQ#Y@Eznp76aWJ~6ZQlmJCh<&Q*C(P zvPBJR7_`w=2%UV*7vDmZfLjBoZ+^%m!J`_5Ybn-Riy=B-UEVc;)1df-5*r^45dimM z^Z6(M1UQhgqr;Y*a36H~4KRRvqIScr*Ex)=j7q_xrm zcK~-$k2@ntmvZ!67()YYU6v|N@EP>rfVz2pC6AnRdvn;c>pKNM6Bp?bs0)P00jVxw2|)C55wh%$SSjk z0M_8l5{V|KymJF)Wz?=73q=v-EgJ{8BQM*|jkmcd%dqZOPB8P*vm5|`ULu033)i-V zVeNBve)?n|9;Hv_2s0Hp_lL(g0361FY8JQ&t9>~-BVXqW2wPl}POl@C1~%f{Z zGh~TA2`P{aW& z;odO~5?czHTqvcp?0MP{Nw)A5c`$)E{wy3f)lC-?*r;*K0Q~ktOq!CINf45YKZD{1 zj=8~77iUW8tf7a*!I+dgIsy3C6&?rspMx5f$6>ePp_fe<2)T)}ER?v{ zKtI-7)#h^36FGn9%l;OK1?b*jUf#=TPHV6^0cb})ypSfYwP|+ylmLBuH^Jx3MC2`V zY3!*ZxBzOcnfmvq8pv5&r92DC#zHi-k*RX-*e%VD>An%V7y`G`UowFc`x3?d9soJT zQx&d6l;%yK005l5Yy==O##n|?bMjJFQkSfKi;Ac0o*o%aSdg};W}DIHC2g*>p^IJu zF|i5VkAOb3R#+Ps9q>y!kPECs0XJ+?n(E$Ixs)+{EsNJ8M_pr!Zc8MHRxOi>Bm>E) zHNYR#8r75YM5sArb<*SjLzM=YU9u)bgpFWP5H^ee0qdFar=tRtq6CsK7Sw0sXFXH^ z00tPM0EOWG2m(i&2rIbw{+AeeCbb{LgspvpjaCX5PYy=${%uT3>ryMuPg^N>Jl7GQ zH9QNU)>=gq$-5P{DC+1@@bb4CGAXO~{ifqL%uM-8g{jHHOwZ3k(pbXI%} zL1)rWL6S872T5F)xsC7m7#?ZO&$Rub@0jj@UbU5} z(X79R){#7q7E9p^?KQd9fm(!gmD}VK%<>zcga8a!f_up2C4l7j3>Q_T_#!`Hh5E@1 z2eEht+odc}!0!+l1L~>R{RK-PHtW?3n9u;~Lq)O20Z~YES?REeEGL%$8P7syV2wzT zHbdabVuwI3LOUa|*`Do-g*>B`P0VwZ36DJLg^DkTWLW`#5YSDjj(I{8H=Lx}w{uVJ zM5^r^>Nm^4l2CFK%5a16VdZv)qeiM*l&)$%$?c^>HvbTWdsIQ(z684~(}1HXxPR`t zGB}vxe+D;o8aj%cIu8CJgDwC3tFayB(!%1WFfoDX2*+9=>3%ylyHZTL(y<{?s3Ar4 z=wU^Ll2RZN5t?KIC?jcC*3RM3fqcIP-nD~U*e@w@FfAobYMLW2Q8T}z^)!}}RXy1t z%3EEP-lUwxNN?@JfoZBoing03>~8G|OM!v-(}&rP!0f=qPimyWD5+AuQcqubfQJ70 z)T>Y5&`&-8hInZOz(DG1GRm!NjD~Kve3`HTl!+j)P63go!{d_D*T*7N$qQ%;Lw&;r zIfoOpM)@SAN~hA&XWq2lavNjXK=`OSy9&GCZAQTr3lL0Hitafrhd-9XmY3PSZYjAE zakK{D3g|W(0c}k>b%N?LURVD+yNU!`hn}|;7=j6L+*n4cRN8bzl}JiV5I8zxf=j0( z7{;%E8^7w`_%8|3R9Gp1iK~$I5^-N3YD?fYzjt=pak$)HgLcI0J|nUI}0UqVdN1>m#IqtQ(n;n zOSuL{0t5vy%m>QA_qerXD1U#I*NuR3X+8voZsqpG=|DEe?=M%Suwo_j*cAK8IzeGu z@AtMy1kddF>tcQEs~qmqZHx`|!y_Wua4*;+2;5TUZ@4B)WTQ{0>s%{ntclV}U;si` zPc-Xis(t?dMJJ1BKmmemT2&?6Lo$Yxs*41(_`(6{5Gh3mfdNE1G?D(88PtK!KkOr2 zaE}>=iU2=Az`rL`Fbn~akWcu8Ai;mCEj!`FOj$=4N}~O>grAYUxcB9}I+?#(Q&faQ zptm(Oj-UFH8`O;-E9ov&+>EcFkqo_d0i)Y3Z}@*_7@_Y1&yuXS-``?(+5PqS7BmE^A`VfP&=2IYg2^PQ0!!y zP4jW%78)cKlJdEtFZsI*zj-hU=`}=hF)uHss2_Hb8u{*0{JSx}3~*IHoMcZMdsD2oJ0`E_fZP*YHu^5W04-$7?McjLJxDPSsHrM@ zw4?MOE2t)8moq`M+F%W4h?`@M+!n6cjDEO}D3%~@AtRa&Xv#xc@=7;>IeHrqzO5s2 zI7Z}4(=v3tTJKr-)z6^Pqon&2}H{x9`v&86$KB@v+@(=+`!9sazo1B)1J^THHoQ3O+(V;{>#IpbF`4VoXKuP z8W+-M{!aI5$KUnWlAEa&zb?Y~B5*&-l~;4)jr%Dqgc{nTa|k>_i!tfr z7N%$9rJr6%20X^&5Gk}$4ciTBZC3)tNr-XGpXShq2xPmCzyJVJMh?1ZrHy2LHu^{e zJLTn!af$*q7e7vRkq@A6SZWYcq+1rp_z}GeeDV<~O8?~iS&-g~7OE|gwglZph!Yal zt&|*c+4sGV>HTeQ{A1GQrjmi9?Pp=6ruW-d-6z#B5ssX zEN(_pmum(7)c3Hi7meLVN05}it=16-J?8p|xoyLD9$U&f4mbvttj9MmZf(wNqqY^8IAnTc3nWx238!FRDs zJddA-d*KZj=YyL!6^)T>lq47lBmaRKqAa8_tPXqhL8j?*E0HWwZ{pnux->Z=nAW7$ zH6FdNFPp8Oht=68(!8S_w(NT{Th=8?3~2NW%dPR1ZIoIFfApcDngqdw4f_Xj@hae{ z?pD{F;?#*okGu0J?G!qsSrq^4Tq4w=U>FMj=c)Z=Z81FLJ(r5MCIkm&Lq~uBD*qd0 zN;#?V=b>qBSsV4wKG%Wji;IA#`K7YU4d$=t0x~oVv)TILlAd#t3Nt3^uHX-6HOuX5Wgh34V9O7qsiW4{vIIzWjxBW&3R*TX> z7;5)+IdG$dNXB7I76eD1??v4ta<(dZ7>>uygH;sQVh81IsCwf+C!3>&|3>+c?3>V; za~BXv1)K`gU$VqGj;cDvWu$<^xIL$Sthd@G*4vn!7YD2LLv@FXlt+D=8D*Vj=yR8z ze^1H{Y!-O$|N{20Wb2Lul^aD|y6{c9cMdOpezzbO&navs&cA-Md=0D^U?TBujrwKNlB#0HVo?wq!C0;X8$ z@J)OIM^ah}lb#XL`7K~VCo|IaY#|gG75xTdK_A7o2nuLqSeb_W_8=^wD%2N1hL`NZ z%LVYO-*-XoE2|}fjUo-Tc>!c^9F9ciCA!<1@{|#tl)kk4jXaoFI)4H$*L(y zw48j$h*&=)_qA)?6qD@E_BNR_#r=9|YG-UI*^-L;k<^HH_T2Pb77sos6Wk{7lTQdbm!ozYde2y|sbzxac$qv%ozu~ao4?f5C?)W+4XjRnyX0y+?`+|ts(JFi19 z83@EvF^xVtt`2{uLoGKB5RELvt%dRS;kz$?VmxnM-eygsCqJpST4c)uk~>I;;j%ZS zk>;kOxt&IE=)RqqjxDo{vdPus@G;?&=D(zaKH{TiB|S#!0(K`sOs4y4*V5*!>Y5VV z3Q@qN$M6-$u{zZ#$bshyvK?rsdki#W3SaRlUW*lRPyn9WCYjKLoLMK;0m9Vn1|c2nOg^ujGX10ocR(2u z8K~PkH^Y1dluY~$OU4$aX$6n<{c@A=TaR<~tP<`%E!?YVL~9}XQ^wY^+$M$q2gwY; zwS$D;H!)6pcb7qGi~Ai_l&P0O1J=AVyyAWr!_YWQLUxFrKY4ccmfo$;PkM_Rg(B~Q z24Q5t$v2mOU{*JTJp{4Hl`@<7Rf7BJ7?3@G+|>IHX%8yRE%kIVa5SC)!( zKZYyXR77^?A)qNlMe2%Ve%`#O!ivxXp{VWgzMj!&b1_yC=9ez3U$nD0Tl>|;BfB+A zEmFq-xp;D^{$3sEzlTH-sv?)Ti^t?926HBBr89Z& zZK@L6NbD2A@giQa-uK2cybKDtp{1Kw9&yeDos1xje&-!|^_n)?bq6pb5X~c)82dzzZpfn;+(RzDq^5N?Tb#;*q>GD-2LthXNVFN{_PnKY2fl z*%-jYw=h!RTY7%N-7q6wFdXkz$!h=~GxHF7-ofvQO<~%Q3C9Vkf=2o-KWh=QfF&8m z5xcAS5Yi|M{gb&+)VO_nVjN9+(Rf4bIjUrGIK#q;1ZlvQeNWkNrl1Xk*|$qCAK~np zN_-!;OX#1)-z5vbO}ijLfdkV_6rS3YK+cl$!w|P5*Rmob4MU5&f&R0m`QB){&uFi%ZiCA8WH}vBL?z{jXK`0o4J4+&l%T< z!GNj~FrfN1E-_!f*_z!qs(5Umm=`TbU@U>vu~1Q9n_klN#V*bycY0EdA9nn&#<++~ z-R4&I+Wr%(*RT3*1>Z*2b?h>`8MzDe=Mtxeo(xaT)7p92X<1h%y-o5kV<~d-LT5r< z_q2x``q?#aJF=+7MDWXYY+>HiX9%xY4ak;UQz%ZVY)f0jsG3>fWySCu#;qJ&^NBINNi7G`zv>2edI6jOGn z$g%=@pHW3-8M3fX;(MXp=oJ5S6AYghe4-$NIn#zhs}pua%;ODyuH?YDBnMN4#-3~?lIiOIVi$hL zScwGWHp4aptb1nm?UmYll3Vja=)%zb4t7~!5}A*o<0fk2+o@DJ@oJ@KQv<5Ln#qoB zSAJeCG9(E!dDYf#?+-*Z>4jNXLR<=N+mKE&By~Mtfj#=YK39N_>4U2l>m3}1aASB_ zP(a66FS5VjGpwxSO?8IinA{M`O23-cm>bX6zM(=hF(&HF?1)0pxOGNM8DZB+&~1o zYFT8kSaBpgU*Qm?Tzn_auW)r-S*C@~x$8|3C{Q3%ixzR)to0D%=g1qsGT*3HKCDF| zf%bx6A1d@Q)@u^Xh}{99cTmyj0g=|TFSx`UoEV=CK|?{#z#``@ao1)Cc7QllHX$Cr zX7SCZ?*%%WfsDR6uBH^S1VULaMSvI{-xYp*D&s}8hv^k`l{bWK-8U>2o}6J_JegrV z4BDgeTTG=?qc@g5YodihoN5JqDxoH)cE7+kG(RaqR=wmb)i*B{*sa_0$K{4MU3LPt z`HCaMgY`3OOmMWG0457h|&+&_IW0wN&z^Z)sPfomoYR`H5!06VI-TAsQ?@=|NiBO zgyY0chc*@qB1;wAo6_KBzgHE@vxHIn>lIUGv%ba1SPx-3v92T+f_Fc2A zx_?RGODf5tfWD(CIilvv{vdG>$dRr&(YQto-hPD3K1Ve@>Csfdd>O9lx&cNH5vWMA zw6~!G^vY&;$XQ&2#-tT56B&a#sC3@DOjr>O(0*T-S!ZL^2e!p7B^+uj=o}5MTHH8C zQLm)#kO$u=-1IaUb=y+hTC)NINW(}C?N@8`WuXQla9!tV01=LZ=(D$r{axuJ$mIHqb_qS4oB2i6u@k?(*`X&Ht-rxK!$xLxPx(r)ACO8doa*Q8A=%*;C?ObvzQB%q?L`!X z8$|N}79a$st&30_gpXZ=wvu)=;iiHMtpGybkP&PW9EVA3I*I61C~}{D!y63sHyyq+ zrC%i&uuSKMiM8Cy<=P!cA4Jc{r{#f>R?Xg5?9Ak_;d2czekkAS(@U@bsKl9a0@#6l zku4phtkyUVhAMobqA7!7G)7hOie@Iat+7gNsh#`f{TE7qM_eGYh1M18Tp#o-PDhLi zOs#`2BI3h;#a;FCCQu-TS@X%?@#X-LYRFG3W^fEJD}^+rrIp5?nETnV+SsRS=5z-J znX~VYD`Ar(z$SgZh#>ruD`TMteu~lox{3G8D~HT%Js+Gz!BZFS=$x-EM|m0wd%2G3#b_A&5~zSiV>w&&!MkE;G~)(6*7i zLUx&LWc661Tnv?Sy*FH;tq%=yN_l(|9 zs5Z;yJaGq&He^X|#fh-ZAoO9MKQ`=9;A-U1#y!Wt459Uzeka~x({4Z)7F45~jndrT z2!nY-I4f=<*I{tSnt0wf|EdhwLo?nc)Z)BFhI2^t8|({po;oq6-ztr7lIaHU5&AU1 ztz^gwT*^fO!ly6)8N&~7MD)oFo;MGo9Rv8R-on4LpP&z+K!!hziF;UfRmfK|> zK8R^ds7i}bd0T)CY1iQt!}oz!zmU4ew^yfRqj+wTA!>_H|D_XKRU#ypT{io=d|We{ zurGJ5X8L&bCgX#J7YL2Mi5GP4X(m&sH)TKJRD}@x=I>zndNYzBz~l~<>W({tWhVvP zl*3=1WM#^0AUGy07NS&12i(1OwZ=3#DDei$3Thi-1{7V(ag7r^BPtw1bg)3#ch-S& zH@nirgW>t>+)K<@~ODPtrVDXC}cOm^Knv!9LaDEvWL@FRq087`Nh z@R#rbU#Z@S+*C)v3P-H?C4dSY>+7-Pybf>v{yNabBiSRtbY__vUszg)X1U?N_&hyV z{T1tU7?r`t|F=9}QvK>M-xg6)@Z_weGU&lq1D_Qo8Stp|)I^0B8JY?|_gvHslMs63 zY8qfdHcZU5MISz&=^xlD|F!)<{axguaP2+6{hJ;4w)lY6$j=k1n<|NsQDS|yymDY_ z`U7Hs%b(CfIeVrHx?UyMohKPy_>bSo=qAK8gjItQuE$wgEYWvGBIqbe?{ZXe!-kK8 zr6r+S4LPuf6;NS)b6djBNY<3xKpkYL6eyG`6L>45AtICy*0I-t`?&hid~0aGx0&l| zozik|v2HNxBvVd+N_yMlNn88@d`6VPfe(szt7#P`%^HSu`rSJY4&9pMTTVIS83a<# zsZGyRzfmgW-d-*y;W5X%+uP`E?3J<;a}%wz055TvIZ)%`RbNgy{1ar=#%l z6A)s5p5vt&8Bo}IgRtis>`>u~ehlHEBN!wZ*XU|h4iH$bF8a`)Hvf^C;#^JMVlPBM6rHx`4fAv< z6N6WGY+VIEL%0zB6;uEKAs2CZD^kUA1qkUdiT0<*v3Z_YNB)PR7xIdH`$RTaiURU4 z4C=Kg@`cej$_PZiOOM8P#K`sm!-YQL1lFC9JRD%0J2Af0oVP=O} zcLUKyuyZukBfndYXIV0jn^nk*eyK{;$!`e8?yN(@z3>kF@h36FRUF9a13eqdYySVK zfmr0UruaO8WjGnx?|6#SAAC^^^#0a(ivFlV*d|ri5eVo#VzGti#XlidswyVzSLXc9 zaI+h(B^nw2dQNIY6-{tkbH2=L;axjwVU{7;`-Q*?>^Ta6hO*i477KOSf9H+n4F%vG zfDl@uLpx#mu6kZkh7I1>+PEA0}548M|008A8Z#6B%UfhkZmmhWU< znsF3NpQ?L2poftyO%x_99#J+mTZMKyfC#KYZ3bkRp(EX*c5v5LqbKsPdkLbR@{FS3 zylA$1IvM0_W50s|W5SnTVbW@rl2reqW2QdvxrcxJDbuAkix;(3&my$u3xN<$AJwuXupRp@tiHYx(xU1rTtC(x(f-2XsXSVd;emFQtnN$phq6(BeH6#01>xNVJ61 zprnO7c5hAD|78C`rl3ezp0Iev8&wJJtuL2TQ$^HmTU;D%moI-Jck%i)dtQAiiBLfK zADl6HGKGpDXBl_&Hr`c#Y{N)Pa9DOI2=VupjCn~Did&gF+$ABcO!h;8qf1RuPMlXL zx+C#>$!?Jn0z)=Y-^+VwT_2Tw`g1A>>0se>0~UkX3kcc&aP`_D7)0=j0XGSzn^{Af zqo%(T=a1Pw;TnqkG~6#!z$LMk-;{?v<#2~ve_7gzN_N$5XyN^TM~fu7Xfr5h2CiBc z;I^ifT(r?&vx9?6Z_yii%0+R7HqI6N3ko8pujK=OW1oFi;)h^}YD)uG?RG9~Q1FQx zO4@7-x5trA_Bl8H5Pus;QKbJg_7R;B&a(@rhsAZ~{qhVlz_B}fb}cQQ9+EudcM2iC zMIH&jYr*KeA=Y4E_?m3FUd5O%*QhR&YlbeM(*( zHb9*nAHc1+qL61P$zW3Lrg@)Avk+0237&`YtS!8eQ4(Z_WcnuFJVgOP7<}Nn5;f=k zNpb;=-c5kS8(d6#R8+D?5b{?l{E7^;sJUqLM`G5SwI7#Tkkzg1y%1?B_UEVAdGT=` zlNOk~A|F9rnPZa~e0flCgTw)kH!VPtQVD~W86J3v+D_{NkRkn!{XkZEYtc`2pu(?o z+0xF#N@dKF1VaI6IS5vlIXF2RF)?wE~TAC}E)u*ywnt2t!}!>C=--bqS!<7dA3hNLnB8QBK=IY@oEpt6?!@ya3OT3B^Mj&ZiZsm> z4Uq2KRU4a?9HI5zwjE#-2@;tmYpLLLU~w{VAo$^Eqi(=a8w|v8yrIeFw7LIsQ5!r|X z8qqGA=?!U`d>*1H7+RRaY)CUK9}LD)y<{Ii+SY_|t=95l&Ub+46UHD{S2Ym^-l9rs ze?|)9eB7m{m^V4X_ckCw!H#wiw<1pTsib0~m$JRp4EJSX<$c2>e@oj)6Vdz3akGrC zhDRyn+?l)6`H1d7mllSGqUbSOrjiZ0P;Hn*{I`WvRcCyGdj2*O9fC$Z=Hm( z^la`Hw!;eeMr`o?&uPj3b8-CHC2tCLw2|msr-nd({0_^MN8W4dx)wDZJMtV$gTc>8 z6VNXY{QegU8-KK-3k=luS1K1v~F#dK4 zqa+sg4cWqY>pkypeuv~d7?dbsMSBSc8viSKuA$jh?QrBAJS_9#`(uQ=JuARWubihx zQNei%#=M6-F2O}e233`@Q{ftpCr%_pvde^tKnO+0m|R)Lt_UcvLFM0fM=X$ao>QF; z5_!|2_va0U{G?Yf_5@UqezfM4^WH(GXD-rWCa#8dojg6)n_-Pxjnag%kY+v@&oKs% z@vn=HX{9qbAIg-te@FUVwskGeAV~&2^MhYQWOmHKGJW>yO{_8Iib*Jz1u?>BBsK6V zenkpF^R*d7Yud>h3P1@d?mYS+9J89!;gbuIuGS!NtRuJ}SG53UV7Ua!#75pIyqY_J z>>9cn4B4)-9EIcYf8rG1D)bh!A0UkKz|P?Hk>K=HRvvVbYg7aOL2qJcGx@dZwXtt8 z+11jJdMB@J?h6G*n!6~4G579WJtn#`AgVx*xMXaFRfy;*TKQEVjvuSZ_Y)^I^7$rC z*;Ychfh*UnnB^LCcEQwtTu2JL3yWP?2|l065FFlzz?3DrCKtm^_T`M#nn1CguOYoF zZkf`~+8GF6BU3uor~{*EQGLrolUq_BZ8JKfS+NBaGc9Bo#NcVQ|FugA$KtW3_74${ zmlT=cn+O%#)1b;nG{j^TRXf0W;ti&3MGq8Q)HRJ&PYuH&W{T1QpD|_Ryy%$^jad^^ zQo-REkB#)|ZavBjL?z+wEI>t>F^}iKZiK`#<|-U4JE3Y=FkEnQUb zImv*NB-eFdF#K@#jnIz$fOLtMh{Pze<|a;NJfwp}x^s3bOfIlblM@V(^)}-ItbTjg zknqY_a@yVi|1TBXlB#n02%FA!)NA&<67d-H1Ii~vB->SojT)JYJ1tJX=YxW5V$R_uJ6Id-%fe~lV-*&bueV(> z?S*kZfOxd)AFqZ~YT7FcgYUjtPJI#>Q zm1iu9WM56Gs=v+ayfvkG62=5*K5}%y5;l5EM75$}Hu`ODx)+lFhI+3n99ZAlUngsE zyp%A?9MX~Oq9*|Uc>484-IQIJqyf>)Eqm}-ztGkNm(5-pdq&tAmKH|yy?l6H?Ck1c z<&^#nag3w~^~J0%6^M#u>({-hWu4F37Ix-M(?0_1u*C=-u=V>mvYLu655{ux?c?(J z@eECU?!o%wKYu%6rvW#O9a#}3a%C{A*Pzo#g&1tUbTVriJ*Gw$;@mr=kZeU9&^~TP z1e2(?*jrapTr75fD9Q5?Ne8$yB=6E@&~AA1x?xVolk&8r^;5k5I$8ISHOgUrthG+p z)2HI*(uT3Vfy2d-l0fey04NL|RP{zjxChaL}RqiE%g58uNO_p@AO=H{h*f zl^_^l^V4tD8sy!$NwL)#Y)KSb?Dv9aN=P(h#Xh65>+i2bSNkNj^whhUL2z^UcU0tNNBmT?(QUc-a^@O1jSs*UdJJpmAk zhJ%i5uuurK&R|&09v(R-t=Y3rRO3HCVNDcKq#8jlLF5UT>6YMe_DH*KpBtf(wwkygAM+w3T)P>+3xR<7*;F^?vp^! zhnCllkR(YZ11$Ws2ze5Ag*HE(a01xZhxHtzjR~Kbs$jp^wCYKR#!#w--f?W%d4y-INwG`3&{z#aYf+KMpEHmUlVED&c&0-n7C?kq2ozf8esV#zDB<> z%V!4nwoD*B7k$)cHEsUvVmfjq3^WUCOD7WPo4 zF}zzU!WA{ElD;LS57*7`J5O1RKkcdrhJH5~U1d&T1`bXq5Xx1n=uE_~cDB`9&O(ryWeWCiamJ)FXNljgVC_hf79EwIhRinHK72Dw{AdPO9o+ko_jf!IM02`0pv#5q1PXsUfRo_J;XRPG}9WIS| zqeX$q`TqW3vou~19@Nj@eZnj{v8&2x)!yw1iN>HHpR^v$ zzGp;Y0rZExb5u z;WGBct3!Ax9Cx1$b#z$l)PL)7CE7e!lRWrgnHeT>Xz^52i1x*5mVLJGZcY6_0fPvd zlve{#up_u5CoE}@a&@Ab_9K&rC%dFq2qouWI>z}@5$6-FLN5aFZJ$g_&%e2;BkOh( zH$jrBpHPBEb{^S9E+03_nuHGgvZ9WVAkj($TBchW0ZH{sw(aQ*vSr{~|NxNrxExDJ}XpZL^Ny(byXpqS~8K4a5Mf-O_ zGf?_ISs0R;+>nsGI$#0c>^Loei{ITCBvs3F)3qj%^v_7Y*q+qqVgzJuwxp5#fk*g`%%$*4Euxm%=EO%7DXxm5 zL&7ni2wcgv2pl!iD)QnGct>o2yP?_{!nqC*M6rwb3o2jt!;^@cB|~bwtx=1V{gNOQ zK+bpbkjQ zE1z-m#0ko+N8CtwzH9w*iEt?;osW>*YxDD~j8yV4;~$1y2xVIZ7Z&(HOK7nu!ttrp zi@xDxIrN`N!UE;(R|{$CNWZ#9GY`a%eggvF{!x;RE0Vrl-MhzhDg3`U4M{(aS--A5 z6^EBN?u0{9KpJtV_48+bjd89tOWt!$((p9#Q&AS77*kjdyF-{mE7NVY3Bg-mj=?WL zd=f^)N}jdCMZ0AK496}^U@<8>g-iJhrtj1RGk0t5PtkOX%H`G()dyyxy^X*ub$pnn zf$sq-X@Ofd{(BRHFV6;>pj05{I%(}9a^aK0M|OXuC~edxBBHDy5k>6L z0Myu?+v11nG+1UdgTpR4JqEaSY8@gde#U#!_rETQqkJFTn!C#MJIbA+-B0t%QFRy# z*};1U)AQ;ul9-1aa3jY4MYZm5axxcq*F_rVU%?1DfXw`;>vRcBNf9BJN05BmxQc98 zrW9c%BnDdqjGP|Z8@i&kgfxvE1QMe?*>~_dY;VI85EW%gI@rlJJE07Gu(=06etv$w z?nuv}j?TrQ<>6(9)1C^86VkXnLe{~nb!^W5Y$Wgznub9r7foS- zP{J!fETA74&l`datT?rLP!dh;kNm{T>!EOpd-g0OtqQ9IYq$LJvXm~{t%(d;Z5Mx< zX3iQR7Q=qmbtIPxF_O~KZs>IU;vOFs(ZH^RL#v&_QidyVh$UgAi|GooEWh1u*^B)) zg$-eaJ=@U$I+9}^Q$Be=o`S&W*)e@4x6gzV75m_%o(+soI8LDWbw2_QidW3MW#v0Vdxd`!47_c)GH*WfHdVO`y1VT7Bg&0?d z<2lW``nNMqSl?*at5QlXv*=Zv-~EJi=lC~)^_MqTu8h^xXATCn&w6WBr!i^72bz=O z8wF;7VHm@cM)j3CP)=GmR2o?ykCbH!VEBC3Q-4TVkb!LDcR+dS!^c8oa^@HqUA)+$ z(2Bt69L?pw@N9>_ePM)F$>GZDXH{8Pm$zWaYMJ>-hb6@W;#_1$nlHMU6H6|UN}!xS z|KJLqEhDH0-Ntp5l2rt1&l@jLQ zN!%>h@4~}y=Ht@|T|)(QuL_K8rKuZ>ClE+2^e)k#Z;;O>&<_jC)YtNh_+W3%(Tt)^ zDv99G2&tsB_E^p|n3H49)#l%#$7^}({fq+)gGs+{DdaI|>o1z9Bbu2{R-Po5(e9kX z+sRm;4I^~GYo+%kLprYdy<6OI#Afo|)SkpU-Kbjm)FiIM(#vsl%{6u*;d7d~a1Yv` zMsrEHVsueRd8!O1pLm@>F%m!3b zTF4Engc+e9m8$>Nf;i8yN_2u5=BiwT^O8V&*`4}4_OgBlL!SN>2Q_?tMsbl(@94;& zY{ClrRS(C%u0M~D8l)9ry@8twu)|@4oc)4jf;^b#Ks3ix4vfj1{$guA+r=jVLo#|# zuJ~O(D+&rCetII6Wes1x8duPpstr~z@hN!f*Ej^Z#VW3BH5ZZ7`!aj(qm0vr+ z#YoOWpj0MaJb3HC|Lt2E+(;@u$VX41KO3K;+K7HBCfY{qJX`!K~v zTwP_N-ib{GdDAUeJVaru+eXa+sE8AU_SmT$YUq+dIAZzBy|dC<+{w0kFR?YvnS)h9 z1%p^dW*)L#WuE4Ek<+|g@msPSy+AX0jscWP6x+?@XFcREWx-nO(H;)N?VF2# z{B@j=n%xAu;a=l&oubw3?Tg2Zl{&H5$b^@q@1f2v(pD@sK9F1UizJ? z+&%Db&0(K&Hak|)yjwUKk2`4>eR6p zRpbcsJ=%#pYw8<+#llBuFt1Gf1&svpj`T!sDiu`wkl-esOxk zCb~?6no}QA>0#fk&C9(u8M?gZj*poV6LoHhz8eFW#d27$%^MtOGK+?;oA*8m%PZn4 zJ=(${G=v1DrA!@KlC%3mJX9MYwj^1`qw;K#$3-cFYZMp#0;gX?^0x<`@FJ&*lLPOR zbPOAvGkfJ_(RIR5#426Uo zfL_ac2HYYe-aPLpSsCRENm2o{3RHJu3Qk(F+=u6Vnz800)`eESiWUMn4bkA#Og3)r z6M&})@4_!l-R0wrxfO_|$ygq89m?@r&VNe17!;>t`W#60oA)u(ZiV5NT*79ykq~?T zk&Dh-3`m1bYW+~e8E;V84N>nHU$IE|D`8@fX5k&Aw|@tWvI!0L%ZnDa*1aySO*XGf zmDy4ZU>Q*iZ^Mtu9HArA;%ABxtdRx|h|(O0SfI(@8;BmN+cHqy{6Vt zG)1)*%N^@udLG46&CMGk2zkfRi)yv^}OA)r$jXdDejF z?W=4IOxLQGyV&VJUtbcCykHo55Pmy9_mBH8Mzp+|`X%H`#`?um#_ z1@ZM9@tIp$yMwb1#8J$n4NqtMEOW@cYm`%R4T`Eozl`O2+Sc-HXqJqSG}PrfRd z5iGJLFX0JYLpGw?7)9m^QU4c#qSuw=0K99|^-gclYZ(cvh#;t#v^s#qOY5b{p1h#2 zcWnoB29-O5g- zcyE`zn~x3vL7(1S$VvF<`x=$x-I)r@2m~Zeyy&~TV@ebSM=^i!kqV$QSyZVP!-uE| zk^Acc4knkGB{g{=l(AJ`Ev@jLLAU?vd^bOheH|ka6N@cJ@S>ujFD^0w%wOO(fja<_ z0sEy6vSpBWO2SPSzsvT1uKoj6SM9Qhx5zwo=a`^fzpsd=#Pc(zZU)g=ON;6MvGW~U z@vF*^UWt?oM(;WJ5;HW#x0N!US?!RQd96(N6DMlOfNk;RhU%r6+NtbGHT|P$v|BTL z)oaXTGPw;$ySUZwFS^WQ^{sojpR5`0;457+Ayy!@O5~1WtGn*Ja<}`4Dm4Afeco)8 zar)bc@U9dAD4R7A<(y5al}vMLefmZ#8%AZ`uV-mYLp5b)yV)7Q!mN}(@ze-^ixudY z#+pT9aj@jl(vD+h$Y94o18cJWTPvR+kS5CA4omBsj>RfS1pkW8Lmv4y+QEY7;?5%gLR?wK-x zEtk{eibN*H%Z)DlF&LGbjy{Z1(`qprl}0q;GjG`PM zSx%g1;3|<}@=B^yWZd4+3F<76A^Jx?192@PZf&@YhxB};3v2&#BpQ$=?DMJKJ$h$}ZF2|r|dK0VELi&+&_(E~cPTB}>wIpjB zfdo1uH)Vln+B7|yfxQ@@)qs?-dv^*}}eXMGB!}Q)W{n3hhmK6-VSkyA5 zLn&-r=|G{3$9&~f_D8SpYl(RD=ZRYNwYEpuE$mloFjA{^TF@31-bKiys%_+pDYWr} zcNoLFK_Y#eUgN22@eHQluj6fMG`Oz-uuS=2y6vWgUDP&uR>kpC8j>b4z#WEcUE&3D zl7ZJX!TK)oET%w_z7)J^JZB0;(n6~Mt{1S;Un=QlZ{R(|u%kHmTkisByYDvFZDz_l+k5}d zhtQGUxCunRIIEY17+e4b91M^$1q^)dsc=u&G?j|qLh;Vxi>VE+^qMYY#<8Gzz9ryT z-!*3hKTPdptBB8!@20$*xf1Y0;Njyy-6nntLv7R&?NP+%g@Ge_xM^9YmhJ~-4Oq_r zMl8W1nr?G82+(OzU2MJ^H;!K&V>yOfgR+nEM2LkFHXE~#h@u*qj|tQhbU+w5qz2REt+^#Z!*J&A7l zOmPC?!>xtJJr?cW^pS}$M=)5Y`K#XVVcudxpVJ?wNT zzu(`Q{l8aWjFhk2)wH*ecWj%@_rq%AEE^%2o(>l%f+dN=%buIG%6e5VcIbTRqiXYb zQxM7S20evJjo&$!vX#bb?8ay9zZ>h_=}z7rSmM%c!Rqw@^9_$=$JXFSNkYn{0Kv@-7;3aSCK+x+HD#wtZ`6nfPSX zaiJrT4Vb?TZ7tikDlZ-oyL0^&DUfkQ1OL&sgx?$7%&mlYL>g4Zbon-#!D&C$(GTsl zkwg(5c{u`k>sol~D}+t5ww5TF-<~e~N)wt~qlVX4Zc}QyK1DG)^8S6ay>|=(BTh0E z5oj!{45q~=BJZ`MnrFS;X}ZE!!vN_J2yk3z=2jZ4b1S2bq23T z>J{Tqf%M0>>)}&9BA6;|!e2kRnOLZUuMdK$v&GS42*kCeDSmwdVNQ<85VT&~7Xk6H zixhnZE@E(4IYohBxXP~1-lS&%pIl-=D~vhy^!m7%;iLgt1^Y+%xX(3Ia0zW;cjd(> z_^cPi0khAIb(qNp^q>G9_>jZYx$*oAXCAFj5hBiy0D+&P$g_GhPz*^evsTrslQ1SHeLS``=uO2e_#evpUmiT)IyZ3 z8#u*AgKMkKjs$_7etjrMEtt}rrr1h@FQ7V2I*5;$cS_lG{G&JJF8OG+*d@@uKtq0a zIfc&`rJ2qa-vbV1{qOo49vW!A!2W4nW&A5I(+%%QVmkYye> z$+4e6z^nQ`yP5yHc#j$F1%HA58Zt98J>9DL%rwC!X_b=C4T(Oz4F>$|NJBsn45q@A z#lrCFDqk-9gO`zXU+~7KG8k5< z$8@fabM?jBBcaQ43+T^rVk)qXdblpaMM`Y^La<{DwX}-tiP?Dv{fxga1V`Yk76nH{1}FA#sdDrmzuXag6^H(;nSNz9b??yg3XgB{64Ri^vsS{BFSTA@akD#W#8n|Kcu zM+8>e-?<4IAk6P=Vp<|MF6XqWMJr*-WC^X3V@xGb>}a0$axn*unHaXKw5(rf3VULt z*Bu#{H~j%t>6d`BlLc>44a?y=jA+tEEO4_eSE)DjPRfkWrfWZesJVzur!+s`iMFb2 zvns)G8iv#|0FeaRfqi; zAnLTi>9mO1=s?36dA@oIA5t=C{hM#}C+4eFcl0gnMkHs~YZKEggO7&kVcr0}CJ=Sbl7P&WOJV5(-62a}P0~^*m;k4IJj>v)O2E`gp-h7!8Kc-vP zw!+sW%Ye6rCJ=$ObfL0} z7nv4H<3K*3Q2=8C{O%l0ALYi!lo06wkL-o0nMLUQEE)_Ij}xYwRiTD6>!TixW&1HM zl=8wi(<8||nY9UDIB%rp`(cxaE6KFRoZPkru#&f#55vuCp}8x_Y1Nw$G>LaahGJBT z_!(HZsuwBi4R`msecK z!WEmYb62V7ei>sh6hexP*n>Ncd!;OqL+*NsqC0`dn?N6;ps?NGQShMS287Bg-S(i5Al^he)G9wJp!DhaqRg%fVf&7O~||33UYD}LVtYMEOT zWJTcDL!@V%cRbt*t`23``L9k47tFC?^F0nEcs3ddSCh3}>lph_sEU3RpO%Hwzamw& z0Dltf_R)Dyr_Jm^2(^G`EBA!_WaJCh>74rQXs*il8&)WOrTbCIN>(zt1A-yxZgf8Z zNaunt2(Y<>`Sft1C#Gb?KBcF+seR;1dt65C1@`~bpel--FeH%sUV4qD1N11{cE54ESH%6l` z88;=+g>qhSix!6vkXd)BL+NOI-!b5Na3Odq@|SG^?_r{oHxmpBN(!g(@*3t+)RrmL zyZ{cC-vTJGbQM<>`MILiH;Z=dByM;z4HuYx#6wM~!qyVxWR8dLpmEUmR;CA5^hkhR zPWFXdytrh^%|Oc>e;K{3W)g;WM=XL>n?vQ@7rAtyeS@i*<5ZORp*n!r4dq%>iwdbw@v!DD4d)K?IfmiU|)**u(BSa!wLG+_Vm4m4rzwBaNX|w-_psK?zD`1 z(H;P3fpT&MfqA3obl6(bn|d7;NrXDf-$epClbC#n1~(3N`tRFkGbFEtbwZLD;d)aY zW}%be_KtKi3aX8)(6hu0w$^klScF$lA|u){IhdAVZmXDa?P8J+^ts|PF-DDUK}xmY z(6!M2YYs6JC_&%7sWEn>8TPBsTccf!A@*d6`mj`9I25P3oG|?mf+iMcpiwcKUZ@P>%WVl35A!w4V!&_9J?vWeap)D}I zki!(d2y|e^cc?nba*N{lEIcw2gh$u%_D%e{%Q)dkd6tD9w_ZrAR98 zSD!t&T=Z?Lol1J+O*>Oq)PjDp$$5|7ZEe~u#Up;*nh-|*yRPBYGAe|1BY_D<2yg9S z-ei58YgJ7|3QKo^FomgdvROXS#xGdKW_!PqR}_312G*gIo@vhUg2ggBY9#T`1e@Mb zHu!>IADfx~^+GQEi;5W^{a7^zRw||VN7Pq_WG`ErY2j5pg};lq9X9->;K}kty{l5@ zFe-K-t6TE1U8&j_8tJ>yRwUIX5ao}O6K)v&7qJ0Dl>p|%a#IK8h#Es>X@U24v_7*B z93Gpxl;OjM4_kxJ@srsp1e<|6xRaI8pXdCg;zoPG7qGB5#i}#KkbAHGE!J7Kxb;dZ z2H5eDl#ltdNIhpKm7<>+refQ8GGiqz<9)8_Iq%GW26 zl@#C4@thF%Y@^p#HFZ*y|Jmpqy4-n>J}|f(vFU;KH>EQh;U0AAnJhr&$Da<`Y4jm| zvwJhJ;8bMmG4XN>**BIjmio{hs-a^?LO! zfL92&V7}u`D{r2qPXcbvO4|v5p+R6bK>n1DvrZC6Rte>In79^kgNJ3kq_CajaForEjY-~HXZBTlPwDFm!?M8=`y1?4<-;m&>rOcGRrMiaL4u|(!Hg(p*syDs$D~^T1M3G(*)q?@_ z#5iF178!u2OYTO=CVlQPZLLUx2a5TDj=(l;VtKO(hF|M1H5%(i|5K!fRa4ov^haxxG1i9!P-6=v0s@Hgcg9jcNaq03)j$q60j}v~ z;T??4CD@3K0bcI=LVi+Y>yZ^**@Qzsi(qh*W9r^am+9jvqp0dZK8EK#6Ra-P6%4;e zBAoMLbn$!Eq>tb&be20AnAA|VNjq=)_4@gM$H!5B_LG{ht0Nqr8=dY_G}@!4t=BD*OyTBGBB;S-@5*J zX}|G8M0QGGo%}MuB|w*xbPL3U=e0B$`czGi|ZQWPqNnS(K^ z<1DB4%mNGt_u&#k_4SQQ0rOdT0vo8D7uF^>ZU$P90qM+bXvW61K5RA>)I@*UGIh5Crt2h62*DlW|FowuY>~WqXTX)MfmLp1lu+>y-U?Id>P!q3{ z224PR2S3BZgOKICZ7TW@>bqr<4r6cP!wS&brK)M71z@FC4RUu;L$7AXj^AC%=CbGP zJ`I98q!!Dh?8n}LtRj2be7U2djO0T+8`Evl_V7Z}B97_S=rk@yx}ei{M^v{P-wb_6gT9!- z5ba#9&8z2CWv-^k(p%jJ0vYKw7`-KDBXYl-EbqFjQQ4d*jr)f4$}mxux0IkTN$Mx% zS=S|*YJFxfM&rHaO=;5=+z=*~okrK`oJ2(r**s#Uc!EiUVTFrv0DPq$#@nX2w^0JwPL}8(RE+Pj6b#>kX zObS#uOYP|Q8}X2~29_G0`4nFL)ZpV*l#7&WRfntj7q{}96Y6gWxc8yC(k<^ehr@7h zRy5Al5$1BYsOu;js?LdS_GQ`f2CHERoMeq$^X+a`H=LsB#GCWEbEMTU!f-DzVa(H zbx_;SKFd_5kymmgNW8rFxWXspb;E=M8Tb=&woAV;)gwp%gh2yhj$YKkXG8h0cDQ${ z9`@{&>x;T54h>Lo4zq;H=7uP2@eGsT-%GmRw)gS1q(pns%dU|~I)c$yI?7}zHhpL*Gr$7AWS9*E1YYgf@$xtan!xffRwwWytQaY3OvC zYM1ku8Z5%$CA*0{WzBYNkrF^5pVM%ZC={YG?&sp2Hm-37hzve&u@(*04cj-&DrLFQ zS$ur%Zo_ZWjBWUgVvYt$=J_9WsEys*$>0>`SDyT4>UA+Pvt>cSNeH{AOP==69ldg) zarQ5{LU zPfx&M0;L*VmdV}C4cCy<>!c$a3H~@unI9|+4C}9v+LYeir?buHvd5qp8m|5xUelH=0lX7m{W-DSkAnF>IKqjc)|90|?ir$+#!+uc37FYub6 zv%*R>W%Q*`23h-{k1wjK)sRdvxK1YK--MhkzuQ~mS}f9yb_FabI|Ac~!f+b-P?y^! zhrA9n&H`*@-QwAV3@wkSy%vZpluOjJFBEspjZnlFcl1(4p@rjC$1i|?vnU4AISliU z5@QCBG3LjFU%WZ%&1lW1xt+YDl)G;tQmQQmbPDvd-Ij2pXAd_5x83AQ3wE|OYxANK zL5Hqz9!Vf8v>_@k#a@sPjO~!L(Y%>bW`@ZeE%Me{gsVw?nq~nZoQ!>GIfO;i@5R|{3XfqyU)$N zz3yWRbX@VI$Iw`{)j>^Fam*q94GL_k-1Q}!^H=w4zk4Yo?5~Mt>-G4xfM?88cBtkU zd$|PV4+GhDI!U*khsuD=Gz+r^r7PvSUv#EOh`d8_vkKd-_DoE8Hl3H}*BjZHBvYON zY`u01ihy&Me3M&PY~sX8E(uRO^o+=>9LW;~QQe)1s@k9|Tt&DJhEYVJ_a^z@oqGD^ z>BTC|b+_z3N&Q^sWG+U=Sdx-RRK|VCUd=hM1P#dR_Y4>~za7f~`0?x2;4f@)0bdES zvzb8W%BGGC0HCM(QW4(fs@T0!>zsa)$hzk)SlqV*X_4Ppb*}t_7xoV!x zU~H_a#^D_YXBI10uNGM_p5zlrR6&-|Mglxc!+wvvZ0Gcl9xH$U~HHc)Hj~z}Ra>_{ai9wNu0$j;E8;*b;iA%RnGw zaufToXxhJ6wGCm6~f`*9KI{sq;82Uiixr-I*mjZh{2VC&zUjh@h-b&4qV6hB3R5hc)Y-ypliBw@W-i$l4IK9Pyxeu z#tqb~+qEE@j0tH`8p}lTjy+E$_?FRsg(lq0(vn#g3EM0SxVZAn>QE!7)E5%%QPaChUrQ#CU^2`5 zUyy!hcUUoV^D4^3WvB-X$gj4c;IVrky?9EC4O{&9PVVe2#hE+CkoNt9mlQMGyEy8dYJ!2j&{Pl^PaP=tuaM%nsyb)D`!jJJP>OBP*;ZweKOY$q>(0L=I{92kZhV zn~mQQvf#aE%jKzG>X?^VKMTo!Fq?uVw6c#LX*-TadAJLo10iI#riMIq%?xhX;VEy| zUg3k2{RFhsLQx9}bHA*gDC%yy!0dOuhg3gL%?|s=Pstum5zR-Ob-dO|eT0FLJHao^ zp2l+qV^2d|V63oNDgq9{{jOV81$PTztFs23MSv_5EFO}-nMqxAU|vg_Tw7l+8;Q2- z545xQfc7|xi~MjtW!EIb1E}82XV?q}bcR1}^e9@V8h9){_2(49t-n~(=QU*E%esN} z!`4mb{9eNYAfLgABZ&PQHXqh_={s67(6KRg(KvA=Ku*Kau+FwEHk_r_@h}t0V^X@t zd_E-Z06&6#+YLjzPxPQbMlfR`Uz2M%0CiRcbJW+q}~PMrvc z6*b{nG-@wUXa5HpL(Lz@R2b8PWsP88^J{W>Q21|2O`fmMdtjh_&Oy3|^~h`I&e6&e zDCLHW;~Uv%7G7Gn9Onk?ozUw|cG(B|dL_yDQRFve;`f}};o(MhQ~I2k*K@yb+UpoRBrY_Y_ffWNtKEe(5#%1&oVPlku7F=p4F|GU2TCtW#0sJ{BtvStBn7%>PQfC*+D4&0kmjO#Oy5KyecJFgC}fDpx}=5r}*D%J|1(pDUOxBktPR= zCQ0Y&BLkH%;&+@6?t(W;GqxKhbnVPtWe*CstrS_%xwNqWx@=_pO)C&^$au?tK2)mG z74+jc1I_}EcPRBO%OWqp8Wd35+4=M-F+kyWVj`~cbY&(C91uAQY~cH=6U3XQ!hJMBhSmP6RO>Nnt-ivL zCwq}vL>>M8D8gxOAXjBC6p9aYivT8;n~-Zf(ahxVg7p{+fPXuSiQxcOC8{cTM*+kd zd}wq+HogGFa7ft@ve6rE?RneXjVt&NGr@&TAOWsqK0c~N(>_RS4#m`vSjl*^`KaJ1 zXoH=3x@hl|tCj$oDtcy@=OaY}{n5t4G(lGF`f-~%_?g10!>i$##eln(wuzC_*~Y-q zRO*8x!u(OmVH1*GwLIGuKx?a>HIB@X#gFJ@RB|2HBME40y#<|n(r}jMCXk%T%kL{o z*YBHfzmt#QA`Fa9l&aX%*`u@mV($;N9*z^3eXl(R1ske7uPN=S9$z>VHee8;e|`0) z?#v)pn4%fdy*XY<7R%sRCA71?nvhD%l_+Ublt~L=sktPaXvDnElW_%6NI}=PO$lvI zuplBo>58AL>IA!N3{T4nGy14<*)yDA5a#ndCUd&HF+wdOA)SUs*|1A1E1{JrE8lV) zE|Fqe*|?_!t7SJvj_i9)Nw7^S5oaf8>ireOHDkJMW3Fy0o&0&&SK2Qb(H_fzkwH|U zzG#^~bv%?kNkao1N{_fhsg<+u6&_GwD~KSCu(}DJd>|_G(FuoyE~uB+EQ*)giCvJW z3Ih%N0SVG4l8M<24v+avi?5?<0?LbM21fo9Hd&t0mr=^uR|fLrOf@;{EM?~VI8x6o zLZ_w+L9POyXx^Fl50sk8aYUmyJ?S|lI?r!lM-}jJ5_R)USL5?*U)e|950N;5D{c2v z7X--{>%VzOU&O*$0QZM2(Il|iWW6zalvj~JNDFGV<4=91#y5u5KO;9|=40BF!vXY1 z&YT+=6AX19DC|*@>I2rpnZ>&68Id5II(d#Q=7-#Ij20Hel=P%k}?`3^~K+ zWocp09&{}Jy{(3~C-AbN+jb$a2CwrNBqMcrVV9AO*}W|G1LyV91ANLbUmR^Bc7z-2 z{79_&!_i4CM|IMn{1D2bBCYzXUVw~A znyMUyuG({iHikVw+RSM9$SM*tSGK(1>mfhYjiYDVn@|tsgNE~3kfp}X~#Cf!jdf;4}hYI9L-2?ukdoB!?a($whp`3N*vO!mc>DURQOkQ@Yk74*2L?lM$bwF>pPF?1-Rp z2&!^z`2$vu5uZ}wSQ9`hcxsf!5z!~H#Ls{2O_p*05X1?76ji?zFgV$K$D5}yfq@Ie zzSB0VkIv6W!I{8!M)1A4ohpuS zn2^g2mU2@gJI?AAQtkO3vZ7nE&6c4=(8|H*35J`7=zWN=LY1U+>;YU#*?HdESNPrk zQ^Fz!f*V>N#VjhiD4PM%6j4ltb#xj`#yuG#k@8=GvNd`L{~*+y!y}aEU4+Wy@l3<` z3k&s=c+mNZLmR`k*0OB7=bJWzp?(w^B=7@f*#7Gk@no6lv+cjMc8ApG%Gjk^ivKpX z6M?I$I~%x?YG&324C~ z_?nY>XPnGg&_Z!A2TO=ITls z)n0#EC8RC;wv$_;_OD#l(z>n!$BP=!y4((dipdzQLg~CB73Ky@x$saVGUwZV@GsNf zIIH4XfP|=BnMt*W3!Zl(vx|;7EuG222QKBS-Orpes}eDJbePaA70O^=O!O6xe6?+^ zTDh|4nkZS1QH6)?vMI6%6DVi&5`mV>61)qpTylVXP^3-`23cxW5S7__kHTpAJn*ea z+o&LJB_yoPevG7{d3-F{%DL~N*uFlg#kT!DlkwRQN4U%`f};<>q-rNs89&9r zJh=8*Xui zRkX04*_@CUR1ELn(As*|^r0G=pXcL2PyCHxq=pi^6iI!4SShQK4{K&SQi17pigeoc z7ge`Mx)ge|tb$u%198qgWkP{N3&g?dhX&dhzg6@)z-;?caX zL$$=D>QnS*aOsT-k@b_@rI&Q_k!OQM+@h7;zfi6YiD@ZDYU{i2-|cEXuN<)2%bKEe zOR7|3*S+1lm6#+zDb&r96@X4t^#Pnzv)}>k@IFMPE1fQDE(D4pS4Oi04(SV(*k^{= zm|aEyWW!nHkiuT|2h_PqHJ=xxN*poK5EKq`nTRJJCJG!)Dq>NOiF0U_!B1(XeoB9P z=SCVT`d5?0Syg6(ege-7SSNr*%c+A84LIp?gqO8r+y=s5FGu^) zh#KL`}cDGGVelFAlV)(aVa(B3bbBhPbvc(!^==d28)` z$FjtDS~gq0_D-eHkB@2s0aD7<13g$}`7nxKb^)hdVCXUER^bgy8>!>UzOGcVNo?Sf zOhW?6(U3q$Bw+T{``82Fon9H>xP@{jzWb<17q#E>bycy`9?f%8@a^g9%g6zr~O^9qOZxJJJ955#(P#EhINSzYBVWb_~)o7S~AfeUaI|L2x9c|*<_zr3yE)A$#y!k z=}V1P1%T+nNG5*W?P>P(ig>e})aDy~n;J0B&D}Gwc|SasoN)%S1k~x&Ub>~#J23QD zQ>!wlkt1L};#GR!w_S!R0js#AuN?Z_M1>#^gQbNJ6Q_YzvEkfg*G@?W`F?mcl`pXb zF2(xOv{lE-X<(I4rtHqmk>5HFzWwZRG`5|9R?5fwU$XphVua;H86f`Vgc^q4^QmLV z4mJcV-OO{h!Km@g&F-xKKa_mf%&>ct4%giuO<~|cPd6Lrk^87X|hYv1Pi@t zBC0XA-ahtYcEQ&CsX%gZ{eES@mgno&#uV8=Gejs9_2%{+U(CIWw4M*=;OVU$pnG&D zIqfFlkRsNR}(;8^nw{`|~`_^3ct`#b-6@kVn?6Ta%nb_!g2HZguhNwGBQUfGW!}z@K zKsv2)%`WV+2p$6r>=_lb`QHsyH`8bxj0_n>{zwJ->O(dg1r#W)8<83>!ck$o8r{;7d&Iw`G|C^ z_b#~hm-_FcVdMUNNB+eaC>m39{m7N?^#X?!Z_1X4(3zO0N+dyAj81VQ>3Osgej#y> z9bZZM_&M}h=~WgJ2n(9`_94Bt&g|_{!QRbYUX^dxQ3}>8(The4;SXIyX}QX|u58N1 zcyk9v)p_v9ZURue(PDthzwEFgfU)1|@>o4F9GzOf3$fJ(*H)_;38DE{58bQ!3^5sNcgaFCXkv%tXTPj zfJw=ANBg>>%A2KOjJDu*8;sG{RBPU{0MI=M)Gb4YRL>m~Fn6nm%#kuIh7d8dF^1|54}AzUpKsY5^KciIeA*yKw6BKR z0*{7$IbbL80JjNW^qT<^!XY5+&||exP1R>Vsw+oT?K_zJ;88dL-P-Os$Ln^Lx@>)$Q{M^Smjk*mm}*r{or_K=|qF9a`{! z>0DlWchC2Je0c$Q?BXIO`HPt)$BPZ97FPZ6+=)>l+jazDPVJPfCoonWxxIWeE;9=p zF_4M8D=mGm#~bqgveLbTsnnKZ_@dd2iE&sA{rr9K-o>9}DR0ePFb{Jnki|#A{}uAP z9@(o+hvKW$M|~DM->yzOR18C=11&7Afd%0avy=uBh(=}43hhE>B#1&`v5qf9pxqN{ z+58QGw=I6sST1%cff*rhhmP33db z54oKlf24UY^+eS>U2cKinY+P1T~>-Vya5x2f*|ePBafISa23L4jEQ{((gysax)Hf} zA8}D%VGB^{c4fgcbcx{{EyMZA4tj&u^JA5kdg@T5k<|?H0|)?5c(AU}Q%l2fxmWrc zM9$dr70P^O)TSl}&0)%x4c`pDH%4lCnbM#}Li6V%r=7;)%VMg8KSU{yMD;~$L|H#B z*f=1lW9NWe6~JEwe~-yf1Y3|KsYI)P&)K!1pra3h;)cHtcle&8<}1Gr#A*7$4%x7% zTN$IqPL4q8Jv+ox(ViMKQ$iJ5t0^)RVM(r(07Alm-FZfm5qe(%LR8e^>u5C@S5)sH zk5kdKJIJgpf-CkKRx~Lco(suN^;I|1LWx&z;cC?%^462+Sw@MXlx3kBvC^kQ?6-lV z{1}i@S|StF<uG9uS-j{2tH(M!0<|&n^}I+bzuW_OfU;-Qtavln!jouO13xFkBlj zF$Hmvn0j|C&?Z0Oc}$~sMGG}t%5^k7H5;_?ISQkOu2oY>iebU+z#Y3&C}w5tqE?ol zm8yGcR;L_7%Gm0J9318mvT~oa7rZFlsxX25$w0pk{%6wtSxqI=El%a=ETdL7A zE;1^KR0cyN{PY2*C}u-EW107h4+(B0^M@V%rSxgiB%bZO*tJBJ$N@cdkTOLHevUNN z-8lf(8a}qAN2hOAKu`4qpcf;4bODgQza7p6PTAiG$?V?$&ftVXx~%HLFp&Q>XGGXSNks7g+-c@)7!w{0f_JN@P z2^=C<`N^TU%tfH`+c9eI#cl$6%to+qm|iC~;%hTptw<^ehYuy_OU@*`zyv;z8x z%etM5o&$>?;K1uzV}~m-`X&=y2KYDy_cofFMVY%FV1)HawpsUjcGN;LyA~XvIvjgkK0jDB<2&T?af|MUzdsF@!XL;SOU1ztUq(3H()VP5H*x^W3Io4Q zny7#My4(sHuYlc;G_tDSZ2q-~)S@F}kA4MQ2T>V1PS4cYCfN0IP%@@8`eG#4vZXF7 zFpj!Gd{q8vvE#^avtwzH=SF>AiUl6vJwFLMd#|i71)#tt12gv#+|N~ymMr~w^#$_s z2j^K20r>G|MKfp!78V^4Gog2%&kd@RU8E@0193f3c-Hz>b=)=VFiy1J#PcD z!orQX8n@*HWZ`%3wr_I;E9TAc#tejtkt3nfZi8MveQ4L}`?Kh^PnWCRUJk!iXLB-X zkW}}evh-8(U6dXCrM|7oL05m_+CriM+fULfnuQ0R_X=vZEQXIS%GN!4HBRJd7q~Z zo_co%(%p0dI+dD#z8Zin#v&E7WhIvnuaD|5AfD_RK)|o{Ts>&A**}>T>EzqShtA=v z=sGK_X#UpZpC&-UK`|&9%+jX4jU~SDF{Hx5jVM4`s$ORr1qiuyc@IB99T*`dP6n0Z zbq`X{yEz+lJ-%-QpQAPMt#C=`Kp-{uL|!^V^t>0)F*b+MKiu#%7Sjl)rmX|>G-m(3 zhI9Up4f7u2t$Bf-;1Efqkfo;DVHi=lBRAn2E@jkwMEU_oe1$y^y*>@F5Igg#cYCa= zhTrn%4a&!5I?$6v3fcOy5y+mFi;r$-B2K8*U|B`AG`*HQ2w5_t*6iMH>LNt4QU%>z zd*`-Rlk{@jB93?np>eOZTIhZ*T+o!)@;~^4H3QUe{N*Z#1me1c$|28W8P+rK@uD)xdhxr{6+_{oIu z_oQBOgVIE>^L#4UJib2Uj#`AJWZa1kuG0> zvtP5jwz4T8_KLjL`$r#^eE=_d6JxhjXq+H+eyp#8T|T~v86;8yy@HEccn1I|PS@d^ z8W060T~H^VTS^p)v2!0PC|xviBC!)Y$&b8B4% zr;Hx>v`DQfXIBw1dSi7UV_-e*235{2MTS?|Q{x(oS82Mybr4L{9*xyD+OVf~bcZ8V z!iBoFnF6mo2(S2*Dg;iS7^UB7NM)_+U5Vf_6W2@qMF5SK(uMi3M}Q7gyJ6e5LpdFe z!!(rDy;1|+X@2mTv1TWRN1JPEHo4L^jva93jz^}!Xv1q6CN`Uyip(IX*sLlR$ID* zVIPB^tSClULSEP@fm~D&i*Wfb&9QGtPG7%IC)ap|-6r3qS3QnlZ5il0zY$yPtxS2h zxE38iI0W_Vi8>^l&9e8^iq&;eC_mvV6xT{WfLmDDG4TYw zUvv?&In0Y|V>(#ubY^$T=~d-6G6d%N<+H&yjS-h6C{1CP1!|RsHRNMALxi~dwP+2&@BLB7)a=0i z!rLEfpgFC=YjrBx9K3A_-Dn!^+As!f69Ce8m;u1|pZ{cYB*dg)!p z=MiD{`cBCA(76?@_2`@#0O^`9$;>YOfc+tn4mo>}I2P5t;Xa zk~_A|oGgH9oVO|7SqJTKTi7B03-C^T<5Z3XLI9&>Z|CX2?Owcs#2qvWN;8{x%?Fsz zUdc69O$IxvFlZa@gaxAm0+qs%FA!96u92bH z-EFP;W_eurL-K5j|Dc5zMwn=|bEmavFR*NTsMc;}>R@dNgBJq>PDGb~HVI9=V3=gU z@{P@`NpP@&r)9eS4UB1Nq?=Cx19>2IuVy(1uHzu-@~)kQjDvv@akzozi$)hNlNgs1 zb!X2nM8l70iykOQi^j}5%MP7m{R+g$0ta~|@>7@gA+}lcz|1gM{Bg2=__b{u@4dMu zWlYvxsSJq-ixyutFIX^W0u!sia%T8D6Sr?A8X7E4a(A9AF6A|p5O zqc|@;A5oe}vwAgEYz&o6lo+soWDyFh&1uv%-v67nNDBj`gSZ{4T1z{Qer;ORJ|!fO zqTFmCUue3hHLCL!Tvyab@BuR7Twb;B4`U*3g3d}~URJQ9QfAh6@@TXukLsP?Ugcmh z+h8&I1&#pLAp9&wLTyz7k)1F*#I2yBxV-bNr2S8grEH&mbb8}D97PBTy5$i*WfxA1 zc{-rckI~w@lP^`80!gl?AN7YbxrTCgDLVVV6+d09YR=TeRt?XR@%mi=XPZXD=cEXuZ@0!cjOLne?_Ej)B%T(lQ?fxsN(y%24zo*=YZQN~kVT~q5< z^`5?}xJOse&n#^Dxo()fz=i|qV}MDa={1URP9~F2UBIL7JW$!hh?gG2uHE@luZ|0k z=x}ph$fBgb2Hy23()#c#5?r~?>nuBR$G|eQ)#t%TPcc|~3>x6&g(3`sFauoIzRmL6 zjUtThn0QY$wpWgbvzPBNDdloO$@tA{y?X!egbV$(Qa$1XfHIV9!&DceNZ=xGySQ56 z=drHr+8;oLT*xG`AZ}o8`fq(Dan@Kp6&>su0(94sk+EQ_m14h7$FXMuO`V*2uh?WIj9dv;jH#~>OIzS4kp5VVnIyi||OsA;Xj zYv7t6EEv|IS_aI$d3j@NRl(DSOp)4!awy}XI9SR3;c!s@t3xNM?^B%F_enB)o$Uyp z`gF=4Zlhws_GN&)~X}DKsfaX zo2BrtrgGNmxtgLTZb&y7&4plwLmuKQDd**cfB5j0RBMk~vLvKJv(yBDD>+ zH9g0>JHm3dgEk1hKtrKCXj`&G9zlBPAG<(Ti6yF5 zc7KGq3{GI|{U1~l8s9UF=$d(z4LKc0dbp$hc&mx zQ4Kln?WYzO3*7$EnJibwh4bdYgq5*VGs3`SBf`gdAbztJ$ zYV5wV+`FS5{)p>T*_o(ebH2=PfZ*1Z`9L?5HD?$v%n69X93yQtf}Z?ifPP@8{PcU& z2r)^?X#gPhcf-V^PBl^#xM*%Iq*Q%=yMwf-C=MxrO+Em*1;?e|%4|~SEcGkeajFt8 z*p%x;?XTY4@gI;?_{xWso}Fp$0@K>JlsGHOfAZYv{qASn4X?bQ1ek0Lj@LAs%Zqq` zy@E-7@st9ags+|#rHu_Y{#GRX*rur^0PC>{jlemdbf_@=dDT0>gY~dwD@R`K(m=9s zUe|${(qgjdPcdxBm{seG6^f>`EP3f;N(jru7xb4fWJBOy%etoemZiQcp$&jfYvPD; z-JB65-dPB)g!2s!y)YC}Uu*Br7<#_qSVN9R8PAw$Nm+gs5ajDcWpXdqPe_( z!4-GBDz)TRzD^LhovmWkjhyq}SQm|>0e5~k%b57-i%wFzaz(cpmrbA8wP*IO%_>LM z4g#x65&2jFwR+QR@W!FfD+RwrnlvymEp8S>Kn1v9d128S&9h{5U;miQD$tW)NqkxK(kwNAFA;L&@vQzVL4jwfo2Oe`|EvMjIjaM_DVgnXm+hOhNG(q%b?oP~OSd!$w z{YjncVn7-Zy<9x8_N#G+x;KrMzH&Nn*D`YE^|Yg+`1Dih{y0Y#y!dAp0({@ntL9^K=q5 zj7^e_@_(@*2{7ns0?$d5hv?ra`!j_}Fi>I@3x;M{jdH6vc-ZQUZ(MZg53bl3TsaFN zBGVW%mxz#Q%aW!b&(_+@H^FCMP{|{HNw?#S<$U|Kopwa~u)VdzutNM@5(jH_2up=NUpJt+ z9uG^ceT-YS0_~M|UKJJb zkb7=C0mraESI{5}XRocg04G4$zt7Wj;i%^vy;QU~-(^W?PR`4g=Y+_5iGy~ksee(A zE3e5^HRi1MnuN7)HMI1QCHyaOTDK1V;zlurw?k-`RS@wXD-m(1)j zvr}N*q?-je8JSI7h?^BG=m!t%v3m`q+Y#ZS<{*kN*@{UtVH=_uRknv=(sEM|-5cme z;I$bchMOH#j%ff0K5Y=iml+p?7IfEB+;hXjhATSHuy%@9rt4ue@Bg+dEy-dg15nB$ zC6bsR`TR(i7~$-dWIo0J!B@yF7tZATEGRe9l1P@#I1;u-`Ag{Hux3{Demjb6d@5bo-YWr6&*mLwfp_gpeza2! zQg33azwI*PI`8Jho@mYrR}*9OWHe?A0HiTAhBdJ&yc-q`T5Ob<Lz7i0Dr?0Q1Pd&o_9=t!$2UvH2`vY+Ncg>pkB#%RSE;wPd%TZgxlX)QDBsj^{cKKcp{5q}mR-{Mqq9NVqzE zXenV5Z`FZ)x@jD&H79{+N+*V9D76Fn58g3wA&K{sG>q$ZulBn+tmjFoWrXoL5;~BT z5?~|wY+Le&pjEZI)i#6jXzJL)!BjnoHJ-X%{$vmf>*z@vKcTJH^# z0ynuwW(dxNhw`uNC%e?kFH-68;mWR`*CT;#$KZeJjMfjThL6uQL@G#UmNd9_#9Eac zUQboxh|Se}baW3>Qjfo|JPI+`V*bO&vzwj9)xGnXf97QH-NNP`?CRs# z%|@5Z2m&Sqg#DsA#WQQDC@0_22|6eg&9+GW@_ zNZzksaz_%+JBi6-HCp&P={UvSBe#&~y%Pfwz}$(+A79*B_(}?GwIHBBDY?hduyW+r z1pIF-X7OfPm%<&tEvRJ*DTcMC5*2R}$@+P# zwk+-`C<&qoXL>xUwvZSsT$nk~t>PjsV`3*@(J2S9gAwI4^xZ9~-mo6-IrYy!{RYY> zgn?0nzwg1qv+fAFyz*{W63%ZYmEy^7OP0YQ*1KYM0l{!A&k9(|F{)3zzY@8 z!g6b|FvuZD)B>`=1B2|)RrMjEq=)u6kTL+CA-Y~8s{9r(iN=Q*Q(^wbfWU$0?y$7t zPE3a!UxEhug?)C#@j+ztya_ilxjY>b8$g7a?HIIuFWCb#kzKBkxX)E>LG->R!Fie> zKX7IE&=I>{Q_=b25=$^yr8X_`^|_Vy$$AbKt51VD?ymlIXIm^5Q;0_PB_4uA4mNbP z?ml-n{sdLLEo^9MbC@Jn=+}B)nI|WVh)JVlQ1KChVIwjrD!jJGqMD~)IfMHrQB)VUFY97Rf}FVgSZpBsPaf7?@rWgtvX-^AL>CDydNqbR%D(yI(jx!?~<59Tl(5I zR7Ei^DghDGA*r5(&GI7V<#ko)_S-qPw8oNC*!1CJHn}3rI-1i4;7E+-R_wrKj&CNt zIihnudy7!m2ZgTHP_j;t#$RL^5BKv?_uBTP8^tGaxqd5}4DNaELFhEkVe5CBTUOaP z0ko{BFawV@>);(5%VXL#N(vZ<5qE{^Jq#IKgV2)Sq~=H1@bzLScz%vwefzlLDuTh7 zf86_rYg-AO)CKfnI8@S~VgBBVuB&|xw8!Yh0~~DM>6HYcB=4mMOn`@5J$iT}H%cfT zf#rKI$t*)Fts}ObfP+FCL-XF={BR9`KPgH4oypT-eMTF3^g$p}uvV$j81w`~l%(^! zbwjnZmh}%*;MFMtfxb;>A;rY!_!%C+M>nrvMxeXCA~;Q~8Obt*>_i0>9bk@dH}W(8fy=R< zr=oU4fm9MZ02-?E<(zbTKRYP}(Cvp6IT@ofzU)6j#)DX5OnjOJ@chpB97EP<4g!An zIt*S;|EL5yX6LsYLF#Tik+R-_mV6+EM@Dx4FXS4cW0pi%3~b-M-dH2}c^CD%sitIl zJ?qV!a9-$MM4b+oTeB_sU=cD!b-dRydrTvDQa~w7@OfiL3b%PuFkrKIssUT zJwzD-qc_`YE)n|h6{M1>qcocIf%KWd2;%(+aG#_r;bfof#qFGj!qn4Qz%>{f8FTG0 zZ~?uLY!i1Lu`fe-w-)v7npBNT85M%Xz*1K++?;CYi%aJcWe#Tv8esq%geRXLRl}gN zV|J1?pN=e~B+(@{GFL~}U@G%}ZHo+?YJ*WAaQ))H`EQHr+l&gMCq(#HV`?4hOQRRU zd!_L-NVTW=BxT^)sQ{EkM+S9!1i^<3lV@LI`v}ITVD{5)H)94eE25hJ3xX!GgvTSw ze_QsdGFpHvHn{>T64)W*ac)+0L7x?=V(~rRG%?5D@tR`t6#-z)jdztJ7}TyiiPQ{W z_Ai$ir(ND~G68l(ab=)%XiR=wxUWgHu|>@pz1b25f^=!c+sKp;6>DnLCn)B$j4miP zVb0-J;GA1G$S8+20%(&N4TWQBlx7ywqR*I1*ODLXe)z{=L=YKVr{l2_I$jqt>YKmN zayS}Z57qP{A?L{4@2S5&Tjj#QL*GXvx+mTrDF~GfCbXEr| zaTs)w>MTK>@|=D_`P_}P+N5w2xLj_NCT!|o?J=wHc9STGa(r7MIB3bgO=P(`!^zFl zeh`Nm2)kKQR1X4378t|;K?3#P@p9-UENQN2=hWycA2l^9TgT4Qfw&%7^`nTLw0BZ5 zhn6(6Q#PXOYY*|Z$_@&il-XFv%L)o)Xb~SNc7iXYUx4s5Q&>Ft3Tq?s!B0@DF3)1!rH zE}Y(?%6|epc3-$-X)is5cc$k4fgoj33L?p=ATJ7jjiM>L9lu3-x;#BI>BI8~Vt#hh zRl3G{0od9}1qA;ty$r2TMKrB;ZK6KD(h zbds*ka&w`Il-L<6z30UEA1ic~Bxo$C-XgOJ+MdqlQeei7cW*8WZ;#sS^-j^W41CcFp4ukY=YcUi;ZUGZ?jCbv zG!Pye*jQtIGG$e+mI;5ZBYIX%LMwJ2qECyldBY48TqVQdFA8q)LIo3zgsIw=Gl&Qg@WEcz2*Mc~SMM_z>7|f0GMYY@@hTW`PJ<8j3akNH&0YBJ z>)Lg5{A_d?LXn%RnL48M$FD%A*TjfJN=U93Z&_8%q!yhq0!cZ$Bi{Mk1ya_Z`UoDd z$a&9;v;~!hLd4Y^C6RR{>FVko6cO<#O@&n$Dt}kW+cEb$YZj#G&-XUT(2yaqp)%|v zM*KMvL*^;OpGRx#*KFwpZOurn{lIH9%OzBeDnbG@)B{iq?TvfoAh>Qf@qw+ zmk5Q(8qC@e;tfW&>46%k1=4$cKxZW!MF){KJfO2lMbCB_Lfgz&>!tJP84dJKIIjXS3dBGM##{tD7arPqH0E>?*B0{ebg}$I>oCVmT+4 zlMMhLc+Onn^=Uoj)y`t(+L1giyz_Vg1;kp?==s@wZ;-XGFLXU(a9Cy4X=+6cgyZ1B zYZG7Qa%BZ_Hc?R#BTaY2#0s+E?a`Z@TBo5oyGy}(Pw@C5DuU5`2`G+dD~o#ja7mLV z|BcapHmihIq@#lN)#>nF+4aR_m@8Gaupu8av{;XNbCTfEDet zHY%Jlrk4%F8uDgNH9@i6!9JWDM~`Lo2@P?50+`2`K<@GY=35gYtF#DF=}hagdf zo1=RUoK#|OT!&&=tdGdU{6_~%dC?N-_vy`7T8J`J2 zcLxf9C@2Fmb~Ho!gEvCG*Cu`|_Ur&v(J$YF)Ll0{@!O1RG!aJN<&Lr4nPyTW=*D;j z6%~NL0gnjpVeATxG{&8zhB?p+UBwdvxtf6i~VFAR~wz8jrc7*0t)k zaCOhLO3nlnH!5`UR(uG4P>}-pXRKJGO(1SSV_~~rEsA=H26jh)-=cDq6_)SMW^$EN zkKR(EW*fTP#_Vq3c7fmnT*<^eV5sc@OthyzA*0mhtUZ2(iFJty5GDI4fAXC8`b$FR z?g8Ok{bW6H-qEMrzwu>wxN3hP!yXJs3Zdprf|+}=UW44CuVjTkZUo6*1HN!SW>Ukt zRWNwk{Xj>HEdDf3$r*m_{2);E0onAm&01&Z(lXG$@dBd_IL3zdZ zsf<&ON%!%F+;B{feJN>vRpvIH@2{H^6o%M-^!S<2jo(p5<8**X)b_dTPsim%E9PEh@MZO>X>9>Z7gjM zRz!F%Wo+(!Bj1kAUjY=?vPN{;+ftO$01kjyp46i`s0iqLt{fRea3D%|lJr0@A$p-F zwS8n{5q(lVKBFG)z*aV^2;sK7;G}t$GbK(n0M!i14=5pRP!b{({8P+1TD)BL z;T&NJOQEORIu=oSW_xEqUyN&i>{HCDTN=sQ?pMHCR(+=@oA0IsnAj1gnj z+*cRkrBiia*gy$l?ybt0n0s@Ty)mkUZ!Lqju+GoJ3^g<58mmX#bpLW~lAz68l6jVAMS@yddA{M&iujzC?N#Ji7pM{^fQjfI9s?L&CO8~>)yh{hAjsL)p zo{Ku%zZveVrZYbsX_4eCk_WepBmW^=FU@OCsIcIp!`;X~6|_Xth_QVH5z&%(9GNkL zHvPyi^q~88PgA{ZjQ&>h-IeyC#c;2Jut zSw+#3UP&!jIP~ZwO3Vc%ncxS1&wIkygt$p9Ls_Y(RQjY)@R}SR(|gPUTYss|gcK zZNDVR?rjYC4Vh~oGo~()0+Wx~OXr_-xErBjOz_I0rZi~p%aJ9}IiAp!Sr>jygNzqp zZ}MBg*Iv8?l0dh}Fn!c-e`K{6CV6)*-}~&XLpC9*auU|QmQEBm50x!K*-#Ugk^77} z9nzu+`!Fz)&s#P=g@``agG7Pwb{Pn(ek0(w)A1--b?K7kDv$0eb%OzoC1*KM32f1E zdW|)~P=}EZ&XaVm zw@1hI;aqgI6p%;jL&I$^vD4r3oPm(^PQRE>%3eTwcuC(*cD9Jtl0%k#( z-WanqWbjy=<@Yw5PN2xCgMWT21oY~+7}u#so{_WNLmOmD>0!=_MVW6=@uJAh%OGW?;0`5@#LkS z3@_p*=8j!87t>qZ9&Eh)%{myiLYVYkl9`BLNwxHCTE1g~7V+Z(s#S2WlCcW!UC)Y} zkIL-*JFqtYd2kt~Qq#T?&`20x7?0|eD_t%DmPRu&88XHR7~)UGsYe~kT#leqvWexo zEvGJw*Iqv^2i^l1Yci;fDXW-KIdgk{FaB~Q2YV)ry3G?X=6AnhDLu_>EdiSD+>FW= zTN>DGO{7|nXl3+;yZj_TLlyD#BU;G%i)==OA>?pLKLtQv036>P)$hkvgcx|t4R0|8;$vmd~A zX|jz@H^_E$Ut6t*((h5p6llwno5>ujWUN7x(yIRx;uhBP4{5VSssmbgsW%)D>_`Eq zaO0UZ2^D{A)XtmTg^BP+osuLckT5PoBEvg@v#FtM{XR^KhE_Se?hLH%qbhp5*Ol*! z&p5t&5$a2owIKq}h9fQ18XdNd%mF6K-*H2ef>N(RRF;S!(QPYYB5z-T`p?n)hp{emgj5$$ODGqU}fFJofYIw3Y;pm;2o{BB5v@_Lf zUp!K#lPikjm@b8G|cIjsZU3iR&AX=Z-_ z`@x9)?tu4)TChO-ich%*coot>zHjbmu40jl<7? zj?;qF*^H?*nBTk{3XY45D%e1){2<85waPKSh+3X*9zfch<)cqRC|xk=OvCKlY0!rz zQ9erXuT@KHqD zKRTsT1(=Z`T^wUUAhtbC8qL<<)vIU^h2qAX&k(daLJ2vlF7Q4--@ssRe2sv5h#3F_ zCfc>mgbjag%sr}E-6u>z1CX^OmT;ACiZ4El^VIBk@(${(6S}kzMrTS)#QRET7yN3^ zAbCT?GXrxdm8F$nRk{%hI^)9l#kg)y{##2F2Aa)!xQzb_0GcKw)-wI(0|< zPd1_$g|2Pv$j@4pyGsO;@FS!KRp>qt z91ln6GN0c5n@Rb*n&xYRFGfI zuU%dg;&-gW>3D zit&Q^Q&4_h8#V8Ovq}kO2hWdpA6mNirkg|1cwM2N6)k8Y1A^qWJtx5_|k z534DF?HrLTDx)vCoKO?%xjhQS2xd3c#zBEr3~K{T54Y}7SiLG9z+b);{a8wr>QPUL z35f#L^#Fa)+~SZ@E#dUG2iNV#RJnbkvGF$a!$=`~^=ht$p$(H{-CJ;EeS*pGtTgp0ZDo*)az5Q&>N`*)tim$MoSDi$HL+xrvqtzwcupjOe zi%=sn(<3)eAkZIaE^2Bdq8u#UOT z_=zmi4wW;PD`n@*HW{2c4zSe4m+J>%B+B)#R9!qc*L+B!Yhde3qXBty1&tYWGdsV- z*z4#tCe$Cqm}hXeN8O-Wv%e>o(ks@b&WLrcU@fMP7%vD1#PcQC2z+xTr()%|Q#FUhC=^K!5t#Ni$}vaZ47h;)^&kvYPqAmWwB&sP$BBJ zLibYS-hpDe*ZR>)BFGk*<^FoxC zcS_W47%>z=1^Y_Mv?kTZJvZyGMnI-h8zSPaa?hn-n0HRk_16N-*)DwO*L%Qal021q zV@2O!hlEjetRQ&f+Y$~VxHknRV|d*PP*=}ozCq{o7Waf%9JP733nx^JO&3e1q1~4_ z^fNt|;F=JJm&ZVPf7tYTLcqNj__A;IFdp=)&3a&+-8!!lVb8XC{zXwmj#!jUsN*SC zz#KdbVi8|h$U|LKm3>+ySK+QF~-?;wf(1CkLG|5$n{tf&dS>zjE>aM+xSR!cX$7VxRYNMP?iLTghL= zfFmH7Yh1`dEyLHnCgGN>yvMxpGC&_=suE&7vQ*He?AQT$K{1>AfCX-(jF3-E+~Sbo z&d;y`l~4gZSEX1jS&ywwa3PkQi%qr*8vl+sj(R$oNrm7qT^x1ri_Ubj@E&y;4@c$~ z#`O6(lCRNFQ4dq~oqqV|fgwTR&EX0fbT)}+8n)=ji<5f8I}FP!u;EsSM5(7v1lr&Y z^J1`}h;`Ny6J?e}5JL!2k0p_dOyif7nE|LdhLVwM#D|c@IUiQ% z^Vewqwkt}57!$I}&_i^zgc2n@f?uLuwHA3eZ3E7&p-*E5zYI&fGM6V7=d-6tOB>(J zengiVdL#vI7gniWYJiE~byWJh_&hdL{8~&rjmJN+E(1-6Sr7oI+%MeX#A^5W+j7_{ zqlwg>>Z=G-x0$sTtokns{obFc1^4rz=fOk_I;oDA?|9rRT=Uw|k?~TMvRri5e|% z(nNt$$99V?ceZlRPMtz86v$&BSDy|I$H7Db913m0z&~q(n5M*fo0|mmiU(uJ5^LS+ysXDrsT#f1= z8SAgt`L+9U;A{1g z6A<_i|3b_7h$1fBzjGgGG&coCMw`c`GE=VcB9XnI4Hcwa5TGJ)t*x~Sl?00lO_{0K zLxnZSGVgMd3U>1t7kcD`XpwB{sXz7NPxHDU7_{ZG|3*({ilP7WAn&tK0N{zJz;Oid;41qSXPD9p8TvN{829+62=&#E>#^F35wk5wkp6bmfe|n%$9inG0}j z6e}rzg76{t!{m}6S7=Pb+@%JFg?gq*&Ff+=z<1li5-#DDGH$TaGmn|k)0C~yWUe)W zTsu30i}QtTR6K)Ec5xoc90IZnhOfB_5;=zYK@(cPlk3R@#C5zPD%)~yY<@w^`B5CX z#Lo^t-!UA2{V7osim&eB3!gN8+mhL%(VE~O5T==+1y>oyP-o?jWhu4!%0a$cgo^rGEgQ`R)~C1>{8XyUaQK9|0AculX;=^6yrPpEy3 z1BB`SfTpjS-S<+~Sg z=@O&(U4Dfu0A}UxY;B#SN{Jr5snAJLF994(xCS^&=}K2Xo8H8^7ZTJ8SidR8Blw*i zi&Q(s6OKCHm0-#Z*3{1}T#!#6!oGC{Ap16t$w7h>&lsO)?yb=s-|I9hOet3zJJ;7I z&WLH9?f=>rgAnOu`kJ}hOWBa}#%BVz!)l=mG&*`QSgG&n`)Jb$N-Q+*^Y>o(F^q`y zUQDn33r4yaHIio=Ny+lo1$6x-Ao#S}Q8(HedEIdOiPT+*n7SBMP*=#x_pH}h^q?rF zb9}C`zCS;9GOlRp|V+#cshMU^4WtxNVhF4KWWA*5@WqOWB_BNnM8 ztYzq#fbzv!T>bs{dbqO=iPPaFmrJLjfHpyTg}33k`Xr~K|Fb}vt4T}xzlsSrrZ)LO ztI<*oujvDOS_&1=x*mP}vuwawP_8~8a{P{Fs&ggzAA>XXYs(QumsXtWH4qwK z_38veVvWl9Jvm{ZZTf~N(cc$B`gPTm>WX{6P|CW$;e~Yi$uQVj-9Im2?wjoD-rrFSNJFZjvTgmiDsI{x6u(o+M5eDpIM+o{H_rlPv^Nk_Go#yFdEH+2L(wxlJoiZP&x~2S2tiYM)(fB3PBU=A zkB)gFB@_A0_Ij9OsEs6l*zKp4aZEu|O`_ZJXezalEo8wuD{j$@0w}{P2S*gC28=I} zFoq*GCz3O#iL!b7BISIYydO7r$Pcr%hD9rfB>DVDmFfD#v+sw#RZ_31K=dRINHwww z%nao>eBa5|4#E5CN&#F~z_G81$Dv=V2FIs#rH;7vGDBNh-c&)G??{BC^S4-f^bNE{!#SfG#C?(*8*eIVekmT1LFq|qvPHiqba21agBT}>< zGP8-NobQe2+Z~vR zcluYrQ{Na}dJ{abPNvtF~HEh0s_0j&20jeOsFDNqvWTZW#@!EY&*^3 z^4=VM4uy;N*Y%1F+a4qOa!e%++3J`sbw8%S@*sP|^LQ{%p4>lOS_iSLYO9q=oAPS7 zAY3Uw%pM7^@mDZP%*!8W&vYb|^)9p3$-?D=ih+8!kwJ93IgaG)rwY@oR#JnQrSh6v zb}@%+!Q$i5%K;5kvl5u1Tw@*QK1z`sj?NAwB<~EZr4iwuGX2jJXz%V53R`+{h|DEs z+wT6`^I)od^#Pw$PJl6qz#u|_NPFv65VOqR01~M;$ZAc_TJs^D=Tw z`+5-H4+3wh!|Ndf43s15PeQjFUHolVade>^WCkU&R~D>J_6B~#b?tuTYlUPG9OYTk z%fOPq3>vqJ7BUb|Z}R)1oEdZ^=OJcp5Kz>o=R&s**R{X5^idPM=)P6Dope@}c) z*VQn9!pDKNqOONdJGmOgt+~nodRM$ZuqLPLgzDQxvWZTxRL(2XcwGZ(lvqBI=~+96 z%9s(!oMdrI0FvuRpW$IkCx(jLXB$r!swpe#bd0J*OM2uR{1xP?NmvPMi$j|5EZ3Ea z^GZWr78|%TFvK+RHzvpHFMaRThTuX`{poX{)|inMv{mE8@3Y@rndw@{q2#Gsk0BwI z?=3><@$;EaWNrlD3R6Lpc~F715)b=ElD~bEJ~=E5zAZ#Tw7r)wATIR$GwoW;@zBIl z(8-g}2~8&00|2%=96cSg>ZD#?EA_DSuydX$)+|!vHzG%kLRnn=aQb`po4knREz4l} z$gE-iJ=!f*Ve!y1Xp6)|@K*;+(L}_hBJD`GtO{N=k{;A!+k_yoVaJ0j8yeyy?omeq%7 zW_Ro{RrjPy&;3I0k>l;T*DE^g0B5J-AG!Kx+acyV6VK|(IaupC+wjZ{Bt!tlUw4XC zv=zk3`g_9MN8*$HbjJvUtIZQNl>tGYu56C)vUxl@cbrGOYs28Mg0B@9>8m${CtrOB zVU4~hCpY+*tRyp(Jc}*;YB$aLaS{l+_rwIms|I>3%rEFwIJfz6p_(OcutqqCBdo-| z!J!S!5BsHc>fEcQ7+=Ahq!EGv3Wc&Fw)cDqe`EB^DqO1;C&xBz?t)f$qa@7rTY9P7 zAt3Kcmh`V?lvII*d0d+-##@cv2@Z_91-mP?9=eiymN+$YAXN&`|c3ltAWk|Lp{WK z91!oe*UkDY<{~Wz6Aygm&>2@BxYW;uj5^#8eM3DS&n;J)u^Q`r&aNr0yz@)A`>GBJ z_D5p#q9#{Cz1{qx_S5)uXjU!bp$-NNHgijTz28#@D&JP)YzeXu2jl7y4F56>S|cb% zo=}&TkNUS{t^0nB5}E=v8Nx*^cjV+<`lVz(E%nhn3><~O3+7E7eJ>xdLpeCpqZZ@K zat5TnbErJ#wgb65?p6ouegWV)uA*Ra602niVP+cXzNvKRE$M@78sOvj-}9&kQ)h-|opteh_SnNs$JvkV|pZI*~9 z1)>FVjMvV{esw92v7vNEosjpCSF61@YI1=@YOyDXFm;t z4a!fZ+5o=U_81|)io)BK87H~uZENgg3S;$mH4`AvFuvt=g!%!)2^P%&r!e2QlDO8J zr<7F9J}2OI9LHF}+$(L@a`v_46r~SN%%Ghx%jlTGKTnLplLh$gbXY}BWMf?27kI{t zmq7XXUA2+^GoG0`g21Hj~Pv;MbemVG) zc-+p9YT9MJbwlrov;6@ZNq{0{j2wt@waf%{KO=tuuftwy&bNIQ45^Kdu$MYRl^8Lw zmn$1d`z}X@j^Ma9Q=Wk+5c>Zy-}~~V0$ZBSHI4FtB z-?H5@!I^j``#{AOK7LJ<{?AbSmq zg>wgHE+?GCu-`pSjHDN8gfy8nj@bREVR+VV4_;rP zN|u>Vv=uMMy+~)B5o5esNujtllgXlC^5vgRMvS#+%!)6s|K_%bYAXn&5A&_4YY9=VdgRDtU zeOUzl$TJcB-Dt|zBiDo>w#beqbR39K9lyF!iS(|f39CR6wYJZNZIv9~s!?Z1-an7( z9&DYQ1R@%~4x=e~L6}}Zs;at`4j~leK4caQna%|0&kWv8jE#935ikcBw+N(e^Z#Xzz1%;03f49%T2r!20 z+3lfGy2zrKsvQcAAJEtEHlAHn2DTsM5)8RMVYF;8Em1W-A$q#3KEVJIX?WOw4h00 zzLUU$i->hid+A<{3BE8>WMB1Ui%A(_pLPrYAg^yh>528!Cu93Ss19;c0|r1UN3b?V zL9!R-l%Uaz2Cs*6xKB0-m8cH<L0`LjG=7#sVA0OebU!C3TLx}2Vz zU(fdZ+8rI5$IJT2ch>YCxCRSr#wX_0m4BDTy&|4K%m&s#cmxT4-B&m5ucTrv zDR>g$Lw2gmqE5w0i2CVD<=4hnyFD^NKS6iIQ=ZrCAKOsK#)J&Lbc1*PGVGm@}_{`kOEdnn%`l3f!UqEEI|4)|dNPuLcGl%s=&t?Ig#(#rX zG|t!12~|qdF1qDG>J@n-Od9J$49@YeXI2hwMaxhI0>HWEcEbqa-W!7qe3@a17%Xf2 z#3yAQ@jyX^NyS;*dYG66;B*LS8B8(HN-`P7YZK* z{E#M$N1nlvnlT9`6mNKHJ0*9$^p#-*OLa^R24CM=4{01YYV@|UA*^Y3cB?DTM)TzM z3R^%Y*b88rgXPhl+dOieb$Lqaebb#4hF0tG4(ed~j`)6fucthlDf`6P(LY_Kj>EV6 z%lhHg+^uQ#q2|w6ngWzMe)Kmf611TKKRhkClR6b1r7Iok4G-7YyX)c!M`3iTjmde4 zk&OOohL_m_ezmn64T#O zOQ`=8Om!Vs>Yw}pWQ=!>Z0m*uw%zgGdC3F{VafUG+hjK0F)E9kaoHdTc`1>>bC~`2 zrJ(H5Lcme1Ja^c}E_A(rCe&6-<0Z~jBGhz3i9vq`XiAMlIpYlw}ILVnh ziGH467Ww8O)nQN59(0=7Eek>RH9~G67@I!46 z6)XO|;dD#O4;S7_wm#7R4(Vc_Kghm(G?*e!x%nR-(J!;g$mjXRaBL1l5$TqnTf{=4zLfF>Oq{CS+=#XW zOpnHJ-Zn15crDx8JwBHT=>&@d<)n4?d*voe*{ia4TtbvDAdL|m@8KX5SEz2l$>_OtCU=&+M_t%q-4a zZuWh`WOB-GBZ3@J-X_19EWGqiP^M);qiy?EPkaR*%sPowM(k8DFCO1Nw35j_A{5R^ zBax5gOU5ix;r@o|Af{DS@=BN>Oy0TFZmLncq&yB|Jn^xF%4wgkjU zb3fl+J+W;e|G@0|nCQIhQ*b%f9`w%|o$vN(c=37F`50g${SjljO558ovUE)8S&N{@ z>Pu5Bl}tYpQqUH8N!%5q`+CnIk;D58etU_tYb!;J2$hVbiYXaP?ZE}AW(u2K@wQOm z3D&)6Uy!R~<%Z&!%WG-&3SRaUK*nSs`4i%n8{%}XTelS>3%RuJyP5*YHQ&`_-d0e5 z5lRMz=r-cOjxbULnVa3Tsvex-HsCrqY27JD+!Zv{D!1TN0yA%&B4->+bg*)&A6eoV+ z+%hTMj7U-|X^|n@08Bu$zY>;NwRzSx7m`RP?Fa3qUY60qoZYumHV!bbZ1Z|DuZT3l zx!i&I5hZF9ky@d{qgh$aJMf>{v6n++ZpGk0ao{UI$RqH%TiUy}!C*A{Y?ce{Hy|jv z$D*-Tn+ja+j;;Vnyndvx0~bLFwCPjTd;SlSYja467b;0W_H##GvzzWEkkkg+W7mKg z8jJzO864;5xxJ1glMvzx?VRPriYi};ckJ8jSlxt?bJxmaw_Ah%9oZ+jJ+0<;N^>j+e5Qmrs1Opa+1Le#FsBC>+MsL+@Jd_zO#})h1I|GGZYs>Zc^Cv9`V$>vh;t6 zM0KPv9oJiK!6!@0`TbP)B2dH`cU-CbC;O#aQQP4L^8%=OLL|;nk6gdsUhJ?{rno^J zFJz#c zsD@m-o)rZ#A8poj#K==$YqJ_=s5L8_(^BD=@+Wp-wn(@~d+$<%YTX-$CCpJi$evHZ z|IsOiOJVSs$4T9|d^m5MBEE9sxaNDlQRdqvJFA6v+}=}HR`xK=^WBKt%@*lsuhz<# zRzMFJFMx?5B6a{fsrpc$NahKfNWDpl0QVY1 z4JY*mQW%yJyLJm@i0%ix8{5EyZK!cS67eY@7QW4jGACV9rY&ap@0&v?fEuX}EO(lv zArK}(#hMdn9?arq-Y~bRT>HLRxwkIAN3&Y z2=;HsPC8@HsX{XIGT--QemYG70`A*}V!1ec%`%8SrSs$;0@Udz8N~Tk0~{zs$KCEm z7w2IJx3u@miL_sfM~=^rOv0gXrz*a{inGj^-}EMPkcUy+$Z3ooN>+w2Z#IZiwz-<9 zF@!bmSA5tNxHx=H()5&C}gN%nV{cwhK7><3cIjH{FG7l z50e;v$3SBLq|}N){bGrZgwg)&9_M8YcZnP}_ogXTMys zO%-ib*JOFeJG}m6vPS|R79N^D)Cn}uek{{!fiqlJ*MFm;Lf^Hngkx6$oDXZ3fNwCf z{GC|hKBRz82~mKot(spVVq{p<$#dVF!ny=$veE-*Wid>6ZCk47fV>8-X*`v-$m|QR z->k0*8vQ7nyh(vyvs3-|()g7GLINmGunp~Yys)P_1Fm@G=fNa`g3NvTAZx8bq_38$F#R&Zoj`{%miUrc zVKDk2zuSG4*+3L&n&A5YQ2I^sLKz)Cu?Bf*LVT0SMCQ7L^8AY?(}s12Nf;T4mg0!| z0Z8HbOuU!+t0e)B&SYzf7Xiid?HT1*OB|C;F*T)K@>c!6_*M${ii>TWeNE5f$td}q zhEK9Vw1ZfmYDS0)lNg^?R%Vw-?*sJD%x*j=9J6 zKmFb2tqvlP#oQ^7+IirF$Nj?Z)QYSgO3dKN8(p_9H@I!=dVI zNUobsa2c#h(^9Rm;_-dTa>@H~PS8Ds_PINPzo3>dV_=b?7Knm;KpPhwMmG?xdp%GQ zqQAE*-xWySzYK5ud}r)h_W!;>_Li<=x}HCCn{ zK$fQ_np)?RoVD1?Ix6V;pyjCX_Tp`wy|ZvFrQZ}9a_XXi#-brRcZJu@#D+=Xufp%M zS?Ew}`~^Mr(1)OT&hW#pF$&;BgzBk~W@h)JB9@r`Ju`Il*1TP0<-B~#HL^G+sQt{Q zB1Sqy^~O2$To=i}i>0;9g9EoxnFOGSA%rKq3f1z1gS5%+`w8{H_Q+o$$^$y;=YO zLvwKo3k(p4fW3SMxni?!t9Z5gbtC8ZjYuwIn!HJ!q6$yEA0>%)S~S#J`1fggGqU(MTo&cAAN83If(Q zuY~KH&G%XIA^-8&BVjFRJ9#+$6`r?mG#jNG_=XE5{D);xBmaa2sqsGE=BvHy~%WbtW0 z8GFz=u|&`mMwTaXMjd=pYZSI;Z?4qPzU|-oOoEq@$W{f|H`PwSi0H=103$oDEGzo0 zVA1Oem-2X!*mfz<_?qV-UF)nd)|bX?)HF~FqSm|G&6`JM zRRdf5hKR)X=w5v%o!agqh3v6Sr2jjne2`uUoHBapcdjwviU1?eNwwCwU~D)Ns&LEb zwVuV`iv$uLOhoC3LhlavP@4>uEBx@Vmn*2i=9WxB=159`?fou9xL5g1hstVr_9C0i8 zOuE#5C8L6QkQK474wiEOP;7v|J>ievEC4MqdZBE+XbS2LUY+>kmRMmGS7Y292@lFw z=u1-P7>14UcM@=Y!=na*(`uxOahHMqOTXIeqGjfHqmdcPa+5Q(6y-tU(a6Q`RMJXn z*mgbuTf_=JhKI&A-Z@261{2a@h<|amRjF!v_6S)2+_)k!-aRRD3LloONWY&m&3;wM z_@Sd=S5^9S_l=h!RA`%*?teMP5s&tH*r~z`0HcKkqN_H14#8Zne2n?CBxgA5RdTAS zF;X_)NCb-3 z-9jRaDgw?*I(8cy?TXZyZN`siN6Ixb6whTTZU-1}-=pxvmm2sFz8aNrm!PE24+$fs z3`BEMr1*)#U@DjX!KTK!%ODe`gLvc&q56?@SOlZVCpkI?5aRL~#>oVW1!tgpl>-wc z52j!|4Ked^!Q&a(4`IM#XikF_FmrRfdX*Bl2ny3C+!R6d#*YOLLCYI{ZZ& z;NA7TA6h&+N5wj}89dmIpOuNpjUblQ9Lf!_TISzl^aqP8T{@WMl{i>{EzJd0UOCp< z19n~MDA+DJbxjs}KtEc)Xd8MqU{V*LLC(|shFO++d|p#5SKoqd)IZL&Cp~_LG=*3t^_@| zPup8TUbi}~LMP6D1U&1BwmFg#wj7arb~FAvX(XS0IySea2Y%V;O#~9?s_{V&;U~SI zfI40z(YielOC9BNcxgf~cogc-)9~PKw!pJfI7_?0ElkOb6M>ElC%l%LZUx)ul%R*S z@!6s~mN`DkiqL@)2$*Xk`b!f+ZL_rf-496+h(3Ob$|pcGv2Omdv#`zN63HGWiJvTs z@-JbltsIn_B1bZjK3D#Mr60ly^G;5$@V#gjn1amm2c6#=5>2}Hp{ZhsuA9BxcD<7m zlpRR%eANeMu5!ER_ZXCZ%*_$biXg5go}vzoilR)Eg4ND3Du3kaZcnE1-py4y)Z1(~ z$)YNZI1tbkZ+cCvVJY7%kfqsBpqj2LcL~Zm`0vUqoR@5#-mhWyoMn$BJnARp$9uNLc}axiUK8!=(Z6#K+RC&EN(%?iOS@>IfdU_Pu!L!pHYE%=FE2;A62CJln8UrM_6|nEQtx&8w7bqCso9g zo?cq>d0=7pm}BRI@NtuFq@W6XoOk*V(mn+J2K(S}h;NEX@64@$hal|$+kKEL0oP0m zf1+4$wp#bir2dkQC#CsZt=?G+8+`4L-BGT@1W$=fE+}<0a6i^_NWFv+%>(P@e6eoi z!c!X(S#=#E{qb_@;gA%9ow7n5xQIj7IxA>qE(&jCH!26==|jx%zj0Pd&s5 zlIN`5nR7)V9JNVSFY9Gq#Kti?2N4376umR;}|~vWM;O0Z`@0gnqnwgYwcc+KdYkVJm+)oeqM8g z8p(W6LM#s3;Mk68kC}BMZ&bIl8c+X6_i+M=Brb+Svm$z$1VlAB+$VgCDOlK5)1J_q zGsCWui}NIRS@ObwNwo~AP5l0*v6?9~<7jYP_0ZcHfZ170)Hzj&Juo8lFfNvhKLn8` zlY1I*d#JxMiym`>$v%aX1-91>Yxw>g8jAIio#Q|{Lih19IC!L%zJCDsU}Wnd0vw_P z8k{2;IF$_>FOZ3}gjfg3%QoN^sP!~nL;YYvvMd3s4YJD~Cw3S2(~-duu2qmejPj&S zog*pf{3E5tBZZxQH9<)orvTf1s8v#QGiuoW z|4^S@In30gd%GjHF*kV%O|RpAo!Ro|lvVyD4pq&4SaiTjdh@0Xr+}=nXGQUhTIY;b zp_eDASH=0Aq^0p{Y6ENr1%w)>t*WlsTOenL?foNzjh1~DYrH)S|Af{?Jq+!(iy;|ZXEv>b#E zkoB9PmsycRZm!b;af07*8}I0y$$7sFM%s0X8FbhZ8a5@7WQLv$8-Zt^;fkQkgM1In zr?i>)@awzr8bA)8p*NI|r7>^*C(b_wgfAj*UP9H^iEg@zkUTJ7>B9rtPYCQe1}6Sz zp=H`=$H>UYH?wOey9Tm1;7O7xkKjnb^Kb1l=qkrV1e(O{1=UsDQ`w2?wFR8pI0JeCX=H zRbDlo=4BEsQ$m@hwCP!P(Fsmo9!`lZ#7|3d`9yca_bmLlaa~ukc=6VU$tYqonia?F zTZ$2fkvE-sL78!b$3>Ae>#qun6$ECxE@QVeYDb3W4g833ll!36swYu^k?*SEX1ppT z(@|0wUsP-(eB-X@PJbPU&5M%ZSOQ-@I7NBmB7}_?hwBJk8PZ}V-H32tk0E0j{z50398wjEk83frURPOMj>tG)TU6Izg+bKO=cJhj6pmt&{B`+GsrX;J4l;> zER7Q!&F^8An~)rce|)4#%!Wfccu>R7&Q6**-PdFv`?)cb(+$#R9Mf40^t5i+=I{Ss z0)GWuTwp|Y1#11a7i;35vgN)qVlnG`-ZEPBFqy$M{KfC6;*_aJr_lh~H6c915Hn#S z2=i?)VMpOGM5aiJ*sVk9l9Zzp+^It!0m{tp!2}=pOXl}|Q~suFWcG$NA=$YzelmQK zB}Q~@j9R%l&3VHEg{6bcCzAUNRZ0E6KlzKfXXa)hI zL6EHq?bF|MQzBuu4BEJ`j8icJMDrggKq{7nSmc?Mbn?n)sbEFmVG9VEdw0aNq z-NkZ%NKk_3lD({&LVGbkI1$YlmDHVn zF}}Tb*`;r5tt`@U zal$lphjFJ*mR-I>8sx0j*AFjyKHhBJx+ zLM8H(Ho0(6HWn6jKiPH8by)Q@o#Tb>d%73+pumTN^E;n`?iNFgKgFx>UtGGEI_6E< z9G?H$G;pCkZ$?nG=|d>?bpiU2|2XkM5Qj-sY~Xx$(*gg_p91X>X0B`$tNez>)+{_$ z2glQ*!{wd{HKvHl2b?m;ZJp08;s`8>G#b*E)uu-Q73m)^YKe0olPp|& zQUY&*a#PfHSJBH`qZ%W^2Z^f-44TJ$dC|Vc@SOT%X8e-;fsrhaxu3&FG+Ud$*oQ?q zsY-R+bSvIedJ%_obt*m7f$`|P6UJ!W9b@akHasqYUmrbksCU9xY;Ze^^I7;Oy*4C6 zk!DU&5QO*p<2Huld3Qd|`6Iczz=G0vt<@rdNtzB`pi`(UuvXb5zCA7Vx5KZ-@KgC7 z$KWc3;QR5%+qh9e_wh$e^Mn-RG9F!)D?|f!z>NR-bCn{oJX%)cV{6kF`vZHA4xH%f zibGW3;|&|17^$n#ej*h-dMyUNdB(2RDDi_)Ewszq zTjoTTzl^;9d3muFJ-&<|SkeWmi1d2Pf#QQ>4n zmUeSSa8Qn0#x|)aJw&R5UY>iH-E2|Fg3;{l-l*7j(`{GYcQvYI#E~e7 zJJLpgRy4KVx>_G{mw;#Q(^Y_uR_$+{AsCvd>yAhj5#&^h6OqnZvUPo5`y_{8w&E@^ zp1=S~FGwuM04_}y{2=ol5LdxSHV{4LfV}YCeFNGl?wu0XhBT;jlGM(UzQvMj{rgc- zI$!j(ky7E#GcZS|oW_^sio8#R#qG$IbxUk6tSo^-uMs_5a(1>F4wggScv{UQM@q24 zV{Kwq-bydmRR>Isx=kLW_ilfL!diT>eqzZ7_)mFN!}2&(uuyB8Pn%85y`=>tMZkThr$ zpaS^~gSIgFEg>HXY|r=}vJX==zV#^L4=&s}%`w16bTyDVY4cf92pHfe$Otq969u8` z*I3%LDhR)V3ToY%0`|a;gljY#;%ts)U_7WjzZ+zEEL(k2((mo^0O8v7A>xHqV^)h8 zX2-z%^c;QOCjwj8_7_Yt6PivpO__{JVYNIk`O&^15+aEqZ$s79!hIP@5!nZqvJfzP z^ntxHg?#?gds6t&Gxet;*vo?yC!kU1@%#|B43SF8e5a~zK4={lG+^hHl4q$#uYKN^ z*uFHpMXO-2FVxy!qiJ!4`0oP?;CyjIBu>?;`%ly+vGX5swl{DiO#r#%Q$5{v+gtEQ zb<#aaj{PJzVxzp}BY*i1RkheDdn1P7?|gD`5(sju=?VC;q)A%BjRbf%_oN=y^lrBz zC)$+ID>!QcRBDA+GfJ*#-IkSvy8a}?zgDYByJ>KPR;pq|PRK*txRrWZrRhKba(C(Oc0EZM0g~ z!SYQyHpR*Et<^Y$%(K5kbY%6c#pz`+aFtfXA7FJ8m|XYcQNgTIU^l7?4A~SR{hAAJ^VmSu$21H0&>ox^;X$F!0Ef8foC z_R4xFkl+Iht;OvFJpEB{W+a?6CgNS3UJZnFUqlvZ#Ah2=MQZWj z^qo|25aMFnMTJ%^@pMDA-q&IfEjUV6bnDeT`y>7@r6>0GC+oS;XVE2~qz zVVgTR7@8WphjxNwimsBClu_&_^ffhH6^Idx;byonQbYVbk$R-s2#IQwoMw-vEH&J? z5oR3}>}%g_-gv5yl{j0x8{jRntjW#D5kj=MV;dblz`|BwPiiF)wnj>~L{!tv+IrkK zh*PPZA$u=TiW*q~%F8I3U%9HvOr1?e!b}nwCLeiYU9+w#iomMYk!t=6JJ4j&Olk{L zNkpC#UODVI*(bS2qH8y7jD>srVls%hU6fXeJ@?vI1{uK_PKfzerSvapZ&`b`doWr| z`gOsz$tv#2`z~-1xZ-c}6w;9-8~#xn3@a4hq$sItyaEs{%%ocb)2d$@;&arGkg;bCsWTXTXfJwo6yP_+ zEa3$}dmd=Rzd`0KM~|i7@{{<;pZDs6h-Ez=Hw@7FeM9BIIKAb@QtnlsD5^-va2L8Y z*DpZtA^v;0$9X4!sFwM;N}O|5Y$CDPE?r{z>Fa0mig{WM)+l$&WeSC=uu;D{9A@z@n~!REtmEnlq!%XAl_}fX)|C(<|9EO;lpezgLNfcD10tw3lzi{b?v{yjzr??| zh@m80s5EX^ozu9DUl_$A-RrV*=|&dgeoSYr6{Krg21fG9m#gAGY*SA8Aux~x8UTPU zTx6-J-#E#J?ld^Hzi7o8T-b7qeB{yg5`O*r05qX8M(FL@K#mPfvY-;2??`b9I^ZYoX{Oh|MD^26gbLjUxULsF2#h5`(b6Yai%gZ; zuy*8bSZ(l?YjiqA(*;DjB^V0|&kwAeuCSyC+HBGVC3D50OBpfNg^g!7)aP1~f%bl?)?6E$O+BC_7@~N{k0+O9w z809`q`3rK2o~LF{uY2dFQ$bp51$kn(lC(N!)fO~Auk8QD^;#Kv;M3$>6;8wpp#D7* zqQF8QL&(y+6+qz5$loCA3&`TOrpF!##WO)#HAVom#_tfon%x-0aFQrrOGl>qI-^`1 zGt*kxp7C+Ut|Dr$c@_udw935+K#$X0E`=QfPr@(rSCn=72M?Z=dEA^HJOF89uAkw) zE-Qz`}h_{Z{`#dA7Wtuv_oDC+nxTM3d3RWUarF%;g`P6g3fuQPmm~a zbguoUZ)99+sP9)p?o%TGyoOKu0!*pN47e8d*s3EN3sj2}VhSAw((Z@1uQgMxSr1Cu zz$*JM%>W@B19vsFz+LLKiZM0gi;8F95^6Uah0AWsDi}wkkzK8fuzRS0$RGjkYk+bV z38xcW+<}?{&fD-@Hx*H^1Xc6q+(f#z3LS5s6kjAusS)8%_Gfuv<9+O0l-UiI8LRTL zuQX~kh=UF$1q$IeQrjlG)|FXq+nOCTk(Oo~ItW#%joJ#jXJl^r5_0uURFQlS0?BqIBYI5bX)J2?Y;=DgQzuEYntB%m&%YsYB0Up{s%P({?8*CfHn ze21in3j=n7Pog4mi4!T2n=?8xmsx&2kU=^AG^}lL?v~8sx28#1gPOH4I&$H7pv+*z zTgv2B?%L#q)|S%?KeRg6(^(j+alkHg4{(sLi>4u^bL(Q{4;k+q9k-O;+#;bp9En)A z+v~ezB);tX#ZYe)zeMechbh$)TuXL6ML3=~j-g3%r4);}(vSasYK_Zak1h`11wi_o#Vh_H@n;Q{u3_}}AH!co?w~Qs-@%GIcpM5@7nQ@^pvXi_r&jxT9ObW}h z3Tj$<5kceYQ)u6Jb%Pd=BBYa&NBl6Eqmc7?_r0F^%5MoiuC(^uH{W&6WLuGG%ZCr zt+mXce^}q-uz)yBBy->l=As08)MiOf#vRUTEzwsQIQlqWWymJy#((R=gY|U6)Ibk< zqgsZHj{9eA+XWV|LfoW@Mpx=RS~lVMcD+s@8n_}dgsdH92so0KM+qDH7xstqp*I`d z9XbAC0zDiKw9?A{E4z3wqqJS@_;_4Zc$1w!Qq1QQEt0BIi8nvO^yg`Aaz%tHz_FsQ zH>aJ+&Ow{19`-`BT@KIZ=2`u+b?KGEtjXuOw>0qp7!RMkYYHlWrw?!+?T26?IHYKx zb$%s+6lIN+j;uoJ#fs&eRbq3+gdjGthWq4jZ~26h*c-M{E=s&qW`Br^6aqNIokCg@ zxM$7}d}2M)7^G8 zOC!FIIc1N~)IiKyBr*j=NNiNV)E8GAE@tq(+tMkW1|-6<;vADI%DHwj1+j? zx1zni(|_KIR8DL8t36;PzE1iB;~!-S>dvAK={ZzFOOC4}F=GG*ba0UzB)$u_GvIW9 zQ(*R8PXydefmU*HgaX<5bKbpuS4dSEC;nqozDFNnsmrrz0~{bS^1lLmo}+S|^}iG? zA|vGye^8bU%0OY`{?&1WXxfVxx3LFmNY#anGiFt>=(@y~e*v7NTw3OS3Z0V?Pu=KU zj1$kfcQuK|Z@dHOMCoJ|L0M+&`M%e^AcnYX2d)Xlr#m=%EPw^Pk|#8e$8=~py|um) z3QEsl2U=LAh*OP&c+u1Z`oA{bB;A@X3_}4zh%Q)0JG6SG?-^h>Z+sM!- zy^YW(a^h4`CY_T}zo?D6Jv3G05lF~};J+F%;1V}lQx{GWP|viR5mHggT&?+B&}*Uk zXNp2Vb;GVHzFHA5yR5=b_!kfWDVyw>n~ z0a%Oqm~Iaw2~V4w3@O1ezJZa3gh?y% z`H^;flLdDIf*opN0Acn89h$}Sp4eq9zfeK-BR2VOSHz-~ym%emuuvW`*35O#e4VpY zZ?(V+uQ?P0MYyjBSw z*_4BPfDxKCyu5}v+})fQC$S_v9>LkHl5%pHtf4w87e4M6$w_Fe)%m40^T6qPmL#wF zCdD039{TJf_Q{Dav|YzFBub9Bj#!arvC_a*yaSgY*=v{_Er8ibQi5$r{NJSR2C z&XaC1kgIV}9BTU;<98InVxg$^bCm~TOfmf4*_Aq=dm$gQ=MKU5q#}xAC4gK;jvFK) zPW5bF_){9b%s52FtF#pU^aY-}4f)R1#lNqQfC!+e(2MP<5m~y}wDvJH<#5~;lx~WP zFGR?^huup(5hKN3tAqd(7b%V4^zQR81^kvFa+E)>ipSlYrZ&+*@KkibMnj7zEYssb z8ZHs?uLM$-T9(LGt(joc{xOmB0e$z$tMH{6u1gAI+ov87IfVGX1`X-nr=3jvVLw&C ze*0E%P)9IqZK0xR29nVpld%kq4Rth*v+o26iSstEMscG0p^VCS%>5ESSc^S6wUgju z3>a;z(Haxv;t%L{o$m?9L?#I?*GN=0;t9p>=!A7e!A;*+Eyra#^f_^Dc#cS}SDfg@ zJ_U`N`B~eEC|z&;-Ul0;?;*%tOzb`3(BAVD-J@(`9Vr@`QEDSWHN?DV+Ho+=#4XbJ z6x03JuDQ_SB`%fub+fKzNB^9j7sGRuXlXc$x>zf}uZkPV2*X3Ajy%Eue1=;e&wGIm zP~Cu5vOCOP8@CDA^l3~4cGZU+LE%P^>!xsuAWB3#a%1)Un9W$2mLx@Mi-I+WQKD%} z$B#oSO((!d>E@G@&2$*+2hZ%#UcDnBD$rbXr`bOznt+-$2c!5CgM4svC%3GZ? zi#YIdeHwZ+0R~&TR~O&S&M{oPX%xY)-l(P?h1%5JK-AZ3znND7hD_P%-^5GJA5wV` z8lg-OG4fj3h&`z#fi0zD{{;8X51jHpJrVnqLfe(P_WI$XH|edo-eq^SkJ(gv zL@Eo%s2hq2*0D-KkMbvRXwh2M(miK}JHm&4^QTF^qVQ-h0@3lo7#rQ)(qv#c7Q*!X zU%ud^)%cVfi4`9fqIqMp%vOe2QYH8A2D`dg^^|)#6e`!Cofz7y$3Pf!#pC;6uKe1| z^Qx<`EAl9~-HIzWkM!OTfk-z?1PoEgQoI7oL>XN?Mx-1Q?I8B2P4LWiJo(6YNkK{Z z8hJNca66jPSI3Ly5bS!^CTz^YM=1t%NqLq7uyUvzm88F3Zeg6{L4^-BvQVz!%vFZ! zIS!?ET|+u`3u(SN=wp&l0(Hj>z&mIoI>~IYHr=2ok^!WhgU`h!Z`c*E<%8hk9PG1&vM*T01U<;Wt$YuI{i zFaOee^6=+{*Y)&Ag5c{!wS>CJ2TZ&{Vu=OI&#}t{oG@pxA4$WM+wW}| z=Frb;?FC{|u>K%ZO+lns$)Rn7tV8IIX~4#e7jSe&_N|N{Wg=3E;qGUr=MX8iomn+8 zu#g_D7qP{LFTF~V@2EuW#W$*t?*VOGqXMDQ6YZc^T`R6%Sh4_O$D772U(s#kuJCH+ zdK(h<4KM|eAFYv62Ie(QwoMy|_m_+Kpy>#s`;y|NUtD}FHwZ`AB`+SHy*$|IEA3&D z;O!I>TFTBB2m%gO5+XCpq{cbIcl_pYEZ4z%hV~SO;0ba40NXfsx?A=ZTMZDb`h{aLRRNR3VS}UfEs)D9dK6U1OQQ zRV2@`uU3xN?|)0ovnp)H$&}=BZVVkq#@^CC-{orjQVBxS8>NM1x@6CJlaDFE1#}XJr@7ZF1*(x z0POtf{`NHJ1j4TEpkz$XuRl0*!#FakJs4FA;QS9VbVq2!42)ck=wUk)twTFi*yL=N z8z@5L`G3N2Js#GPIbYW8nSkoYREzA`xtY3FVSch>{K>hRx1^qHB4P^)!-X9AfEN)* z7fS}WKtOe3q^w$$Z zEn==wd$A)tFVFKx3UHh%Crj=NkxjNw+MdE8d+)pp4CS+$m{(&OUrnD1KnRb^V=2_b zPr6f(`E?H#REDkr;hUUv4p#mQ<;%#D7}Fr^%h0_$z`FM6PNjSDviR6-YX^5`0Bo&` z)grV+zMOQwmkwFwfB!BZl|G5J-X#y&voI%sz16 zDwM#Wo`XD*=JDJcxxWQMRGFjz#P`$hM%7{hNTXaN5yx8cKWU=YxDh9bt=s6=RA9$H z5hu+!Vx%*&dn}kOf2vlrP%jKm9?!51$MWWmZA1=2cPI_Q_0Tcr6RcT&WPL*&B z`!;3>brAmS{`}(8qhT|+!RBSg9Q3x)Z5aY@owHFt!LS$Vpz_jK6~-zNknv$&fyUhfk`d5d$l}HaNc^ z#XLc~+qAYBax(?hUj_L?oyJtD=D9rs(x!`6BDJgYy_TMvL@TGhtQ0lneWPb<1|zxr zo#F5^)C2ANTGmy>judhg;OXt}7fPe9F3X+Ndn19A{4o*px~<5z2+hYem=TgOc!IsN z)v~}ZNV&=iaa_?2n8#?UphtFSubNjQU2Rt}ENt$(A0=pjNdv2C(sMO0x{mqf=Op^D zv^I^c)OM1oa@T_OKuvswLQN6a)EM~Ivt7jD;C*~+Kq4NUP1X&w&(YER)FHT&`ZEhNH!D zya-5pIk}F4zFhHI&QR>T3C)dr++^6t@h4RuQ9;cG>RC++i=DL4fm$g%Wk&^Z9*_XV zEJ1Kb{N!!<-`c~b2|QaSPUj>Xhp;q$7mvp9(z`JdIa~Ek1hU(jKr5u zvorZt-8Rc}uSkZPPzeE>Bn(DWnR0PEz`nir@_Nixq%@e$iOw7u5BzhwbX{+-@ivsA^ECcS@&Q90n<1Jq$4ObR2C*$>^V zkP8E+_R1~7i+T1&U-ZSbebV?_E=c-k(JmwQK8#lFGa(QRl+h=BewF;J=6BnMjG>j? zcS3cB)f)pkt&s;Jp^{yrs9TSzUepHqVbpa7T>SKG{rYV+vJ+nXI?pBItlF>0!#FKDTLmRV;9`k8jeq`YB z^AsST8wAs98O1^~q`sQ4@70W$M-XQ2_dy^=Xaw_RtoVG7?BW0Zu5hiV9K#?!VTnNJ zC7nh<2~t5&Xr34_L6DuP0zP+eo_1>XhG3Awq!ex?MsScP&p6kkf+f`1(q@2&H4~QT zc7&HR7zEBdp}btU;(4ORN~$>EzZF%iyvKejq`y(jje8zcah0~ODKi}Y|GYQK(;NWu zArsrrdS_f{mJ33D(=svLbJqpe9)|ND1yeNq!s)2Q8v;f0nX(L)Zj)VIO z^vlyuY&8;F3Ymouq{D4&>M?T5!V+3*^`n6)Ror!Ne;8$G4|wA!+%b?4*lcF2Jcd{< zQfAIO3j9&rfTp@RPix3j0zs^ZW@O}Y{wybxG?4=!uGx85n!5tXkR*QeIuyCJ?n>qP zb0`UJA%h*LTE8f3?wXR#_+q@g#K1Yu$^CdFKL52uvQ3_pd3?K~+pk1w(S42o_^@KR zyUOMt>r0H*=j0+5vp3vm46BEj9=7f1@L?@8pnaF4}iyEvF|A{ zmuIRE|59=uC}j#)jYihxyVR2A;zP&7KLESPKGcYzl7&>#Pkl6G4nzgyx*{=}fk-ze z4s!Y?wL?9osEk3G`a}m5yCH&+=UuaOL68~txG0$~i=!R!FH|Fp=>D32C>ne@dZ0v% z#e88(P#=+l+d*_p&z;RRt7$DOq+wHNeB4iI)GtIJ7w|T6Q50K#F2)ziQNH2mYg3^%=(nN|P(gc(y-9l3Y8!9M81StvvqJWA@QIskw z0xC`TH&ODw=R5z++3b^NXJ%(-X7}bClF;bSVOo`ap!W1|*bfQZ%werh(MZd5^Xu5* ziWEt4diG;eM?A~5cDTuBMIK6#Gu$7CQ@Q&TX)>YP^OWa&_{EH=g-9OBnTPKqyfyfY zzjpM|n2KTJ>wXXIh*@MXIfz@S`Y=ql*E}*+zkps-?=3N#S^RwZ4t)#z!624LnQR$! z>G!vgnA*3Rk9*;2?G#Ay8YX7*aP+Nl_E_$SI_f4v5GIkuVV(#%GQuXDZ`yLs;7 zC1M5GCuB??naPJ8F@I!a;N4Q0a(p#(rKGNly&xqX^mh>D7>!KbUI%O3!3H@yAC2R3 zgYVzE(r2O@UAQ}rovm`2-~KKBO`gHEMI?nSm(`bQ01t=qns)jc_x2Y8ro@hs4qxn;|IZco*3C91G;^klO~?pZmZLib}A zF7CH@m(>@nKmsX^=k)y>U4aA(8(-4!yv|%ANl$CP<-2HwW36=$1&;65AT<3NnSXPb zvxlR-a)YDPU`mQz*Pt+#>!k0XI&XpqdMgO8AZO7V$!Pjqo{9Ip@uf2%SA(htd>{1x zNL*~8*+uK=W8-4j)AJ*rCD-g(YoE61r2*Dk;}+u^bs_m(@qzvC1K2ro6Ha0KTujr-|n4aOcPneriSk##^0!o zkL*2hmsD=~@p|$0ac_-VCuns)*$r-JMC^N&O#6{bMZf-GHYW2`>}jEqSF*$5DTDUu z)-Pk;{I0S-rB}5~m$*mib(>9f%Bx!Xi1Lv$-xDx6o49Y*uiiQlmDl}${Uq#*lmF>| zHRJZlflF#t;>pTG`|6IQ&g|tr%T!XNdpJYub6my)X%b&y@Pdkt$IkB~`+`gt`u1dw z$(yi#3%2}v;eot}#$Bj~0_obf*)+~fn~#=EsxviXuOjyx9oDR5S7Hm7 z7ST}Idos)1wq##*0JF&|mtg3@cgd4!-iA?HSFEz_4)#4+8<5orelD7*FtAj!v&|#m z!IaxXj_$IHp;xq%8*keWrbBD3F3AE}7Wt@R?8b26y3+dbo}S{pj-v*v58ZvbynpiI z6CHyUm$VzYwdw?AwjYQ#$an04bs>G>BUK9!uQQUybo#!`nwI0@D<3;MpxrV7mw5nt2xH)+?+R<>hMJm%Jt|Y9)M#Q8Y75zo6hhwa znsr^iJ}P$O@Y`j%-~gwl)0OAmYj`zBhT~QTMxCO&#*Js*=YL)D_0ALWm~`^c%jCD= zu&S}8w@O<6_-(N2%H()Q?>eEdTYY{-BE@O@y@0!BnpYpSV>QgygxGB(`uXM!88aHc zv-YoW!D1(@UeWl#a6j1 zqP9>$%xWdMp(AzQA;tsBzrUGGoOR?9uBm1z>gOB2UoA27sZA(g&c{kB&9}DjXknhn z8QYpLxzfjBBI8mcba-|nfl=wjZxKuG z3j9dQNp?LOYSX9uH0Nz=z3jfx9mjZfdU{-Tuuk~)^2)CVQMw$w9rnB|lgdlHS4?|$ zXWF{x8_xR}7I`GOuUZ*dwy+&L9*k3j-RCM^;pa_sl#(eb(2|oSeiz9 zYJ2xOfAZQfmg@|mQ-<&Zy7AftuWJu8Y5^N8X;RI+$g$FC18;MfNNAU{nHaa~6<X= zv{yhVBAmzPFpBb#>_a?!yQ5u3~E5TxrU`eCgV^ z+TCSat7r)|8;cR~?X4jV7kYM1r8bwwm0z}EEN!lhdiN$ipe86sAtddLP}bucN3snU z){BN@ZcaSLL^m|Lu(mlynkVY%{j4^+e?oQg1W5$`u4sLfyzm*P#!$8%PUF?o?e~f^ zV!JNowe|6|To$%XEu8fzO4FE@^35?=oX-zJ99CR_$KUGaIxYN{8pi`LS*pmC9ye@kg=2r%;#z5M%@GP4zCl%A$`8^`XA z8&bED3j})Gx7I!zt9EbBxX&}&8fv~Q9axOZ8?d+Sthn@ooldD$f2l|nJ(_&{ZE3I? z=JzxWx38;g!ia|AYafe^XNlPPL(|`oEM6P*8{0xTd4nNN!Q%u@J?VSaNW?v(jiPw^5h&?7evp_Jy(64#dc^g`k>+AkE&z0 z@6Gre)*VWH=qF1LYf;|*ar_lL_PuN8fuw2kQ+Zr?R|&(V)ArMk!UJaS z5yrH{KdC=*e0*`m$nN}n*z35bN=9~9o24~Q4)x9HjjFS@#6Nw=-CS8)F{|mRRJ~YK z+2Mpre678**Y13dtEpw8VUKF)v^&Y5!8zsB+WX1RHqs$CRGb-{aXx*tNx8!1^d+(P ziab7@6ul#3!(!?D55K)i$4n$0&11U!h$KhMlM&IVI>Ph)9Ak;+%Ws=XDaMU8NX3*a zXJrOl{Jj)i(VpDh`{?!S7lLjCpS<;!mv?MmoocsqoaKI&@QW?TKT4kEZCG*A8wKH2 zPLcX3>{jL&i%~WFEeCNepWKU3c3=lnD)(mSQMTDY@FYHsV=0(Y@Pux3`l)Gg^Wk^veH-#)QOWwJGLn>Zm*>0f z$MjJQ)(jb2pvm6)GYYmZms1V zRrfhEdfxDK>=*gc8`yA;hK*n*y;w)budS&$+%^r(SWen-UOF`ye?1P~gqq_E9V^f9 zgV%3mzn$MdXO?JWd%r@%THyobx;66oOTq#9FcQPsWaX zooXH5>aDG2y)KVwvcEx6mwjfGzh>~Lx1Y=Er{u_0;g^;ZQ7u8V4EG7Knk`{teGyw+ zF${}9#z;v^NUUjRmRtAI&5`kG2a)%=f>m1X%uc0>JI!ZqAJ<%&-=5Xvu`=|!!K^nu zA#%s;7scXO3I4FyIXnOa9D%5Y$Egt%gz!W) zB0-I){9i5M*n&;}Q193aR2-Bf@~^K+l7Dd#0OQl1 z%p1VF$qS)?kK!%Z`#EE10<-rG(eIn zF9zU0zJS)C9W4Cum`xexE+DswVFcx=*cRZZx>i78lZS~TZekcgMJmPsrA>@@0Od^# zBd+!ztWL!U(4b-r(4k@gjHws}W>g>SfH@_P$Dsetz=DEzLi`r&`H#Fc6_e`)oJTXz zlc*nRj($bzkSe4FIDlP%A1;9fhyY(ujOL*6=n>Q!?M6C~eTWUf10Em+3r!qwLtKPr zqp_$zx(97QT97HA509+vP=Xsu>;lrD08K-qQ4drbJ%cnOXJI;JVH&ql#s#2U4w{UH zp$AYDEkY^@k}1y2JHxeJTwsvM)#sGkVb?J5rbjSf+-M&WBfn>_PJ0$7`1@j zPaqc|rwxNC1B>Gy*o0vLq`=krq6X+X5{{6dM+QIzdM^O=1>pKbK{OhO+M^4I6Vd_a zH3WJvk)lvr0M0E2*XWBLLN(C@Bodgy*L#2_)E0#Eh)_l)fGw(zV$pjrReaF%KxkbA zjtW8>WNk^HgUX^8ku=BbXf84VPJ(z~2fb5*dcqXX$l5T@ z=nArid_r81uOJ4ljsRmS0d>g_@;D7Tg=ir`pcB|5g+LdUmE2zm2{FD=*_&OgB-W%rZ8|rQs;^pTa?CR|6 zzSli4z}1rt*$QYkjKp2+COFg!p28hP&%TXcQdV9?lUz%1%Tj6z0`mFr-)q;#M$BB0G;3qyxfB4tSg4~51!G_%pIvOaDhf)f1Z4$TJWg3xmPphk$g1ECh_bqR zipmDcI29db9m)+7kSvA35mg+{ACL$n9VL>AvaB9anIKElSJ07FRnk+ECF<#u^!4?X z2+Dej(DbqnKqLzw5QK+|0PNw#c^05$YXEF@R@G5f&{b7Zl-1MMgGO|Sy0R)Ndb+a8 z1Qk`1s;-hQQI+&ZhkP*648Vhz>-uK!`pChv!dns8kP<9oAB-Y{H9-y!8$ndth@LqH zYKm%qn`|43F3yR7ps*xiCFKRTI|GcI?n{G}F6Yz(m zif$%gQx+c1Jl*Ypbz>DWl)D4$DR(2-Gr@-apLZWZF3zq#LT;hXzCuU6+}wp+o&DT{ zoP~&T1V29^4|%*C^p_Qe0EN1!IedZ$W|4dcU|56C6keaqV>Wq4PKd~k{c(<#!b8j` z1J9_xx{O5V4Mo?4tPB4y`5$>kQ&?pb-iFMxQ+XSBK>W+|P^72 literal 0 HcmV?d00001 diff --git a/media/so100/follower_initial.webp b/media/so100/follower_initial.webp new file mode 100644 index 0000000000000000000000000000000000000000..7f93a773a784d43fe070b8e69a349fea16fe692b GIT binary patch literal 198594 zcmZ^K1yoy0*JyAk4#nMz6?b=cDems>?ykk%3KTC;T#CC}f#UA&kQaKt`+xs?YrSNh zWM?wx%*>u`vqf1-T)Y(q0`NslSW#V(Q{w{w0QdyDCgA~H$N(u35k+ip&`$t3wxNTA z4I~J%wR3S&mJlY^(9|M^*#m%q-hW?)#?B5xii)!DKmPsx=bwK+?-u^)J4^rmtdrNG zIL=UsUfYHa1+QgnhJSngf4)DMm^vGS{(AvkjK&U5E&u=+9SBx*cX4=!eL(O>C(xuo zaKbxm{tsOI4jcUgH~;OUsw@KPGX{c*jV%mKK=26&rZf6q?dJarwzYA6ANT$BzET8J zJ2e&1_eao$4-f@d0-OO302_cIz!N|WPz132fBLij?Jokb2le&@IDzgn2Uq}HK=%lN zTHc>v3WB8ob^v3*X8;`tW(F{VF6MVUgYE^r?&kl4Kf3?61+N1Dd|f~wu;R z9R~pLq2<4ApEv;kRCoYjsKvq1$?)&vAV8nsW@Z4uRVe^~s0jd|Pl4{yb~a;S{`)@| zf-nF8wFU%UQvv`m$pFA>0ucCI2n4Fep1=W&zln0dXr|!1kp&`q z7ECw%d2SW`PGA|83yY&6nrAr*k0i7`S;>@dm=-i?7PlI%s`0Z+;g6-k*`4r=ySKtpkS0VEA@KdDOo`Y7nuY)Ds)7ynm#LN;l4j2 z(QkHkykZ2wE|E?!eC@Ou$X-AZwClLw8t&u>p#w%AE*D=o==#5 zNtu4zLjO}nZc@4SKNBW>EiKLZk`5#voZTxeo`Qn1g2N#ddzMB0tS59~vvBxfx|$vW zwX58euzRSZ^QqqK8$WKiA2WPKpsga@I-dDRFrQh&|Ni>c=#fYl6 z_?E2&owR3uAIRPxH~HnYO`=ypLL7aO{ny*YXN|m;npleZxlVHTNE1A*AaTjWApUcN z!d1I^fdJ7F7o>5%BE!hM{9x|P_i24^!B>eM{?7&$oZ0FPWE@K;%G~AV+JbgYOV>{d zW16VU6>@y@Yp!LGwmrfqI=H%Loc=;eux$;ZLvtd@r_8js^P8N}1zsc0uHu!2)brda z$)P<~&@+7pU~PFyt5H6+4;7Yui_W*-=z_*+swAZDi_GgLHSUYpY13MNM|vdIDIf3h zL#G<%KjZ2*+-h)`+TCtqL>6VDDhbMVwC1^fLi1|DxERtg%8>%Q(0}69lSsIQA5L^g zq{Vdp>|pTz6rgxe2FF0MdXXl8ZQUlg&kOaraQsrs`0$gHZevLPGTh&B+NUHZ;ZR-v zqPfv<=bhj<3|T-F3fk~8Eh|mlqDFB(&n*OpX9a~nWz=N7V^Tly@eD-rqXG0*XM7$j zTMb%&aVNoE!}@W!;H6C^6tNifTCjisnPTx1U$$FH-2;P7a8poacymlU&<}Tv)xT4YkFVQXL4g~G zlTGluA3o}&hVm&U8w=KH1yTEYgT|DUZVd?CH=8K?nic=g3W}qP$?jasxp)5ETsfEiHRdfS+u@lwdfe zg00io#lC0^)gt;;zoZNKl6X6rOVp-pP@hFHVpS*p0%@n z@ol`~r!(jOU?O<62}xUkPcZ^o(P3;Ec^#N<_o|Gl&X~`f{M)GzNES+-UU2AAh#|w7@^P9CP}2Ag2Hd zuUMXJ^MF`r^O&aic}0|>;GmsT348st(G8-G|ELO(Oq;`m2>%a`!FY#?7fyG|jN)Z9 zz&R_-E*kv_BUb!)n1AMH1fg=LO#7_o+XjHQgv4k@cg3smm9(7taOIzrcvw z{k&8E2!6UF{WUxmbK5?ufDb%1xh7mw2ZItCe&fm22=P1xvn)2*H`TSXKyUU6P&!2;4bICKA_!T%L`@0|KC zZF44(yJznO$yp|tG ziRW3kT}>JRibN&cuHfG|s3i@dVF@iD<-D%(PRn7*3JM%h|E%tvuup>iFT)`$6scBL zR6+dBn-dvinphq_UxD<1fLs2H&=M1=_!5U4Z}1tGwqQ>H#ZEJX&nVo$ck6uw!jepE ztUA_dNVO3slpNvMrZNx%gRIJSUXr4{_fK172$*xZ^*A+ zlh^rPKSsSF^3gCoDzs~RVP3iwvR`%-QRCw%i?ZHumlFa!-FF5?NZ}Ay z^PN~>t*Ehtp38Q#2+f>l^u~It<7+U%{J^q%l8CTla2@qaZ-3ZId*_ypg#RcUFAtr0 zVvLZ5Z6Num!O8TC^E=sD5i+DL!GqlzV;ZzJK)D;|1YhpQQWo+^Y#~;Of2*n_udx1$ zeFd$sftSYb``Y>Vxi|hatZut=srW@tsyy&@M>rj)NkR89Fj!LOQ^F~{8Qtish(J4v zk-O$A(1@uR<_%-&%d#RJ7Nau&SPXeg5{5TGZjY z2)LcA#g92y4vCFYGFJg@vS{e&jL?Yr7T%xMTNO;+B_?v$FRW?dzVI}9l_GVp4YNO)+*FH5lW;H6a%Y$HM`{zP6`DYs^%s zmO#TO!94@-;Kre{AiZ#3E@zye6Hcoi++Vsv*#7%pbHDa>>L&x@dAerWl6l9k zTw8r*{dekfVw*e_NqBDPci6mQ8_ncpc8K)8lfvcDWMYiaPk<9Ho>=c^EDrn-ob&k6 zyfM&UVvG6}Zf%T!FoKL@Q6SKd5f~TNTe8^9rLbrlyJ=-17LjQYn8MY)fraLyzs#KV z*R=QBMfR!tYlcmtS&(r)Zq#f!&+qFX7^R)s<2wm_HU3q-yoM5M1Eiffwd%??D_08l zJ}&wz1o!5%DI+s%oi`60wx;VW!Ap%@_%EWV-WuMro^hfXj;YlDN@6=i6=(+wM?dFV&oVR|V9_t|eqN2ld8}ZHCtY(pMq=1j@a0Zvv z*`U>#wY?r`!Jn1K^NZ_J*dWoPxoh)01RdB(bIH3n1$^3ifI;twm}JGjZv$-~=ETn74@SQx1Z zmLoWa(GYs6Jh?Wyr4jQ}((k{;ichlF^x6Dj?RcbBQEC-F!kdTp|1Bxps)VM)Cr>Q* zRJVoDK&F}guDbq5;7gvfw1x*1lrg-K-*-vns@A?}ybN zVnPem>Sb8g-sqwY62?UgVi!cd9z^Sg#Khee9+WHj=d<<;${TpMW|Lzm2Zj6+2J8Mb zn7%a88C;~-H(*!Z)OIVzy9-WaJQdgtxfa+gfi}eckG3xpPx19EU-w`B#xqkfkWkd! z_$q{{`^_LwSgSnc$8M>c3h`d%B}C|YN+N-?%z+0`U(KcfV&ADMHfH*1#}I$!v$@ET zEZ_0QrUgs^d5TsX#4k!ly*)V9@VVA$oQf|_`5qsgzPJ1IKmt{?12*?MrnX9c@8fcQ z4F$16l@LxVPZGx<3osM=Q4s$13>)z$6M}M{tRO2=S!KkTF^0s-X?Ds!_^HAki#w{^NCi@1 z<%Tw}tOhGKWQus$capqL_@?W{1TG+fRp8ykZkG5+cRC>kh7{+EGL$q2rHlxeC}LfD zvc+Lv(c&yAtJuoDaat-&E3|p|CE`Pa2RITaQl{i?x%9x*nM`1o&wolKSbde=OP7x# zTj7T`x=`Jhh^JlMwh&rV;xy9EZB9*1c0@jLAPQ|Nkw1yFS@MEY+tt?Cf%({*ZlEw} z0rbf(_)}fa@uP=&x>^8ikr%}l`o+>X-DIBZ*!Y7U-17zukH+J4h@c;*c68m?#i8-G zD>zr|s<`!Ym;6465!0wRpONX()sE8xg>=9i7XvtUcbmgtZOLt$7X4F3Hu18218H^FjU?EvuppE^M1Vh4hE zFG%9DwDt*-Tcc=ZN&iM%G?Ve6J;Nj|9?dzUF?b;T(8hjm=35OL3(-KHW6oBY(_~-e z!GI&PEj_w8dG2X@f&!}+|Ib4Ke(q0pMT_c)LKmJPA_F+GD zf+2j@J*)4Sn6^ItYozgUCcT7lIXXLW1Rz`ju`cY?zBuAJ!Ul|s% z@q56IG(ISWCCJrUFJ&);85(}c3zH9RSF6)jtALL%b}qv>empwy@TD9N*R!a<+Yohy?jPGtTk$R9{d_*l z#96EK`WU6(hzzwe;SgWnl}p72_1YMh9-p1D_4`+2vN@t41%4Oh)Lx&1_LTWJ$7we?xEnEW3b<1X zmw!ECLl6N7f6dpge-A}J-`#y!l#7cFeaJqQaz zjUZQ21O{H00(-5!E&}LKK@no{^4_X+;K>HC+`uy*9ZteYP7fa+ST7BOrZ-XL9^6ShwQb+E^|T$H8; zQx41woXy#1a)P)-L2cITVLUxz_e)xEIQRoW;)^V_&ZSRpIU?|plAx34%8-6bG{yP$ z70t!hQ*IYL(822)y#7WLuv_Xl?bK}=vUpp9bk4bNj8AEB2IRV6?3l5%BDfOb;B{sY zIgqy9_m2<`pW~)2;r#^uXMVwe*S}NMGTMi+*#V?^{g&TP zdt<>qkTGD;P^9p(rd829ncWcS8BY{OCMegmd?eU(h1ozFx)4gcQ?N_i98vBiWRP=a z9#tZF+AY>`@*#P(q^{fV7qTZI)bu3!t;<=%+t;otp#@%PCN)mT4^heD=tR8Mk{t{} z3i(u7B7BUriGFinAZph4HU8&VDLjM|$R@}>t3`hQ?twyK+R8C;q`QmnntKktYw{Bu zH5}ad8D1B*wI2hs6>w6SlUZ3U9=Y_kb9yizQ%W)<%rv@tl@zY;GLTC~GqD!c z45{K5XCZ4D%YLZRMXl;C(j{H6+uNtVqyRD(av8)tNu^JH?^Hq_^Cgj(hhjW{zTR%7 zr%$+a3TDu5n0^G`y@!W$Q%zxn@M>467LL znAR6yH}avtT6-!5ivP|a?SsW|JziwmZ1M5O-pgx_F|j$Ss=rQxIGL<*$g*qq1e=hc zLE^t$Td)rM2Z~&Kw+DMULEUAegDb9UE#$i2r`ua8_39u-{nOqi3PsTGN56h~u{e#7 zVvfi^I*2O8d`%B2cg~D|3soGY2S^m__yeMB29R(?h#2xcET6+=u{~J2J5=(zco4(NA(K2NGVo_Pi#zw zwp00&mi|&Gj+e9~uR(HwxX8};{SNgJ^DlAGcmzoPLRu`1XanqAN~vv=gB+!ZlPIhL zj#*JKX(s2zBmvRqE$3^fRQGa1(%tz2l^AgefxyeqTdqm>yY&;{>+UQ^wY=?LJ+yL= z9cNDieM;IJKvN@-dK|d7xCmZ z?c3El4SDu{n^tF8o$W&irTxL!YL*Nc7JTULH){f}5u->>rlr^A*gR-NKBnZwqVWZ$ zaQfnMSglom;XSeXvYwtD;=6}rxIFu7cb0Uapsz!hHwt?GNsvF)P^!Ck9P!g%(wt*~ zk-U5|>a9SST|$B7#oJoj%?&MhK6!(ZpPA2D#$dL@g{xq&%X3D&UXLkv{)mG+&$}y& z`ukwbkF}G?67(I}Mf(t+!Vw3{b+&KZdKTL6QKC?5Sax=NWGQRUNKOBgp+99+Yr};Wi=gz67STh|kH%rtcgicvV)Q@@qSxByvGde@vz~v)IYUBY#^9 zlB($ATeee*VZ?+Wl>oVY(wM>In(PkyVx*iDSjxZQ%9-BWwHI-6QK8zW-Nbky9uHs1 z++GwsUdxIwYF{S?>-`Y3p2xyY^HQ(|$EQe3!Sb475<*<5GnpWJgyf|1=lDz_1u@Bf z*#jpsBaP}q&Du?$QXqV>tqRs13uZ@Ek@roy!>%rUc(TX;X&`B^deax!8arI6E@Yuz zQ3a6ph1M5I+0^&nr6%!%^|Qd1#UOg%vgmk8ug;2cvvu$kQ*x`~cG zBD|?1Wm(d|57+_k&)Fo?U`qWMpi_VRv{ql>?<=hv@)N}XrQwLRpL;KLW5=PqKr_~O z@Y`TE?G3TYAKEk&S8rD?n1fFQWuHz*CVxJECn^aHOuOm2B{+Eg{4M?u{#($fiAI?T zA($E(yf?tzC<5cM*M4@$a)h4@B*i9X6|}r&e`k8vDYjX)jr1WvDkf;iLM&HNFm=z` z{X*~^1!6%QBU(0e=qrycIVZ|=>1b3&>E;g)zD#Z&32(Ld1?-=0k3gPx`S(p&2gPl^ zyUw+>K)P@2C}8b4TrK4ltvC2PqfliJf%%8BT9*rkoo!Drq}Vz>S{yG*Z_La@93ZyE zQ{ONYy~>2VMiGZ>KYdd3qk(ri%PA#p*r}LUUkw}VWNctqE>gg8E@vD3Jk@y#dc3Y1 zVXJrU(`C!gMaMyn+$w;EbcU8W zc2eLHny_BNRO+7ad$l!m50|;t5rFyW4=d#5*<=-|{o}PFjFG!9X%@Rf*l{0ZTR#_0dSLa@)sy@#3@X&f-cJ3@a^2b=ujXzBmmTg^Nh9 z7p{2Y6-6zlpAN7Do2p`a!j-`770T-ij^!`iz^^)^94Puj73%VTbP9GK;pa4J>2&Co6RL(*xT^T2AhoOyhaF{)5enHv7@ z!%e92+=&h5YIZuJb~4B#fpnejHnV=l`p`Nv(vNlI`;q+9PJGxdXlT4LsED9YS4D{f(#?I$rD4J`{PvRvXszKdWHJ5-sYe+b6s;xmWZ_dU*%5P2!E`C*bhzhL z1F($^=5+UEB=d%jef7mS8X1^)+rCFoy_R9HGxE12R8GeFAyKZ1r#O~+`?qEM)PXU@ zN{pEnFDQ+7?DQU@3Lu>)6@LH9DW|e;oG8I3jD)ytMlZc13DOw4;f>#8nlU()h9R{(y6cEY?WN z>d<1ntN%Ljm*Di^?QiyX)_m}~q`@TFO_2sNvg=@XHUwGJ8eK#S1?GoB=mhHK^uy6>a#T%O@0u-d zf?sO_$di&dFjrcmDCR?PJVcbg@+~3MHaG@euI+oeoMfz;?dj-iA8J|&z+CZfVY z9lfY-o^hCL!}Ll&o+{@8(WvbimIvj~>8bQSE_YGMyD?@p#tDUL(#3r>jqJ`56;oM( zIjKk&J!rUsAcGhHe?Rc1EE!8lK>TsuL^1`M5=l;p^rl&a?E|URjVRE)Dn9>_O28hJ zXjnc3#>i*UShHoVK!1L&M>NDPw$JVR=7U1iM=gT(Y?TbIdVrPr^U5@6P3?;fX>@lX zmDuQAU=NpeuW%>0IIAM#*J$mxv%E`dFU-$UR>8$y>d{uR`#ym<6=p-qc@k|Qh&;%-~Hhd zX_ryex*tp^trhTKw%rKn=sMuttV4wfai2ATO4$ydBAJmaKn2gGvP>Cop`|M&Oev+^ zFc+QQ?{DdI8FpqIe06qgv&)+gfCs~ZX8w2yC5u3@l1WKxQ3H+;#fi>nn zN7vFggkkzA2z|QwRF36>j*0bP+6{}y&6F*}2Ii>e{6$Cs=a(j#fdax#r2J9DVHX;? zeqDP3Zt@S-xSepUG`CrdnH(HfBFy;gQSlYLyF0cYmWIwUi}S)O+awct@dI6Ff&xTU zlyF;*aJ@CMOKpaM-@ZFHYPp`GRi{Eq#&QM9*J;<{y1E$fTHoTZQZUMZ0wNPTk$5_P z<6rwanfpE01&S72;W0yLPH%$r;H*yeQuZZoju&0jF9}wdg^LA>2(Nd^+|tu~dAO*b zd1KI?bWB~zCPH7Bz-F}@G>>%5jrYpZaveH80N|a!ddqKRdWhC8<-4JGux~Dead_e` z?I-Cc5j{#68?RNu7!3{1rmkzn_~ghv%*+Y2XRfq=)l70mfTygS-bpL}voi=#znfO7 zef9X=obMG0oJ}<|%~7^;B&W844a-Jc?2}Ir#G1MXM*P_1y!zq?5!Bk8R*I(?Tl&X<=1%I$v8 zw)2+6n;28wLq$9@UQ#O?Os08%__o&YGjgh*BL+L-iJdD5M321Sr~j(Jwm} z)n+QwS_2J>{%gc=!_|d^_Znsw!o-1I=N?Ft1IGVtw|4^tYf+g=x=%=;Ead8JoHj4m zWQJ6??`I_?Ym8kurlW|}0m#8D<|-U)pFX=T?|)Ip%Q@9hNf%<{mN}*-y3cRHD_b28 z5M*adR&lapvKi#OP?mcq^9$QNGL43UUF)Ov zfy@CrzbR?#@#QldZo)!DyEBZk^Q7O>HxzMqW6}VJJ5|G&Ayb&O8H4$%*J4W@Nv zt2bT3I78m@h6~C;dKx#G_yv_H`fu-=iKT86AexC@ds| zQwP>&w!yna#7(hK;5{(~pp}qXoWFf3I@&0fUCCU9RpF|&ZIEzV?0ku%;=HQ}Cpsk9 zMk=97nY;TZQczXJS^e2E04vV-JcIVGUAS?8 zkP5%jF`;-*i)uOicW8}m9j7KjSnzKVNUZK|aditK#D01u5*6E9Dn#+TKszu!TS07k zvn^h2J;uk0o30u5$X{WO)M1j+_pUO`e>0E*W~Gi?DMLyc*9Du(AtB5jmJaMwaowT_ zR~#X-uwsoz8a9ItAih$!z+%;`g!(Nvh>k~c>rPA7osnaRl=bkJJB)7r4F1J>CnovJ z&clx@L?l~Ki!Na5T$PfnT&hE+5!V?a`PM5*i$FZS6*oxbuC+{#>~Amz6fJxi^(t)B zxLK-8tdVO#b8w2n>BGmU)iq%Jt=$z-6?H?MO`J9G$ZC*tB2R0a zy(?j8g+S1J`A&oY6&ga&5mh6aEbqkjk@e-GM<9MyzG1rQ+pklv*>evz7)(XI5xX_+8L8IM-kAw zJmeS6zbo`Tyj?7Z8mNFAzAKMF7jIz3eSR;`A6xDy(WVEAmCH=}QAaPak@}%RDfY~$32?H?*dyD^#1>>aW7vqDXs+t5T z3z##r?>BL@laU?6uG&h)x3d?5O1Hi;uX!=$dz87PU2zw=ui)xoKvQ;c4f4yP`5y^L zoJf48*@wtgoZ6{C7&!OG-@j(CG{ixn$t1xy2iH}v9$s0mDU9Qi4g$%F3GOj~(scCL*&yCc9 zjENGFsf?XY2m$)RQ-us>@IkOc361ia-AsY7ZG}9E*)cyy-ojhK<7s7B?+}Y&Z>2{5 zc#BALgyWxrjrC6kUQ{C>36fjX>~0L@(%J7-E%v6>wo1-AH{#YKOqmtSN5@wq6@HX_!P81;H0VHrx5h~te{W9-;xC7(PqzCZ*>9m{+AYIU{uHy8o^mXD%FLA&l*1mx zahX)?1YDvUrjy8OXO(E)u8Bu@{%&Fe#dd6)4a^*Qz0J5)rUwRy?*eC#A4gXuEau+u zZDlAC>Im0?)q30M6GxvJwO_nM1ALWa-^f$mF4PT}@|{BFl`|ir6$6qNK%#8vk1k6Z z+d?s&uhIfOPkZT3c@!i3rE_~gB>R#3N4n3YVmAqy-r;eYNMKI}o95=l@EfG%501uT1=+ zd>>qDWV7?^Xh467O_!QhByZ!0MYl-9m1#%r6qO<8W}&C*hF3_A0=O!IURroW5~}|u zlfhjoOG?WKYOrqvWAzx$YY6% zzz=|8Ox>)!m;ia6v~@=dC;1nx{a3OUcCflk_TKOywOc+3*yg`!d!cJ_G#1TJxZL7$ zU7~r64cwJua`1vg#e{ys7Ge*FJHl5h@44A)M{wWlrj*GGweZN zvI5uD47IH5r$PGJ+JxLg#SG0kV_Gx0@DW5Mk)TDEzZPxCpa4C9D#ASh${%O$(Wsj0^Dc)K18^^)~>eJD~7InuOL{l`I&Wx8Q%~ zt_={t&p*iMU-cjrs393yJ;k%p(voJ;G*}dsGKMbd%sd#7oG?7^pl~Bu{oFmo&RAh$ z6Fi*k=nr)V3J+aU=Xi8?Umxl7;$0?oSb2b>5W=-2*zMj>H#)joNq>3Zs~rOkn#fHj zXy)JjwE%-*WbAWAIB}Pa!jUD;420uxZ$u00N1O9Ug;d3A$YPd-PMDRpYg8;P?2t-B zsG3a##S)@BFk!EmiD`a>WN}{EoA@N5nwPc7D+_%65p;6e4r@vD4?x~!p9!Z+n&E3d$(Us7^>6bj zphmoefAW`G_Qa)q&;1VPZQ}G9Xd%S3MdEHec8)HH10&p_Ne1m zlK)BO)Iv9vgw0UgfDa? zBSF`FgsDZj0bTPg)Lr3C?1)6l@)&r76sv{zNZ|J;_^Mvp%~|Dp7Q|?X&4{Fff8@>u zPP=f=5p~9wxhqhzbHhcVN&576fx38dLMNY&a4_J@3)_wSJw=p}$qP>WzM_Bol1tij zLa=LIIg`C&k#+%HVjNxJNH(XZ)1SF7zcD(n5cBaFY>|C5xvWm!^Y>ytEYIGdgjrZ3 zBZ$BoThewuEx7lV4BJ?r`wA#iWR5R%350<|3`T1PyA!g=-)}C(lp(3#>j6@@atzlo zF9lBwySr;0{nCcYsgBovY`D{uwut5|G&AXZTtSwF6NLy$*u>fw>%CUUIQ4oKcn&;` zUNOCwdQoau6y$cz_%06bJ+@1G76G>>49dhd{$X?T5xiOdOiV;#iGw%}3dXDN2dMa@ z$enu!g@tGMnCE5%>XTJG#nA`L96g?W}YVNVyMBhHQYv63Q7=Z6X?vcHh z)R@OxiqB1>+$!7SdNQhqLCd6}Ur$@|>U1~~tXcO%O(NBC%BfL0ryWBii4n$92DRv@ zehhHh*KFA0HvpcG;3tt+uk>F2K_~g#aP{gC%=VS1$K-bZ4XTssH7_rQKrPbVz81IE zrPj6eX?YL0;?LW7&hasHA_liUu%1ZQ>6@-61OdDTpLw%4)+SE@`Xc8 zRCIcQiOwtE((&-s{15Q#3KXMXsq)bo!gm#jN!!UXPm5YtfQLJ-$(;P%7!3#wBR{by z4~Sit2pcp+zAS{?NUDi*Tj$E(`$Xn%IRKuHYu5Jil6xi#yt#u*x>l17+=$DWQz%C`V_c#n)F+WDvAKOyjobK^u^c??P7^wPi07S`Wtj#bYx+he|m zR<)yTC1?`cWF?UVbWo_~AaVOrAST$rD$b5ipCvx}c|cUH@EyRjp@JO6IetrUWp74q zXei}){CRSYUe<}%na7{JD2p88A0PHi0ptC;)_${{4|;c|viY|2n~GDmR$ymzA^n#F z?cH1e{m#U24vXCmoGeXBxmZ$m0D`%~QGjAyy52f;X3KCms?|Y;?A?AY9d7NJ384W= zx%BUk>)3OJ_q0**^i4(?LZR2OB130vX?eg$YVYb5&$DFEk;=`ABCrhH<@^oe5ox%Y z4h3rp)fZF?HOq*`;u#Xk6O3l#iN-jCed5#OM8*dnC}oSrXKNF%eT#?M)o-hE@k4+y z&%w6#P!Nc6M#HJ}0d#VXFfQhTJy+fEw*-~iSUB|i(1W2-tJKUhU^2bTGlP*41DzzY zv1kch6r#Qz)DKP?X;D9JnwAL`rAxbRT5>wkJ579yH|ibkQBdRgb`4H0vQE*Qe3^)K z*+*%Az4C)YsdD1}jYgO2fXZQk>qH)9wi0=qd;cD&V*OO>?ZF-OH(BUcHB#PyAvt9Z zeHcKJXm+>9&}esV!`%|NBPs8pyhcLnaI;&^hZvV0ZX@dAT8|xoGw%2Do}(UHtS%2Y zQE{5Hs`#5ej;`n<`HJQKw zU@+bcWV{uFD;If9Z`FPISr4rHQkAkR7aXaH4?|g#kq0MH-NVMx&{n+tml_(aTzA98 zmaZmXeja&07bcW_}DfyfakE`R+cg7DYTs48EDooj8b|04^qdc4wX z0Xgg`&Ht;Y(08_M)2swOC2(n(&hPHAYa@is^yLPd1~sBlnWvr{nV`~_#L<36 zhy-jCfRxFgiB~AuUP^lLtzQ-LO2OH}Cx){~$sNg49_m8$y}Acf`?@jL6dyLTocJ#4Dz*Gbc5talTi*@t|YF@N%Fhn!CUP6fb%iIO{fFl>kzrl;zIW)m!1S37X+mM*g#IF)z*JZ}B5>JZVG zu7|DWBj8OZ{YtRa-{320>KYV}KqR25xU&5NsE*X@Bb|fb6AvO^sXY5bK^Z8opYdvD zHq7XStfIHS39(E$45>S6!|Vf#FuvE)tLq5s2*HJ8_3RHxWS}gUl@>E+hqsxtfDJOKRjt+ zTTY>I3F+$OQY!ihdzn9KO%4R+b-c}s`&Zr87;y`}<(q3JST|twtalO^PJ}}$4@%B<_tgG?_-D%=0jKS|>5^%i zid*Z-X5XM>oGES4u+$+H{5M$DXI4#c+26U3>yy5?RWE7dsn`1Xr!6k7tXq6kmSZ0B#3@8(n`qJ10> zv%&`b5u5q~U3o`2vEnwGpB2wzTUZB`vujT;m#H7ie+8hRwtyn{Go8qG6p0Y+l<}bB zTkzd}X_f}Zct2cnNzW~rb9<)42b*a9HuTq`qKkR!SKlHU%}WaunzdbF(WOXX+ssZh zf1%`Uem%2oBzJK-ln8S+4McR>m+^3k@hS|2@t#k7;`Jx-o%rEj?9`g6QPGX-_{GXU#Fq{%NxYQ> z{8k~N94)qH(=VDzI+INFJvUrp$ekHA$rI?y#Jxu&*R~{~^hm4dMG-rIySUN)^jWfy z3sD&1WrrXw5KI2hx`*QDjJRmGTcV!o15dyZ&j;5oRiw6f1pI2@n3zLbtY_dB;i2DH z%IQF7$lDMgd60kKrjIRSSgpfie14BL_r^o_?i?YtEvrAal@4F2F#Zi6RN9k+|mi7v9<3wT&a2XPK4!KL;qGuyl+mg7rx&My7qQvB4UlQwZ1!(i9hrY znPqch_4xpv^BO;>%lG;-aa2}{Y@SiGCGzEJe^$)XPOpw-s|&c^je+^hhf+Co6T!ts zeUnq3t)TV5dpf-w-KV(OJr{reL8czsMSC{wQ$nwZmb>Yjowr6k>k_ep-eK=+6RE54 zn#wZ_?dxp+p#^%ko!^fRU%jpFN?li}P++M(aiFcZSJ09)?7|UjX&5G?I!v$o10qsY z#iXBK(Y9SX zY;4-q(m|2gSC=0w&kymQFSk>-WBlw@+hxJfbjrk^Ne7P%fMW=k%HJ8h@i~hF zJzq9{<-&mg8U!L_&@C5S`ts|Vtp(9blSx+vrb-5t3=^_=Jmh=`Yx@ZZo=jJ7_iJrGEMnH^#XSU=a^;>wKa|eA zlFdmjgFmdS?oD}l&T@nrXhE5Oen)=VUS%v+Xgy?$;*?yW%+%cDjsW%@@fAK)Yh}N+ z-+THQ%skztn-;{J#vLrBvhLe=Gn$h_$tC)&^K>5zGu0uq!o)+2S#9cT@Lod14e;3bt$W;mhb}{Q30uC`H11=*CE1I;C7yebY-6u7BD0J zN>&0YPApb?S~tq_?T1*{HK_=jm^;RjKO#f8Q#pVm5afEs#XnWF)t-WnmfObFbz7(A zp^@+cU}j?R`6lChn2}LT1ATs|Doz_*et=NTdu{J}T^$6$#5gYgn4gQ4rz^-=^9ZiN z7Wm3DllUi@*^(eC+a9g-k+%_c{qbAG@Hob#t84#~8?bJp!9g@k9E|fF48YqqcRn{m zG+BIT3m4mox(W+LXcIxB*7cmm3GFNRk(*~vEc!fzQ4BoNO4Z+sO!;CAm6xGML{sPm z?Nrx>CfeY~+N-H#5u@htr7vfcPF%@TpG^eHW*wa?0xS-mG&lAOoB}mK^z0*{I$2$i zhbGgfc(c(AsMkJoS!R)gh={qMQX^LHq}1J0DB;b%p_KKStp*JvjS}h@Sh~OxVH+4e z%IN5KuUtPod19pW8{>Un_g>+4SQEqv#nFFm22ImCZIeC{wjRT6{LDuRX%p-f{t-eE zFVcc6_ECf-PZw33)v#Zw3OA$7+O+bXGG|yB6dMZ+w|Wvb=dxi5t_OXMBzr z_U~KQIw^nklI#iM?V6)XEM35ZTl)%i$<8JW;pAOf&@IPm0Loedc@?Wec)>lL1?&fq z2#jWED{*QnDknoM8pYB`?)O?lCd*G0GoZXd?g2(P-%S}`Set8|9KL2NjumH*!jhfXtC4(i&uQG7sL?0FDy65xbdr z5M&u}jxI|IzvCW|Hi%1F#r;?|phr{S<+h!N%I6Va3Lv|Gk4Hl%N3-8NbD1I14M<@!Nr2_;E z(%X5py3gj`eg6i2dUEXAPuR~WQ>1If9p#IcWhId_pi$+A3xt=kIuHhSc8S%fG9(cR zE2%^=Obow3|?I?af`mW ztge0*{0A=d@WBEPRALeSWpq%qouD5s58xJ=KQgVoTl|2_iw#Zxo)P^1&Lw%nk47Y> z%y3^nVO0twfGHSuL8kJH2&pA)>U;auLd4mX8no$^OJ09BcwFzoQ@-h?FktULb0IffkBw7;c~*zRsR@wW$%2maI&I?P1XpRDp@2-;FZD z&cfr5!Mr^p%8psr9+PLay#4L;BdWZE{b+n7B`DGg{i!M#<8oYagg)4HX-ju;LkNQu zjM8ha=Y8PB@wzu|YE7lZOs&ozyOn|eOe&YxyERgZu5E4I zG^XDXif^OQ)8Kd`Z{X|W9e`42egOsaYMud7Nc5UO`e|vxuBP(yAYn+ZIiO;#2lkWr zk?z-;%eH9vJZGOKwTfn=3gLr->mDuvhgU##l=Cd3l!~Lf7Y9#tT&coq&!_%nKokX* zsp6vm4#O;RZQdE{UeIPmjofCPF2Dblwf-_`26DKB{hX0cySJTOBTHVuNhA5GI!I=( z!0fT&#AX!&#X-Lts!*Q3g@RUmOTR4|WM>}c(2DiK8zLkldfPXw z(Pw)d?D72mp(gG|D&IvgGoiVW^|whFX|vC)5P~Ct>9<~UWr_m8yhHtO8Wmj2;pX3~ z^!o2$Aq?Wl?&L5%*A?;|+9_qWa-$Cknja12B8jj&m`9jY1L({-7U^EuSb%;4<8Qa zHDk3{N{@3Zr=xt6b}GU4^@~p{V*E~87k%gp7_{!?O91DezwJLW($!MePr;+CH7iea zGA?kbx;`;1g99@4l{1g_95!&KO*K++V9bIu6}bndJAaD6fv#gZsj#p++#IcSjs)jY zNFL_795*}j^{u=@GVAr_#Le>d+~~P7DLLtf5Lwp4kLIw(c@vH4c{mLtZpH6Gn+?T6 zpCz4s97Ru*Ip!I-33E)x&18)RO&{MIZgNd(0_c6bcBNfz(th*NS2e2{CtuiKd`Ot2!W&*FRI9}0KRdk*nhsRLbTnG@1No@58!oGY>Vf9cy6wS4-k`HrzW^>HKij2wP7%)l?J^Gp= z=JRjhO&D9Nuz5VDi8E%((6>-mpB|->0WV&`bp{U2C}U2hil>q!pB10~tD?2eJW_yB zp;XUiuH^`S%>|0iH0P6pC1RGB6QOT*^ffX|HIk2YFst5{92+&ieCm7YMJxBd7^F|O z0bNXO|8ZCZ(4W|~p5#f{zXY!QP5{iQRseoSp0%#`qZ$@Xq?ydYml3X^F73!&?InrQeO=v2ep`KI3)Wj>B>jZt(a!&R(ZP8jA_ z=tW2QExTr<2s3Y$It1?;8!_Xmyf0EFM14Xq=iGpk6;pjc{Cx+Iuh>MN9EH|Ap+ZN`Nv*aRks0M@|DKS>kXLmrB+yg9R^J z2|Tu|CEjea7R&$Im<48U0b;|v*H3?q_u z&v37gW?zfJ$}jb4+~SnqkWBrh{#NU!LtG|UzCuQ1<}k9LFP}lw68!=qYfHHw$jStc z&JK$NP(A@2>*k%kERQ9%dKNAKlpBCjk^S%e$y;$%Tod{}gZOQ<8^8lhKHG}W4Ip3f ztaV#u@WHH4B|_8=jZSN3 z|3!zu|NXj*@`ih8iz2rfL(lGpBR|GMtskMpSyp-a{+k1$jbt&UmPw zLJ-P)gTL|gjtdR$8Ge{IKHc5_@e|x=YQ}CGxUtX~e+2dy8wGD@>85Lx+Dcj!e=lI} z9Ehv*@3lesUCkM!oJ)~*iw8Xk_^)H`xajZ3V0K828li%q6!C@*rIeBCo5G>6rKG8nQm2dBhuDuWyuR z30Ix5pFL5%Qa>WVBdvRt)F(UPV7{xWeyBsB7lH}u+B2K@vDQ~<5J*!ZDm2fakP~R_ zY0GYamS4U!(qqRPqY$E?R>J@MHMCetd9zy&03(ep^aRjFUT>#3{#4Q^Ud;SJ zn5^C9_M79ptm-c|m?KT;Av)^~Uy@RPBDg9pF`m8*%S3XNvHJ|N8;6rlw%0qfSF+rCP#hgbj3~JBtxIs0aWT*upf#u|k$4Q8xYYY7@>YtZaHa zkSR20(PmXVRAHXkbE(+M7pud)P!*Y`D_e6ik$Zt^T}V;%)D@I@X~X@Qgl^AZ*8P=q6bx~| z!M4rq7x-iRqy#abB;gLgrjuFCixGh)WLsiSFYUN>7tsP{e^eaT|=IiZu{ zIRoM3uie$_yJWfK(W7^-4clo+$<+d~YEw{BlC-cqTh{@8e+jOEcujNldBYN)I7Vg9 zQ*2dK6d9T=d~|^VnRm#)hrb$5*S(dN+F$sVU!wQ?kGuj@mC^pZvc}BblEAG|I@Cg( z3z-F%-_iPSf;R33Lt4$~)8_I0WJdLk`C|~^Xd!wPE+yxTJ`!29(i<9>-gGJ`-}Oqp z@4t4v^O&*XP&!T~dnl8Or1xGX%-fma7|;M%<3T{rjjo&hD$5}U6Hod0))c(E*M3D? z?aP#|R=lVN%IG}lv~KjwwGB@`Fe@S?VQ?MCjUurG&V(F1WmLoAKLyf1556d(aIKN~ z**!nliM7Kn^OmTovjC15&xaDJBud*UOS5Jd;l(6hEr|=E2+g(z1s<-^GIXw z9X6f2Nh;aE$@#M1@psV5*hq2Vhotb?HsoUlXqj$1(fVE2>OdtN90*;I@S8J@eIO$f zP~%OU=FjOLfQedKyQRCUoUw=R1!nleiM4n~)aJU4;|a=5-XwgGPnUO($2;m8T!v$c z(wOI1o*?U94>GOF$p(HT1>+JYF`EE;J-(Ae#9;b@)58G;X4Hd?7=9A7p|#T6}%NW8l~R z)%@J(y5F!eG<^^?O`xSLvD7&g?Clfw3T;p0>LoaxoX5;kNaIuD5A;lc!8<(=v=xMQ zBp?Q`L)v?LKgZ6xhPx?ki`9@VLsBPM^m#oD^Fd4984bkEiKFJ0{`CrZbsHJ~Qi}{J zY)swclWnJPuo(mZ{sC4;`q8)Yva9%9+aC&YuF#C7I6pAqhxbJ zmcM44_)mPjvOMOMWC%UM`j;Za&z_aLNj+6QGDgR#liG@(Y-MrmPqZoj{;GR>x?G~k zWg4_qoj_<|m^qMim>k2cEBX9cP_FT6E}raiFo@KpGxb7I^LNPmZ%u#9qBVfCF!X3J zjR?iBCIQ4)oz9RGv(xNoC%uB;)Jt{@gbaB4oic{7bEC9X__c;9z@W%qt59j|ZTV6x z{C9j8sbUZ(a=+Q1JdxpOOKmE^gi8H_Gc+951w0oBAkmS@|%=WXl{m-;??rr-~hIu z0wfuKPyb^}S-;whPa9;32i;MBXP;{2<{uf)W~)7!4COMZHc_alv~Wx(IALg^PCL5 ztjaU_WJ!?4e2q=J1)XL&;*+6w%}SdUZwfeAZ*vLp9yU=4VNL!!ewdX97w(ZpVrg)3 zA#U9d6?YIskk)ziy1Gc=W5z9=RsA`^?<58p_6dGgO%4%BVXCVMDxC|phf@{{Q^egG z-a4WjOYElVV7KjOjnHf?#H5hm_rk^%G`igz_Mezo5hhj1`CMfRZ|T1ui*xbtu%UzK zWv3?8rx=m~#ea+ZhF%ON76HDHI@h7vkFzee;DBsHPz1`c&zZw2?IQq6MG9$!%F5K0 zYXRyu8S94;OP!v?yF&HAwXl*eQ11GCP3T&-!-=FR-N>m0lrsbCU=v%RS?2I**YWzP zR_^{OWBrG$QbFj7hO|eM)jBZ2rmeg2(XUeBztFOKY#DzLwUd#t3+PU6Cy$i|Q5TOI z5ee@eXGHnDCpm4N8FLs|jCzgx1DDrV)d!PGQk%v603G(gp+=}+k*TdT_wpB1?rD8i z!zw+LM`g4=Scejg1{dy=7@`(5ymaa%QB<$!VBN5l+lGCcZHd1jb4cl14HXW9AiUxZ zXLj-%^16W10p?naa_t7!#`o#h>9xCV%ehak>eLt5ax#?1R*Vi>>v0elig>~Cl|*G! zC6=8S%$Au!6*nHercvf~$DsyU%W)C(iG#^R+-JEUw$1W^TbP5YW#E2zz_08`2lfYP zf1B8yYX|Ld`8&BrAEC-Scu$CtIi>bah>9Y^w(*<%_YfBO0Mk#1J_yDP;nU5ki_inp zrF-ECRaC@wnjp%5&|yg+O4OQ>FOL2WI47?+r)mS{I-}$M8O zsBg{KO%p;Y{q>r>VRf_~To7#+VNvUs(9*7V55fCh0LfAqs-U&?uSC>532$!XYb;8Evpu|3RYQEH?UVCiF^TLM-u30fPmK-l(5HQHCuGl{)6fchH1FJ&PsJonV!O%eY7 zG&T3(t*>8SD?C{Oz_lVr04*i$wjh!gX}c=qWlHME5Y-(fPt?#;obvgg~nuD<8Q@6{qW2aHx!4xFQg4*^=DA8h! zrwK%aoFF|n8W#__wQj8D7e9=w%J;W}{_?pHDdtl(4+xlxCy|xy_BbMFP~Ua;?v1o) zibbrV3=L6s73$uMAwFyeIXWn*#b+_}8qKSZkU|$r-2iG*i!n#8nZ)~+C%R49h9aQ^ zfP)Rq(!q@IhHRs23Np3qd-w@OM1KGja;h9Vx8T)Fy!xxlP>H;+YF8^5&e#}zSxgNl zBGA7@carQkA{D%hjnK}3yYI?6gldVYmL6%7yCuqutoH1rCUZKs|+q)g04 zd?@Glr7fMe;>b0Ovuc8C(jOtX3CJYw54}&QF&{Bu>O{4X%zmroL+-^@U@^!DM+u~A zW8jiwtS074Zul;8>Hz@k#U7LyZu!B`l&(Fqzi=mA2t3*uMmAtR=)7)!PYE+eP8_~{@3rV`pfOJ9)dUaJ4`QJQsIwfg({fscQ8DY>V`WFo9!!ZCvA8yQmA#E zGqI1+;hc-Ax`&w+x76W(A`BZOS)6sWzhM7sgaB@e_3suoG82`? z)#UJINcYz-y)Q_6%Hl?GrNyYhwfU(}8834@ym38QK7p1IdFSgJ$vD56Y7!q@nFYSxzfc^c0$uH9k8h>ZhQU&?o>Up_=wapvKTRtKe zMPd$%tW_^V=1aLC+9)*5atdEMAXf4w`ZN)!|Cf7G~ z>djsoxp1{{+}OgTVdhir0UJjh%r&zHBzL1mzB619JRsL&o9|9zSNseJjCNXP+J2d}qyczrIyciGzSO^+am3Ghdpix)R?j%e#1pJoh;Kl; zdbpf0SS#T)uL}%32tl%IYPr3IdMo9S5J=S$SKgCiJXH55SojnP@fZ4O-o2S>63MJ= zL|l(DJF7I8tao;Mbo+mVN2k|^-5B-q!*y<$-|#^^AFAQ9wVO4Z`6g_h508H3)Zy)e z7*KE}d^n;2*V>wRZj=DA{kp%+pY-uw@QH^FpheI9Jk0Mi&iU>iJU8mh$6ksnw2o5R zjtKw}i+F@mjtia*n_a;5E^`Goo~WC$NYsO8-D7m9jU8sCiJ&fDf~>IsBjv6)dYO~{ zdR|jI`LVlal_@Z7v%2@zi4|vBwtet}hO-3HKj^!k@Io!KNbjA>ABek&h?`<=!EheWoEJUv~1}IovS4qYmoR%4A)3Y#GaSNDMdD+VTJxU_&AY~ zNgWs~La)9raCw`dP{ci9u8SA_$#5VjjNej36KJ5p30UL{{cPs$=1z%NyCl?wJ)@zr z*w4Sq7A5C1OCCyoJCKo&#=B>7Zi-fk7+*B-xZ|<<;(5OSa>%~@&c`%(Zcv}@IBEej zd3c$jTiQQ3J0U=^zoTWQ-1(!4mmU!LIy^ps@U<}aR4Bak+B7ik^W|tExOB-g)|oP* z<`|+0_{g01YY3CkhFiYa!k*TW5JUPo6^6dPIUTi%6=Ia?y9NzQf^M(|)!ou5D3uYK zPbRY4l)R4&HCzi8fm4VR=Ztm#lQ0d7^L3V1H zaM9B_$P{R$bK#@T>J1)pxqt53SN3k7`+gA+hf#0eq)_?h#{G%3n=gQYgu){A^on`W z){vaiv&3j}zz+96W)rl4Vt?r9w zO6t;zsQg(U-SfB0NR4^JzB3)bJM>?9E%+u(g;PuNoV~G2dFIKGoX8QGiwD8pja8L( zp}%7WJq}=htlqYeHPyrb1w-n5=%)9rGoghk9xKG`U3U!o#vK?IMc?tN0$;5)kI?3P zmvl|>3>CFfb}v_?6<(ISb#BjM^I1+Rf;Hq<=CyA<(rOgw)cl zyA=jKWQc=jhMWvoKH!hVGSa*bBA0^lIE@;*!5_C!?`=G_RI%4e?!!mlwPfjPpc$uEY6%#$H!aQim9_EI_2McU~0*CS06 zWRJ{DVyZH!QIo4T7X&9i-n_P%wT zqhd@m?n_rsR4>CwUOw*OS?F%@6CJq7Bqzpo>^^n*nfrgms>-`U_E17v#)1JAyVRwJ zXlX6_&(6;)KX{I=f6IS>`fzC+_u)uq`8gJpX`b-EooCs_XPqKM!<3lKEt9Ib`|FJ7 zvYYEID`gDnap)}bh7_;&&l9cpKMP}+I@+o7pNSso-5G`*nkbt@t1XlY{r6|{->O}p zKeM$~29v!{>d#)_+2)_#JsSFo_X`yr%o}3)27w^c99XZd;N2rLxHivrfsmG1B!CJ_ z`)qFeI^b1wXxaPVu#@n{e12Mmem{4>-0EBh^g3$=6G4F5{wQw5g18~+3oiugbG3d( z?H@b}Ja&ExpIsS&*QqBvy=ACE5CsS-0ZwyFOwVpJ+NtgT#Zh?K3kxR}Feq5L$+DiF zhzIdE{sOhLMDA1u^D;8cl68FC-WLg;fbOWSOsu}B8tMmjewwu=JFi%WDHwrFB*k$Ays08Qf)Sh z(q-H5D!%L^lkrXKDHjjvok!O))Lb~QVLK}t4$B|{YDiP2{6?ggHaZzRSyYsQ5|@_w zGkbmIyHq6zyF3QSKL%)*+vl0ugx>VSH{85&ZLK}z(Jl0&yI<1Z>IAQ%xAU3>wC~F% zZU-rN=G?%nORc(`>!rDC&l{Y-I@^mc7PK7hR!GdX5Qlg6vi?SYhF`u}T@^)?;8TY= z2TYQJPcegHU+xd|eWhv&ye2Aed7HSb>D~sj=s1-a-Z)piOGqkj(*#$`b(vf@j|e9e#Yl>e7~lyyUE z=)XM@Zi|`mSP+^t=t!(>MxIUMBNVJqBG#mlp!!spgrx%d8-9h}Rx#kpe7Y0`^RQT% z`+a?rAdG63WOYtF9@Ay83K4{3-I{&y|BJX5WKy4Ls4%Wld4(5qg5D^k2P>=dDmhl=ZH zbj;R8xA2>kh;c@5T;~H@qyHS3q+xIZ!H8BpGFp+$d9HCe9V>M{RA^;5q1J@ zh@Y#~X9K#N_eO(Uih+EUB}mC@Y9^{l{K8sLZr;>2Z}V>_;Kmvt?qAh}{tVKBC!(0? zte4*gDu?}FMv3UV0_t#rXmuR#+qTv>oU(9T>~;$1jR3%4j!%E&s4LjvMF%Lv{|k3| zYI`m}lZt?r8mPkU1>8!&HAxCcFC6cY5PeM|$qT4E%H@h6ZIy+sc~D)0A9d$YrTAef z+=qqraXvFAH7}XLe6^LW&5v*{7I?~c`48!&c{VCtGp!% znIL7i@3(Ccwoh_rhuFGAEwy@j&G}Ak0?kbg4-}UyQyRn#;Chx6--{&T6*_|>k+I4VAqx|q3WVJpn~O@vI*I7QkbwE!+w#__ zI zS3*-J-}o*GKXPoRyjD^>iYucd)|m=ejMrottN(i|?HahPX$1;%HI=lqoq|Ko6(fuV9rlv`A-4?cM8da-@Q3ztlE><#xyBF7 zwZZ_)faK*P2{{@4KLg>m<<-?ulCEg|Ly+@litMXcH-qNoN*QgcQ74$?MvaDX+PJ1o)&8F9MTq6{9q`Hnj*02cGl?jaS+e!n%bZ1b1Is*pFdnlmQI1N!ovoi5o8QAmU)joc{!?^AIlq`fSekG z%;ZXny`0=cshr7&kL~46Vd6x4rITk0NHh;7TsKB&eq^%_d`u9!y;rqPCkd%k>@sOC z4c1*nL*JzZ0)RUVbo<~C3P*PkPS#L|QrYnzM;-9lK0(&3b+XSSk z5!y2qC{<DD98s z5bbQiK8p%HF>%Mi-*>t~%s8Dbw4EAATm)AKIzhK?q{okQd?H6`zvCbtPR{jzDmoMwHKSN!{RUN0 zqCl4<3hUREQB$!4#AU6StJP!At?~j=4@TG~#bxClQ%0~s_BaN!j1~0E&jEW&0Q96F z-h0Ip<9}%XG(?DNHwaV_IF-TY=NaC;{;`R*9e-X)p-R`?cQ^L5UO>j6z%9KsP?!yHS;>#RVwG-hC zgv?W;QIw3H@~qhl(u%pP4@>s~$P8b*ag*eO5(2e9_02`%b~6TabBp)?MNaXoi^53`N!Z-FAuprbd7Tm$4eXC zZs^YP@Bpp1+S~j-wu))4sHh7B+XocL;R{aQ4%Mk}+Ezh)!<74@Z?nUDOt>}702KZ% zxW74!)t4B1*cWz0=_s)h_qz(Yx$iyh&!2wWHR%yoAwI17>h@N0ZO~@+h38mG{l=%~ znc>vBWB#aV9V=ly6I*~m-sgv1vOY3JquUL`*zZUZcIpqcJQj+KU;1Z~M&O(5;qrMK zy8kwy{|Z-2OX;jynj-)#sVfmldW#q}mRNFirK@e{P_rY&{iUa~{F>`HcN#OV=JvBu zkvJ3c+?@%1xv!@T_lh_CZO9+4d`5B0-T_1g?&&Cgr>A1t@3++IHT1Wp#Z5d1b`fzy z|6o*4l7aiuWs`2+fo>94uI7$#3ySb`54kqW4$$b{1TFNp#H$PO@@DUoAGz;cOiF{y z&aYV!O^fRyi8gWU?pjHTft}nKekA1jRU(1!E%|lA{L>TM``#!IknWC@)b3 zF}+-gj1aqnsU!|KE$rxVU?i{O9XL+w7O1r|q)#q-9btZrI?^fLVVzg90F!kRM0{J= z;xYvp*!dd%?dcC_eD&8tjBf%d<$X)k<|Q*+pYdC?(_EGN>*-5^jHBm!wC4;Lw~O2* zn%v$=2*m9~MV~9TYO1gtVUQ%`p34skz_L?@JW=L@;=zMVPf5c@CXT=>YNNfpG>cWu zqv}dLy=+$vcmIL4OvJVizso_9{aQ}ATZJ3MjOP&5a8fwIj4o9O(5&k%r&D4A2m6H@ z!gp0zA64^+T$@sn&KSAxxW`~H_C!A=ubYd}9u4C8c51`#WS83t8Y);~$*oLpYi!l` zoPM1GdrJ1c1{*D`H7~|i3^Ip;Mm4sQaPZvyzT23c?3dp)my5|_GnQSpqdsgOH97>- zVD)qJja=@;il8zz$ZieqSF6v+F|n#kvWImm`vuW~r z8`4BFS7CYD`vb3ALMrFYLYEXB)95ynuv=Hf${^}&rxpQ9Nq=UgS7Qxx6AYjcOnUz& zTQ8@J@6)_P8RzKaP0eC%c%eF_0=$ckJyFOAR*NAfcO}35)O{o|K&cBK5R%^W(0ukeyo{EKWV%&EjFp!Nrdl8@XhIA| zb!W17&#Pz(BUOo$y=-hf8+B0{{0z{GYQ^p}9a9dBnei0b!ykgAlutj3X-<0jXJfIOHa$iof{9Y$k{ zFPU;!p8`F(I)0d;uvj{uBWhBJaVZJv-kZDiZrqIVv8M8>*m*kpKDGzCysaI%GZ2bY;@Wq$1tTj8i~|m zF=NKdyXv{RMW8&OLY43{lZ9CjC&S(5*`!+SBB8LB20>k1K~ieHPk0~pv`Ti|)93%M zKxCrqHc0dxB7gK5YkDG>ciWHOdrfoPbnhl1%%3#uBzBhd6eM}Og)Xt7j$Tq$ zW)o)#*x_^;Nb!{X6@^8J``uEJBa>>ImWzb5T^(YOlt@Hkt3I_E$ytEMJVtmW9&qNX z*`xzb`Ab>*Q}l#|mm&iMFRhGFC)qq@j>Q_kqC2yj3ZOF)Yk_6 z?Lw6jlrHK+9FU~APxw}~(TzwgFUhZ>`e%>}yiPF7dycJeI`X|ML5Smt@ORD3aepSJ z(e-sgVXf{09cm;BNSoRaQHm@k5!(zkB{&qY-z*AyK4D|z9r75a)M`tmPj?{NIKOmH z8VNTDJ<~C0UR>UigZO=nr)s}o#_^v0J@H*G5@G*&KSRai2o5z z^7fNl@)4EI1VBL&7s1kR z0Gb(!srG!fP;%68s%KdZU6XApfg#jKP8y`Q7Fq=6SOI3UW&Cg)&GrRQ*qbYt3n zin=uZfUfM0nmauBpk_u{59d2p(NX_mWxsk?XW3=;Xn?eW0qxYpk!rJ;9=C~UDD1Tf z>B$E!eUpl|d*?2gIqgI1#ALrHEN{12c~pyA-8;=%(gHcA|8O|OZ)6*U@Hy4J=x!M^ zG5oUwM!i3fV%S^Ha~wAn$e(V{ZRvyuw9hs89y)7N6)K_sQFx#_a#Q}5;P)B){=hkL z$@ynIs)#0XfEat^0GztyXlhI$DdPdG87MLmgy3=3#mn}{;_zDxTtQ3AE5f7;aqtYtg zJfG5Y@E>32_kwT$n)Ue5(jq#>AG1GpKq~;!M8i1=>~7Se?wOMqL-p8qBUzGSN@U|9 z@K!zyV%FnLSYwNo+I^(t(bv7^T|wIsARZAj?V7D_d8?57k|{5 zcGx()-K8AQ{GlIriACFVIn|nX4+{MI%@Mx3j{ug^o=?xI{r8OaPVhI*xAjv%p|+8b zn1?>x6QqzI0xp#DXbVrsY15>zvQBsT!J8>pk6D3ow9p9%+ipsY6%9D5O=b6s+0P=Y1zG)QF-$XSCKJBb~(>?01N z6^UPUPUQ>PWpc{5;xnzK58?gphUd9J28}+&qQ<=_wY9S=yyG1yUT_o6&QY22 z5N|E1t|{4?I-VZCPb)~ago7g}N9?j^=Bh&u;=~l2z80VZB=Vpedf81WxY6DC#H=MX zi|waR*Hi|G6I_+K*6<_>G6QgcD`ok&P<~!b`!^ zkurt(sA>_el<{nM8oPo%K?zyUxaeq(Ow9Ri+oup1pQY*Os7*zt-*xDvcL_8v!WTzxZb;MiS+}3j92Ufc( zxv*F)X2MdYMW)NMJc`5hk0(J_BC*2HgcmRc?h4S9CeC2;v2HUa z?5OAagAEYs(NiBZjFBNJXGDkW_2XHzK_!rang6xQckn2D=&qp(U36-=uAJ=EN(H}$ zFq|~?70!Yz7XixvYYbKf{*^E7^{2-O@@HTDVmj#$v1vG5@DcP|kuTP^ zZtS{B8OM%ffu9O=UI^@ijRUcc|W2WS9?&h8HOzt*bjJT@i>T7Nl| z>#VM~Z^VYJPNtc5QKHARZGGzN|9KhXv%e(>-w)O+->@ebC}R27A7?V0V`EJ_YW=kc z%M{;s$yhYJU~Q<7fROMj&eIa3)1VWhNjeIAvgc!3$vqvC1Z{zUB;|%4GIBVW%N% zPxykulzN-&3iXU=HHl+$2w@R5pmFe}DmP~itdo#clQn0crQnk*_~fde>hA~k=PxRu zEHWytfAQH7A*@^Ji;C2~s!)UNDMV?Qv$bTd92liiOb;Q2J>jEseCs787C=b-%}AwHK-)6G{V^b!?+S;qf#NhugGQ9-u)R9JM0`|0vN*4 zjka+{B_>|_*?fLO@M8O!zogW*yr{jXi7evZ{i(bF4>X|1;MVb8EbfY+L#O?0_5Ar) zAv!j30=OG|{qAw2=a*Kw|p@N@{MZ%oHvaVEnDit{lDP0^xR0 z&3VYXx$t|&R#7$BYZ)$>s$=dy(*1|g{!z5Jc-iQvH>fj}TF<7aZl*hP(6Y(bxB-53 z9$D8?tqS4VWIVbiclr|6j;bk5D9#}%G@*=F3xbR(l+|mG z?e_fxRDUnc;FVvFz+Y@QYb&it=cBb`?(rG7kU1$oMw{C$R_*hqogIpQc9@&$%@~-~ zm00UFC!nqI>Lw-BHdVB*Bii}V27;}Rr90%LP=vVrQqc9T-0xY1bgg^WnAHGf|_LXnKZ66d1VtblDN*y5#6f zBibx4@tDh7Km`kQ89ptbXQe-mLZznkmKw*PlAqm=TEvjqZ}~p}azKs0x6h7*&ol=T zAzRCZ`1>U5-xSv@lq-i~iC3DVbHJ14ZBA7;ks|%7NUCR0wFa^jar?Ca`>^~-82ap{ zp0qUcbaSRpt}9n1aQkJDX4yAoM(wc8)OJbKO(uoGY0w;uA%g*Vd*kp-krzP~`Q>(( z_z>Jl*msn|yPaTmmYPT4AY4&gstpY5O~BnuqcZI-VMYC+$(4YUO(@Sir?$#n9nXU$ z6>xBIV6MK@(Gxvpbc&lbkhu#aPT}=*FTexcuDtCpkPC`8DoE~xGiN4>miV6fQI~dTy*|8V9&wuaF#v~KfUaGP>_z8k5Co#D4yZ0G!ACbs^pHgmjISiwNn={E4DMGf z?X%V+p_ifp*C_tT#!64>bTloRrcNwq$%<>zF*r&D0g1pCt?w!}ah}K}vi-~(Yl0pH zHTyy^8U-FvK2#H3&g9e6(a{+qOjA{T5J2o>n9zEqR_HcXh7gn+L7XR*{TE9>-^2P6 zZV+$Cvx8vDStYwT-YHQf&6y})-3k@A@CMIMNBW?G%U3g)n?z8yIG)oaNVG6YQ^9ub zpb|je@xf3N4P1aL8rXHeZD*avJp5MdJEc_aix7?V-Zb>X5&!^ItJiwNHHm`gW7FA7 zkPmV7keKtpLN>I}*9;5`9nIjCD+rM(TBa4*8T1tgGFmom<9WF@lU)Oaq2pjMrL$An z75x8$4vbz|K{t&Lf+&`AW%? z@DiVAkTK6)2kI+~$vy8=D5^KMRlZRST6`d`&mN8-{Y$ap{WOgvkYm>yR|5`$B~@X_ zg)+XKTB3+*J*J6XnTs6W zH8l%8EN}jlVO=53tBGVAT7pJMfeI7nbzb`M3*wm~Mn)SlH2bwxw!Y*kYo_Z-ekkk( zebS?eXN+p=rZ+;NsyGN!GBBz}T|>gYWmXNy*MT_G*SzLcdd=$*=n`yJe-z5NruJQL zG!zVI{G049+%6$$2u1&{pwZJi$tX}1j{q2WH`}S9O>hG&u=gf_n$H(+<{iOo&8;pu zK{JRlyoNExr4t(!KW+sp<62`6yYZ&PXM+1~idT_ACAFi14hnhMKc@{^Yqz3F@OHgm zM8L5Mw*Yu4?!4Qj1dNdb*vL_Rfg&fHtb;eqb49rP9>&3%voBD4U1<5(0G*VipEJiE28sgw?GaFj$1^ssG!ie`dUzpx zV%eWy2J$HVP_cbJ*nbn;w3dUM&Lgd8SPBrZQ<=^XZc?%_z63+v6m7y6UT|zD==IMO z>WF>d?|?&3dU#zop-NAsxl0}UFNxf=x)m%kwi-D1fN3N_Ul4ZZmTrrDm(YY|pRdv(4VgI^VCTD9ab3r6pM*UdNmS@w4Bqb{2S} zwqBS5JIHCAT#F!tqa1JZ6y*Q6pF3KM3$Dnn0hQXN6rNT5khNyI91#%abEu0N_|OKJb@B4A)= z$Xqvl4d>CC57m8vE<@cCS}-(h`Xn)(xI@%IgU@z3_0%luX1>@M!)4TNad4dUfp0LqQ*@Utlzs;mjU&(BbeFUWxZ&4VLiI~P=H ze2wEq3rz)u!$Z##K%%l;N@#u*9c)F=`N*EAZ1P=Moj?mMIt9NtqopcLh!(?nV6cp6 z+m-B8!fW!mQ)fS|&q7PTMGoXQyGtB$JNzZj~&2n2KSdek)X3$eQW9 zJ%vBGO+zd}y41M98hKQ|kKThdFq|1|k(=3L<&BxvT*?VwTz$A&R!E`}=M?O)0 z)6>nX%>;|}{7|~i)6Meyo4J<(M4_fAz0~>Ms_Ls%yP5t z9)>zrg~4E^!k_C;Wx(c{Cqz`$7vxW^Bz0^sC>>Ta?xcOm_Liq^pDnevWRmH%;-KtM zxBE-X3tPE#4k#ZZ3?rU;ugKC~>(_|qK+wsx-LfA3!wt9b5^!UXGBiAvXuX=_{CC7M zU3II6?pGKk`Wk#+!PxrPSFacGy4mvLyye4DkiDQzj2HXJFH*!}o+MwqxMS#jL?yze zFLjOr@PUt!sME)9Q*8OHIO^zbNkGupI^>UFn#w+PDrtDV)N7nTK{%gxBWWJYN{Hia zJ0Bo-L(G242d&_K04wrjiwUZE?Dv{Qgo`U2DjCJ!$ew7k^(T_wp>XM6>VKPBf<{P@ zef{!YqKhjv3(3eV!C#VGmVSyWyh~MS`^YxZz~I`yQa0s&6HHQXz};2h&F6HVo5K{< zc`f~l}R zjm$T$q~NiD*`TGUM8j%G5ug-9268db504X18be_vx~mV}s2_QC4C z8V>XK#F|OJnq|>z*b%-fsGM^H6rgNQmn3I_R-`yUF6yF5q57O%^>Ly!?&O)M(&`w^ zJVG^~xB&4-cr2OGAGCY(Lb?_N0;4U3x5DoU8gmjeJ*2*#VMmMkS|Kh#BP8gz6C6Ka zfcR5VGA{N~q&!bR6g0P$$jYo-{67oGSrdw2V$Eb5SrPT<6#w~2Upmr;9^bdZof^l{ zYy-1(e@1g#A(yS#)_oY}U<cs$9X2^Fn%i1DL>Yf&c&o^vnbl|kI3mk@) zo8GX<)GH<$@G160@V1(>$k-R|RbS?*8?4Y-}iGV;r1<~a

4xX5n`_Lm9(^Fj~=A|(*P zJ^lB+w6CdIbla;q2eZSdN+O#jIGJu>DTEyLm#rIZGjGITY?_Q-7cWSzd>$E%#x%>Mxs-|%k_Sq zu0H(wT)9048p8d%5yBUb~-@r89MwsOxOS5p)fGI=gO12qaF1Ffl` zkJxEYKb=NT5SsRb4EGQK0^)|EDAJOJzCnXj{kM7ewZOqLL}cx37D8pz-v&>USvsmC z?}Y*q$!fjMl#%<^S!h*>3VO_0#JsdDC<9>|@I~W{XpN>)-W2FUcRpC4U#;9RS1>=( zJdeYU<>3HHkSJm!NL<%R7M~e~j^4gTklq{OmXb9B7SQ)M5$7mPrk`#Lpr@W4Ss5|%aTdGRn@ z#EoiEz$_eDu(Y?gOgI8mzQvqNRpwz<`*6?^VzoEL_s~x&H#{>c(g8`9NXrI^W8;Wrp)WaB^44HCcxvE}o_Z9bIpdzYtrTf1Sygs?&vi>R?rEozA@zu5D%|=x3`FC}fuOx_LS-n_Co}DgX2!A6>9ok6Qk(W-0ODoD8d?DVLaZ zS?j|n$&E3?abxmGFB|y|M4uc*Mf#yzq~I4SEHHY<00!5?k)sVynv0e zMEh?@@D!+*^O-mB?0t&tjp0EQ&JgU1r3$LeXq!F4W6-H!=$9{KR>BOGNPmcDpZp|kr|Vu%|04V!IBfSP ze_I=AeheP*4q+&OjT3iz_PHVwg5^S;6%aI5V?(Y!o4oK61;j=OQ8;UiScwC}5zxC%1KX((TW{37_ za+ve6!=H5`K)3eaZC+&G8!0{Q+(A^(4lnTnPJ^Ou&>^?DHBA5z-L0>)22%^)1OOmx zPdZw5OXvuO7*fCh6XNv@Z~_Et?Nu@hK(aiYcvwo{Y3MTr1k4!(3LI=thI0WcPo-=I9``l~x zViLxM)SkpdWYb!g3;BP3KW<=3g$-{H3TfDML%8bVQ~x`Mt~Qe}Gl)5xPy~X)m>hz; zN|HR~A?fPMVZ=Ak2J$h)oB=^5Z@BD?egxHuZKKk@z0?*1;iM20g;n<<8ajWbOI_Ub zw?-@oQvVc0KY8w^!`oBc#&bmgN%f-ZQFI@dF@y*uN=#c*O>Z%k4SiHcI1I{YK(kSV zA6<<@2OS@qw_Mt5lRDzxw?hrIo@jI4n|{7z$V+J|%cztO#7<(G!9w$E0;ZwFG%FhA zu?XCuQ#*d&UIhN5prCY3Tj)q)gVDO8ugJ_pLrzfS5F0x?;M|iP;}vQ_AM41&J%tr9 z$>QGJdcwbPyOlTHi?&DXnbJK_|K1FpA5b*$UA%sL$u6o8CxGIjhdh_g&%kZDiN$FeMc1$_zxAi;m0t(a;g*7{_(`%kS^W$NdSlC+?X^|dJD)KNd z)EDT5>|k16<#TS`(XajQa!mWEMuEp|kS<>X;+J)uj(zYz!#V`2GM%Hl*C5V;9$(BE zQ0QLGC74m!%fnU&B@#D5fi#@Lb0^^lN@9r*H}D7dl>M;U5U=f~K-w{x6a3Zn>M+Gz z_YZ0`WRzrQ-1H|MqJ$h%J?fmSu=_ywA-Ez-b$AAVy_#Lb=3+es3m)t|qCr($8-f<{ z9c*%d1YA;$yO~q%f^Gm#p08v*&2Rn(af+iwpn{&szF2|Sa91y@plX1tH)%yj%RSQQ zwByD|w+}7oEW~JLMy^*Pcc*)d8DYB?#)#;!J+mUX$7>pyx(IRQ1$|FZ*@6<#eFq<2 zbQPrHp`Z2!f+Wc=1=Q-{4C;3543^RDQ2;RGNyzuaf%GdelZRDrxORDnF*|hNOvBTG zcCv_C-%7nZy)UsFBjN$m-5^1$%_L)DZD}5Ro?SW{YS&^zJp&Tng0H8Xa`=wjXMmA_xmQnq%oXkQ0JsNSzK@JF z=-kU{X<(+y<8PgS>Ob;M?VaGL3F2}Ckl0oDZ$%}K=OmjPo44Qq5)*(du`>Xbs}LPH zXlllKjsgs37@`2E?TV*KAUft`;Xou>8H{J{z|z359u|*&#bY``jzJOPaADP;Iem^d zgmh|mPfjak7{RNl^=?8cmRRj&TL2|dh23U$8e3Y9o|0wTBDerzw2qHbh8wRf-)`78 z{t?DpeNLPZWZ$N~64P2}e`M3FqWD|t|3PeoiJ(`6xC&WvYNZTF<)?R|Mhg+h%9I>s zwGcsb0nbk*Hbm2|29`cg8kmq;fHEopH{p5o*f%-Tbpvzb%@SvxBWmgFT@+_3H8j*JAetbFh-gzOFn`P@P=x8 z5r7Y5{qBzkw<~EloQoUMLe|Ry8;zom;0&Mq(pL4Ur%|>zd=#_tOg$8VuaEuW=h_|M zwIdubiqeqdaaxj^hIf$W7F5>`fW6>bReDeYa1eN}wi{j`y11zs(Ql2GGvM zQGC_si_d7h<4}qVbbc45ul#uk2Um3Z;7rd!LI2$Bq5_})_9>^fswTN^$T?uA4h60` zXNF&>3C-d|m0j&b)u2AoSB7%GwjI6Wbw)9k*^Hx#{WtyjnEB(M@hWou0u>-C1Kn8> zqR`4pTp@{fNEzENgy0grd9AublCE`0zYk^z<|7|PXaSVO# zZ#*gk=XRLpub;sgqge={K;{4$vp0Mc>MI+x7V73bdjh6Q3uOtmgg6w0{PoU=av?q{ z%xjNKOrgeNib<1QjzV+beEcu99-^Qu^DHw71VG+U?a9QtR)1ph6~d^tb0GdbK02y$ zMu;)+4d8RMHz2*&Em!-t&4U%5^!OT$mvRpZy1?&3YT%etD8!F$qcdw=h(y5fT`z&w z%Ub~Ko5%<;w8XR80NBZ^4!zoX@Izoi1o~!wlC!8c#ZvozMrh52`~ zb2<_N^?xu>^cNeTDo9Zb;u`SuommYuXPHO+kz z-Wgfp1J-?k3X{Sb?tjSM2k`bO14N-WC_GIo8IdXQa!@QJY&yM6#Krx!*jJV5=*u-_ zF}^9jrjBYSaiEmZeiW+Ts-_yyg`DGi=QC>aL7-9hjROyWYbm~sayST}-=muPX|nN+ zmWN;RyzRF)wQ3D5OpW_u?|Nrrv^D*1IwLo)rU<6rzkZD80{R5qeN8|!gBaAhqWKp& zZu6@-F*^An0)n{a64iW+QilyDSLimv7bIZ01Im=*0t;RE*u?qmEkk>up=z>+yZgwR zhnj8m4gwb~@|@;k9dXBEV8$yAxXLEWrGtYk@fB(2cPb)U5ejjJnhbfP z*n4r4O)6c76_-z`5$c z;lcoPfB=XOM9K7Da%w7YFOd$33v^Q89ApsdE znyg6%K%afenDr9qGo^;EAGn+3>EUGNc$d$GUm-|+ojV0S8in6H)Uv$#2_~aS!0(AQ zdT_xap?1jN1E$TDW@(DYCP74*I!Zd5PJ2zVuIJfzT@eT)Gk|%=J<=S%>d=qe7%wM@ zND_Tagx@`ygCL)PP!aeM^I#< z*44Ic=pz&8xy7}LO~B1T8nHwNnd33g4LePizU(CQbdT10=jE7k7nQu32x)>lm!IFE zSUx(THTMALT7MwcF!5`H$t}0l;o41wzTpEYnb;Vk=mywIgWg3SW9RkBALAxsytiO| zyd@TdHGOpopEzG*Ei<=-S?smi9-seR(ejIrl(~`+KLJg8B(T{f*ER}Qa@^1ALp%8W zjW{8@1Xo+#Yr%W2(ZbxWbn6emGmMDcqfr8Jf+%z_&?6*%6o0z;E=N1Uh1&vgGsdvQ zXno;m&Gs_lAQG(*)cVVJqDbIV9On$aSZaUeffF3Ad?cpTO^mBBrI@#ml7_(;H=YJs zqmHC>?;8>%%su49WLA%l9Ez5zP;_YnsV*N*IAJ^@07vfdSAgFHJyAB$v~%h6G3C z9N(E(r^oOkyc1a#)`*l528fLP<;5KvrsG0z8$bhx2G@WME#L$8R2ebZvU|3{sGl~Z zKhEUXB#M_`d~)z;2PhK6^~R`2{CZpYlcANsa7wt{wewLpNnlSj}r+Z(6N{W{k@L!$+9zv3jVT8~? z!Ya^7Ko)oLYocew7{w4E7)uFW);d}S!3S#oZ)`d@BG7MK$n2xZKuTjQ5+YH;)*aEx zFku*cOR@xF3HDwcL=Sk&AhEds;GOJuW!-`TRh&rd0*Xb{Mjc|Ga_-lb7y)X9WR7Lt z%f0EYV?L+tkIj=q>RHoAnz$U1F9;!b&CG5Zs{Yi*9+^ajyMs(_i%bxHf^2O+;;7Cg z&?QeZVW4}nAtX@@@`E*)`Vm_g!yaTd$BsY^0bv9S6421BLq>9^rUikGE`iMs$Y`Mn zQ9Fh069v!!N2f({+I?mUp=yx71EXr8!;2!+x$h z8?VHt`y(6RsYZk8_|T?+cpn5{vj?W z;}lZ(r#seieL`62t&0z&^6#Y84z2t&9L_wi|)%D zPX_Bunbkwq{in2WgnzE&2>jhC6|Xc?EmP^syLky<6SMalw7%o*i#hhBdUv*ntVKhk>I z1X|up2AcXCFO#OFGqy+45EAFVEU<*2M(e2b{qlA*LZxQd5G9T7FR}rCH12)MA2_++ zG_JpZ2lXsfXfguek)dcbKuL6bc;s!ZQB#$$UoXvm9c$sl`<03q#o!Qqq>S<7U)hgjZH5tb zM1U#TW1yIUT5R6>6CLk9r(iZ&q<8faLuQ4me+LTV5r*xcVnV*wYt4cDG5)gl5Gn6* zH1@5}LCGVv7xZt@xc0~pspwAJ5Y5lZ*(3=V=~>Y7+^PS%@KAsu(@$&!@+qA!g=5bH6Y zvmD=~!OdYaByih%Rr6DMt0sC$eAm6^Dm!Gs6mFNFIG^g>HXwV*ia~Wf7PQ!8{cqLK ze~i=4Zcy4nV=7?^C|>s_lau046V=sZCqq5~in0{=aq_4sQY0;$VW@RW!;FH&3nJ6W0Qexy>DD{q1HeJ0vdxl&+u<#>T7i(T ziE)>=&%${4f?6yC6y*3-AlU7?O~^G9$0BX6gR+qNs*_V4SLjJIic+++&1?zO3@Hws zURiNS;X{2I!pcfSLf^hdYJR30>!M|6{EN#{Lokij7HOI0V(NN-_{YF#+5J#wj6~TPb=BEU*4HDrygy z)N&4yxLD{8;zt~pZxRng492V$MN@`A9{g&{0(U(A0Eb3|hP?E8kOIOV_?iE`r6!)t z@X~w0aYO%@Z)apM2W=oD!6$RX_qe3>f4Su z9P)k&(YnA8s=YYjDlqnu5(CEqtqT`sQ9ru55K-wwjatl6QW$)H0nu(o941Q`8CQbH zL81mfJj{^Q?XR0h@;g>M*Zj;TG;sof{WxNjB!N-;25v9ny&T%lV%HM?Pd2Y)69afl zxccsHZ*q=)vGeQ*LIt@d?8@n0V*7LqF}P6E-x8+YEY7N9Z! z)%a@eCnG96JG>iD@dTrb^V+9rzcP^}qe2aH!V12jHqw5vGoAA|+wolL2plp3uELJl zXaaj$aoZ!1NUwP8g)mP zG|2jn#{fz}B)ph9CIKqIo8J&exQVQE`YX@JxS};_aIRQiaasS#-j?$lZ0s|U!z0CE|r^%t{ zJSHlv0~(tY(BW|69f#b6-l@#F20A6DqU{GL^8-C!BuKu;E{ZR~2$;Wf-wgbem!Uf7 zZqWg~{_|64PyjaQOg}ts)q?1}K%fCb{3VzykVm%#qQh38Wyd!HlB!p4h^qUGFv16S z44s0{(|e?ya4sL5{cYoR^xu)gjV?>4js-gV!~jO+C%B6}Ys3-&SI8^LsEV-*k2gR= zzpt^TC)E2qYqRr^5VodgCqp)nL?Qs?edn!2kq4Fi_oxqGl3h9^o^`I2i4`K;ch8M~ zN~`|l039Ft+(<&t42!^P)rEio-7ZSovX3qAm)TD0Cgp`9!cbTLVy z=IvqRZ%0=A;~-&987RSE^0ijkONR|m?=EacttmhpPoqrrG=F&u&mS9Crf5-lZ9l>jJUnTuBkGCkz)@ITmk?&h7 zd9}bE@Ij*iehENkB3Pc&w-`g)O&mMa-kKQmoeie+r@ilHHpEx~g*% zMsPp2ejr4Dks1j`b=9;BkChhBQfZBNM`QWZuXzHNJbekor{PDH8u9N})9-{2v5fEn zk7pdUXDPAEx-P7T^rJs89d>O7f@%}Yu;f$z)8qN?{JOdUeEnRg_M_uyTb#`boJhcW z;2UN~L%Da7?*11(9Ys68c9xd9Zpm3gxTBQc{}~1e5F!KuEg|myZLb3>f`MNoSnlr& z_bEnlc)>t;Y9jlTfETOI1&j@`mKRvwCXz)*ua#LSb?A9tZ52s5b^W2vn>H!lJB4Cu zqVlgQ!u!7n$i6G-m4c*Zcvu4_-0L(TvJR~axpq1ca2D{WP=Z9;@1`UR3ER=Hvgp&T zSOgzHm@YyqwQmSh`!*Pp$MTlxXx$X31A}609}2vnxoiclr3l>o2N)45FECV)C$JPf zt;Wyq!UTXw4O*O23sj|0)tVhnY2IP73>5%1C%6-sf%Erj3P7TBH=BiE@IiN)tVQ9+ z#UN}#;SGLuqg3DG^olpx=V1_R**~aW?Af~GT|6!)_y{H!=Vu~U`+Qs1&2PV2?#eD5 z5u+G&OgAkXoESR$YoA9I(=imnj;hC}GkA%(G{Ob@(ZH;wz4zl=Fe9MM=R!sHQrPUa z@^U*Zfio45@LJCTNZp0Rc;m+s^ee5e@-%i=bA#Lay9QIkR{enC_xWn${D)~K_My*3 zUs86f;9GVjW+;Sx^vVn1Hc)eafgo*IY!C)mhQb}37!P3L<#Ob@S!bz6OG>~jRq)Bl z@iW9)c08J zY7`2#+IJNZztpXzxjg08Pg*cTz4@U$;Vp@=swIBy>7gV=lM|A{5YF&I(;|SlTMSWv z7Co(|yo+$-+=ToTS&&aSxV+*O_w54fFN^GBnn5pQRDi9}793=+TmtxpvZJ}{VSxg~ zY!bOwt&ZWBm3;iw7BA=NJ%3~1hS^z2Tb+UPRh_#nN+Fd1mj2duf z!p0|yply0}6r=WWEFtBeIF)CRi^5riK{QphFfa#BN$xP+J=_#5emM;_#-78kAahFl zQ`uzU*T@T7= z`S8}E)y;s{?l0v~B3&-a`cfiR)#cOpg234@usUaBVd02j3{E`3#b9jcPdxB-Wj~`V zM3!N?^NwSj73~SiC8~GkTd*e;V8(xU$acy?hiBrZJwpp#eX+Y|c^TrgvI9xe<5mv~k*E#RZkNv{!?pL8AGy)kEy4E?~h2qPThbS}pTW+yTe zBbmP+=sJVB%n&RBK}iywL1+W(^_XAdl_40L@0@ z+$^SX7v>tOz8L*U8-nwvC2CsKona!nyEX~SZ@^e&jbT<_+kv+XFp09u5njIN_`od7 z4q1c1P;_t1yq|Chl2Z2etc4qZ0yqO|NY@?+50tMxk5B80*~5TV$emTtAr0J5Fh**o zYmQ*&{$c@i<1qj#**vWOybyO~ZKusDNnD(XYsjXZgZ5Xm?x)De%P!_;?PGhyPThn^8Ai9^p z=Su>M)=ic!w}+>6RS0+GagvSXf!vO$h)$RAfA%%h8w%N1Q3CsE9G=`S{m5b5jsmt9| z1}~^^N8uqz48Pc;46tX9Len5_%xMMZn!D6$n&3pzNHU5E&s*uhOPYd6Iul3nJmY%L z7zt{~sOIZalgoysU{z>uVLB5WgZaQOiGDJBhDd5M8e8xP_J&Cs2?z}Sr`vcNR}#Z? zH&5mJ7%(|~PH}E~Ax;D2J7|bMw%wA4ySFF|7@PsY_%W{l+UyDTKojJcNhBFCvM(my zS}tLL#Rq|!vomJk3|ZA~f)PLs&+6*8Fq+~BhBc7@VN-A+Mqtwewz?Ua6`UdgpEwNW zwgOc2!;8qy8QTUCnO6U@r@%(^F+6ZuXdi-1aR%~z!psWs9jM(7;M@$gC|1b3HkjZ8 za@?}Y#zU6Z(j4Y`EyZtu60edwAaOu_YrFhN0cC*%&k_a{J>*@>!>!A*p|+y`_x%Lr zsGLiu7At&<0TbbL#{iRJmJuGc~z|W73$K_hTJEeQ)3zhK;3%i7#}o2Lc}C3ryI~U%(p#J$>5!qy6P6n%|Ox0scs~1PtLz{yL)@xtlAPuO(iFlBr=>5Gxe2^{!3`(1< zMSW(M)PLCMhTAQ{3my<@e7)v@pOgjIIT4Hi@`zvkRhU2e-M*7KP&alTk`!V%JvZAZ zGRyD#XqfNLl22K(#>Q662aP@ytxy@`z@b@BzvD-=8eX-Cn)gHyZ-Y1lhF9v)$4|A2 zaGNO7L?~Of1p#8996_9|pC+fov3`BZamz$0duP~xqC>Q~v&u+f8VMTZ*D=fidG_m| zVGS*^;MkFx8cQjYz$8BJl$bz;hMCzI1p4HgX)D+!w<|BLSTV5+ zd8smV0(I4{1_hrF@FIg|`g9%CCZ(w#Bg=J4%n)D0Y>4BGv?sJ^2OY$ydA6;}o5BwK zZtP+r+W_yUU#c?r6dYfpTH@5!#o5Urw(itp5`l%^ELDyA+>K_)DAJ*29V~@ovVbKP6^)XmMN&7>^Guqpve3X8 z3`x%p@w#IMf4;+vJ~I?y;X!zW5oWMSq~2Jg5QHdnhiEN91OQCV*V4+Brg9D%$Q_}* zbiNhVq~+?U$dNnzXN!`8g~(%{7+#zA>MD6`4ZHdP1$BEJ*>G|A0B;LJ9E^Qr&eOGX zX4T;E{Xl6v!fl}@1V`9@M-U=`5NT64tbBz(bF6n94pj1cPJG#V0L&Q+5beDQm|L6u z!5xz3jI|s`W73hp3%aiG4a10vV3t|vUBzPd$UdT0lr@d?cE1r7b1J;{b{2M3IbBNh-^dbj$I|Mgb)4t6&}#ERD6)iec!A+bc_a9MGI-Ma@=tz0 zHB5K3tSJ*5ipGH!!W{|IsM zUgIDub(XeP1Yi-GW`L!t0?3`>#3m0ESkVTAIZpT)PtyqrK_;4$^|IJ+BIUU2DCiwx z;xtxgXdi(JLx#DAI4W7`M9iqk1rp~M&BDB(p@E!3X@>fWR7f@xhy|rjUh8-7v8)dG zoyud8plJEf^ctNmSy;a*;;f|%r+;F-Fe3Cq{r{%5MkvJ>*nuqTj0&6tj}smRBt7cd z7c6-Kxu(Ope;&Idg1hejZzHNe6pHFg9@U?HMHSGS2oLzT*99JxjOH7?jZ3e3X;?Lh z-C*RMhce&RitFtUW&IZjNu0v7$5X%@?!))9T!9fpc3P#=o9;PrebMi%eT_-|{lC5B z9pT=5l=O@c>BF@YCTi^JF*C02MP@*!!4bV5-ksD}AJz{a`Se$?S`&4gm0`APlwn@(q2>ib=7>r|M zl6Cf+WGimFjUo_RAXi-CvZqIV0~fkT7`B&anCymz=V2$G3V;AyN9%i+Ch1OJl8m7{ z`JWRUTjFJ6?pZ-jS4Ah$AwT_&BxsxsPZ!BT?`HwS54kNSVr(@jmjA`!xW-HtRn17s%IR(s!}X;%@KsdjuX~o zv48)};3&E{#b!&Z8kxb*>>Ed!%ZS-#U4yuZGh`qEvsVd6=>^-^JFE$1zc@#q&H&0b z!8j&flA^9M)xK(nQma!C*)ugZpuxKeu*;_fK;0`wy;f-p!33QgznxjMJQw?~4gFE>3;$RdpfE4}vkpv7Dx1;Zr9{`3tdZ@&GW|AeTh;R} z4qFm|Nk|VAF19BP*Z@SNNY3st!Z!Yk7*Ls0l~HL_I>7e0nR}pPYB_j7lNILGPy8qC zbnaeWgQV7YZw%(?;=dIo(2%+Zg}5rr1l{PR)}^2MXNMfTwT#J2V*{@C zu^Y&npqa1I7mC6_g(ZOP<5=1}%ZWcdV@*PZ3}w67iY9n5A~6b!6ajHNYHaQXlqfkC zP2D?|vBbvUkwCJ7(+!$BzyfY17y0gQm(F&tcES3SVj%c8ayjN`5#2V%*uLaMC2#1h zo}I73ggT($-~uDF(eDTDlu^z{b_>F>^Lt{uY3Y1VZaJu)US=UwE+2tH7K5j zoTzy`Voc;o;OfJ`X}jd=JO+Z!cGQI#&K^Gh>&8#`JAhcTJTTaX*!H+;dW#>dQ$bI>X=_7Sl`NrOYcni!F>Zp$5q-zcg6T~I zP&lkDQh4t34h9|rJY8kWR}HR|V-|){Tt#v?t&m#>1vZS0rv#Nx(xhibBC{!%{4_E6 zElSAiVDzNE;@!_{zGT38aJ4k_Hr* z-|ac|E)EsMz;O$VZ9;eJMQn$Lx0CMiB)3ChPidN~&%P@86}%Acpb0)-9QARPur?ZN zJ`hEWQ%fXagwh~SJAwyQA~3oB;FTksz#a`2SCq$5Zkf2cAhT67-Bf#ek9p*YlmcWSifkqW6=lt3BmiAUI-RWwXZ;?Ebu(oIDje9g#2m zDpiBjpfzFLDF30*QyWLLX)?Fi3u|#yUd1#~lc=2C!uY<0SJhe;AxVOM)hhK->Ef%0 zaSB9EGP>WGy;4|AJbW_Ln&T<2_p1D_jDU6Bp@0=gPD{9NX-?vIqK&j0Q@}ep6SRin zabLU;O%TwX1r0%fy#$p;YCsRsw2|Yr0C%FIL6Zi$HyCnqt7?ZqdA`Lc1(@9r=5_b( z*^i!dz_#+$0}JovK?Uo~0bvMZ;>{;_xEY55-{eHtbohiMS&Objjy9QO2}z}i7$bwx z)ni#&vvr=Cni&a2k0b4^Mw3*`+3`3n!ihV{ExW|&J%<`F4U~>SjMh)h2CxbZt!n-p ztTfnHw01v?rBpXASE*Sqow~ag8$NrUop z=4*_0jkt7fc_^g$`O8&o9YM5Dp~1yS*7T?bhN$7chQwVuvVH(Lh5c$SuumnSWlWL$ zPPPc$086`82`oyHU51N~yo9^u=d@w4fi`QRBnpZ$iWOs^WCOMnNpqM432iJxLC-yl zx2K9AoWS|D@z%MTc^Hvp9`t6sv|$l`XW`jW!ezJJ=&`Xq(K?|v*pL#8q zI2`K?ftsjQ)9g6_JpIBq6Z_1-?S_;Kj&?uh{{U|*iv7&mbMS#-VS%&=-{>aplFyO7))|$Bu}Oga zrC!^;3SU9WX>cImPDeuw8W=4X`Vk=VS_pXCgiZp;6 zO!CN;3A&kaf=D)9i{L0#%lK@_r#@NtUy{@z1@ROf6yzqeN!`j z*!*1v`dw40RuiFl*-2K(D{J$Td*njti0M@sXKG@aWx|ECtF^%-5Nm;VJm5H3d5}2~AH8$`oe&WBo&ylm^8Mhy?=QFY;i9dfO(3~>%m|(XZPKvgryL?eb+<{5XBN;J;#+7R z5XwBf$pTXa*yR+LDCjKo^4ZtRo06a zeF7Q!n86F~eOOJvryieo@EO=;KURURCH07*TArS%sx)6N5HQYFkk|kk?%$m7TZicP`Gzn3p*UF6h zXo}OXbYFz{1RqtHX-~jZcCJ%P+MpQ-6`0iLEID78J>@17dfI&Q>&m0DYG}+Bt<*P7 z$gXwD36`&Lz+@=xWehVqJ(jQwgn4uxvOo((7f}?b{{IGMcUJ)90$-pEwlOf^;JovG=Ir6iQITKM&1b^Y%x-y^ zcZ<-j;7RVb`#sjW=ko+M0$l6^cnT9+3D|r4UJ4|qpktHInder(Zl;zmM`JS}-QM>r zM?a~mF#PTi#TV_5LEx<;!DxK~+T^DOLe z{AwR}7XXg~QQS5nSx>5o3%ZnB9m4`YY_tAfFrAq{Es$G}55;wmPg09F?-c#`Kw-2s z(0RLjU70j!#H9gCzZ-2;z?6snuIV>cdE41|##a@zs>7?e)-q7@p_m$5WiXp9OtjXvz&~LPYl}nmr|f(rv9KKQJwg3_X^_Gj9W&?j z7mpa9+}g?m9zu)u36i?cO%KcHzcO|5nEh+WQY7b$eu$VH-@;&7?uw)wb(N=86OmT= zm|<(u%(JU#&`fSABYM6yt}LP`P`aDUX%W&YHDyiZn{{#E8&-swqpz@YPT^O}k zl8Zg!8SKvM?*P0I^vOY}jKkf{x~4%(sWJs}oB5`oLS@`0eXsG3$Wp?!*YE^-`aYEm z%CROY^=Cwv;3}ywq2`y~|9m>N!|fSYYF#*(#fAfjy@|5$gLsCY49K~g?iIjPoU(9j zlNQ;@FCO(VV>$>^;G0y!2GsbRTS>7omJ;R#-=qbJ9~7 zP}28c1)(*=fV*DUOEKWc8d}aS6%NCf1NPe-4qy^m5qP)=N+=XTj}9~5m!zkt?dYuS z@qG(`*vwcmA1E-l7(nN~;Mu<9Ok&FEu@8{|*V}(OTAD&zd%%+4y)*zj$BcbfGy!?x zuZ{u`c%OOqg1?H8VYi;aw*SRUB@yJASTC$9B3eci zhfDw)7I%SF%&r|RpQAESu2(;5^-KNP&7_ikNt6h(yTQ&1^4xgnXw*rq&Wbcp-mI7w zT`q8le+zWa%v?a>)7*6;2tZvLj6Zp6QilmwnG=8*#rM)^Wf?Yv3;__6GIt)Dz!(-x z7s%~;<3Wjw_|L__0jZ{DAHKB0hlqKJM#(1B!9bhl#Yl8tLrtL0NjI`)Cpi za(e+*leZyY`210Sg6t=~ngl=I+d)sLyg|^`C=vX-*zQ^4g#qX0TtfL3)4^T+%=Vwrg1S>9q}Xs7*N?Q$x2m`%nWn2)F* zD@o-D38|f~r%v*5I$Qo>v!qoHHZg#aZUGWbUaSy$J5J*a$Lsn^RSYLdIJJt<2^rL* z84G4*)Be9Bxat!YN!cV@4RobtMOk`iJzPotibiCQEyKnPPcRVKWD5bfe6$^bfZ93c zF53BhSlFx&yKDQvI$6q(j&lFlZi~-MD5HYF(BzelXDBVH-OAAXpgT}OmF27hvLT!Y zcB;bI%IMN%%rE#%+g=4>0_s9rRvHuhmb-3`Fv|=9PEKJa2|O|1<{)wa&(xNLDH$LQ zO$?i>3Z8ARx+SZZY*Y4fXqvZxSwRqA{$~RCUAplgn~5{bt&C(SpsD0Z{Vvnnc7sc9 zP%4)>DY*A%_c5qC3Lpbu`}$=Rljjo12U1TTHINdLE;I4jS4SQ-Jj}C8MdX)lf#p|D zn1irB7Nz+cy69u&a~i(@6tO`i2|C5mX1H0%bQmB^N z7ZPVeFSO)6p_dhUw%_nV({moBzu@-dGacYKdkeHI9TIm(!;{FFXBmztTqUL{!=W4w z3^6(#g{n=nP%BuM4y82A1u!2eg_=~MlG!)&c)Akc&C@CNA3SSr&(4@gEDjG*?kxgd zR|{fmc>S&>rtB!8kTpysh?-YXKVqjnAN7DzL*_`xb(o|(&@UC})H1}9hBUQmx}}xE zBJ1rm;WG!%54s|zfh5~5z(1VVm7)$0WxyM=zF8%4##WZd;Bx~GPKI(ZAc~8Jt}UyF zaMSN4sNfKvp$m>e9jDc5;H_%e2w=x?8}p-P$auuz*b>@3*Z`F1I(vx_U!i-1P3<2~ z0wy@r=Mzh9;DK8=`Q@N8d)t|b zC*vXrR*Vr(ADZymbT#N+!6M{EwVZ%v;a^ucethJDkzemN-39N!@qB#^+;})jK**Bx z%kZ~SjzE+Mm0a|dK{D(7-*ia_ zvX?=3m{Bszj3{Jj0S2JRIuNs1`iLlt9?ha*XUY39uEO%Yyt`vlOa#v8BXb~9)|hM` zG5*~1{^{%!ZSxd#4sxBiy-}tJ=?t_M%p8L55ec9I88xc*`H=FUV#G{a#2YXSYahD! zRLk(e;47ASgf07@o!>BV;RCw}tALIZJuL~&Leoqw!(vPWU=q^qh3U@-8`bV9-ArBU zX8yt&_O4!ap4}~Y<#M;P)6djdqc7;Rao2mgye(YCIjkZwTf**HK7Iztx$cVP?26t$ z3}HCJgA)Q-nITNsRgCH*2*EWg#9jd%dYeY%xS&^U;52vx!m0wW3YNt3f6Wplr5l_n zn4nVDza%EYDwITpbkg6GY@Z%z6ayiQ8TA7a^`tp-bls3O0yfJW6Q*y_El7n4H3E2G zh=y|Ft~6^vlJ1QY!2GhMsN1;2qfQ{@jAdL5U}%5sOgE*dPK; zacG_VQ&cIh*K~n zS9IiDm|+7&N~y>KR6!l0DTBeShI{xitbgGkU6)rBWW`fa*5$cKHFx*jWPBC09IuWdkIUDfk2`cu zN1p4qXasJ{EEFsG;kZNwX`VMZ0w~%%1zvD7(l!Y(ZdNp)n<2L%L8c-Kr}1sZ=0WNKQn6;_2L}hL z)#D{}93(cKvVJ6YDw@_uOVfNbv(>t4`~>{!#C zNG>jYahIG8>YlzC!qfnfe$&>73FK~oJ*Tc4VmYl;fm+12E|uCSDIH3IQ&%9!KfL9T z{cvo5|GQ`lz5iq{`6v5fd8R9`6^xWl?b1jJ>}LxfFX=+L(?R#W|2FSh&AL ztT*tq$cNdx8J)x%j-O%zy2hw`GW<|Kou4q1ldLt{pf6xjPo%({;36lQWKh2TNby`0 zxDVqjpc8fxxkH**5!uPfRPZVQMq!@-zF^;v_{k1C0^>=Uj#f<1agG^spc>TFMoPgO zniYcJd~rpN!%$WRECceMpHC@z${7m3uV6L{u(QyXZ@~Arw{H!}t|hAQeTet1#cZOp z{3cM7=>M{o@Rfe1Y@FjD+>_PZIFA6kc(}kmWBSM-{=Us7NXp?-xr{hkok-p6Au5*~ zK~x;i$pJ3l%4s6kG*qzyM${W2nhBKj6ap-06jRf`EFt^~eGB)8h?6ia&Qa{P`jd2U z5@E_eF?d&bDqm-gfGw7C(?)mZ@q#;F;B1ppWr^S|moXIkP)PnHB&WnV0tY~X2g@Fe zc10S7e##c;r~3;7MoFg3z^QMx4gxy$sO}*)b3z%mBhs6kCWj+H%NIF{tP}6KIF|_S zT5RR%xJQ)3oh@++Nnc;Vpv~t@Ds4o3P`%C1R%(U(PL+Zhor(Oa#K_P9FCI8x;BjM` z+TYfcxDk4+R*?`iB{2#bKL`UJ+Ry5yLDUs4zLXTt7-OC@)X(56lLD;h@q!4@*DYD% zbKRGD$`zjb%SW$7Ra0gS$ffX3yj2Le<~kowos&VNA_0T_Cmuy21Q~9erPxN50dx(q z4+Mv~4G!eT))0|kWOjlK3kHWfxJp+_Q;o1JkXZ&)+0=pyK7mq`H>8^l7&;BdRW$WC zm5F2zap%6DA*Ch9!9WnO!N9jIK>wJ~yekKTx&cqeU*Lee-B`*dSjEoy1T<_Y_zK~2 z{wdfp6KokTrf~=3uwqKIuf-r_Vp}(TkL|7vDO3kNnlXv;l8VF@XV3g8(@G(w&*#^) zSCl#&;c|T&jDNxtuKybkI{5gcz@JKwO;#g!5WxsmAN_&q#39_|C9C z^V6F8RspmGn5MNL;BlvRXKPqU2?)9%k=Rvf!kb$|bg>t?yb|l4HcCSRoq#W)iqUkw zTVaghHn`eLTqLLcbLZ)GCsZFjwsV8k!o{RGL=L?1q=o=1tcFVgGJBAw&vG5)jw&D! zy&fSrh=3RVQ*V_XjKfL`@@eUEJocWKu8~@B>2Yyn_Kn_6YSv9mWk|DT$*ed)U694f zD!HWG11iupEkvSZBmumj!)_+O4~SLZg&HJpZ9ydyg&git7&xx#B>=&CM7JDqTJB|v zA;J}Q_{JH}h))wd2eM5~jYt9$j7B4HEq9zPJ{bT}T3bY&1%#tCX4nB}3dhum_D{j+R2G0Yc~o_gvV=-1}kVjN`pP-GdqC#GbpRyyNZDePB;sE#-~` z+&aV6v1Z~JmyDh2HH71I$z(Gw{Q zbQ%XZY)H{qQDBR}-I=Efn|7dDO5XO#z_M>;;nn>2!dvhX zltu55rzl=$Pq+|u2n>Dl_)!EG>chZpgbyXJFO`UHfqlpFg_!|ZvmMC0s2xxDLZM~I zMdJY=xqpKY@w#@GCP(bRI||aIf#gM07)E6|tUv#KzV6i>7B$ae#Hs^KYHX^%gZMAaNNnGQG}WO8u^0+Po|j@Ga=f!>E>S|n7f5swX)t3Z z8sUPjO#+KBsbQiCQW?fd>I{m+X84F%s+o^bpe5baW^+efMz&tK`C! zpFAQd$GCGcEg-19#kg`lYZQ5Dd2eT*cH{wdu}nj=oh%5q3s*hW<>#K7WUaO#WNtTP zMUl1447qgCyCPU!i!|GEZIscy-yx9OjvNtFqJF|Rebba zZDrNo-iD(*GjE`VN>{}r%44KT@tn&L_sjzF_8)W88nN&c@EAD(KarIo(ky(`wS;X| zlt8S~uZPoQD5{XEl72g3WQr{z&jS#LvR!^(Mg7sXacRy>CWN$Sd_IwXJaQ&1ZWzR0 zS1}fd_f&HQSqq1Au)J2yIs^mcf5=g^!lKhSb}JxhFYFB8hJw-rUh=dBsBZ48y3$SN7%Yrm4>8%fA1?Ie`$t@ z!0%8GE-IXxR>BnqJZwms@OnezNs)963TwJ`mbMly68F`g#nIauA%2T&Py`%r&>Q6D zC$)@S10}oMYuf7IlHWow9JFhb2u>lnZg}eA6WBW&hK+sYVHPRE#ay{+18k|)eUCjERuPXV$1qPd-+%d*Ewk^u(t#W?4 zTGxuDtBGS&v42C3U;`wrz?hx~5G-l{Y~tiUMMK>XFucA0(#rfweTN)W1q>L@xfm7? zmB7#_GEj*F%~TLYNsSRv zD~9A7pQB0z&xyB1CPj&-6u zFlWGf3@?vY;bIm(pXN4uU?wI``$u?YA{K+ls5 zggi`kU$BPITm^%oK*-oS+xjufH6WHA@!E|523%@{oT=G`f?igJbc_9}A$GK(!M(M& zJ&rDfer4s3?z2_ayXQ&tIeDb3nZ2H(o8(2aR=C2URyJ;kW&@BnXej*Nj%^3_S$00a zy3LZ8S2^sN)>J_um)N)v3}-NtjzaM-GrdO9@mnL$aYXZ_Zl6IWDcB(=#nfIWIr4Z^ z#b{HNfQ?Z-ZW{;e1QHXZF0rX2L8If;IxD1_@8$8S6*Srf%2Y@>a5_oM?;zMQaEm-! zM5t13c}DS$;V2**k|r}D{nbONa_|G;Z+bBiGl zG=NunGI_Cs7{|B>5~bBFIC2XY%a>3SwwCS2tEK=>H+%7Bf~EP4?M-X@lCwRTH` z1vd&fCeU5D3DQypmHee9YjvffIF@l1qSZBg-|%Tvlh4!7X`|wvW8MSTiHIgXY|22e^jj!j(pgSf2Xf|4N$7an~N zqu>p3Q>Hv1rPHFtJ*`=QW$00xxqd2BV@t2ssq?1JcsEEjwJTO+4S!fCy*2JGs0JbM zHzb79hg|wW!2G&&2>v$2^EViINZCj0{nsE=Q4CXZztu6j!1#w~=4%8cK2;<^AQ2;?H z#xw*1SL}K=2E)%|&ZUw3*14hcafp&KHvN#0m?WUpksT6h-77eJEi-lBb!9OqG93VM zI@Njv5rV-(!KX&l3qt;jf{!p>o-AIy+Dv{y?JAvxNAe+kP+5 zP;zW&FDrsTbGzss<7^pi8&c62bD_CemR$K?=3KAa==H83QrpA-5^|jsE#6EE6DUXs z5x5W!g*sm8TWga&Qicm>_&;2EnF~;<8PtDsRDZoFj`GfsmI1CrAVBM@b#cRh|AD&CXd zB#gcu2m+HKygcpq8Wsr#I?TxdpLk{V`$Jcn4F8R+U;`u|3lNeP)zG?-)nz~@vS4mq z90{r@dE$3_JSj1-{Q&G!E(MVE9Xk+yci5RIy%YmqR@4lV z^;iA?6vlVO&9b6~jXb3jC6VTm7^NDF;sL>Gm=KPd>W@*f1+LqB6VesltpvZ6k=0)uN%Qb&(w8mNaDTf5AC z0znDjXiKK*BZgM>%h~@xk&a5~wD_f6Nna-Aau&#c$7#f$s_HQv;&2>ok(veZh;r6byr>G*#fEHt&b87A-UQxiH zmr^r6Z+OsN>&jiUib*G>@ypb8YHAbZ!}6x&1jbb2!VGHWGk|@s0N?N%@SFdEq3zPz ztD?)Ef$wy5D{PVaFiY^Y62c}3(GxSE0A+4PB!JOycuVQl3y!knt!iFw;K`GY%3@-Q z#yoeW^e}2b`HOpaWmFb0!*h=;VNcDX2SWTTBK}f5Nq?y);rn5T1q&4P{g!iSFLs@y zP(>C62<)*ou#B4yxgOc&h$l?0A7#mgQjUjN4xR<6m7xWN-&(Hm;$m4;Dnz0cNbE|o%Rs8i@oOG8{P2kMDZKZ#-waJ7h3XCWdOzXvA;HUQ#>F?r#kSlq#V}my1Q{`F2yy1@ap3Ks zT@NitjNm#DCU|~4{tbNart7~~&(5%aa_E#)@lvV_c9Vp=KpzF`u@V1$fJniA@kt2~ zF~4&U8tcyf6RUlez{is#R9-qOOjMsOA?F836zC|z0YDl!c14bYI090j1zV6@&6d^_ zs0Tdb)Nwv*)M^6xbDZv9Cz*PCYL2|dx7-&Em$#@X4g`g}npW9H$)@idQcSWE@mR@I zLk8dUzRG0#@WexYckd2r)NVO8U?{~9BW9=^iHMo35zncM&=NJv88KM0iaXqtD8bjn zk_>)#@=!|fvN&fXz!PB8o4H4O76Qcr8h~WUON6w6EGu)cD6$RAg(PFcPQE^I}Mc z1t>UJz=y0#;f)oo;n1#sYKVUW>KJGTf3a6e9u%6 zZUS892Wz7xHxP{{RHBdSj|xstAo#nux1=`0AC{K?3SDs zTARq|6Q>JZu|=1$UM?`F9q@~8KDuv!0osNy2DOF_{+N%|9c%pU`q7$#GOC;2<4Sck zjfC#0I`Ze!O{M-uL}a)j;{8ppZ+ZcO&qT#CTvaghG4qNglMg`tME1KNSjZ4WszY*l z(ieeaAI3o5s_U{lUFYeW=4bDYu+=@SHu;Gt3=`Has{wiHn$5h`*==96^z&R_?`*v)uPP-#z;0S+0I2<6Df7nTG1S^ul9=o;vR9{1b<)k)Y$0brA*eNN- zTMvYuyD<{@tuR#xrCRn0V(^AI?3lKQTey5?5PLn0=~KXL{bLEkTk~`sWEX~6&^3P9 zz?KD3MjbNGzoB7a*ceWuc{t zn!*^gVv?*^JPber3uG9v8~EnUT+<(bZgFUWd4x{L@Tw$qAP*)zGqV~b#9jZ`G`#AO zMkNRqz5WJ4$5Vp%q%zjV@wv4dJ3B6nv&;pZ;gCZaNTyCRtF)Som9vW(iI!*sez-PCW&p7Aes9*!lCJ(4@xz-7v%RI7Ee4I$S%$2zrY$^7AMJug-7~#?63o00t ze;rn90$>k5ql;XbC8geC%7I(~7iPRHK?F>VH6!d4pkssqzCj$^H|W2IGME>txKhX0 zo+~4Fx?Wq;IfVJrjS<5qrOyfLznmDM($djpjrO{lv7nc*$$lD5u3zI$wQ$jRC=|`Y z_OiiXTmLwd#4*3keMzlv8>|t|f_@tEA3)f)F~03eV3GL`va<7>{W>=@nA9s3JBc5D z@;}6C5p=sFKJcW1W5JA|!5O|eCy@nwq89LC?D^Gi2{^sDy30PmTA(Kua2l|_&L}3c zg9Fvl$U=2|e3LQ202VJ~g*%_~wfJbvGQxus%)p>OUe2eVJRiw(S#zEWmS9NT8tVs~ zoSeNoaoh7kW!EyANT$XN7C{2qhlS)%=dkJFnUml#0#Z+d34Ap6AQwFRcPa)4$E0tT z={=f@LXKO*h3Rz#@<`V%R%Il43%_8eehm-i1vcC0j&WEb_{#F&QF9GO@XHZk`CPeC z2FnoKT!8Y^iIjt8ObJi0=s>?g?jrhh%7kKQ1nQzf7O5d%4q4YPiq#-E3gznGs2F2Av`5$1vnAN}Cef#F{^<_<8p z!>pSQHB&@#mt^fw3oNQRXnM1KpqS(2)PT?{_%wV59avRminlMft6UW>7SPM=YM{d3 zbR!a5Kxsp`Zn%w-v%;nEy%`c#_caNi$Wlm`o#1^#l-ws(%o^4aA`(V4Y$ecP z`QnsJZW5*@3EX2^Wg+Ux(eZachUx zkZ|KK84}*W*4qk*)FYUOsTuEdlNZ2%hFl52=M>?{8Zm?;n@A;)Q>!1WiHLeI;_%?^ z5gEchXnkQS5$3S#pg>@;DC$FbIh2^3DAnjM^OHkNt@tqY8y=D8m0Mw>5%;6E(osBDYu|ot zUT8D=4LD6xAQ>z_DWwB|w9KDCCIfyj0AOTnQqs(-ZD6_O-QkmU8s}OS|L1ad&poftZi5?-EwQ(^sXK@uNBxP$H^}v^zWX7 zIdzmnQaJ(q^Y3>MqD71M6#}=fks&AdE$oF+NUM2X0CMA%yj7#%R(km&HrfH4}K)U@#!7tY33N!B<2$4XfO`Tu!qMA;_-*Ga+^j zz^wLt<**6TxTL|}1rnqndqtbi%j4<7wDw4Zc6Q(X6p-RUj7qK^l>2~OJ{ZvLO@0f1 z(cus$M=^m}!RIfyB!QREOf0kdt;X|}?>lJ>S6Cl=oag0yX2YZa zmky7d=P8>q|DS+y*d->t4X9YwATr%EVK0GD5Po379N=(4&f_d1sf@rpL=;(m$_4Hg zwAZf0QE>11Fa}>BrY(epfogtry@8#w|A7Jwj13rSr{R+6eQ{%(8G+=cR9M0hSTtrb zE*(ZS9l(fAmbR7NB5`HYK@lpQ&c~7!LAqg*kFgN)W~J3n(;fl|v7Cs9=C{*_9B|ul zZh$0@5jJ3S8`_=Sa!m>qjZ;Qzes5RTSror(b^KSYv5dFq{ey~-hjWH%2rwJhGaz`C zm@)8I6|3%`i;(J1xQUx43~1e(F<}w+;)geHexN8EhI?ahYG76;pdm18aZcWzJw{kw zZ=!=5(wGnuizC2qqB^nY5%Z4F(vU_p&@_w>CN$4zfGR&pf2Qu!o`Qk(hz#g@o~(4Xh-7zN|LL^JtWa+d5L0^6 z%Y7?Cn>ziS6{CO?5TVN7A}WdQzojmk^=8>1y&UIdfXvA}V48Cr^CDHb6^y2c&_*Nl zV<=YVAXm?VAjot1eZk%;5$AUISOtt0CC%d#o}FA!;V%advJe7pIzR7W9Z6Zd2>sYR z*TpK41sd=Gg&jk@!WonAJaO&!S(}ZOni?eCFklPjtma==yZ}v0I*+G>gy6n9qd7_K zm9r(LoRA>$e3I-CIv`H5u9jB%1Ltv9jj6B{4=K*$123krv9X79`slU-qWo5AFw!cp zoSewKKvnaW#?6C%k{)i}NBHlM&HS$UNWsgok(}{codNmL8dkG?w|jNI&{6J2&UR2gIFw~H=b`^L(P0OVb&nf zq8TGuf^na`ceH%YBkp7hZK~*vF0#jPB`_+K^8O6JFNmCuXT2eFvQ2pUCd~S5cUUgM z{PFJs6qS00XeWxkP;V3z5EA~Y5@>>xi^7h0Ow(*$jUmr?d~a;PXPt(jBfVpsIfKCb z5Jx$pWb=gaw5S8HSuG2i;Gh}AVuoK@r5B`3PjKh8zEWl?&iAA+s- zK8%19qnL4|uC>m`aFgAHa@!#TOu(-ik%5DYz9T{nkr(R~hLy8Xi9j7e4`N8h=jSOD zAj{xW-P*HP2zKNhRuT|{gbwRP8UY@r7;zV+Dzh$ z=7cAQV>Flr`U_Rv^^4-)(NKk8m=ovk0yh|Y3 z+3nS?@(aIQlxy?lP+q0IPPqVMH)2#cIs(3JNnayhjVTvX>J)oD3r~kjr)=85iWnML z;e=KKtGo-<37YXN|ep)xU}a!abD zi7+TFVbhGvQ8HWGM*Nm7J9l`WZY2Vo{{S*w1M>#^A6BTCA_VfYqAK?T>xEkbvmswr9XMVs}b1AWZhj7%JAWE0VM25SaU?2mloQZHr`hZ&Y!f~4c{ zx)Q?yQ7{zZ0+rSac_jGbqVnhzQ8r9AW7KjWys$t3^i0D^t&I&Ni`K?RDXrC-)i3jvNlO&GX<rMIZOf1 zZ3CE9(V##KeDwk?WB4fkEu(Cq;J+r8#zB`1$!<(UC{!^sbko!LZ2~Eq1Ux3o4T6V3 zzZKo=z{t*4#aLmZ2KXl?eguVH7_2l}HmYK{6$94G_RaAgpQLdmsw<(-AfXM5&iu&hg@w?YeskQc=qV5<2q3Sp&b~ zFm}LwJJ*!acjQ;CV-ykS+hHsggR+3>v_JRxI42UVlJZ9ik7ZPVX;($_KzV6jHd(Q_ zNYZH>gS|x_6+fcaAT+-LdrWce>kfYCV?KhIfkYrvyquz$;zx8^#PH`&pMlsL{@WUw zvY#0g2Kd|nXQ!j4AxTWTu3fDy8^8@fUHv^L}D3>-EsOsj;rCV z1N~%4CmFK5BS3WC3Lwrgz>hNnHCN$DlZ0ZTn5}!H1*InU`ink zbeO_}bkWa%nm*~!*jhF6QZ^_ao!g!#t*t#g+Qnrux#U2PhaBuUT}rhoyM3kO*_h zc)-mzOcp+@9c=SR)8ih`=q`LadPumr=9^8UnOZ`{nNFzBM5SzwR+(f_(3Qd1ggk7? zdI{!KB4chquvicAAz;Fpsk;o>P@bSMN>(gT5?u_B8$^RdJ%yM~jS9$w)HtLn6J6Wr z+~!Ti?vVwlJ5X&?z_JsC&?Zm-?vENkb$Wmtp%710&JIWOzaf3~YE0US|8mCzvsXf3cuUnFJGGtJvrm`*3#Z z^p!K7H-UC&2>No+#Yb8ZcG7a{)*3uhqB&_6gkNhxH6oBwU1N=eU9%E!Kox9`@?F}HHtyh|U}#R6QZHp8?^&sF@x1u9rPk zM`+`#H-;edT(ZTxD5+lp2ndv?=rx?^mb_#O&C|FM*8@u4Lv}Qg=9}{1@Jbm84)vwqUKH3#2>Pds0D&;AFf|4SM2lzql7eyTg8{ga(3(z=3 zKkElgc)ghm`=qQ0ES5^Bx=w~yz>Q-+bZ{~o)xNO>@Zed6yF=ONIw{qMU&gQXC`SYiel!I z{51(3B-lJIQKZ-Nv7?O{C!mqzl$M8@M|mOl9KqThN4|Eat3hC)8)b^WkdU`okCI*H z=IA`5*4#@z*3GgL$9WyvUB$Vrvjk5se67Hg-VFCS1VaxZucZ8B-HxjlqrdlzO-`RB z$1TOYphQNp*-*wg->I5ozjRbzH-}7~v}dbfZ5S%PPLsKw*sl2j(t{i| z`vV3zI-Ht%gf18zN%+$P-R<LXK{9c4$8oF% zYDcCWro&=1#dwf&_b6P#bdxy?UPY9=cppPlYvXL3W6NI!lO^Lr($25jI8=H;gH0S1 zADswZm4n^Dirk^Ss>MwT7V@CdV*rb8Ra)&9qt zRaBb;N?(*~(A@r8b^rkj$fpe@Vl)uy1&HG80Kl&*A^GEyDP_?=MtZm`QY}Tn62Qnb zU=sVc!GU;*t0Gy0q9@y4@k2HU9;|kut(v#!i!F+1De#62K6<7E-T(rUO3sfAY-H)W zD(iG`0|LW}VXIM(Y6Zv2%bdgoFft|{d$PAnY|3n-%3M=5 zy6UPrq$86gD*}QwA(HiaL3%c~f7#+n&RDas}b zgF;~pZ~&fD#+kYnr%RRnntUv<5CUoda(s>u_or#pK>&j306rx$yu<<5N=%IJ2IMwG z_vptZRP*a@4Y99!yescgGPm-k4DaFA4<7iv@S=n`KY^Tx87TM%M)ceQs2L#&?M#3f zU7Q6q?-VLyt_^mF*el+~v}w@JyC9-Hk-1>=iM*Nv0&@ce-(=fah6!&zonfD(kB)ir z@?@MxxRagyZfYCxXcGxM$XNgYOyTZ(W`q8b&F2%ilbh1=D4JTCI%Yc$u{HRh=T$ENhx;|I(mNot30AJCwK{|uI<7U^*KT#0_Pngh6 zUNa>HbrL2=1R3kdYPweVjn!|bau=eXO%i>srZ5V!uf`C~(PWRqG6XR)2^sN6j57%5lk&O*a#>8d48In9&E`kLglEElwFAcUd3> zU;sn$!#DsQj0hZW`w$&F^SF4t`85XqGY9Ol!E9F!90?7Q3*E~Bi!*W{5Ve=IhJb@t z<)jxTMqBt1W6!l)=lAqaQMWHexdlgg76N{L;t{6Yp90%v3s17T3I%}>!UIQGJgNEMGo=AHS|o7@B1IkrwT8NF+tTrE zt*2t4JIkO{&IfA1oL$ z-60#QCrB&@PM5VD=mY@|c0~+rAO*I{a);W(8YI0}JR!8_aQ38~p;hQu6q!6?6I;__ zcJdIH3H{}^^yQtSz~wOa1higR{)LtLb)<8xdj^g(Zrb16?z`tNoT~RT-O{8N;@iLj z{FCZ?cbk#C!s1}#|A}g9X8@oWPA3pYu1pjIk~nHx6@EnCGdLjoj@p&M+jH3daf5^) z|D0B}=qRD_uK2;I^J+lOrM6h%G*5?EK(MBq_WBoY05k+}A9 zgHuMI7;aiP2W$l#fElCyJ}{bWg#~Rihe#1PS^cTm(%j;W%MW5K!vs7KS+$n+&hiAp2UX#vCjbuHPM@bQD{wH+PMU)0CxwI*57mDZ%){ddY-N>H!6>as~tpT*IkqJY&0u3cqXn{`$vRRe;LL8a30}8fC^F=3u}-5 z6Q}m2G|}AQGC~6MkT4*+$2_leZ-@yio4}VIz9~~x)hI8U7!v{f<4!Z?+>f<4ixetx zXE+L^Xfy$@;wUU`_(B-=eWT^8e1NXA*%Xz1d&lDIDBZ)1m0g>%g**6k;4ZU5VR%l| zmAA$8%lipFFu^+}z~jAj_=q-kwyQ+4JuuoZ#*ST45x=_Q<6AW15I{BF(p%sHZcDB* zVk|2uPmtW+zf4R0W_7We0NI`z*RaZGR$hZ(R4m=C&i#Eky53d?!>HT3s7V}Je!j2B z5e)#uoos)4d+=q7;x;kzFo~3iwye<(RDqbaHwXX#5Q0)yb9=qryo@tcNUWF+j00H9zpU7X`C3HY@L7yUv^jKs{+e1G$5#O;n(C0yM zQVl<^$l=-~^chxG9|WhG58d%poI>yX<&r@I?vqSiG?Q&XKKKWRi_kam5G^ey*z$gM zdRC-T_(>~)bMsIOXlGZ`GRw~;+0IBL8YRE<)uWaddKjj4Gn4rQ(4+^<0T$6}2LQKc zy=F8M$#q7;m1|T4SNbw@CoiVX2%s#Dv-pD2;dq|!Q6H5!0x029p+_!5xmJj0>`M$; zbjV8xkLeI~D8(F5l&X1Ry#UBO=>?m0nu_Z2pGhDBxnw?-0bs%w8EB#qVeegDc@@qC zX<#l3(G0Kg2TfU9oNL-p$5-~vNWy_6MmsX8Oi+I&r29;ZsDFB1-4~>4?=VGBu$P!; z82_U%0}PfJzk}Jm00U=%Bom-bI3qddXYl1z9z=?>Dc-geI$~C6uF9ey;b1CQs$&(8 zvY=_|Jt-g-jj2fzwNbq)tJ%BCaM8{HWzyZ2?R!U!Bc1xy&s!z@zw1;~@Xy)H9OaIrqY8MJzLCXIa;Rou5-8;?BE5(}`NQ7RgpXx$?sU_@LrJR~w5;Yq_fP0WVPaFyr)RbrZWz&Y|*M48;qS=!98vWMl^&eJxVAk%>TVa_kuPb z%{A>{UHFDvJpUg2j;?9wNyB>vuo-49+11wykMAhO&&_!}l_TejtkCoY%6*GOAS_M- zV9Zic$F5rT$?yt5kak76mSh0Vm0uzASyvs}5L0$vigdtCLkuF< zaLWD^G4Y^&1l!X|8iJ`07Of66TZE)bZLHshIaMufHQV*TvqMZArU9}a5?nwQ9C3j* zLoqhqf+h(R33)#`3tWQu3k-C@3V3H3^?Yj{ZFh0^WZ6T7*lOL4Odp;Y--P2AG2#uV zqp0x5!DR_Ph`75_T4P;Y4$U?bWJ4NH_!eO-Cv&anjKi#@Iq-msAz{4xm2`EX9qTm8 z;%?H7@!tEOzSZ*uS0yP3LffwTebgxu&{S=^Yki^FT@Z}1`M`-VwxP$d5CALW=LpWE z9T>vLGK9+z_#kl*no|QYXM1EO|BBV9`aKux{;(G=xe*3>3 zRO^}kpfKq{s0Zmv0aOspt(RLp=-Cu+X1o&ZvSE!lVOMacfy3=Sr% zD>Bv@WB&+P+4oj>zW{g(T9ZrSo~qaiBlFXrOh1H z&VVU&6$^D>r)>NX;?p{Sc&H49mauPZ01)rIEXiIC)Pwa|LlBF@zyjRjU-*q>h-AzF z1X94HQ?6Qf7DNe16c)&A85~0FXK*D9H#BOZIOfsX+MJD1U+3%U5!>{)^1ZIK?XzlD z=;6!qD@_L7tR|IU*jdQd)=s3vN`!_1YEGyUh7Sb>F7LF>O#0ay(sIbmnbW+w##xDw zC4y?04gkHu<24k4ghR_eU`TTi6$y#o#x%cq<{p|>I^f4KQhs-Usz;ayQ&ic_mG;8NjQP4Ln0fI{?R3+$V4%EbyEp6>-HoL%k9yRz`Wt`BzO}Gw?_gj_ z1ZWPxkLnF)y^atVeF~>dG!w~f9)CT5n+AXY06H=N@dA`;fTvi=8t0BI=Ui@c=@r0!Pa}f@{>>Y6$||95~-qwLOtQE ze8auWHX#sveV)Y1;IRBK0Uuc>%FpN52Au?*KxT^G45<*Q9RTkbrI&$a3h*|f&3E7c z00FxSaf=9B>stRtL@nbjL*4zcQK!qqDN1Di#9ZW^qYQ*T9Y3*PQhgQ-zI6yZG&^Uk zjldGnBme{2005nU002-x00000E25vMx0N|US>gZC_`*A|6;pu&^!|H36|ZI?7ykEX z;0r;P1D#x^sD6tc3SQY@)C(b+GmxNm0004Y03T4n02`G1QJ05x(~GuM9;E;-?NH7+ zoNFf81q!2=>XTroNw|d&Cip<;?RoEnkz~LUQIAW>VcY(l77zdc0000000000001~4 z=4S*v1S!~+*m2fZ#F2|288rQhDxX2i>f++^P!yHO>;gSuEYOf=q@iouLE_sqXJ7*( z=$7}@kN|r?0e#6$ky+>|5cp_Rm|1L1R7@%e%dv?NogjMPunMB#XP>ot&%>DCIf0V` zffZldsQq}_xM`ne;NOgU$BxFW4cQZLU9oK+*kqDs?hsGXO-%>;fM{R<069$T{*++& zkxeUT1K$*^2KPJHA3RzK^X_*ehc&1YF2+`Nb}ub>_Xr9kR#;0zp-BP#OuNF>fB*mh z2#VEbhf;~k9YrQZ&(z^3!A9kCp{$x{%Xrl<^VAOK#S$;y3){#}6xNMb zWBETjB>>Stg)}7d4IpmD2dqhe00F0gjsR@Jx6S|(Zav0ue{`_u25&%{E~CKNH9*h+ ziIMDk&4$Y=J$tbpSAN!;UC|Qi=;u0004qY5>p)8VTZL7F<9CSg=E^ zpbZYwP~V5C9@jQ<=7=fcz2kVLCs@S<06|}Cv;Y7A!o4go(aKYGn2K0%>=0=BX=f{SRep7 z+=T-@EE6>wE6QgHm;uHrbfo?W(J%Vq_bczoPvd1UpdF9^00B=F|6v($TJez_5nqEf zQ;f`vw0db_>JkKohlf-rYAppa1|Y;21!7ga7~%8q|X^ zg1~S~Ng1sX#_*y4a*DJQ+LX7(V7p?>8gU(-5m;02e}|Rr0jC8R>Cag0000000026egLtU z%uC4C3#s^k05aa5iLcd+Ae6&{``&~A000UP5jyT500g8)ro_zDXcQaZk=Vu*cOIB0 zXYrEws+t85Abx{~s53tqa)P2T*T5}cFaiYb0NUzQN>o#CKu|(XIHjORs7XZcKHCs*Pu<(sts2 z0d*92V;n}tW}-Wp+n+`sNM~Rm&t7Ur^W=18)xVIkZo`%n>!uVY{cB)fh$!GR0002? zfMN4bBCr>2v;#B^Yo0KE0IKaqJS|8J3sUG4;DVTlG4O)s5FBtFLAF2u004h^j1L<= zrU8bd1>t{ENp_9JFx*+C?p!WZY1NME$*NhiD#fP*7pk^HIlbdtGTYj%9ZLQxc-1NL zOiD>!*kLb?KN8j)2ImNG4PJf{M`CR|w|&J!vzfKiSbN@aGlDs+oTrdAU!i(jg*R4y zBAH{Qf2ZJn00YthC(-&O3hp)`XQGAN8lbzP9*&IADc<}r z8Xvsq2fr#xl&U$;vIag}BZRJ!O{F!cePwn-Qfd7wJ0c z83IgGN_)s~N9lV@W-)B(EK7p?x}){+`gA;zu-jZcu6~1?Y3exH(tGa^Jn>_Xyu(tu z#3DEx012BXn>#Yi2{a0P2J2vJ=ehyuyo&(<&m7PIdrM8=2Q^I3X9)1F{iIFjCNT#w z0WTxZbd~0fpZ@M2GI|G`FjJrrCNt4x9nX#WlqD1j#dF-^7+rn=jzjYr&8flI*eYS3h@42Wr3*^ZzI{6ji76z$?Mg1sw6J6aWGV zkeQ_iYs*FD`)jXgYr@M4${^5})yVGz#h3s900BPufFVo(00P~gdGyYnhweGg(&6~n zzdh29t)fN?^`o-H`(=y?oUwuw{MG|zGKLCyYyYkm=`5)PKx_m610*An7*|7iInz?s zJ@yZ5JCZ|K3l3)OEs7dC#C7G4TlEW8{^_INn==-j6JWcgeaRN2&;9oa*eES}We+pS zjZ+5RgmO5@7z0oOi+YPbfwHa{fXQ{gDj_8eY|~ewaD)Ol!Qf#wm_(qvbewod8-=qV!$gVHe-Mmo5`;hKFNVU>pb!Unz2FPyPhEBM_k=kmpnSt zZDeFGXs#B)rw1QZy8h)23wZsMIU@J^qai#LwO`9Ki2#CmCtMasurILW;f6peGy@2( z#h~Ds3Lm9LO8JgV^|**5*WufJrmf%IK%vLspDyC5QjX_9qw^iNfiPatj{5%e@-C|R z-K#sp#Zi(IUzU4aGFE9;zSU!I1MCQ5J)Z!S(Q>jckWD}q5TQrR$dKSjwRg{d(?RO8 zR%v`((P~>yrL=I%h^I3W>7YVus;nkbMAQH@c?71Q6)L36dE3~>Ve0mXVB|`U==OrL zIJQfb+y?=ZEZYGLn#)1;*Z>nXFhD0dr)HV~C|aNih+m^95!E%0$fT-aZTAq%PB(`T zQ6zmf^_v$Ut(h|Sg8!+$xW@oHwLm5YUCCG5YEQ1s zO6b37qrzq6-|~gCgP!aT&Ah*|@R8g-+0 zWpZBOoX;)m+oodwTF1AxU_vP~g~Ts9^pHltlI)yKyb8k^j@{%m zfX#v7B_I1(0J1|onCuC(zF#8y=P#&SP$3<#<$u=VmY_FP-DPoDm)vuqXzN`q%LlSD zo(XX7bW17Fjs$>~$I8tQ0S`|+Pj*d!4RS#szh^9h@?*#10WKl@|E*~V3nNb^0Pq7# z;b_F@$60*|a&WVF&<#8XNK*g-p8{!W#%ig;1vb!fJEkTkJDoW9vM_J}v?QO1e^J7O zVHzGm>dRa)s40hvkqmq+^jx@w_^lV;#Gs7bkGVdl7{Tt-1^Z&i2ERXckPNZ`6^V3m zq-Pe8q-Fl}0JSU!))_6Pq+7ZGkkJ>aj3H@K2Mw)fYKWpcHOEFhabIj^LD=O@I?i_f zm^wDzy9;_xh3{{hTqK@@gIV%H(WQuFgCJ)cSj$W!e&eoqNPtl3H^J6-usY)R#ZX79 zMfB=K)EkRW| z$DFz5!UTMhU|FwGo{AS@1XW*n@*+0jY)&X%)LrV=mvSIV`v3*lH9?{YQjo~g==je8 z`qmy|gL+UGUA+K(-|*mpB>16^7^$8B)G3)oJ*M7B5@geNzfX#E0V684 zhm_uF7oG`x(S^ewf|3%VI5m>b(n`q%#+!)Alq@IZA9?M6Jwn>$lMxTHl+&Wx$$gzW zt-w<{)RlKymYcS)znX?oX~)_`=gn;@_h!H{E; zD(20N1Pw5OgbM~Qd0405Fq@kJO!OXmsUG&`aDg!rGXSkYF?z6yF`9)(SFT^TbgHdE%%mU~D zA*dhlOmt;b>3EJF=~>4twg|Lru$lyv<9>y!Jhpte@-wfZHK(Ut4O5OByo<(U{DEog z*AEtx7(x8`j0?f`ey(L{T7;z&GGXRgFNU=2+t}x=112@^k*6x%o_hhSsm39}@qf=QB+DC#7V+8%rU#-Ue2t#bXrxy! zP6+cr0tr(T`P<5_u9Ljv=||i>uK->x@TKa)gtPe4lP8x0{epUdO8UE-BXBR&EB?HF zkU!vN7q}O1Dgf@!3d?FLI0Fth5Fih)p4H_fSy$R4wf*kTp+I*oGMm_!>CrpHX|_Cp zg}A!%;g9Fr2_?pp=Pq@Qga>>rP_9K-jtd+aoocuCH6NvCxb6ppt3cGaI>}8|v~+TK zl4>N410BqjFr!phoFO@Mx)~g_H3tdD0AusV*C!eYNg|b9&F+%#EN<<{s==tRWr^kn_5)hiI*S|X>#MB&<4x|_MALJx@O zs6Rr}Y1)DpoRPh5Mu1kwZcm9`l7#?bX=mUOh_Ngv0YmH?rliy@a1(%-*W9QBfT@~h zdH+_*Mgs-&^T^?ACeexJM|#)iu$rrqK6*x2n9z22+ql_*W2D_BE{H)@3p@)IvX(Ah!`Wpt( zK}b+dhgmoW;A6hP?2N%=oaJb6!6pWjG=Z{=7H}h+GcGTRg>icz22#SMDpwOe0!|rU zp9N{@bLth0~yh_~x0#x(XHlb)gCk zixu0grgRJq<*ucwfuWvx>Z1IC_7mZ5T-A-dq}!|7R=h179{W(U%Jxu%jVP%Eo-lG5~xXUm1i8iI;0bDYnR=VNoX zn`y2OEJ1Hhbx2Yf=iP8e!qTTfK`zyLdSlAdDpV*vX-<)F@$@L)^aDFnKNJ#D@t<6D zG5)X;N?#N_-+V&2jSnzJ2ogiMHeabqS<_;uoAAIo{Ht?Uebxg5ZcEp*+Au=l#Imjt zZ;N!VFM$_^*EvH-EVO+p_5RZcyh8&nCcNizYjudraFLLx+h#xKHS>J5=bb{V<3XEx zwk&3un9bzB@;(Brn%97HRbr;_9D1lblJk^Y@bOa~mnJsZGqxI20QEywiuHPIn44wgyb;7do{H*3)SRmpBE>l z0iVsJ?as$`Z&)Pl8+?Kq6${OvzMGr!j{<4`I}sK~S*Pyo$FU4QN&JAlxtgYk09%x+ zN3f6d3-sK+9MVY*m!!i%r1*7jci0(})s1j}CV>~Qw1N71%S*fuHsK+}a-JW}#e$NeNr$P~?1SL)?NgYhzpru&@ z8>^emN2_j7#|eXhc9d{jA&@wj<65Oge4;$HUvf2^i>HPwOB!z5OYlsHU=n%Ai+z8W zpbWOb8UTVV@mv<7bzcr8l};MuG&2s!bVgP%m;DzQ=yrn!;}jP>?sGpW?!fcI@l#uQDUEM~oRA#81h373%oDR5(4 z`+j7+`DQ~AU4DEx9MV7l2Hh?$f_tkwiliDdcL(t^b>g^)#Q719Wwn~c2qPMn4%{*& zz|gmqMl>Q+evd_IFORwUord9oJ#>K6%MY&KIT~Xiz>bX2##hYpcuYk=_C55#7P`2E z7ygo^t5cBsUNH55M0MK=!+&(Q=j9jDsTyS-FbCIGAYlQIJ;9r)y8r+xw4$Qx+H!cQ zn7S|X|GK|tcDze}NGP&H3rL6kdc$$@TliiS7&v#QB{Xs#cTm0nLz^*HP3Exkx$E8a;KJ8zFn9@E4xHLD*(s-jD#O!Xia6_u zUSn$V_3S078=I>Xd_)0VOCK{)XJlG8i4v%-ofLpqri1_0-YvAzm72$YBBb1;D;a_q z=Vgtzb@f9;zULbEOlfY-v*lgsbE^gC_sBqkG$Q6n#%GT3b^geWP{vwo6Roy5wK>YH zqZ6Hii>Ttu-q&rYz+EA4?|=YRL5)fR?IyXA@4K^*kCepy@J58ILCSfLnB9qp5W}IG z;Ow%NLl{l2Ry+V{Asnb+8GzIVn~Mnm{t`3dm;nlT%zKTUA{$T^Zyl3-2mYU<37pzW z^Xxs=^;gyL1k%%PdlTr*=pKySIIwCDo^+B zVM`#FF|p#kc|318?{-YlMYtZ_vzJuyWpHQI?dmQW0Sb2x9vhf(bPLfGx=!v1kZe7> zx{?CQSG+XlN?*5z_>R2j+;|LC0DxFheP$}z+%LU!mPa!SrVv`S)W{qS?TlJCMyZv5 zQnee41;6215u@K>z^jIIXj6w7O1d`eJrS{u(P5&wMk;d#*5vr@2tC3aQ~D0wg(jDy z0$0t^+>dr0?%Z&=FLUBATiZqV@k3^&%{iWD91QVU_{v(h2zkEZK>nkh`{_;h)sM)B&&8LUFUOZT?ppPtwg(mA^q?nMhvR_ST=o0bwd&006Ax zDH|lRx$UNLWKAXTGP)IzHWx$P7ql6Io^oXCSTqk8Oz!(}j%x}iu=~O(HY!8n5*d1G zf9P2eTaGQH9U6A&i-4k;%|VA!AQtN&JOsqoj;f(*D?M0O)?#w#TRXmZ+n`>~4O5eU zZYLakMrSb3Te!K&{3cibagc|30%KtfkbskY_> z3z`CjVHvQRYB4DcTwY$d56_(onVEg31xkmg3~mc6AT}{EOuV})%i}Rc zlhI%ri>w_0}GlE{}oufjnjmcu*S4>&QFAXxZi!l0uJmo9<{Sgr_m-iG;6 z=NLIlU#pZL3rf&}j8v@D->*?8T{-NC^IfwVT9MTadut5h7Liqs* zK-`MuN?|QGL)H-+cei2jsbc0aUEjhj`(;fz-F2(PX`i>+Kf}r*9&|25b6!fV@=my0 z+KX}k9maEK3u@wg7zX%4h5m>wQ5+<3a(X}c?A;amEfC36V{+?18VKOw`ZA4OepnL) zx=RMsc`BJv=s|%0Wf%=su7711R^h#UgK~G%Yx3?!{*&&}Ft>fvZ7Yljv(*%&*1bT?sfaR0THi8;5IEv@015Y< zu9YJeaF^@4mGlfFVy-~_z3;y4Tk*>ca5|N+X=Z)=YK7KPKPXz)NX;NZ2IEIH!=JGB zeWe#AvAC7p#P}BoIqgHEgQAMX0mmN=KgldoS@8EPn94+rcp`d3ykqtX8Qu#-7r$QY zP8b@^zAL~p5Ah+rZN~HD7wJcJ&zxqf$86u2&t@`Z?u6{vF9T<0>qOqH-s&*iO*_w^ zP2#;j#*vthPq>3pYJgbr*egb2ZMNwMFzS5@HpduVf)qchlZUMWo-0YPxs(VonOq4E z2n7rPxIf#3CjiETu?u7XJYi^~$x3(h1k7P4js#Np29&moPiigSJ?ytUVygk^G`r!PQhMW?(=4R>iiNP2&x4g1txYw(I$LAOX zyFsQ_fpjYHoBT+u>7x5Y#shV*$-4e@il@RsgfWeD*P(45{f4QHgG3>taGqp~!3}sL z>U#g2r|%LL&u#qQ(%Y`_6#F>wdYQ`#pVYoT6-ajiPsO`(?e>2f<9M?0T7jq!l)51P zC6`6IKLQCd3ZNgc=*@af3IG5OPD&#{|1|t;InBPchvIH;4)S+6H_?Ovlgl|B9%c@z z!C+fHY+nb4f2a!)fRgvFD#2A8tned<@Vg-a9`b-709grFT6D%fK4FgIG-h>TJ?zW} zmuknnN?9=qF1Q2kww<4mi|j|4_yX|@3(H#Ot^3kFG|XNjIhy@ZPF`OkL1YVNYv} zh+VdTr^W@Z>)Oq?FrL9+t*y0vlVd2dI3jQEmnGBE$I>`rx`+(-x-9fM6vGK|5VeEj zLj2NzT*_%b*N97EvD=waW;&Lxi~VPYwa@8t&$LFTg3PX=1axmA7KTFNSvmYUO@3ut z_Wr`Yjr|l`QGpkE{D6*TKVHVuQ99U$wMub{hE-#dht^1^u!=|1SgjqjVjY}@S6%V5lG3z`OL z_LV?dPKP?jq>VA~NV2#}ZYk5@_qYeGkRQZ6m#=HkBbIlB5>|lTm9#m9uNeeHO`ZJ5|KjlCOo=LZ0MR{U#CJoUckm=+9>yOTtis7y>G(zPtlq2WU{Qc+OHB|OVI#5#G?D;UK;2*tPBN}c`{o7*zFqhLl^uAl zH=aH`LAUWm`gR%q#b*@hH+<%X;`p(JZ!ys4e$3iZi>@qaU-WnqG|!Si`}Y- zqB=O1DA5SJU%bdtFq{;&hVQOz&s$v?WCpeVLr53jkJ#kEq12-EeDQw-}xBmMvn6hW}q>P?iQj&v}5B``|gHu z-XZ!WOPWau;9QgvXKx$NXn?|#()Ce9epjmIDvo7XSs@XBcz{Tt+W{vG#kfI3&k;#o zB-tYB_>|C8FMKn+$-kK!pIEI8Z}UIEz@-7!{~mxhX3^q{OXB~H&k|V_|4YulDv+5M ziBur|CZAJnMYgE8(O23%EvuLlEs^BdRXe~v8(gDNsQz6BMFcsLbC5%9^{>$yYAo3H zI7YL<5symF(kk(&4KQkaKB!{0Fwp|D%M}QM!?bPf&(+UhpaJ@a9?*Ej&{#lV1U(_I z8LPWrIvTLKND1GKyHc{3v^?!HU-$%`zCw}ezcvBv0%HsS1$?4Sm3-dDap7dQTaps> zdT6h)ZlQIP7>DWs%gnwEK0QYpdEnAy$5$U75dzchuoTz)#lZLL^o!3HwyAn$#uWon z*wCz~MQx_p#8&ghWYvgEBz88>0Rp?|3GbQjieJ7)*{?B8HA>N8U81c;c*@|4dpp0Y zEgru3HEG(#qU_HhmMmf6)3L2<@>+Se7V2Y*tGuDGG$A)|``48bJ |07CWu5oSp@ z<+u3+0M1uOD|g}lK;)n=MxZNm3P#3ExCIjbaJkR#KwJz`f^X|Fnq6gUC2bx?$XbxAnW3M-g3HQK2{exoV^}uxmP$br|h2nk& z!FCZ`HIjxBjV*zDyzbEL10pFjE%+h8Ds|MM>PJ96W16|HMVykrm5zp$LsS8DqF2x# z&S6i&h7i8jHP7M24K>9kh@A`zW{L$RARpcT+q$;Yge#iE>SfWA@Fg5EHze6_dg5YB)pwM!5>bP>DCEzxw+*TW#h5i1YPS0w?ei`?zmTu>R59SNgX`JMg^Cr zUZ3O5eN6e0nZxP1@)^9)W4sY&Y!V%2j}U&^@zGa6A?Gyn5*r}=8usCX{%11)fzwr; z8>q%f|Czf^`gLjvQI5BJ%SI(`rr1%9_X!GLI2N}@pybnwU*eNblea{<>j%sU%>Wlp zNe`*c^B!Md=h~eb-l!DWHE&%+R=oq%&N*{PZDK9aqmnx8p>@ID!}uaOktJ4hy;* zE}h{=4;Xzzx5^lSAqBS7+{k}_oP5K;Q5QGRHdIE}A@xZsd;6ypawB-eAn8)bQocN5<4sDBLx*8Cer9WV*oE zS(aH1pPh4t5+0C94((WaMqgSrqw^E(mei!AlXksB(mpPY%8fQzj=q$D_Ht8KsYSb= z)bwRCkiEC%Pge>HoLCDW!`G3NQ{+X)Rs|Gh$D$~y1VDczP-Jr?_S2(7A}V6KF*jGl z@pI?F3An(u%fyEf000TnR!HQhq#~P5h}>j|p(}U(_-&!b4o$*(A4C23HQq+@L*D^m zCkkdZ^$P77%5JCTm>>W&!t?IM86~et=SrH)PA7}+L=)j)}Vrpf3FG;_eZQ& zeODHJ;L4O~lt__Q_t4uHcM*&jJN=;IzK9+?Td~R7f1l zKB#L}>0=k9?HV{A$9B?WZxb3qrwNz3>vM*122U+Z>q41vIW*`g&>C69Hi^M(pzP35Q|d6XY2>m6t{E z);x@ddMT?0GZ~Te_w}VC!z@fh2~6Gmvc5Z2z^@aRH(IQOv3fXDH92=azb`A{I3U8X~g3V7w`V?N!|TY z_c+Jc^&^Hk`Af4MC{!VnHSO2TNca=(}-WWcY_Qj@mbnd{_+| z`S~BdwlP+VUcE#z40X87y>Jat92wfx09#_+OCsom_&GC9o$yz4(XiCxHpO$r;xTnc zajdGe0IK?OKc(WKA%K~faaIJN#LiyJyiZz_eA=AnjlHux9guK%%$_r$oX(f`7}#bd~} zWMoDs3p@&N>VY(Rzdf0g#6NBtVc=4HqWn5|Btk=mn$#EJtG&zR{)x1&V#sV|8ODC0 zK7iUTRp^A$dzP0&KCOTNP6R(lGzgULrN%-3+$!*26IW=Q^!t>rKQAp>C5sy=WTq@Y zNP3frBl;^TP|IG)LR^RU!vS!F0{Q{XW+{FWWiw+)yz%4$0*z7dOeO%$<|v;Qip*bQ zDu#=g1em_P^xkRA(@#R5+6WBZW%y|He1m(m)+ge~4Q#ma$di-}6}Nl=igJ#X3%H6m zbw|#Gg-Aof|HP^>7$08G8Zf;Ohq#CJr}Fu*AqsWeRntS39G|!el>TcikeZXUZG+XX zfG>D`8A&J~DuEdb1rJ`5a zMG<^T#+4C85Jtqq`eD)prG{^N`DZ?}c9=axsXKyCR-GBVR~`U?1PLuc+(HP{glqTp zOW_ae5A0}Q&vBx$vJ4Kyu(0 zAZsj~{`uQF9P;h;43mkuooJt&65ksx$?Q@YBJ>DX(`4oXVA7Vy> zWg(_?PDkt89ixU6o%7BXQ`o^65(wyJ$H7ig4dd|zv|Y>Jqav)ZnQrNUSOXm8A?2** z+aQbWK^u0)dYBV5=gw0ufJ?BFy^FyB@bTL?KX)KMm`1>yt3L=B0=G}y4Kz6bTyeUs zi4a&39a{Wm2NWxDrn-%Q7t%_QrTp3fsq^g`_~I%S#i`xK9Pccu}BO zsF9~0t8T8dTXCg(>lku zvl*B)u0Z!W$_5fNVVVmctOc2xNf+iXb~7RY04tFe3VtdhkVtXFSFe&WT^1xMJRt(QFf^@zfIi^B$hQh>|tVm1Eoy(nLXq(FLw~#8XAQ9OOTv?ZS;fldaB*h^gUjN~iou9??t! zK$5w~D6}1}@5YIc7ncXXbeVw0|Mz^Mf|sq^Y7cYvrro8AwcJ|OjT}UyD~`q=W>hoF znXVj51s@%O?5)=8w=#`TFVeB}AuI~4$c7ej6ptw=3}w9kp)5f%3ywjP5EaOn zZ!qAk@|NmunMY_w&0(YPl};qB@ZkS(!#yqQ>9i;uoS}Qn>t+R0vSC8o5D>!c09rt$ zzjl`>>EO(#6Pj?*kI(E@TwhC~rE}n+Ig?tM+GwSkHF&8Vq#OKCMpD_`kFR+m0$&BB zLE(4yVM1&URc0RpvVz0yy$C`Ia;kb7re%yR5o5M6K6z_@n9vhvW;$1p-%RF*X|Py( zgw&4{({RfdC(va9T++C!TnpIAx(vgOLBIzTa1I#De}2^?=lMrv;o|XlZ!ECZVbd6< zXAqQKk-fY_rVAd;Z=qLfTn*!6hwwe>xX^;W?f?O_fB?CX`>>nce0`je9~Qk_)bZ^> zeeVJ+pUotZ5F4<4hk0)7TEA^SwEjV}0rs=O;QtE0UPck(V+{#^s zP=D45pu&;3-m`eTpL0e|@)|l+uaF}!`*x9>JAUC_*fnU>{dG0 zU{QoI7N2>d@NgHQ_e-Hd02@+~20u9nxVy@J#DD|<1Dj3>c5d4!s>C$&-;U_2z=i|? z)JTrLnu!VY#sXX*Ep?Zr*MaP9V^GBCf1*baB+Ov_(4Y-N!Pl-99KzQ^jjUxN1<(UF zr!j(T2qK~-te&u~r>k^99jJX)Q+?nf)R#{Yj!-bshL$^YZRG55m*grd3de^}&LK0P zM_6-%Sl$wGGE3C&c!*E3?}B!rw}}V)Y`6XVIlwySoB3pDoq;4ER#YB`OlnX%TVCn^_mRIQ75-~rx}zF^k)fVITM zL?m-^ix`X-iR$>U0HTO$;I(Gj0Q&4yM0mZI{q`m~A24$SN6I$g8}y0y0Ygd5@J!J? z4iozUPWdBWgv@J49yp`1t0K%Pk{j^j5T{#u5z)IL+tf}?I;YYcWTIuiLv#sfgIq5L zicnn`@iE*g$^L$pJfuKG@8#>s>)^xC9oKL=`h>mNCsGmE;*Adg{P6piHo$-2gP zGSczD)`8&F_MDk`c72bK2oewAKtcj^%<#z-UQvtEkxJK1;h_uy9EM$HjHrU35@Orn z=c=LHZ~;}(@^Kj00>KK-W;kQgIdMGxlmXYEWg#%(syDmT2xMSZIA)JhzKo2GA&3W& zK*<%kfY}O6EWZ{h?S&0WdxziTG%Hs z4keXDOsMmMn!T!%K*RO(PG^X3hv-n4#-HsdBI+q8w8y(Vy++ zJ|y=Wm|8k`^X$%2x)U8*Ov3Z@n3(RUZz}JlpmayZYG!>L0?Bo%mH4$?z9VZ?6-=j0F6vQkIp2SjKMCRUXR!d zU6T=esI&jWAFAAWRvml^ZV3PYW3PCN$;e=gaMWzcqnSw@ob0y;4?t10G#9GbS+Wj5 z9*8ACdUd%24c$7LEF%1^mLvyr@aAi6;K%e{HFagb+&NN=+B{)ZEr11w8%s4{%F(Jy z#lzjG0QOq8T#&w8mA|Vgs(A+AHJr=qBd(S{zAcWUJ-yWTQOBVhszZ(LkDVtw!QF=i zXOq1a>3+9<`o4f4gg*R+7e{jFc&}%fd-AjSDtoxe58F9xvl&f}(-9MSCskdAi{Atv zoqz`D>5Q8qKf{*cyz-jY%8J!YEW;!VmOr4B+y0SD?>MNr|_{!QK{aV)QSlP0y z&u&Z2Hg)d*f)qWJ^eqR6Xyd{GFOJmGjA`bg$>{(WHL%iQ7oNxO{eyPWj0Re}1Jr&h zH{e(R0*&GcUkp#U&M+Ags#pLF<^uPJx4Wdk7*vBsU^l_}^fe*ssaN$bACyau!YJT+ z`zwWIq@;bPp)N}5{p6uMevG*8M(F*2RRG4P+GXF-Ic|a9K*lCH0MA(ZGkj_jn`j=( zzxya@ZGYQ_yn<6J%aiGrw{qc(0@y;Va2d*_>I@UzcVft?XCYNF-Wap!!vTOU6ElZZ zXeFK3XKFrFvm2rqE=+s8I6N@#{u}Hj3#5jSg`)OQp}PhI6j$}Kd8Hg$iL>-x;w)k| z+1|+w7Q%I|O&%-0Jv-!l&|2Lxai%Tsidr4x=a@sOmKD|((?U=~m@)I}83xd5{3vL( z95tP4U{xM%7-5SlXQrTDRt=oUSwJCCn@zkq>Xz|CA6I}xzVa~#Kb+7X49=I6+Cf&W z_r5Kp9U3+W@IVU~V@EO7iS-k}@0}nT%UHj_9-K($SC**Q6@HUnPHSQ*Wkp=kWk>m! zRxeO4##D!m6Jr) z1@Sy+*$=3DqgY*X7)uvlaD7d5py5}=5 zq}e^1kIpr5@O;UDSG*z}j;qsD@l17>2%ApwSL#Xhun~Qfk@SYyW{aZMJs;bEIwO=3 zVaDyFome|^vzOks5MvE%n8{P_yCE%3g|EOA)MTw{WW@o0GMHW&1Jnx}U)orq_AVht z1GtnEx8)wrr-ad|IE!w3I8$NLu&hzQZ32D&Mb&y-veb3wcWR!5J|6_95%k4-8lL~x zI{&3QAD$ZDerv0C@8ZxU8$jdfBV)~($BAC%;XmO!B!U-Ytg z33UBaA}GgRzAr(nU&N3lAE0H>bd-6V3AK1EqUt>_Z`dez z6Gv?j#h{)LNs-j~5s`u?ZDcEo-BDQxtK5sxXE8fjkPGbGW4pf5ih1~sL<^W)3o;S17?_@ zfHjGroI0s+5QAundDK$qu{m%JLAmk7z3(~D>Krg{^)av0x9^>=LhEvoS?@l@VeZnm zp%aZ+89j~$PB7(_jpHx_)mpzX9sg19W#*CNMS|~w#I^`z0tA-b(!86is+-2`1IYbd z^BH#WXO|F_iTs+GXE?Ny$MXuPGn`=HaGwOQYosrb&?|JdK-5L<4ln{X#`~UR&Y`}r zlgJrKwwJAKf^?szaBZj6krfCxu(f*1TJVTtSh*WE+F%8GcJ@{1u&#O!$ahsuP zoW9iS5uBugzUFF{Mb6lD^qavnA^K{*|LJL8`-Ve52(c}{XxqXl-f-qq zADA#S0Zz60RiANn6USOzrG)W-L?twzKp~X`1wWoHF)&?)f~XBa?!&Ee+mVcfQ$Xh? zw29r5_F-U243qbG*oy-r!2AZh;^P{nJ|JdSfD}9T5Viu7UaKpT!m}|0QBa@u6ouTI)F=EaSM@6$> zXjI)NNEcbE5$%50*1~vfZo)Gb-CgGB5c{)ev3%r38zzjN(O%LIJ_zrZ6=wNvNx4j6g4aVuY)8366?jMeu!i-MFNc6SrApLMugfl@YVv=D~ zW?(Qd7xm-%?6*tQJZ|yHP9F}QF&s1N6u7RX9JY93D<+;f)z`)CDHBvCMP5pe3I^W( z4}DmQ|C4iA_y1kQ`wdbBIJ&}auclcTA_ODY<>)9^{`->8&mJiNIiPTJ>spRLBO@D- z&V_$MK&PE{B?36;7W=B+T9idm<}LZlK*`^f+%DT<*205<;AF~AE~xptS@gQ8dwh5; z*|3B^5N&K8(VooxJPt1L_o;If7hMZ~$045#5>Z*t3(Tp%)b@C8%RKJd|KXj!t+woe zJ9tJqt#XS%p)ozv32Ry2@k`)ZJ6zu=fW<%q?By0^SM6422P z&Irso8J9S7ZvxHW{TI?|yQ1yXhiz8~=5*h-_XnEcPTVof3Tx*u1^h9_C%SYRTK93l z1W6wi)beNVf6ccqLCY4Hu3b6_f8X3QsC$cyM&kcMhAq3rCi?p-dn!z#^72evnq)Ca z*G6g>52VI!32DH^=oA!K%c1Tp-9Bk_Fs7cq*dc_M*qqbQ0jNG{IzXgj!*dMb@m_+L zD*#{x=Xx10^Ebkj+&nR-GXrzfAB_@jIx2~p;$}vRjFzIuSmaL&%&F9N5XKz*bW`<) z7Uhr1-uTkGz5L(`4@-~tuCwF6S*XJ&O;>9@aZ6panb>{tirPr4 zfZ%f9(kZ9>c^0k#E*AGo5gv(+>@9dtbOXaO@+Vraa)ir5B_T+Hr54~#ENe8f@DyO( zxRe`Wg8cmYD*+vV#71}-5HT#6+^B^3qO(o)_m6TGEu~2- z)3d);5AQPQ0jKcdyi)%=zo>xIsK&lxGCoY(%|(AUx_;2+RfY0oX8tg`KdYxG^A!U@ zP=LZFHW{uXc;B&e%+=y_i7_Zuw@+_xNzY)Jz*})#tJnn(-5%NNoz5noL6`m~CS;wg ziqtZx-d$QM0=b~i$Uab*bJ?+A3VohWeFeN+!S2ZskhRWSMv_M2L4AfmJwWU= zB#Mxv8^{I}BxrhCwBAVw8L2GxB_h+{y2_Rv8&k!5?r!5sE)50mf7&;t8+hc4!_g6n za!T^jnd$+miXY$|1|&4NyFe|oS}^gokoixe7UJ;eGvtzcg$*7{v1XdaLPutK|Ry5iJUVIxqlmz%FKcAy-`6Z4yxzbMw?-O*VF+839}zCy0vr zH~`_WN=( zK}Qa5We|K3^>y)wm=>4F=GIV}4B}Fj6l{wm&`0Ya20G!PbqSeuCM?~kM>E- z0p}E((4ex{fg{zT`+{dSi?(3t@#h{K^bpZ!4xfA(SsCGoXI*wBp6Iv|(=RDPYnzXP z$)W;B4`tx)W{-m9UXFCUkdlwd8Rh}IbNkf07FX?x?lqpNFr@!T=LcnC;~{JtwktsB zRbp1zE+*B10)GkkLVy4Of1r}EG`s-kU_n4GS-~ht$G`xFQ}GoU<_?c4J*{W4x?uob zfCp&jIOw3u?r2GB^i{!dne=suIUoXRg3PVqndEX+>BP_v~N_k7*^q0bv?LnsvHjjen)3~Cr10c?#%jdY$Z>5l(APIC!zwV z@-M#y3({U=F7)qy;MEz$$d5n;YH(BXM70}L=AfolJrS3EDOY|-mx((9ys>cQZa%$& znSiGWjP_bX0q-{_8Q~2Dk%|30OuUf_{Oa9(*f?W0 z>*g(2Vbpwj#>0x|h3#6oYJFsBna~U&%N3yF?H~a9jCKG3nncg-w9lqFLnvg6m01uw zpRzKf1nvy9AOhB>|DG6fJ*=e|R@IE?^3JLGmJ&oEM;&S6kE!pID*JjFLm#}ZvIx7q z9$|o7TKbKlJj`fUsx>~*=CroKeZb&+z5geXM0gcZi06>rdTmy4ee22GpUxhH1-Yni zcG>&dRkUVUR=sq^gb@7l(4J9v2=BYwdLB*8!CkhUYgE?))mXpgtdl^Y26JH&QXsR( z>&TEOA|=-sk`(-7u;kl{&STil_FWREse%BZ!K@{VaR&#OGdRp!iff3yk2}m8$$u)~ z^KE#lm1z%o9+06`2Rt-e@yyq=>ZuM3Bg;{JJafoWr0KC07%L>`0}9z@B1GygjF;+a z2+2nB7v8|Kce`FHJ06ODS(d>g5r|*x4j? zT=-(GCPi%q`B1GZ?^UlNPvr>)6k0DKGQ1l*Zk$h6f-&2YAX^7XginJ06X*d0An?a(M zY=5K)Hc7~AoKhtUGyiI4n%IFJNoBZei@8v$D8Q}=HdTNu!a4`nDn&?NDCCy_+eWp) zo=jTn&E>S>ulC6Vu0l#%O93VfXd>TZl9))(B<&&q7`?Lb1`aO(an#u%n>PRgiXHQg zqJhU%Ie=XT_GemyXQ8}@?;9|?1{>$?BR2o>saxR|8!9p7M+-?^NqKB0I;|Q}>=AgJ z4wBKSTAdX5^FvMvk=K1Udion=1BM9AvfBD8m|x?4d5jMO8ORHjcQjZ@hcdlX01EJQ z6FC?W00(>Wc+;$@XX*>y!2{Av%mj`l=9^prwX6n&bbBDM9 zdFF3xJe7E$?1N;w#I2xD5A>EgX@A+q|984;X%@qSoro}thQ>xu_!3_Iikl#U$>8E{ zs>L175Kv1)r>$Q?hEUF7r@f#Daow!xi@jpgR{IjZZV%|X$!d?{smV!}q;Af+_s+q3 z+{Iex)@9TszwOB60~v@x%poAlny(?VFK%;Vn^l9iReg<+;}l_l`Uct3zM((;tTdl2qz<@!i@+vUvu zf`R}SlRMi*`z2=JfDaK_DgE+U=|;KpELH7Hv>!Aei}i^F4JKx^-7^;4ge~Csbl!%^ z-Q$;X4+dQ{bs5+T!I3zn9ZV@~Bw4wvhE(9j{wkEs`YAhj_7lNE5moM4{Xc-Khrc8X z_X0bmW?f6vWwXz-q5^@6}e- zS0hcg(9Qg_qN8YrZCogoR~w3{#dZRNL@8_|{*{$K*L9ubPg5U5^GxMQ3-*wTXTcWR zgyzN*{EL1Pa5(^jYpwwWfTvXx0zjDQHLvveeX*5nKmz7(Jy5d9Ty7Y`Es5Y6%-pe5 zS`{u;TWf@CSwQP$q4qmr8j{$KzW_j=Fk`|>57W0vg7Qiyt(7?SqAp=zmyPbg{e3rW@C0A!9_FxhDs009?lL3WWU z6c`Dne6Glhj4`z2a^9xBVx-J7j@2p`XM2Me@krE*aU{ewq@vOWG4;eEHmkpg=pkGE z`p*7+;P<55#2~A>UQ!W+tYWLu8O)5GxFyvU!E3tQv)+t_9WETR4gj7Lvn#*8jGB}& zux_Ac&GnbO`>+tTPY*d*;fE0QjA`+)kT?P@VQX1z{20Horg+tt(+hmr94qHfM{fso zrMsmwpubzJRNNb*q!B9yqvH0}BG!|xw*?uY{2A9=z>b*yY$vL0bBo!`#IdbAd>F(* z4qbSP`)H-8X@M6gM`up;0Jzx(8V2enm`>}?Es+6ybH@MxU&=xt5Lvm|p2`-12a@Y> z{lnHJ23%;W(%&v?#w84oMA*Y?MkI@z&bO2y-WU>j`Djdp~IgQCz@99ug)SLqU03k_uE(#&wQY z#}m1Y?k1~hR06vG3abDc%+M^Zd*GYR)==MVzo`D~J`V+mEkcX+{hoi~0F8?9jjSEk z;nv`-ezWfS{!Pu2*}{g%SZcXK^a{ z)KKB1`(~f>!vb~pyW_vE0%lBy;khCX+3Eg8>(mEJdART~+`$3fP13x4#e4(~`~4m! zQcRX5(6|5_V2A$b{wOCW3l5qd)lXY6FRU}5008CymBI;U#Mspwk5w&X1FtHFIz&nn ztm+-#t{cL5(v}FKxdVju5omGq?Za0VQB*DouvjJ`9{MD)+P7sanU^2|EN#7jp+cXd zWPq8YTqHRSq~K+hT~zK#z2N^=_vh%vT8%R*kvjrJuc8@pr@rK)Hn{Qqx+E_b%nif~ z8=lAtu3b$iORPe_*1nVRb>1&vl_aY#P*nw{M~9Dc5uHW5axWv47!KUysU@?Pz5$Y1 zOl0$?)SL=1DKkdklWiP;*S^t*MF|pv2gR*aQ-L2y2x2Kew`A=hwirAXXvkeTKY2kh zV#mHH%ARB6>*IyuLjxHF7Y2by94_VjG1Ms`Hgs`h!E4guSjtd0c8B3rX92je=uISi zNuuyH>}q1^+l`#N(W}E>3L+^9vDHNVYpy?6RW>2E6832K9x(PeSCC4qFaQ8t=~36_ ze|V4lYpG;NR{!9P#1ML1o-`^BR>mt)T^wP^*l6oL%8zRouj%eI#|5w=NlNeeY>-h; zK~=-^CI7M`>ZMHdg_j3v!(VV_U(0UJ*wTHDysloxg@9DDkoy>CC)~-6@J|2G$`08# z2kubkvo3qsNFk;R&EsLfK9{lPIyW~=Ap^UYtbM+>$Q z=uJ%R$AHJbT}!%>ZflektmB%DMKvH0Wb}KSa5{~r4l^|-FJQD0MR@bP^;9!mFY zXaqI*KKF{ycPPNnEz}*%apFJ{YW&TD9HQU|VBolQ;=fr-z&+F?^57IQX{fa-$P2Sh z3bnR>2Ze zvj5VFyn~_H##|8*>0(Q3kRg%`ye2(y1L*qX-93@(_7j&o^pNabH1xfe0;LKkpTv?&3S<^zRx-&%6n1c z*Y0wc(~c*z+A_Pp!7jS-+(?dG%@3h;HyXS|^`2WWTfK`gP&32BMZ%HfJq64&(=WG8 zTcfg8dR0cbdLYXQ8?e|000&7JCX%}y^~8c0qN8e-CYw1Xa*i9tf^LN z9$$-K001YlY5<}qnJSW%W54euyCn%FGXOXBJ|Sg+PZkV4T(dSRdY}dR>?HFT6i0Ui z6al)k2d!e;%R!*LLA6yF1kkozNF`2j`Q(FKNFh$;v_{CMx6Ek;_WDO(JiNOIn28FwnJVQcf*M#y+Vl5Y^#23@!BY=A-|7=Pyd}ioe z#XkU~sP@H6pcHa#0UL+1>6W)EcGF|ps}>?|p|k-4Uan+r6?YsEl4@B)00zzwS50{1 ztv^++WG}b%r#6CEt=78#NgFFpQm?X;I%(LU01NIFal;U2Y`7Dua!n@1oLl8e&@wU( zXZ8a`xtt)&{A?#OaA=dh^tfo_L7r9h#ESSc|G^cX=4IK2og#ql7C zBSp_h^7*%r-%HM{eryk>@pj0(-VkV-Y3W5RbB$8R;tE3o^!B;E!{2@y&HFZPIp>xy zcaWO|(;ez-O_T2B=^i9=Yt{r|wc*KpV`zpqL(UXhbxbx$vhm}$wK z_s%Y#fbGXq3LiMzaNDG0FSu}R$zAN!tnT~k>X6zQtL=!d7(nIZPa>;M+x;a*qdm0r zA=Zj<#~~(&hM~6a9M4Ies+i^MX)Zje24=+6W&i{;)gHJ9y-n#UjbA0;L8`V1pH|XQE!1FpfD1J)^=Jmla{zN<2HFAC~D!v4L{-vT9`Z@ zYnX5|%UIkJ8bnb2dTH4magb4tY3jN!d2Thw9k9OuzDTxxzzkM;Xw~EW-J~6W&xZE$ z+V6<>#7=}VLat>dKJH)TPbw;*;I#&9I@?#uRj^EDF`p99Sw?;qyfxxYj*;|)gt^at zP7(F!QgLR9wbFnUt0WkXZ2>l|=?sGt_@oSnVYdUw=%KKz`0lw!_wp!{q30BTr(9dj zAe6HZ#sUH)5USZYXWQarwF*DFI0WzmKaAj`W>hJvkeQb<69fYYZxD8Y+jmZR@c-hqy!+(TNf)@DrraI_Uqe zSrvh|>7nTEwNGpS2vM0AH8;mz5JhvB)Z8F6nzMtchof>Cc6S=JcR9WUtwMi|^glsu z1Fm?r?Gp+_Y^kQfp=+js_-4i&Jv6HW?0~`R{YS=y6xDl#dvv7x;l7tfV@_K?X0Bv zy`{y|egivxvR}g-PgqVG!&0{y>NZOz8CbK9TjQJ@&xy2``y zS@F3Bk|PG^e#w*0X8!K7GOPUATV-enB2RrXg($N4*}4#BadMOf=~)n}4`U+5hu12L zYOj)9WDG#|;`a(kr~hn!LK6UC1$b}cq0{R;popx0l5`IHi4gkbqrBKbb8Ie$zzM5y z)-7_j0Rpv|F$)~MC84x_@u$BGOYdIu6(pyZ{mnC*b}a865OE_MEntV}HX4PP%@J1L zbk2-#HgLesDgmc17IFX-)+7VFoYdB)+X3>9&3#YAtU<|TQXIZ__jV6O8FX7XWFkpX zY#BKj^mUfYxK`Fks_)tp-hghjH8WCb4q+1RSI1z#6e-fgX`@t^Jk~y|W?`5QTDH19 z-N=8>t0!PgkvJ!hJ`Yt|t)_jlDFjXbJ2?IW4u#K2M?9^1!Ju$v?kiGl{Go*rfJs{r zC9IVZcc2(IhBY(=b)t4k^1FU5I(WfaY5{_H`oqmd&#WXKica5jT!2sj156pQAR30G zgHTGgk<%U@t-~&|MCOAKcoSxZSV>}w8Ep-nIisu4zMd&OEM;yDJ?@-=b~~6#rF|@ue^q& zG4owvZ;|_5fiT}4Be;NnVPB5S-u8{$6@u%?*Bg&(ToYvcYex6Z94gPVyXg8JK=E#G zO?HwF^qp~AdDKnTa~$IyL`_8#YpM>yl+KOGwwNUF1=x5B@ADcJxkjYs8_KpB%a;#j zjQS79%3*XtNnk*hr|nFA!=BsXWyB(Kd)1cp@e@9AptuqH!LilobZ9plNwI41LrN-B z8d&-X?Fk%8$3f_E(4`P4-000@Mki@}3ATN)(ULf*#Kw=y3I#vCLa2q>s{4=Ij z@Ko3qvtuvh{6JbxZS1T7q5!tG$E^&H)^$F%`mgHZnG_lGG20zMkGl1 ztNKZjF(2NNi6`TmoLcCoDb~CUX?jqDzcWeP(00bC85J!Q6dax^z|2E+0mD*lG|f6w zdI^iVm)RLCUa}lpEPV$^bt7)#JGEuo<3Y<`+{?M?W(X%46F>{oN{Q&lS;w@kenCf#(b@w25l$zmj7-R9CXQ|f(N%=p% znF@}_i%$=77q=TOm>0B$qB?uE`f;5Az-o}QfY*y8S8txmfd561QM^p2>^tO30bY8< z#{P9#jy#=e8h%o0?f)UeKbh#*I|=8I`!oK2=csV(nKLl_+X}W7F!a$ub)6u)-v9wD z^SC`ow9sjQPRYN@Mu4cvR<7GNUMzbN!MF@l{?3&$ACcm!iH7>Lf3>W|UQG?+w`Z=S zKhuq)e6$ABZ*u@bl48cKZ_Ig-`7TcJYG`Y}%*ia2EFWY9iAu97kWixJ5>{x~bD2vI zPseOdq4HvM5Hr7Oz`C8W!$Gn;3V;9r5%kc72`Gl#CR8t>##U z_?wDs81*f=hhNOV-x;!VT@OQIZ%#lk0AalgdVjjD?6Tnt5>=@^k4oT)DEC$$aT{Kn z!ti-O8Bfm|eVez={+kilnr=5S4*%?NZFgMLzVZ|Uj0s<5bARP#K#az_K_Cr2o^GF8 z8xneM@&}E;kh+X5M7z@9PA!88Ly)}1zZxX%FfmB)p+ZCG6GJx zQ3b)poQD|f2|3KV$p&;gMmKij>xLDAkj>ZuVWtD3 zvaZmAfBjt(a~0%~4g z^uPPD`zDmVD~T|$qQ`CABxT3KayPE+8PSrBKir2TR2#+0HQHo`!2@LRIq;aD<@1oq*TaEw#0w-k882F*&(t*9t=#W_e025jZ?3(OF z5hz9}>sp^C+(n(N{fxr8c{-D2ia<|>fjFvn;@2?%38{{cB-}Ip->{dO^D5ky@QJUb)%@P#w2!O#8eC+C;xyjE5ZLH7&@b;2lKyr-w|`*7I+`dXsZK6;0SxA zcgQ^TcpA_s(9`m1$zuAeZ_UT*i#W)N{RHtz-Sd%1{v{M-Be|oI8JSA^kVf&18m>50 zIsTw~M44A!)^q3-qo+Ez* z+jIH52};_!l`OQBwpd>qeb8 z4@`gn9V>YUF5N6@un~vcTgXkvf@PIyKNC$V4S+tkZp9EFC;<3W+`<%IiA8LE>g!jf zS%wD2)#B&2vHAKo%$>EC(iUlaUJ`7&asM_iFIKtIe|A_$3+Wb|E3MQJbqGd-Oc ze2(p;j0rsy*y0?j#SYnkF4Z*IAgIo8Og%_A0JAs2uyDofXajf z8BRDVaz-4(`dIQI{^&`v7%nj`2&)I=p%}+bnoEJ)1-TkaHcIP&B%8M3nQO$Su;>Vf zk|OG7;(Ps_g~S^^bs|{30ac@9MEvT8M!eJ|f?{+-+DRFx7Hkkic_Y5UrMwymX0WNM zNdR}a#ZfeH%^{tdaq=}35^y@wwh!*=nma&EN7Oq*z>(8TA?}s+e_Vbt1X$PLF2{V) z?h(DNzqN~}2#aQ`uzND4d|Y7L+fOtE&D^1a@@4-3)q2FdGeg0r_e8Priz$*Ssq$M} z!*+dtvaKtV5B*t-Eg*U3kGSR%JUi_K#aIN+fc`yT2H$>rowV&fY?~>vR7~mLt_oL1 z>qGu8yTkY&iahpO4Fv!7a$@cpcgt^M&G-j}(PmDkbOHz0$Fjib$p%?Ut27ZC0wF*c zf#LS>wXI@tqCV{9g{>J~%Jl}ngPp{p3IH{@Ws=s$qkEbcLOI=Mihws&o)`KEZE#I- z%~nAPvi{)kxi|t2rZqxnaUh*Xjg{^E;*GAG^qo;?etl{3+B^VUfFuoo40n)zmF`X$ zGvNzgKP2h;Xv{Rp#UcvY9RpAkx6Yv4D4Fc1-ux=~y{955x{xU`twXw(>qJmR&b0qK z{YbRPk-eJ1*mB=^G+rtsB`b1ZA-mWbH0TE*VkN0J<0M9O@9A%2>LlnMU{Y^2?HO4$ z^`Y|MMgiMAC}2L;72GCKPJ{|c{vtV4q)b7bk3?~54TQNClQgNbwkHN6sii|6CD|pN zW|QhUkkw)l;J_bH{&lE=dA+A~WnDn5KYI zOz7>;mt$I`UcY0W!tAiZaWV3|c#!_%r&#cXt!%&Hy-+PL&!cOl*EV7peGSC(r3XiU;w{uUOK5U%^ORm!$3N0RdJb6ijoqb zH~;_!zyVX}J?kg*oum;Rip}EoQO}zW0gR57fE8tDzR?42{KMN~2V3d`&GLk)V$}l; z(R`giEPzja3L?fvT{VUS5{qTNvDZ)rk0;|*Kz;xLW0|pKVc0ljil|)$AK?u)wQjEh z{7J;maCc2X@|^GmYq=h4JjX8bUB;4eC5u~Yi-dRlm4$NZd&Dw1?e@r&;M_ipbCoHV zl^rI`+?b)BxS`Q)J>mHIZMR~wTH~lJPyhf;;{*%4A+)tZ?$I6q%-PMQVF^aa3TOri zv|g6%kxzVM#d~pY*EWg6C)U5;a-aHe;-zQZ_n9_@p;RR4?7%*VnO+c`?$3%6F%fk8 zM%bFh7GB~h5w7|=3w68yRuT`F?$1|GAI@i7wGHTD2V{(mCt)OYyU&3<(|32Yt@gKt?jk zH5Rxhp|#<(bwu1!H8!Kj_~a?;s#at9eAbusv1YAp3_}0pEWS;ykOq9QnEt!8_~&qL z(xlj{6^_Fj4n88|S1^gENkEXC+7g4EQ@gFC>tpbCIv*=+}Pdj zU{e3KkY{JAqK!AoX<8?P5vrzm25^i)y|aB$1znb-^1zZb^aVZO;A9D(Q`CHmtX54&fP^O+t606#scZ+b3MnnfTk zpfkRy)dR^+76PUY;|5_-t7(|*ICPF=osMX3;YM10faZ*kZIB0v=Os@@gp*)Htxkf; zlIM*NjtS;k2DU~|imc08%0NIW*Sv#h8N|U!?1N&ofd-uQ8UTr8JYt9rF(cJQWzZW( zpa1|vzAq&J{Vwz)USziShbRvC002_A+(DB<+`i-Jydj!oFB7y|3MdV?$0U;d3DNan zH~;`B6*wH<^1Xe_Cvv7y*q*}?76x;5Chje*upII-Qb@Ce7+5T}H4bMi70_a^%#b67 zL9!oy9Gm3c@f(h(O|78W>TD#ZI<~(Pb)fugy=felb|Ruk18?e{vg&@i1QI-Q;ggDs`LMdX*oZ42`*)ki5S4J_^HDhh{w<|4ZkBKmr0<1BIr~snrkT5-aR=HvG{CLa7WUq zjV$RAX>u_lgjCKa1SU^$C?p7ZXg#?}%=3Jima3 z3$lbuts6zJAJ*q63=zfY-A+6})v+mI04xze42!}Pkl+?m|J4bAz9&!?fdKpNST>)C z!*?K3Aq+fENNSqlEVvaKuOcke9N(ac!goaC+6K;GtamnKi8PCXI!%-6=go>W)D`{T zkuY~Cp%jCFB2l%eKIy@zI3sF5r_%RwyROOL*gSYWUoW?3p$re@c?l-3;*zVZxTa(J z?+^;dif7e_8bVNqo)?2PLUq?cCf8Ow-jSO1%!b5XRr`)r0Bm1|ozJ^fJ48=PSl*0^ zh7!>OXK=~i2#;fZnW}pknUo{v0_XINlNMMsGy3Y13Qc)v_%8?mT>hx|9UCJnWt<3( zST6cNIe>nrTZ;=OZ%%;4MSpzFqIzIPSbhXT>(f2G4MGh!1mFZde-*7fHHrWL04VnS z4&DebPB@S!PEf%EPiJ~_93YJMTvWle3DLRwg3WX9o_Gu-6KZmetwapnumj75296!bwDu5D(AkEh0U%+iT#XMir>~ zj&@#L^6BwyJC``o%EIP7pXZ^lx|=cq8G`7!{&MAEap<9Q)Zgfg0rfLPOSl>HwR~)@ zUsduP@7Q|tL75cqLqrfvNBf^^7CSA_f0T+2%zOH@3`#*B8!fn_c4Oa0Pyly5I;t6u zltJ^9uP9)Mp7iy2AwiVUSRm%P^CugtUsk>l*7*sTZd1U04|u*d?Mu)~3<*?>rRczd zeXEW%imo}NuAmb=M}n~kE^OkO0045t2@^Xp)D)!uk7Pur!%tBxJ5N}WYq%!y25B3s@kv2_6^3qnxd)cEsCLqpMxM@Uh_d}S8iojAbm41?zWWE3nXLXRbGiYE&PQ1reM*7NjXetMf#}-- zJ7zu4EPO=x#!a@oPkKeTtqq2H8aoVZ!}(T%Er751P3V*Vq{II0b2_@x*Cp~1XYyFW zAU#t&e+X9gN|h)Q-HwG@U;9RZF_?aEuq(+#);n@22mrZI8`X=5Z(C#lYCx60iF>dB z00={CqOA+b;rB5me3NrnL9WNGSg}cv5)skGT||-5{4QmjTgsgdmnSoiBrdk?5Yv1C z3Z7*BsM5iyF^+{v+KUykHg#cM{z@oM`F96$_#o9y7;lRS{4?Bqdr!NQ(bnp3PeE)o z|6*Oo(Uky8SzQGY63f#T_mr(JV#*h6$y_l0}69aCHs2C|g#QXyhtI zWJ&=OO$BQ!xodBY`i)jo7aBF;X3PYXxQAGC$MzX?Q{FHfx8k{~)zUV{6iO{gt0&svmAXt08j%SxGFgAnj5Xqd{?2-ShA#<_P%BW|ZD#Cb$A5_vOZ}dL;>) z#W1t`OFyxWa?jxK7+BF=~m)J4Sz%x~EFSa*;tXJ|O5Rvvmoc zgBUOcpkmwiwI3p418zX_LLwh`MCSZNORipfCnMb=CJ%g4z-_vu3lm#j9C z%}oH|#v(uRyJ(5*5H?Yt6&imq7?+{d)Kr+R9Aw;*#)L7O0yR4<7PU5=IHe#boYIU< zx)Hc%RQ8RxJNU;!Tjrc6Zg=BW?+HB0EZ39zQ_B2aTX4#t*rmPvniED?+Sf)6m?2X= zhr&q87Fc~_>>C4i5(Hr7P(tR=tWP5paxsQEEPF7*s5>}sg?vXx%sx}6vRzM+!gr$D zqBBVw4%i^2v2L?5GmH_^)SA8(QXX%+4@rDbl4y6Hfabz`PX+6VeT#|Zs?05EGBln>012H4u(ivCixBMN zWEm$R>rwr9z}s3jZP@FFggQNLPbjt%APW$(Umi^alvL$Q@rY%{KqP<6X{AvXTF%rd z_72gXYvEW=mpH-|!#GIZRN$Bn^TL4ZETE=Kc5H! zYNB+mp!~Du3lX^K+}X+797_O}eWD{l+Zwl2_iN-^*Me~w0`@|rpQjHH;O2NM$rJzzs~Tjqg{_qsyp7iS-Rf=_E&b~OnwY?#fD5C2^b!Z* zG07%W+e?=~p^4|19Qdk@9RFEbxLMOpJR%m z`zW;;QY6IdYu9rBS2#6WC_vlO&Jk26;}ecsxE?c}6^FVLSWOEfya+$dM%lz*qPw-d z{2B++OEcGKxVpNZ-#vCTB%dVHj~QJ0hxw@NLitWM!$7LLLI^B8V|E4VX0e$0tQMH$(u(u-Ob6Rb zA<>p+Ey|<0E!m2U1aSE;!i(YQ#jD!j}Z#p^E!5-QZ=~0)y!n2|F3xqAk=SzL^MKL1^$dksP>ICfi zTiZQL#EI?^ZAh_NAO$k+YvpS2w}0w)ZPOhw!He<9@ga`k0b)vIK8e-j(cRI$-t11L z45kt4ShChzWiT5b$@P{JYe@PTMC@7R*RB>l4dFMUIpgrz(&6I@btmG1;n)JPk7@H{ zGW41LNdUTy;UHZj{cRu*TGDJQ-mGY4_?}J~@utbeLMPs6O-FZxY$xT?;;_Ip1kOSg zJAw+c7yb3g8joh%q%nr?ClHR34!Qbb_h{vX)eb1mqj1P`(#PA48Pl8yezcj zuO>aVdfjZ3|5$2$)dXic`Wc`$&DRe_m?e6?K!)QcG01LSQgG}PcD!C$>#34OY#Us9Y%bAgK=h!d+2s6iG{ZAB4?S-t9+A<$-4<24U{Un$XI7sxXpcFOz z9-RgI50ltH)G9bAeh_)Dq&4UElSg!_7XB}sj1nL$dQ``nB+ITdV5~AtUpx4~8afRI zbN##IWU078C=2NXx`!^iPou0QyU$7jf4lSJ21NgxwJR5w=G+gl<-wB*rsDZ8bKOEI z$LHe~@Y3ca`)BccEUDV8%U<2E8i;fMDWtKvUHk(ZfWH&hBn?8dTsPI(jU5&{JW$`M zS6%iX|S=Um3mr1w--A<&az?!6+ zF};4x=2Rd}62FFyE8ZDG6T{o|8#}s8RLjYv!THEwL(C{z_q@V69}jYk9<~JnDYP#a z{+B^};YUj^`WuPDg(%)PvA`{swEGZJ902H0jy@%Pa{VZL#ikPQgxm?(So*724`I%4 z4nR@VnpXUkvrD|VDy@uG3A^S&tvI0)OLYg}m;95j^K5k>_c>O`W$=N;g>mYq9oFh5 zyf7vb9@8vA*xSUJJT}AM$!wVoD}rPX%?Jx~vTq9=!+F_Fj!^!RxTGF%01DWcU#!7F zH+xI~06h0EZTmdhZ$a*P>w?{M1BT|gwkl(h`j3AD*QiAd-{jjt0ChkC8qYv~jR%?q zJWehg%e7`y-4lRVy70ij0~G@-5t~*1#n|~(a1Ul;13@m^^wjnmBs7EvCh6}*6f0#eoo=ebYj_q+)Nt5)c;aMl(JZXSQKKBlLPl%NFqm=^3k)CN}YXmU#)t1SJN z&Qtaoa172!6G4jv9O9J>t}Xxb-r}Zb3zdZhQsA=$jIkypWQD!fII8I@h3RB~;Ly+# z000XsmkrG@p86&OCY#td^R^d}`eTy0)=ZmkLz+e!qm;!;8Sd>Xw%R1OJL|oo+elLr zc7GyiUvW%|n9~u0gs=?Lo5|hx;!5nyPv^&;krSc6+$>xtR#n5WO_X>1rCI#d7!Rvw zrHbId127<5RYzV>bVX>G#T4hD-Iw-xXL{p5Xal6t#MMN3@iCZw8H-rUn0_R>cyI3) z;ZnURqF%^V>cw{*%kZS()s#7A(E~_6WEfy7$v_?E zD^7fHYwv<`oIMmp=Wxhz27ABOUkmYoW?xm4z05%dayM<7W+0Xyy~9m`H~~%oOLDqJ zh^0pqHNjEAV>ra%9BwQlXa$9$9kl=gIc#rx=U`b#7r1v(>lH1dj9c-|sz2x+l zlrU`<&Uks4u`eRj@M`)En^bRK*io=lS*&gp?@k<5og6xOQCMeC*U zh$f}!_;Qk`E~$ktdKa#l0A4C{_0>tp08%F#@Hq<*Gp*UVVk!r^s~oRITAPV&7AgK<;E1;LY3^sP&F;EVg7o7W;)0`@#v8rkb#m%CH`s zhW75rL~8>e#Q5f*2HG$nNXp11{~9nsU4T3`1Woa`JR9ey`aD{>MU6xO+=B~q5H@$f z!SEwYvyYY30N|cIvr;65?1H9J1YQYR_#~lm`o>Tg@AI-jeNq+!+*V|e=L&?nO$uiR zEqrozCgA)KP-yLU4%J6K8Q{k|l}t=KlmNEDLJ~oOAKQ4&wdvQ}kj`(B&}$hl>~)Dz zC$BOu=hr%Y<~itKW0iDUp}&yR=0QL}5KxC9>zU*y4pV^n=nTk`O7TBh*RR!N%hzm( zlyn#uCf(_72&;ut=-eJP`u}~UY#V7R`(k)i>BL_(23#weV=+K9g7NYS z4*WM&^Xv~$JO>by^6r`WF3uRJc%IcfuCGX?FPqV!YWgdKEYnB;p9)39^{m#?ow7X3 zTLHk=+2=s`>oJ8FNN!sWLr_D;P1X*kfU|Y?#b#u(91UpRc$fr zI%%rJM$ru@Xre+i+NHGgS3S1mgEDqnEa)K(YDr)Fe16htpUg`6VDyA?%Y(m!`P=m2 zA2mUX5$`cTtp>0lmgh31_B+x#d_=W83~{g@z?VvgfWn!=0IPrn)kF>bE&lyDu2!E* zd~lo#QH$5LFmLiu$%@W^000W8i4Kv<32KC!D%~tYxvGdNd#7qW4c}nNk*oV8=a@W| z|KGg`xmd>$t&6o!^oV`xDUJ1wCeeuou8IJoV&;O=L}eb(fDQl-=qsMCn-|Kdxd6kQ zid56Uz1wB@Oj&A^Fm&n^^Y?~;R)mSnvbubRrrE|n!@ZcFO+-C})CGzxs`{|=y-nO9 z*rL~8oduogjQdS6^f%{1?G=-u>YEcu-I3npsl3tE7krsm zBBTc_Q0q%FgC7?0>s%0-rI%&V9SWeb)2vCu-zgiy$yE{;6__Pf zYkYVtWG?x5Sf>lio;tbm8H^9zA%r2%j)8Bl^!4&m_h1-o{(pi%0gu9sJ6!+;d`8GC z1ps1BPh5d{om>cR#Jw;=n4FBSqD@tUSN6*&lIrJ?7CX4+Ctv`?YASJ9a9~2_(6Yy6 zZr8j^%oJli9`J*8i5b)F3G=~Tlz;cI!kVYowsgT`nVf|uyLV!(RwwGbm^Y!OKEFQ& zv%<=IdJCUx-Qu1uXA6ZKx8e1`E*KhN{Y$zVkrN@N9N;Rp(ZUk$Yv5HHmx~{j@I)KW zg8R}W3*gMFx$tDXk@fxLoINDi>U(H5Yb7yjQ0|t|0XYEl1j*E%5S7Fb_7y`~_e3W& zdMhh%hQQR>OOhV!?#c<9f1PJ1KZiBFlbS++qvA_&>kd=zD`)@=)QkY_i=#9MD}2_a zFc|J=^z+OTb;fd{r8%9n*Er!;1Y?x-@MNm&m}>Z0tea~HnM}$KpV>1;Ld!Q=bTVzy z)7n-xgQ+_l0d0j0->x8&BT&O3tY*nV8i`?b2e0u^U4jTnemj)70y4y3!^NxVDsMy+ zzBj8LX*XseqoRGUqJ+=W7x=*N@BxVOU!THLxuqTMZq7d3EA7i*GR4O<+p{vVCT?Uf zZ_xaSQAN=bNE98iEe4hHSeBn`W)eMIf@kJ(`;9B%NuTKNdB7m2I>Y z&7_|MhmLntQ#-UT926ubu*BHwcj9B@#4dC@DrFi|H@5Kyd+cDBySzF4`4sMTNcfIg zTPPvXfg;pXkoW8e}vx%!JU=i1(GjvuO#njx008t-Hg~c-f=%cp#=y-I*bOHs)+&3%6N>)D138dS zZUg^*Lyj=F2XwTK;q{ElD8la`CcTWn@et~cV)Q=&o^etEYq{7!xoVyTQ|N66`hGkS7^?Y z&=wLocdhNJRc$nZUT*vX8DSHY#}vRwNd^?uZ$dVp?1LWM+PDk0nmvw*7tMTEpOCGQ z! z00B@CL8~2r7%>`WYYQb5NuIi_(s}_j{J%c(NtujV!g9nR#d1t_E&DVFaFh)SL;^O- z^toX|hbq+Xcsd8L}fFgAkpwa08q-_LM{WlZbCPq$Sf3{{xdV5xtx!k}qV#10E|So3WM zw1MH9%j(^nH*Q01wy~s(EH~N(s&s=gumCC6dO|sOpBG~{cB}%^f7DxAhwCo(ipwD% zE%xKbjs7xn8o$3Dn+n5Pu>v9eY19tIxlem4n_ELzpQ5Ix_RNSj2Yn1?y@Ovq+rWxa zVZx~4V!I1i`>}2_>@R@S!HYcWE?zOtjCuk%W5F7;+y)1VilPqq7E<^H)s%UP^xCU+ zyopn$Hf3$^Q;@6s0+Gve3b3n0>h zJm+|PZja)Ly%j{Y9mk7t-293EU*=Y+d~H(yRaq2XCk4;XHpC0)`E~FJugX)0 z4en_yp$MUaoPqt|da{?kHfY%#?7E6oV25uu$IILLXjJbJoH>`CW@@~_8?dK1?-lgH zmS8UW)lTg#!?w+EMbD3?9cH(pQMJx5nqHV`AsZ92gew)rP{nTnjxh~C2x$W;M-E#- zE=LmKVMy$$<9SMxHb*x{kkxCw`q(TCE1-;G{9(QOOHg7uadtA6rrv>^cv4^v_i_yS z(a@8<$~w(sRmWpxNGXf8*l7?{v$)Rj<^T_N`6;h;;bymJh~?NT4I4g(Iq^V zh8@fvfj7lHX@Bzd#W!~UEdRr_XAxVYR`UTjeROD8Cba;t;O}lzi(uwrMzK==;LaPv z*S=cQ*tOwCtwusX9wtPFW-*=Z;10Qyag*tXdpo*SPX^Q%pv2AB$=AUtB(G|3FF0dJ zvjAdwI}!WSCDd(|sfHE2UH5oz!}fE7zX^S}VBWQt_)@4=biw_`9rGwFcAuKX$X-0T ze8xs$ALol|V}?v#l0>uZk>Reb|5Z~<^qP1#9S$7Pyc9$M{ix&*wO%z^;&y63u-&AuChkk1A;RV6fX#S#h8JU7{DLI6F{Q~NaO(RK6t2{VcB2p1)*WyI~ zN33=Etzr}75D-y;y3XS~b3nl-HUvfnXXkdYy4{zH5#I056ZYvCLD5vvZYKt&45G%1 z9$3{!!`55gNTe9}Y>5p8Tdzw#{Jb(iKjsouCwhQT-ho+^S3lK=zi}iTG-a=ru8L>U zK~QdD;4N-NA;21xKV7-HHW?`(Kw}H8zB#?^$?)i)oyP)}LLQ-PWA{^=HOqi{`;u%S zHjMT$u2&Q$QRec#JOymQ_p42unVpS6ClEGM&< z=Mn{*Yp+>{>j`GDwOYWR(w7XHHj;gX3j>=Rx`N!q;PgRAwW2eY0mhrW>2UCyCLk+5 zdV>&&C%~XuVv>dErE}&n2o&}<9(=GJXB}pe&ZHt%u_|m@{*KXx>aSCknXguQjrsyIe)jSJp{xkZb4sCd$(fFw62 zE$55^;DqXnd#EGbs&E z62#q{ns>Vx?c!MSP)#*uP;q=`Ks7qdB98h>%}n#Er4`1hZT2BCuWi=6A=KNc@c$xM=KR-GP6d6mn9>CcLSCEI=P8Hp{d(6nl|$u3U{(vdC;- zuID%sX22^jtHpy-8bTaL6cI5CmDwI72wkbBdMC#1rwiuEbgcL z(!P*^og=q!>|VGm+xZ|BCLR}%t;(o7@F~oO-G4-aZV;PRMBQz-j+g%6?tSD-S-~a#y+quIq7BU9T`=JSyzxPXjLl~A7C}E@B z{6Eg1ISj;GxUp)2^WG`zpaKc{3Rj35BAAzo6>KmXu+Ho>zHy~wnLNO6TY8MWaLO^_b|DC1{qb$Krv6VIlqq$2SjyMq$crBBr&D1E{CzI8; zd&7R&64`U?0jguf<*3Kd{d7*t^qi0h%QM=9*R7#LtyJ7y9@@SZ3UVHTGfWGAd_!I*bKQt+N=E2mvr{mVm;KXrfopm9@H^(u{Xdmu#hZn|0^#3#zkcpr1+f$D~1q z5Dty4N(L%oAm_>Rq>w}Z%QPXZba43*uAys=nVAfC=(guCt&N}RdBfMi?+ewoG}Kr5 zwxw-)T?H-gQ(A_lLu4<1{hqGYOUR5s4*j@SBkScra9IzW^d@uwj5T;!vu5vk$~9w$ zD+q*Q&2!l_!KIhQcb#v^pV~B)`rta#RJqtc!2<#i5`I7tVvGaeSkKJ2HVhP;CPa3O6p3ys$olf0ssd z>GAztwC;sm$hv44fq7bcf|Zl!=IW3{G)Nf-rX`VnOKWu%9T~4CMc2Y3^fSp&e-6|AOHXW z0iXg+Azsh`0S))oN2=H7U)<)?esBnNwT|!9jRCFm++D}pJpv9O=`US+RM9yiU7w2jB?lqQ#IFrqP-5iXoUclD0UA90oy-< zp1NE8CYNqi2zYCCE(*KOKqc^Ig{dH`0tPUg1C#!e-Xb6SOhS0-(G4>YCZ2S-)R7E} zmU6hQ)@>~tcKk6~BMeI(-*Ri$brQ|wNVLh;gDASes-Z1InZfBQ-=%garIGljwOR!i zENt;HFnVu>1cYLN-Y$CPUxpQz^|s`HRl?L^LXn1gjF7*$lTwIv+n}xe_s33Y5xsMT z-zBUhP|5~+Si%3S^dq7HTuTQXzRUhvyax-&fE@u|1^ZI#o*On7GifMaxh~$z=^l_g z{5utgtqW&vS;|l}?efrtnYh>x`yl>)_0*}2&IF|eDR$90=q{Un>=x0ceWuV6Dl?FVNH>utL=B=clis^3i0wwY=@IZ_ux zftsG{*~HK#GLgwivdpH*+Y;iUJt7M8NemAuwwqudwn@WW4ibey*ON*tUI)`*c3?A~ zOAiphgOP$M9Yr5gUToL*DWMy30a_)Gtp~S&_VCsMn_DgH2ALy$a;`4_Y>W^f@!vTG zdA?Y!BBJ-uwI`Fpu@yeGoPy72TI1nLm8)S9aqNuX97SiDYPE2uk6&c*&m_7Yrn1=8 zMev)$4dNEloMCd1M(fL)?Flwrfj@veVL@5CIASPv1I;et&DMMLEVv|Vn~D5dLKU6+ z-LnEFMP%I+@Bj@WE?lq5pl}(Pr1gCUTfao&9|ca~!^`$bU~ZMiuYK(W04Q)12Zkjf z0ENw1VUYb>rv#nP03(2wUs$qShF!<`aL@mvE*8nts!w0x&?v1F^lS_*0r^aj$I6XCaH9Qi+h`%8?%4Ybzb>r z=h67%@`6~XQoDE9pr3Bm0%UnopjFa`Y2z@i;Fq1B>MVvg&ygI9MHY{SgR%Qy1C8(# zZRl_d5G8cUa{2`EmARE2Wc-eANSwDIorNvi)(AjyV}BV&&ERo^NwWNTh}Gg!OHG z@NN1J1m`>)u;8fGa5gK-p26oYIZ<>*RlQ0l>TwVPuso*|f+h)JjsnH){{9Y*pUq<1 z-qd`n*rYpQM6*=`*G5PZ1Ny47qEfro^yt$$`KHiz30lZd57+I$^k)}xyy@k=RR`AtS`h%}P;6@bA%nJ;}>&qF?h51E68vJ}jmkWis z+2e(nR>G;!5m9v=Q{;`uw}N0+c|&ZWF*X>-VFWn&NHAP!<49J39OJYsInL&^1u>9W*)6f}#lIQU$O)VbXdFSN~L@8$!2%|X(}8iD{i+f$^_ zcEICOZbhcAmOPeL0h%Kxo23<6dPvn9IJ-&<{ZpGuTMqsa6Y`sOtlW^uG}_!E_Z=-P zC1w#0JylsAhX);=6%O>7MLG^|m2nO1G-Dh@WpuHd)S4kxaUI0~mA#SC&l7gf`WgXc zjzbrSX>whczA?qL^nFt{(gn3lR0F)^5$+X@Si|ifjNW+k#+)s`uhzAA`v0y`WkaP4HZ4fwTF_G z$G`t9gdFe#XPtrZ4j+f9=7k)4NgIkm4(;Jo2zm|OfsXznqC-CCXTw7e*F?ySP1`;Z z0DAUou2s#7e;RhqjsFGE%h&&Ed(9QImVUF@q*9TNIeR#GdulsfjJhD+@xigL!<&AR zOJ;92vu&&2zV+D|3Tj5Bum=>X`_pIknwoR|;{0fF0FA*9)m2+&8|GVw4_uzf7oHfY z!O|jbTUd>jk66EnQ6VRiQ$@AD-Ys~&S&0V_l{>Ty>}0WA9h@)1j(4hYIpl{xIT0753IvBERHCVV=mcf}fscrxQ!qiNZY^mskZIZCb= zOfh20eEKXfYdx5H1SzI}U);mJg)WN|0wcpI6TqAC7{E5FxYl~EbW)d_XaGnanhcZB z`CPZ?f5WxWM?tdkrug)dkg--0;Bj?&M&g*C_zn~zntsUxAX3lAaTU~%rON5WuC>L zmsUwQLy*)^@NyvY4bVaymX~;(#+z}H!m7jynmIK;>(pL$b+T|nS1ahsv~jO^12x&9 ziH8WXUq%9P3B3q{d$165Me|KHSo-DWROtVMKLlMT>;4!qY0!&v9 z%912VL!mF(XTXtzu_yrfqooTtjZlogGZlbkOq8~IdS%b_{uohP7>eYy|`j+YI zV?H$tTbYj4Up%HvtSq%80-}?;S~;em;)V5mdNT< z+I+=u@B_Y&&+c1+`o6ij1HlsiE5CpU9i zwvDrnlfk(rT!^eOp}VmQ+?o}(Fw#0fa38saT)0I4CZd$@taq4nP#B!I*;jqG=mkf# z$PHv+5MG`ZbKTG5PJE0Ml|C<1g4a2U4EPrEo{%!%NRmM(!F?VLWUs%N@pPzS4h16>G7Xy>^G-3Z_~I6OgDl>tp{8fTQ)VH` zNXf?~6z>E&DW!SAhkCw}W+_J?H@%|dN_RoVP5Tgv{;F&@oVJD8mS_SWVXn0#(x%~F z>O*uZlRROD)D@>ThfLYskdaY>IeAP|m6xsk(Ls1p?*=E<8Q9C>QV0Z+;S(@wL&72y zwK@s9=yvXv=OE&4k~r=K1SSI5K*moOA>K1DrWG;5Uq?({|Krt&I2csnppv9%tX>Z( zxz(@q>K&+J-X}7BGq||WJ)ebnL?{S(6L4ic7pEeTX~K5+sM9N}EZA-2^ zKfAfTveski7ptFu)RH~Q>%Q8b5O!~g4E~FUe3XA2kI<$WQP|F|wpbRpcUo7|dJ7qs z+F+OnO*Dw@%nxdOPyqh`R5JFHdOv(?g{F{vP0~r8f!7fd;0pD*OMABW0u>6ZY%!xv zS7Kc-QDgrEmj%entpvSPJdC0sP_hc@$`JW5Zo0i=#S0Oy5l9GcaiW4uze_Z%+#Pdj zdtt?N%wx~Htj(GN_lrC2M zW{+O4F~MH;0fVr}6xtdbJMP4cX$aDATM!7L-JMY*9MDyQ%&l_Q_cxfMNUyEg5gG!X zpeLeDX-iA^U1w?cTv&h_6xIbEwMqVcOIBxL?w`eyX=Kt-uA}^3e@|YyP~{#ZT8;vF zd_;`epYhD#S>fZxXRx@yDc)OV=m3xz1uip+5(CnzeOga8pMh-I83*4YI$`MW2QM>~Rlpv$(jc<wnxY+av z9z@|1!g$Wg^+y&H1F{h~EA9@Z`Xocr5q3)I0pYrT+~b6jaTurrc%5Z5H_RYZ;JLoW zvC-GM_Kj^sO>fhyTE>WH%RzwbZj479g+|fRDpX?5)TPX8!6Xx1X+1$`&{)(}0y|B{ z%}$(wXQF(_+X2R)V=XnCKcXDApNWU@A4j|p_vM=W*9LR#($6{I<=OBU-NJBI;HtIB z4({4)zs=hDGe4DXw-LJQg9fS1w$dNBBVnh|_XG|Kz44ik@jF{h*Jj}{r7FkWK-jH_ z9F)h^K_mg%W&i-?!Y>6-A9hoPuE(>2!h0Dg`23D8-_DLb=n{U;5Xq+2Bm={hT^Jml zYd@`%1e#@Gs|QYk){@T;-{jf5ke&PWoQ?t6Q;cAGRH z#A|WO#nJl+P$<|4pKVe=P*f z?XS&zq=sahjZZ2vX-*9?TwD=fM9jj_pp8+Owb(1M^=_63E$!JT2uT#N<5?Y0GVdv0 z(;sbiWiFH<8t6e+M$O(6khUhC@8W!VZnYEHC5qAFG}9{ap4REvtKUnM0lTp5qntsO zCdb*`Or`=)n%J820${HrSJ#t*U~l2VW%R6~1Y$t(&W#uR-HS4$MAD9*h>`E2@A8s` zV=-nK6dJdJR{E>R?<&-9QkZfE_ideUV$-QTGP0D5oFK{)2lf0*f6{fL6%;&Z!x#Cu z!v3g|x{VWMJWfzC9ZN|k`{5=APkz0F{-k+`+Tj0;G>Syqb30-UJ&A!xaAUNU9^{Io zASeq1c6ynsD@HyH|LA)IpLA2vdvQ$5DN?Wv>;49;>F*t?id+{-M^>FBR;Hpbm&5!b zzZAj5%8_dz;(_pR^f2F2DM3%fL9_};09nhv*FIt{z_0A>wi zs8A|as)MwbabP3`%>4i^fRZo)wpZ|zG$+TtTXpns7LOz<ygzWLK zg884sUduWss0O(Cvw>ZyYUpiSufc-&)05V3)llA|{FCEj(Q4g*mX_JOgl}Lwjg#O5 z(8x%BAKunv!ErpNFFJQOH_O+)q;_8qw(mP?D(T1D3KCLv5LaOeT^|ySEi)3L>;M9q(bynG7q#3{PGA%ZIAZEjM9^Xp^H(+ShT*Xw7Lw1bf~e}SRPN2tL6&uw z^?GZUonf;c#sU{-r=P9%lIJoh<0dGZTah3~_~04NpbdjXkeqKwaFW72mFoFdIlYt1lY zv%1aD`HzI2vzp#pVq`_P4z=Ya`d5Lx2`Oygra|E-3r|TVWc+_^bV{KRpwPYMDwHdQ z#@Y5N62Ew-YL?H7X6_;&(p7s~rb^9yO>dh8SizTk27E;H_i_1wQ~lSuG&iIV#^D8( z5I=FsmL$I$Av#9ShIi=4;Zw6Qvl$KYp|} zG3B|Tr>+em^)QlnHGDyjztEO}bzbI_Dgx<8ngjL=@L%PwWAUoZs>-o!;|JivK{_}% zpWgq;w*!`VTjXsVkea$nTmzaRhL<1&O9xpsxtTfU`e zn{hp(BQ7BDJ9-0B&DbQ*jyAVIBtaDoBVohs_r={?YqS;j^pD_DlRU}kqU_;b zu7auL;gXV#LIhHbjGd0WF#^pll;L{Ed&Q01qEx zPv2Few|CNQ2RlB|jGrbm6TvB;35@~bU2GzYPqMf6g7lXYB{Cg7$k(o`iZkA&s?AdU z4IWK@eX?%#xS6rn`Rrf2w{=_t#{y$(qwyJfiLcZn(c+ASrJv6H;gMF0YnNe>ahnYm-eh&;)^880xppdT)cMWm`?_*v>ytE%{opK3)v$U>enDfpxY2mL~8CvXoXmE8o>GMO4P$RmJ}{cL#wXAm0-6%KQrqX zI&euSR<8()Uj;9|r(*i4qT-0qpNc}XcAOO8;9dsX9+Bf~(u3F)8nsZ18F1?1KE{oO zz?%(0De%5!KgtaQsv+uYag+jG?{RUxOpRDNEVLy`wL0Je{)>aku7W?|60Dv{TuBcA zRMik3YRgwsUfgdM0O&6v(zbb+Il3uY{l-1$)kY~)=;ubG%)y$XblL{5bL1P=>=6Ah zArt^XK)%1;AGQFb%NX`L24%R%XcM{4qVh&&EeUsCd4l(6%!XqM%fXP2ymaA0_IT+K z3d+EF7lK~URHHgwq0qf3(~l&P5W+z#jWH zfm&JzP>I5p5taU~8(;^-$nI4ca7I}td`l)uqVgafnikzs($_-00m3pH2roGot)A_oXZ2I3-~b&2<1YKNmNT;ua#JOMcwnvG^Nk3>Gy05`(?R zGrBzBd_)otJmPU8(ukGs6l?mSREoo$%^;h8N|5{@=O62Ud}WG@4sX73nWxPS3Q07rifQ2(G(Z4 zyl=1K`1lzqu*AQ)QOYEbi0}{xANU5z1VN~6E9kUG1=3+tl_u+H=4bCVa<%_(Yir<+ zE>9Un?d&iM#{PB#okB`kb!6q7;$`>yTHm^LC@`I-Y4OE|RWa^^tz;t>z-vL9=qItc zE0=}r#%ZF4)59mmnbtf$?Y#X=E8yW@)_{E zcztQFC`#{kH5T7;gJsqF{`F*y-t5jgQ$DX!`#tVjUA;Jal6|$+OV2s7&G<)Kf7zd2 zx}s$I9h1Hyo;ehPeyax`;CWyRvnf+AAKbsV_wzHH-O!K78JyQKYBC{CPM0?dYkoZX zlAyexU^GNMN$%tC*S{8CmSS0C$^!sgO7>ws#a4W2bFtIp6@(%BJ)qTgStbO z7lhM0E(M;nqMx%A2%YZ-f_@i*hVPr)x;nS`Z9YOkT9h~kgV+#p6-ey$*)$f=)qh(p zu{%)o4?mbs2fAksDcc|Oe<~C30jO2!xWtVpSP$={CaZ@m6Lcv~PTU-%Pfs+85*kRI znx}U19W?JozbHa&)l7j`R+ClkkBR(`1X)_*H)evBe><=)?1rkUAyXhrNiz#R6l=O2 zdNDVjJNKJgtKIJg8;AS@7hMA{CSo%K*DFj=e%4805N@31iJo}2x!#PZzl~`?$9)Lj z7k5JfA}p}4Km`sL5X)gi3!0e1!y^?tQynDh-x`pW)QJui+`YWw_zq}4_WDuo=A{){ zJOw7B=E$O@HC@3(IcyxIS!_5H6(1NPet1k!B|()5j4Ao#RMyL z295oNi(+!uD{Dm&R`LN1gcXE$NVPK|*fGxdxnqQqhxo}#U)o+1u{MuYBx%6lpG6lbfxw}elZ zy~3N?#^9nvUcK_gE5e#JsH}sa&>RYNM285Ds6fzFttjjWab%a68+?L{4AK>k4z%pA zr~mP(N%l3!w#|Z$p@w}ZW@(5v<@R<0S-}^JAsDbv(k7?>^)Ay1z{Vn~f91O;O0RGj z@?Q3GVT!Wf4giD=P>EXmG+f}cMyS!V-uT-$a5L5VvQ)+SJmDp6usNmh5MVngx#n-F zKiUWYjc*w=V6Ciys?LL0TDy@e%RNBBJ0vO(94jb}S|!p>Hy z>>qa5kct?`+nqLeX3L6H_}mwh32p0VO{BC2$4z|?#HXg8sb$}r?TH3@@Zet9ow55f zY+Nwo{LoPKo6)-|6T!}`HXg!Dyw{)A{Y#bCQdQ^Vu_%L_K5QrMZ?RDOK)lK$>I!6S z>){JpJ(9UtNT8859X&>-G-NtZjkEb`avm|j09(*eM96RoZ_k_c0pXJvF|C*coZHmZ zF3)yHmwauxwy(-@p}RBL<3BQxD@vB3Tiwv1TwiZ|8Ojy?$XfJch;Pc08-e>Rbo~~~ z_w<_}^)J>!uPM6IUZcd1XDjp3kylopb3VQ09S3K$MMQ{a;t@}#+|k(CyoK!Zsfu!F z4oSb{;nAI@{jZjaKVH3zjNeG=^vFz!*k(W8^$9OD`O?Ly1nJ`(73(JCp;7$?N$Pkp zv*)Dg>N3vyaF6;5Q+Kns01$3Aoy1Sq!zq=PlA;JhrxJ-mry^g6P%u`<&O;wtq>Ymu zb>j&%vm_Asp?FZPyvd|fk0Lm(95l1kMg1FXI5E`%u;II!)3F9)u>h6{xfZee7xz;K z73~{=;xw~Iy=;$KwF%ZV9UzJ;FuRNir1h>i*$c&CH>8NQt85uXLu_QjUEUS*>%5*& z+;Wv~GcM}t4a^=h3M&S43pN!nJuKsAH%df!(Gw*uHpgA5XnX{y4+-s0^;X6aTc=e6 z*ZORCob6DN1wr+Hc;a?F}#1OUf|@qxj6LdZb+M z4EEUOgvOhUNqv{-_Nh0zih_(aMRx#!zKI_y<^2RY5M!86Bi5CEFhnuYOn8*|K0OUr zsZXzigEfTzeYTB0lnZH4mC#T*L`{o;TpAGOvgL<2OT2hh<5{G|$RfR0xOt-#c{Pi^ zE``4c?P$9f4nR?vpe`BDxDRTTx*o`)S)3~GyTeB!wvgHx$^p0&Ii%%^FXk1coU14` zc4B`lHt0pM#A^1DSOo*z4a}qiaYHpmQ(~AQHfYV_QY|5-CBIllr zl`pPWfO0@u3v4mnwCFeQ1f}XCdP1LEJt0N$KGsp-38FAXZ=h zyZq`r)z_cFR?)kmy#L3XOI^!R9;LpJs+=W;S**EkvSJI&;O0PYR5R*gFX`!xZGJXK zPIMw{e2ZFDW4?&Fk+l?6K)YzuEUhSDYQt`;5<|3fIq9XQ)!;6;vfNA4@g?2jraFF_ zWt<_{M1=?C`{25_$Z2Y$6!Ew!^UWGjVa#c(q+i}coxd_C_4)d+j9}`EF(0OxT^-uZ z8iq%uw)a(sSE_}TI)kpQ4GCg#V3JcynGr9V$fNG~-4L^`&kd*PrgQJq>M`gDW;!t4 zO@(&tA2s};vLxdwZ0xR-GJF%|yZ4=P>0$*2?BsY;DXU=vDQ*2Fg2ratJw>*eoPt|l22?lIU@zn44(@KpwNkhgX_>Ge<2Oc=MsM|!a#*MIJ2^WJ1 zE@vaw`Cu~yW>iS|s}I|1y6f99$V9~pL4z0fRx0sJVp*Z3OX^JWChYBnWYUYMw>yWx zU$wte#p8c~>ZaIq;MOjj}1O*`hw04bkC3V}&DsP_?vzq`t*b`?}V zc2@1|-Q334yuROZyh(R?%V(}=&OLlHPAx`AHy5%y%T8OzCb8CT8#$KKE-Q}O0ooSi ze=Fn=D?Viio|F+o+EIm-o{qUA-`bM->-SL)1M%p00q2Xi}t+1Wnq#O8^hHA zg7p~3-FnXtt;y7_8Ow>xtCjhgQH!z^4~p(`_=F=oMW%D}|KeD{kSJf@z;WHgFuT(w zd>+qQ@ZCN_dl%otEh8lxPh|N$oi@@EAVxsmD&~NSDoa@a%ZYY%-Z8Bx@LN|00&ndXQmX&sxX#h@b56v4gdHr+@~P~jrY^j} zy8a+U33Go0|6Om1JMBoR_EPPZQ?t;w6ynAMJIG?7_O8n}#5&z0T2vgKUc^J8`y9wq zd$-AF3_Kb;eVj|sf#kcD+A{b1mkj)!lr^;OL&wz~Uu}?8|M{GyZSZ-|w{Tncp$dGB z`jGk?m*`L)Fm+9T4($p}<8UceoB#57FV>k-xWFhVoZ^x)PBT0*!QI9KRZA0X*^j6_4v8ykD(na zIWxN#HGa|F5kK~BGo7KM@@3ir*n86FdjtOgD zl4n?h;}WhjV~Z?ZE?};eEKk6kc{M*#rgba=3}G*I8S{KF@D`a{*}nk8fU^cRc%#A- z4gu1*CAL==@GL!k_5m|}`u)4Yuy0oU{S8mmAqaGE{Qcy0Q;pwzyR>p=>DZpS+S?^3 zmX=x@C^Hdg_#BaZ~N)qf)Zlujk zduLJ1b~C%-)PCRJJa8~d^4t>c)U%2mEIy^K=~ZL*S4!=c*P=6y{_QxI+HLRKt6>+F z$Ph5nYJW&FO9@xk)i7LXlxV{q5VwIego0QKZyU((P(6XX6#`^uo#K}Fb8NmxaEQ%p zRQofdm>&58?*ym3{85iOHy+u8LtAB6Ew|(kO51%nG_(a6zr`@qDO(iDI@Fbr*PG53 zt(g#W-=`Tf$ndIZIIbhA;{TI7?8QdsptB%%fnbLJC57}jTq-LSp3TreLNJI?b z<)(|uoPk8-Gh(QS)$cQ7HR?4%;o<~Z4kuorjh?a&GwBT?MAcFeU^AN&&97IAK4Cd% zzT!@zX#C`6rJVpI;<%uv#a?mX%$~{Y-CG??71~)#0kgDmDWez{4qbN8LOY*W?8X5b+bOT3svg*kJ;moaF38{w${6NE}zNQ+9JAxwdC2ofV(jo zd6H5rn`J&JxJeAkT~i_-FUQK#B@6H}^6SGduZZ0ijDUrQft3V0%x=#dLcqfLPma-F z)K@HjbYfWjm?zwCzri1422nOrV08p#HBUcTb;FI6zp@|GZRj-}1%b&8E_v1-O%xJ_lBgOnI2he=?qD}E}U3L7(2n;gq2*$EA(aWSeuX87AmPBW>g zPn$p8y3e?pxG40aQ|$mG2xX9-SBq%KmNq)rmD~zNrnd;v2~#F_2)(s@tcyM(!}UPD zeYV7PKorac+WDt2QVL)*n$?+ZLDUePd~UAutf_lX@Z`8(f?gU%lr|v?iojD52ollW zN65UJqtNYVl>1yidBk72IBQFRK{7wq+U;Sd;=I`tki*@*G4BeRl*?o55MRY4a}IED9`^K1U! z1XSb&K#0i96llSFgIiSs6R^DJU~g6&)-Cr_Sb|K$VwaW(4*TiGJ(Rl`rs=CYk);Bk zWpsp5fHC9P^5<#3i@kpjdAF}$qeNxu)Ra2iJuJb-E6(pw!L5MDC3-Z~#~bEhw~p&H zPqhF$dhcrau>uP>zB2U;n!}F1dyDmG#Juz7rj-TOM?fo0ZnH1dC-+?VXqb0xl6f$g zO!r8p-hRN2KGM^43gxad7{tG~%ixd%>q3cXMuJ{nk1wPMgB7Yulgi+z#jeUI2uX+m zZI3dp7!gpVa956;c^@maJ|AmIxpp<9hz{x%+&hcSe_XYPRFBq5F+ZN1T*lvJhoE!e zr)+FkhdUC}BF;vi_&C~#oE88vEF6IkAd6fJm)Y2R9Gk#+TFezL3Ue<$*VB?|r2Rc- zJSWxoc}e}sFC;&fbd&^9Gkh%v2{^458FIo2KPAlQiW~$V#JY4D(*%=XvdJ{&90NnS z`cAJIbj>6;e+TPksvfEg)$PyxO6XQ!Z+OU(G6*1Cr`LBk^C^Thu|fVyD&dDBy&n5Z zpO!4=1NIH z@}x2ZaRuqE<8blpI;LH97B_-l9;}Ox-6mFtNXnN0%~9y!JE`YXq**gsfjJqn%iV#( z_JFL_2hBsAlc5zTLzGv1BD$ygd2M!gKSI%+vv{^x={d}0S;V08~W^8(gM zrJo8&Qtq_+3s-Rygxh}vfA6OUck2R$0>wve2jKYjUlZq5{#gF z6IM5pI}@Qp?DACnwy)8lCO~+y6w{k9P&Q;{knrOpdjUB+E*{~g~? z3^(6DV0Gx)?nk}v!Ew-espCYOX_K%yZm$Cx3ooWB6z#X-{ovcbkI^@t7~!%-#Gt^1 z|RQ7)dq}{}?31Rp_`rp4!E1QsGNCN^ zQ9BTY{#9JV*pX)A8MOA)6!Hp*KQYMKACw4S?bpG{JmioY5S!~gmS0-0mqjZkK=Ele+G6=PPBurqyh}2W*m9@-oM?O$Z2E3}F

*5Y@}sU1v> z8-jT-V${UXTzBbCK^5F{jRTcjn^q|2V_o?%v&07|uP0V!I!pSc3I?)cLN=W+B48{0 z^+7)6kQf&lZQQ;FwlaQw+}3FjIz$lrPvZ>1ts5Du^kn$r^CD`d^xMPZGa}rU!2%Q- zvSg%cr$00q?U+rYm1C}{U#Ci*ZhS|rsLT<93o=r%fG5p!dCQx@SX$BecPwPNPqf}~ z3no&mpMd~s*Oq@;B%I{t&m@y(QDi%k3IisiF+el4_vI!o`R*&lb4GO=IpZ%o<$L*R zA6R|RE3tO5Zfc&ai`L}Sk?`>9lh$ZeG)X`ZthG*Frd!5wE|p%D?xBu(GjxLB2K?CC zdR?s<#kUs$D#trTtz;omTX8rIc6@X#Kp1Y$2`dN!!-3~o`LEI&#M-$nyi4zDuTDizBNcXd9sE#_X3NUb7Hkj}uF9+l}0*)Q;0MS{; zla}p>h)YEdL}@WAS-rRB>&z1pyd33lt~j=PgDPZSUVgxsBQ`EXU6ifB=uFXoGlq`T zexg)-bWmgrtnJ(l(gGL6V`-W_&lCTQe;D#RP@cIDl|`0S^-)j_lJ3GteWp%9Na3}2 zdyWufw9^4u1C3-N$c?amhlS?=XT3?{0Z?N{N?bXS`>`lb|2{}f!fCSAQ<`65Ude12 zV%*DCDuTI`b?1AQWRl0$F}Xc;X-Wt!8%Pg1{R|?*`>&5Z7fO(OY5vg(@uLuy@s?t* z0Sd#l07Tx_NdaAkXEPW6PH(l1d!U*p1ubpqe6;00s-)<#GuxL5tEm72gL)d6< z$7bpfb+EW5re7Tg9j?^MtJO zhP#WIo|*PDw-x<8Ufi)2mSN4U!nFEgWkv~%0ygTF+tRb`vUa%QFe zMuo}S`zT7e@kzF8N22kB)0Ma-HXegL(G~=H+9(V>d;yY&C65skJ@Q_p{QWbwkx-8M zxrx9XK8>vGq;e-KBQK~#rMT<#nz7!nfZ5RLb)4TW-^=bW)|!9Fe|SUkp|Rroj)w7Z z@7c)OZEA0F!IE)yV9Y;&aHu+Kpp#kE=-HOL`EEF`lt8@_Cl#t?e;rIUJ~P{0Vt_|vcnXZ{vqp8((-2`ON2c>il{e-h4!`%3X0ZqCc`+_nqnAQS?2ZWS*DJ!zFA|06Rt~yfNWG+-Dx>%B9pmF1U+3AfH-NZ$QxN3t6 z`|BKv!`&#h$$=Cn;s|I-u?}@fbYKqI1Dj4`2%2p&-;K_9tzCF<&GnVRP!kAMCHP_K zow9w*rVk6nB$Hg7>NwjS;H-zRdn-qPT?tVIV(=FFYsG(_0>@2X)^F}OP0t`2P5?2U zVa##L`GvN95AVZ>(@a3J{3fGjt}VV0+-fPhz~FiXfBtA^68x9xk9jL#Z+(jvZr!T;xLq;Kq~dph3bmE^RO8#`>d?S7`+Z13 ztFm>QFKxTVQ24uV20pYCKvW0z;s~Y6eE3<+M9u8Ce&~T|>OQu7A;JDF*Hw#2`!_$B zZxX-*a?uJ;(z|C`a|;nSklTt=e0WNh98+NWfKZ?Vjgg2ez!+ADZ`T**6B))6k+Ec( zPz`?PqIdop?B*ls%s+cRpepA0f9_0fN1n$MB-=ry?Gh)rr3<~p_~_IV2>iuqR8+bv zL4!ZMR}bk&(l!e;_0ulCkIRbi^FEFmaT;M=xa}P{k0aBqjjB}tlwnmEsP8Lxj7=WR za>8E;S7g4S7hKY7BM{22Igx<0Gv-S4gvj-(Q*`Ew1sj2K$bKdp@pG$_NX<$8+Lm@a zXNSPSQS5(fP)w7l41x4(21a6XPiPE%eYpZR#=6ds7(DsjCKlB@x+<@SI z;9DhBBrry(^us3!yLpyPJ`27JS&`J3Z~jdWg|Jo9NfaMW<;&{y0URwCaf~}iGKFKZ z&ZOXI_G7hlz^)p#wXdH z{Wjj+ctNiY<)4m2$`Z<;|9ktqq~ zXmFpC?2cILV}yhzFU#irlGvowe7pZ{yFVeG)bAKKo!s^S6tus;YJ|=*3jU8rK?5+S zMDmd@aVBAvb--Qs0-!G9BRRyVBJy8D5M)|sPkf+5<^1lIP9DDRoZMRIv(;;P|0Rf% zE}FRQ?QGbX9743sk7FFl%5~PuXn3d+%Y=S; z{~u}#ZK7<~@`=oLV&&~>{qyZtTpSUF$4nNR>bvi2nw~UmSNf zno;>QqYp~$sqHxGC#~XSo2qd1Wwj6hxn+%&*_tQ@I}Fhe%E-8o)l;w&JsH~9t?K|* z1$xIPn`#?`>TSpRy&(QN$*{3X>d<_WUTH2l8K#_I0PhC6R@F6{_pO}}s7qit@^A#o zerYzEzSyC3X9`y~Iygz@Kk3>$QQ(14qAe~FVzmW$w%3^+ewO~<0)sjLQIGpYAfkn4 zlF>Mi(-uHeSGGYU;P9|g=iIc&X9UI7LKK)d9_%IBZ(UCw zLt|gq%c5W#dn0_iH&-n}?#SPZ(dxT6Ig~I1&x%pdj&_>$1H;Emnbhn+uQZst8kXI> zS(at?L{lYYm@LGf{V&-agS3iA*8)27v%c3{ewvN7DVI?(BBHI2{}*6tO#^(S(xm9& zF957qYK&dpxrgqj|1nBkPX_2Q_C8T8W&Oi+gaxl$akbm>czXOELs0m7O$h_9ocT zXEC-mND0EQ((rUw@KCKkGj?7-k#meP)kP9&bFc zbTaOoEMG28WvS-{C`)^@Ms{y~cw;m-f35%~w!schQ4B{8EMX^YTPHa{;2(0MD5xO$ z_!~q5@^EgCavS_A0-8Th{W1`)k$kw~NG&3L!99*d#c%0(O>mDC%D;{Qpfej+yr(}W zDVChlqC4D-d>>=qiZ&EEjc!+&XGEl~G_$7AFD1m!hFWJTkn)n=LYfZk`Vh5_kipRJ z#FV^dwx~Os@}yjEMLgK(YVA%F{+aMN+kM{?Ru+ahp4i_UFtf=J~s^|q?p25rlP%7aXS4N8xxz283=grW`xJcX9L~Qal%us@wSf;=3Pk$ zm7O|>uWv*)2KbwhcdK(~YUcb??TXBw5NTe7TDnbl0o@E#wf5c8aalt&zi|`-RteMd zunt~cv1nAR8A}s_g{`ZNF#&$P)VUrsea43nNV*&zook}<&G?r!!<0c0V>B2}a&wq2 z3!Z^DWgdV+4T&ksDJ63*7Y%G_f8%6JSZo2eX}T#}bC$^jVG)IPR2|plzL)>maj>0T zodQI;=kh15e*`#ntvc_AFWW6Zp~B<~zJtx_!bhggqixRdGIYfxV;O;KbD)wr6K#n+N2Mt`NVQR)wQCY zw^s39(D6=WM17m90_yl;R<|I;KFH*|)w)|34|jgsIiK2 z#zyqu4E%!Vxo@l^R~{|Xb19LNGxwF4Ncr(P-o$)0EONp^+61^(F|ezh<+Da-8zB^n zLP>|~9kf*lTQs3nhIrKBD^0qH1++%1x^07AWG`nEzqa zEtcOwZt+s1&yF>YekMG@n6{2Orzz}UbmzSAl}3>|m;e90A6XguF8i22RxdPI0E2bG zzD1)FuIjOKB*N6K4z&3!H!lCJF?qhL1; ze@AK0CRLmntT!EOTY+CFv$rmbuhqtQej8w!%xwI9a-UNccVlwi%m!RqdR7mxk^NOETkFoClk{*NpFl5n*LHwOwfAd=buz zN!^w7a=ROz64m6%Fb1@-h738I>WqK09!D^*SfjOq>%2jBB5|$meY~_=j)Y4EDwe=r z*Fv$Q96)A4aMshOtm&w7svsvH{LJkpAb6tt^aJB*o_xmN-bc}6J~GYGt*n?x)VS-= z?JE;tzOk5N-0IeeLal$QU$<{pm#UQuW0GxGvWj9J>BSKeyy3NIODS#$W-l95@3=g6 z0m8OD%R80JfUA^70n)1B_FHdHnly4j{nZ)T9y)JE#MTQ4jOIz=QRCkZAbRDw5eC6f z>s)}Y^h&Nygg4SiHp1KI>lJ&9p@#Lc2&R-7{PObrz(}mA74pK^2z)u;dcFDl|L^3F z)=D{pq;ryP!uLEPfEGG}FFhaGHk0*UYmRwrLElJMlvK)A7K6bpMgMqwNkBSQp5;+8 zo9#alvz-qI>v2#N;)$PtvQL^pXrX|MHpyX7uEbvme;?`(GMMtxXyt-f4)a*J%q5c& z+c|To%Y48U)rCiu5_$B}Up{#{62?wj0p1H68P+LLB(YbBjELZcKb3&|zEPL`5wUvRn}zEq0X2CjRzllkcyaRFBICELmRn2qVZP4f60cUl zfr*YV=c$&N=#A|FHOxG38bwd~1}u3#nNv+-sFheFg(%;?^@;6Bo9b$rvp!yk^kNo` zC;oyv653`4nKW1Y;MpL2WCtKU*`-e$=PE}m3e*v%2rc=PC4~Uz5uiqn)9(i!7yf`> zUNZi%(|(SVBWirmn|{e*Fh>;OkhV`;Q8osKh*QiyM0HqWSVbZ9Bv&(aGs@cBkK8Jj z>=M&Tr({kRYXEI-Kl0y09<}D;LSFjikgI$3xn<>iz1dF{?bDI`)>o85>C9@ZQc-fY zD@SCNw_K52kq8W?I57msRBw+ZUMEsoAyUBqz-Lr-M|?F z{lM??u}vSc0#tbzDH8%AP9QC=y|;+R>^BKM@x;SdkrJ!Un8lMA$cH@+f)jceZ?#jq zdqEz9S(T|BouE-_T$GICm_0JzYq42>eEb6;4#K4-V9=Iv&Fd1Vo@shK^9EZ|xs75< z1g3}{QU=f32Z`q1U)WFs3_oC(vw~O$)i~<*EcV{VT%dRZKbQ+BrFeBee-=O+nE0f8 zZwKjRp?(*Zs{UcrN9>^Z5k(aQ<$O?|ch@M^H9U*An!L|?G0E(L;vkEp;D`QAFsX14 zl12Od&{tml=YUS+&$zZ<-Es7OggNVJW;)~zg~d~_8kfRREaxy$*hu*Xs&X2=ULbx0Y?d9CO z6R5)WM3W5PbAhS&7_q7OO{3Wx+v8p>{piG#Mw6&{@7>1V#k(X9ka!+&&rClU+H<;K z*Z85QDtd@D{^EuyInDD~iF((Q^jZ)Tp?eX`WKx5Iyz)Ci>zAp%zY>&M6Tp;mvl8kha~p)J5yCFcR1cOG3CIWX7w|T9WM7=^@z?tS&B@gG~PD$&0KwyN-MfN zac~POJ7ne07=7({LaV+1hl>PV;Ye#k zycW5(P607oZgLLjQ8jgf&@3`!B)Rv-9xR_)7sXJWK4RBx=q!B9C5Pqd5ahX9_dy_i zv1infKzM;s&CsuuO>;j*dpvSU(DV#2q`i|j2(8!lD~swwO_h=-s2uPn+pGQ|b*4`Y zOL;vE>%(>AiSsCp^mb-XZMn_Fe~ll1&;U<<@1RYf!Pw2#m%n@Q+Il}0{+InFH(Qgs zyB|aom5;UXg$Igv33tCI?DH7+6 zOBN++)SK3By+Y79CEAaFo^hkE*h7(|L$^)#rYew&2Hxz)R04&8v998lDupT#`XMW^ z4w1{ERWH1dG-5qqY-Fh&^BfYM5tP=PRLr*YB3adpAtbzRJPH41<@ga-D89k9okkMqq zT54m&_M<7qTuhk$WY~HGV}=c>V?V-kZ4oJpE~uA323olH>I+~Nvwfqngr&4zcY-~F z{Skk3_2RvJk*A@U|25?)tJ^P3I)jwj^i%WI&f<3wq9>T2n{z@48FgXu$uBS(Zl)z{ zRpUMc-lHfV)1=~jih=lki9I$*=!#h2jUd>teLr_SX}Zh70WcvbZ*2c8*KY?qFInB6 z-d=7Y$u7V*QU9^FCdl{(cw@MYTve*zeF`J6#pk)ks5K*VOhhg{7OH|mgz^Nx;t=hU zBm`(3+6f;u;Q%CyxTtXusVptp>fAcQ!biL;K8cYX=mTEAV3~ZCo228jmq9L_4S{SW z8#aaxQM#*w8lom1C+C356vxCL%13J#sd)+QFcVw0HY_Av`6S2=p0KMLAcXT~%`Co={@DBbWl@&muspISx;vQ*UIl+e`d`mg{Ad?x;%amtW~P6D?+R4Af~KVd~1A z7|w3G#9x)=jdw|TNMIzum)rV8Yz?_c(_r#|%*9T3u4pqx9DExJkd^e1_2AhNiBk!x z;(W@v38)jn1}U~J1D9h4f8@rn9oYDmgFuojb?ii*Yr2VMQZqBq zhX{2hO1~tWZuZFHaEF4jKr7P>G9#Km(X3J-oS8>VX~tT~LYv4tLL7vml%3^nfWvl}0vzfTcuT!j_x7-i3TQ7HYW1 z;vbg#sigYd6gFD_l0ZCrhlcXat@$r6^vd;2dm7tSjw4a)fHRUg*>9}jKFsZQnNmuT z1*$DTN)Fb>l#%d?he5+%=H>`zhKZXLO%?y!in;3$3Ah1Av=_EKV3VKW-^Job;|E#; z!Miz%GByGPyk-T0S*|NtKCp1*ll=Sgb&KVcHHxM`Y_eCoW%!~C=~BuEm%s0H*Le27 z$m3r#MoHPs27QJs4hpU_$k|vB+{KW1QZN`AEd#%+pA=K7)&u7Zj(E7}*CL#jH#5Dt z4DswwiUT`eVwt}7G1(|DsAtw!l;zN_r5xWph+-RC{%m`D*x*KfgQy!P71El$iNVQG z1CFE>PuF8i7wT$HE=O`+pGn}~To}HBwKV`rWS${$CR4D&7Hz;6_0+%#==0EYJ5=;X z(u<*6ylCoRhxU}(fM_tIz^fryGZMI|s&7Hy^1i#dafZX`yj0yDVlFj(%n>TjtH#jR z{zZSH-}HQ_x&ij+Vrh;QGrWMOYXqi+SYM9mX|^}pqAZOr5Fzb0(#i#pWGzM8-YZ2O zx1|fp!rxuz$de5jtmDI-Tp%)2+O=RUO{h?QX>9PEM!&=-guHRE<_HU}+eGKBJlLBErL=+$4L61V%E)(>}U`eVG_BDu*@H?BRd?Q$jRv>})oaa-27@4o?Mr zLmachtRvAZh4-GwAy@ax?%4LdQkmKUFsoZJ>@YMY+U)}67E4+lEjsT_y_ERAvUdi^ zON14z8)X*Y#8sAAM6#yo%(ak+%r|he&AzPQl+b7&Qluf*(Tr~MR+665r_Aq=-PtQT3@7*SrMP)_LOFJO-S5f|-Fi$vodo=$ zyA{m4$oaI~lv}n+HJX$3g9+N%2P=o9B>J@9+vPX{aUVO%Kz8i9qlF|GdT(1{)dt{Q z-buTwusi%s-@s!fsXwk00yJ!po>4jCZT>vf$ijD7;*Cn)a|+qSwhK0N)?}I^KJ`HH zEOQ=rwf!%$Rcj(YB5XYKC;$ltOy+Fd*x?j*r3y}4L{(ZS4Wr3!w0yKZ+p>53tWY%+ z16GEfMrzuw$^vPWTWn2Zqx&aZUtKiEhIbLE3;XeCnOB4T#D=Dpf6O*Q7d5$e3ZLs>rysfmJHRAB7PIa!e==RlwMN0i{o_%+NU_DF+QB zq)y;Yw5}>S!>zE~TqYgc-}}Wam01fV9;B<>qXZvrqx|_m0%IKnKozC9*dI6-!{FoI zoq|V9MleP6W*R8hm0&#BQ))a5AN|$eNWow8K`*&5{DBwG?H%zLN{&NnWPY6fyO#MQmw=L1&QQR-$p+WR zQe^nn#lsyz%Ao#z3YCkqwYN%Iq@C50~HP0+XH0@Vkl&@ehI6g6y(l<=cC-Z{av}Q z+=7>u`CKRDZfoiR-7vdukEcGc;nu7RG~g0hVTOqebXApYYzt9t_uuWcmP*Ol{_Dsl z7TicNGpw{%*tQqH+iM3A56Q2e)uR-@j7~E3zfs)K>fU| zFA-YwwhmA|#EpE!Mfa=`Glz*MVJecBz#%N#u76NNfXtP(kibN>^$CLPxbjq@h41i}vh_Dj<=Z>>{37I z@jn9mad+g5w;w5yK1cqwZEHLt1Z{3#r2IsFk!~<|56QslejiW-SWc6dUkU&`+@!&f zW6~4BA4{MTEZQO{{21s7A_w8aTTP#cJ2RaVgzma4^~gt&Y(>~MZp0aZFW&yl<&P%A zS?{hV=P8zeEQEPXj3(!r9&u0EK;dyHV43i#KNwIRsrk{)K;$b}=zlisF4(g&q+WDD zoFOTfgz_y3k(}zOXnYYNY?(f;;QMYXHW{L4Y)mPtIkXjN5h@dQw>GVg5)dh?;D?l1ds?a zz%A*(UI1{E)8T6)(O^B}`5ueFGDXm5>xEFJB*P<8$r;xN%uCs!49z5>7hLoq8Eopz z0FE|z_D%kd^-has+3t;%zLRZDzAl&ZkD@o#RceRRONkzi0zhfJ<{A#FbDSV@l)-z2 zIW9Sj43AMAcZ3-0qyu4y!#MgLgE1=UVXfn3VbEfs2YK1Tkj1ng(YvTu!k`Mx73Y31 z5+p6z=LLYClzI z)mdNT#X6p6^-YQi0r!!UC3tQ3)mvF7f$qEpBzl?s-Wh;I3(@mma3SlM#6+ZNxhzh7 zQ0r7hOyxZKqLD_QM7t15VP>xYCD0^jl#ct=F6cMy0Vn^q*P?N8^)7QV1x@PFSCcld z+L9RVzwZZLX+B;wJ+;zHaF1wqp8G8o2xRh&GD02!2Hof}aY<@b1>v|%>e!0jWa32> zF<5!Qyi2N!#R#rX@H5LH@~cE!l<(vD@H^5o1s~L|nAeWFjXBTJ%S3*YTw!fWsr|)U z;{Mo|Xw!LZevO6OAYl0&pA`I~xJL;tRq6+(BY8@_+s1wIhjMO&|`f$r5;}NdHq_xtD)BeR}3TundI+`yhg{kOZLH z&^;FL{2YiR-CyQ<;xj42u_l9xMsLg@WCgiQ$b*D7A9LIF zRdO+q7(JS=;@SKA21x6W$A|b+C-L|neL4%{sW?xPiYx=uz-0%RZfioxBZ>xjZHOl(1GBxtCOQs6PZP?k7_Lx=RRuG+`4`CXAQw$JeHcD7n1DK zT6P->=I5>ivR(K?%~X;~W3`$*0hJsEzk1lomZN1(GNBf@mTeK@xKOagAbtw^Q)#KU z765er^VoNxt4~Dq+b?{1&TivY5};uR9ZLqld#+l-qq*5kxM7dsu-{2@|6Kqm27C`D zrgOM=O7g&7KB8dn1w64~WKNdrmPO@ay8)YrUhfE}4NCfn=;NfVtw`&|m2wi19 zbiQbE6LH~R7;leGE6)K#1vg#rfZiBy6^8O)Tsh+-5ijdRb&7X@|16f$qCzxXN(q=? z=9p?+a#%>H%Z%FeV7Uh#5q@%&u?;>sM(gSJFDB5BBC9mI^!Qb80CX|4lTbX}+I$(t z0_g#Zo>!*tzOaf@?7ggKYZpX5K^X@pm>n29~MtWBmG zql^?lWESUk8F?GOu9%P7!G-3$N70 z(R@~Ms3c;EP>7i2KdSPW9waCdhG!<{25~M6nbizl9G0l3MJR_mO}at|$g<1Pj-UBf z?~nvMIjtKy5ytDz%}OqG5(;!_OuG}&K!dD)9ZCz}t`LyrHWxCW z=GW~}J75K>mK~HIRjNxppZJS;ox72+f`V}C#!Gpl3|0_?JOtj9bBt*!#t5U_fntOEWm-lwN=!K(iFwyZ)a-AALz*-j5Rm+Gu!6GnXs8CJ)Tc%IhX z0Z4-HOa=j{`Gk@IAuCBZF@mam{Yb z$F9Uk@tP}vl5OEYVMEr$aOcz57~>|+`m5QBe;Q->g&E9xHf&{2D>0>jH+IjSwAV05 z+s)-z1xgO}p`3*rp!o@;_>lEB);8v~oZFf8cq(iu^eZX!D8WHR=?e|$3tgr!q)Lw#3{m(P799aO@IYBJ7c3w`MBN(obG zgjPQA?A0A^#rm6)Z__4acdsd~A*+mZt2ZysC5dhq^QRfW(}qKoXd zOQCD|p5z@3TrN5g11A6`JZR#gKH{#ejX$IW)MG?m{M!9MGfW@J#z<=$UcbboN?m>M z?FI6k2edES40;<0c%J)-Di1uqDt?oqGv%IDy={n^J3sL`dDt;ALh4kUMLDd|UY}<= zl-%dvv&mHHj<9y&5Gplq5d+FZ>9)YPuO9Q^ro#4!aA&y_4DQxSWWLXrIASDtjTPVB zFI*NggD~CV(zlNr#oO6nLlTQE7gbKGrT31XSFDbWTcIn;OPJN`M-*Stbza4Vn0Ayc zdsZ%!kJ5WI+)`L})Qu@jU@iW33V5Nru6hy#izY**>}h6yDHvw_2C_HG-`6iq8t$28yAjPPnL=lx&c*fBykStRdjGwFPE(1-a z123j@!x1j;9ThG$m2mAKjE;;;5v5~B&d6Qj6 z=vA)$DlNBQ@8_Uewx2)?tv2M#1EZe%Y1d1=6kZ+MBhks7v!lNGBNM>Z;Q!O4NI7TRI`oNxHE_3>=x}xrLoi_3rHGBYT^pw5YqgKu zj zNqAWFHXOnx@m|`heD?u2!$rTdz9w#$#q0CbeNBc<(2o7|G6_h6o2)O(dPz3^qK|?k zMS&+I3V1Ihf>){q5aeRd(%nnbbuXtoBoleZjcj$OQ-;qljNxt8c^$_a2l;zYPmQjBtxK!Op2c#ocFPPJ}=(1PJjC?)rF5v z(QwHy2Q^o!yKzSr|Q@|oiLj0MdUm&wdi7w!_`dDi&m&dgpL|DI=V1%4`86s=5j5hBwr z$bOzwhJmj=3d7Yc*;HAc@F%^SdA5kO1sWFlN6 zyXIvA{Q__i8eM zgXvl>a}2u#lXyLzCurzW^!&=1ynY($HAmaZ&?A(e1jEJTfDQky@j5+~?=Dfl1g3SX z%vi=3Nea!ISii?WkP8~HQm6b&u8PG|Tr3%F-`wH$>GCMftfq#92g@o3RO{^{zFc6n zl~mx`COp62U8;DV|O2i((?z5 zfUHn_fWIXkwA_S)vC>$dP~B zk?bAzT*rxr!eL@?5@u~KD&+IcDh##O5-n21TXHK_sa+}lMQVj0L~W~)M}m_v3?x!P zT)P&bRaek6B%~#67u375^t7J+3o>~6kKmigNY(`HRLXoSp!R29M?Zor-JDsP`I*Vt zeB0aLvD8F9C?t*1(P;gz8;zKI^ii?wUI1<>gjs5)5hUF=wwv2?F1KLz@DM?aW=K(uYvX{3DN{A<~ zTyjq>?ANBP42|GY3RZfae19Lwoe0kie|_Tn3O>j7l&2oqJbEqa^e=7?C z{m&UCg&C_~rcWAT^KU-tDGS9jTCS-X8`^Fi1PWr@Sbd8Kz8Mh7LWyUo3VWcX|xVQr>%q|Me znO_VdXSBt#TsL$}a#G+cn%WK9S*Pel|Jnwe>~*|4wc4jgC4Fj2l&k^gWHkhEn)5_tn{>rXmF)$>rZ9s5ANh}_d}Jh;%0ErDpfG5GWt z#@L>5X*z{8a;$H5xr~E}vkVMoA6iq&uF)_;6-GKAB(VY*xXs{@AO2gS#n9KQaw&6_ z(-9_;$k~3WaN62WcPysH+|+b3#Q&Y=$jQ{65}>{!(s-fFdtZ| z>ooSreu0A7>P~)07DjMK`{G1qU-1ihPL*|;(|}fP zhJZQdtH3%!mprW~Km&4}vqBaZlXK^A_xN3GU@ty?S(?iaoX ztb3~Z6y=mQTLeEk((r(J$83TolRi?ItLRvfwteD$y2Jk-(Du+4VuQbLW;QXpkY4s2>;U5m9gVo*bpZQggi@?jK=`eJuI+^fBZtcSyl?QfHt?b!L z9)-IKjO*h;1(2(^Kkvq*=T!^|oQyfykoP|O+4ZQ7cm5?$BP!ONz2A91Dnqi)vmBp< zsKvenp1T2U3@V<8BYqyq8r&r^z_*@bVNLPMOnA|@DL_c$qxK0>f&|S-qV&kaAV}p$ zYoCVXt@mB6yJ+^XyiG{y8D4f&@oRAWw8l3Qc&G=*w0d_kLeQfA{eTALZ*$LrR2G;^ z(IYcPq>kT6rfdU2AQx`PIkWz)oHbQT7tadwVS#x+aJ1U=zQ|g5;1D>!*O)7XpN7u9 zmpvm80q>|ELp|SG$MnkRlx_zQ=WrUsaR>khij!~7 zAQuoyIc?nKpa)?1Pu5}{&9V8v%aJ%Wa}vF#0+Nd^dD14Oec`yW<6N@E?Ihb^$q1j4 zi>A;wEf_HsCv40`e~=dm!#6^fA%|nZ>qyIG%BkkI9oA|rXKj|c*D|(I;NHD)oLFm) zq!wSkvd!FCMoz8f!vKoX9GqyPD?5VV|m)!#Mc4IgN8Oa^v~) z2;+M2_IS}ktfQrX>o3)rj+HkH40y&Z0-ykCxqAY5(Y^QN!Bm;AfFTE7{qC709juZ( zsGkyOYL7b72^zNcb`*5OvoNK@7)O$k4zhuYd{!H9L*+X)cStx(t+V2}l|(yalSQt! zQgku)t9-P4OOTaD$8@46mK4}s%iZ8VrT*$U<4P>88%T#=@l@+byv?jcv@Zf#>hWEa zm^N&lRUC-5uGY$k`Wis>j|1RP&I>gG`0(r(0&a^_Odai00(E@w=UZo4+dJ$m942I06X7b=fSY%y^l!T7 zrH?CzhoR$KOSnY15wZ`w6db~?4$YEM3gPEG?K8jCr>X}-@BU^2n1f^~%*NjFYENm% z6h7~lu@Htk%AUgatrb}8g=5k^abRaOs-SizQ-I&_4ED!*eSYEMRt4-G0mt!-Hcw6Z;dPr!VmOl1W zD=F^D2$5b1f!9}FHY2Bua}Q;6N;7Gl>`N#V;NHa9u5*sC#Mn1u84V z;(H%I(O{dadY#6JTG6Y!&uUU6thB3p?4wBIsSCmFkiQasriA0^!bo;hV{Fx4_UJE_ z;hQfnBNABUfY}=+Sr5>uCHjOc4gpXsoIXD=BM6!gt`KwgP@ih+72o1eYS!OfdKaW? zvce|^ms+Wdb{As=XQLXD-{vu0$Nri4KVZSPiNbVS`1j$@&3{@6;JIy1Fz$TyKm_?_ zrei~SzM;2Ff=T!9Xmuc%*M~N59S#NPk_ybMOCbR=ZLI1Z7`Orq*2Vp~eyu269Zvd* zH%%;6Pt( z>an=7Bc}XkUI{lg9;^zXN~1US5+hvGX&`gOW+~ZDobC53HNIWRuRw6KV>YtE7Jl>a zN{DdAve8kYf$sQOvEjKQ4Rj_p4*os(@Sl=J*hW9ihpbgPh5=+d4be7{zbpM?5ibA| z?JwaxmQDy@HTOk@2N01mM3_Nu1(7xxu%RBbAO(TW&{hq%KB^oDz-eLkzm&T_a6Z3z zB9Ob?LEQmBJSPN@0OeWJ>+I&iQ%i}-D+|gKSX7U_9gDQ%V7&wMww7*fjANt$AMCL< z-){Ki&l?8*!3HDg=M3!Uc9fPwEI^0iZqz+XRLr6BiOSf+IUs`ieI{WoQjUs%(=BHp2LXG zi4Sp1qqUl9a4xw%8}XR^W`FuJKj{$2tyR*WYSdoFJnmo(*lt;1Bam*_njgC+oBiCpN{JoAL1L*P!)Mkq%idN*scwvO#|Dj zMfP>Mk&rW#>=_Z500p<|KNYitE5Il8INI)3*aO$ZhY%ax-%<>O1xE^_1{_9$i4sdt zDl@lqJiXU%BxWgMfs%z`$&SGxd>LA}8n<-zlt@1OOXWQQQVgPn`U85OM`?}&I*6|7 zxKKo303+l^R~&gMt}*!Hhc%{D=eL3qf|~e^OfSK-DU>Fy+jEr3j;aTmVZH-djI;jLo0k<(j9)Q34 zF;aL#+jYs}nQ5sK3EGry{HMM&P)kQ;gLV{^bxuk#EKksL?a$lPHf26_XSmXmlTq+1 zO!F7IN|B2Pq!51;Gyhv@(*kmfjX95MoU6D9EBnzzo~A??XbgcsS?{0@IwVJbV|MUFN?5S-l#>cy0_rnh^Y>g@6OO$ zmSFR=6W~R}w z+*CYBKS;Tu@5@o418TG+$Gg;9Mo_x-1Kpm zHgRDzBi0_}5f+1m4p>-D3b}xp2Gf6cH*5W-eM97W2c1+mTg@Wmv`G&JN&BIlY@$2< z=4v2YDDd*S$a;Spz8LKf5;dMz#niN&#zTh>!|^?wvb#y;>2jiB?VhKMtbz*?#k8nY zfRBr`b&xV&iN#3@`CIM`Rne$6A&s87UhIsEeC_4~8Z=TPNY7t7oeFEy-Ft^RD%+?0$@o$_)Du zq&2>=XqoJ09&M>HCh#bySQgfgztY@^(MwE`MV_%p@bmk^W6UbTUi#}u-*6)Z6&b^i z&mfEC4fr@1fxgh+7&^$tF4w?6Z67Czm^?BDM=VFuYF&+cjwKVsaqSIO@3acj)5LyzYUCI$dcJn1KH| zS5pGmAiv)ng3;QgiJHgsFJH9u%Wxgb$h91;*e_C_FLyQ!@B-1g@!r0ht{yBw0<$b^ z9@$3=mhf_DwBWfOc4cQW^CGkR^5Y0_Cr!^^=_5nXz_{9eOk9kBJzDyWTt>c$ASQ5j zxrOqCk=9evZ;Bd0HS`!BF0P&kP9hLhn7o+45s|xYEnEn7zY}tPS03`|gBN2#3^ogH zt`+A`X2OoRRiBL5ooM&VK@GX5Nw0I7yEQWUBVW*|iA8ePZfeuny7{XZNVl`GmyA79 z8ZQ4qE!Z(`T;oR1P_Sbqz{uCwQjlTf_}zAyH(s~^{8&;k;?=jKc^!Ii813!!m|g8J z<|HI1?)!C~D+i1^o(5KnK!+*1V)Z;-+^AG-I5* z+U*;&l5qiXdm^eQpAcR)H6Z=J30{sSh}g_f?K-1tA$Rtwo{ep77c@)NQe}SV;;TgN z)pn?nPs94^3_W~;w)a@%?CS?a`rR>CJE2aCkf0bx4dyYr!rtzxH}d1Z%vXvKGbOsv zpaaSMNcGX{16tu0$v;gjw|hN-j@xphDdfw z<#YXWki+p;+h1*m%}h?9T?ghA_lBSL3khv$cO6|QON*Xvl~Y9^h!P@jtmO8)p$!MR z%I$Rz)iJ2yWv2x zIdsFrG`~@*9Pl?6g{|}92NnQ9T}vNP4O5>p0KoBg4j$`k>(AsM@UYw%k2Q)~BI$d+ z1sbU;9<>G9=lLf@vx}$s=Z|bX42YP)W;{Y*ZXQK`VO;)1A>(TU&c!B3;A|oRWXpxL z&>s#R&%FYTjXQ?UTKx{;_89B~fjO(3tv+&-8JV}%qz_J(%2!AbHJ*g`fUHGYjR`fs zsxfPTi(bW)_^yK?rcHtWSOcMVnVY$dW^0ysSUn$7y&w`%>(je*c4t(_jj@y>Y@j`V z*Vfe!7}1l|p06(8P0q+=!d2_(%0W$Db|P4dP-Eu@B5|#LxV7o9Y#ByO-!S^`!{6%d zO}f#Y?Zqm<6xk}EU@J#QykDK{PfR{xqkw5+)xM5CK%XRFAyS9;bKoz}^&k(RAF1Mt zr6p#9z|fZ$l$+XnuL}r=4tKIB6zTzHs_$2wFhK@K-RMkqWHd1wQa-AVl{{pLj0y1n zO;ii%i_U7XFwPyPeBL?e>rw}>erD>1x({Cu2|i^gA`_rEeUOSssK#mDE@Fmb=2%Y4fb4=wAW$3AZT-Wg1%bPk zoVW75>u+2dSz8Xd8t@80lFPP39eQ2QbMR$v05&aEUEi`pa41;I`=;M}2TsHnTT|_|&cvlN{9xwRPP94L2Oq+R)EfO4bLcjM zMSPnl9D;>V0HC=#TF-KA7-ZBPAOhRTwjV0?ISqGqj7e~KF+_<47X}pS*0Z(W5gLcX zTJ5jI1yX)NF3t>gr&bECqceR0du3uIAzGdt`T!b>KR~P2xokV7afNa=gUZn~=F2H% zhaq2Bpx1GcY{S4HiC|0h-tBYoIXJq!GakV=Kiw;TOWT~NV@6G) zifJyzfajj0)@UfJA@_@AS^M`l;AfcWa@I9teA1ZrIDtzZ+adTt{smvP^vvq$} zUvL3y-mZu1_rKTjuV^Y9yQ{w_5#M9EKfNNw?h`DWhwsQ8Do}+6pQWESZdlmB?GgCo zfOpw5=hFWbX7S`tntoh1$hpr`@aD9(PY-mjhhkO8n&X2Nc1U^7N7S>emGEsWRI|JS z8Yb->*9gS=x2w!;98qDFkdJ}a9pfyjmVOT>M!+!9^8#wDEU#XwradVRL{y*bAoDR% za*30-Yl-tFZZ9rq0et7Hk&-phX?1X9x7)TVhQetcZHor=TrtLgDIzv1e&h_)T_We|%Iv-3( zN|Nc;b6U{|sdx$LBMC9mbW(8T*-B%yfpd^=3wO5DnSw7k+J<5)(uyO-4C!TUv0sPl z%$SBJ<-KK(kNTVi$Ga1Tk;qrHy8rj80hUkz%bAL#A6Pp})Xu)U_eGVhBV+5xn4&y;G@f#o@#EsGePI1N@~KejilIE&3kaFQekznw%8 z$MQikAa~KQQ}6L}zNxE7OB|mmdhn1hf0s9NCY5xRH^Yt;XU*jXMA#y0piIDB_%e{vx^FkHZ+fEE|dAjR~$SPlUtA0f4V1yQ31}xtMZex zw_XE&RFwq^ zmZ*LC5mR%SH28}rRNIaRD%lIb(eoF!INl`B6-`|L98g!`_XDW%04xEDJcrhfYjz22K_Aul8&?w0gzl?hqI1)d3a4;# zp`L#rn0(j25=+icuG@AOX|5C1?TKiOCud#&{!`wivv_iIR&b!zx%$2r8;L}0lNXf# zEcagi^5D_?9J*q3*s9iCp#F1odU&8kw82kAk)<8BX%2FwYJlwx(FrYQP`5FzAc+=C z1UZKke~lA_QYvr(76>lUZBlmSUKMctiJ@SqbNrchEUH;egYyC_!ybTbF4^8yCN2Qw zGD!s*z0JvUY);-lfz@s-HyR)=**S8s+&@%qQdAHQF~lm<3K#*LGsc(uR{p*m&S0_0 zqU#%_GZ_fdM!@Ue7X`vr=b&`NrB#WHU3djO)gW?Pjcw$raa^;S;_}wPIzI3XtH^u^ zeT@%b4bx{a@sNqdr+FF0L-dqQ@WdkQpqg<%(8c!H8B^%*!mR$2Ru6~MTg~Ik6txI?gtLjv$|=_NmY9xbeW_b> zh4eSLAML|(*-%=tbVD#*A#h4U@rgl(+Muf`i{DdW;XjABxRG=6SNnLt)zHE zXSJQpZo~7aL~Sx`0~>UxzXj`3__@bd06%xe#Tyw|&s%>>|4>_k{#CWNmTRH}=4H8X zl}B6)%gscOE|4`bf7GPZ^ck8`@Ok#4wO(Z9i60QUy0Ab+pn3Ze@nD2H@U=c zEyt6mX!CnGung>P>>ArmbiUK)vt3EC*)OOIH`Bk38=&vaHNkB?X$cGDjufsj6(d;= zm9c4pDaDVQUsBdTGMp^Db^xnLOz1O_8~VXsz>Cc~M^xn(5(6tZupnC+-*3pA@(fBS zC`!RZVZBu!um}KbD~Z!9b%#IJ@+~6>zaUim;oPE?a z!%;1?hyd%oP^UbptC=X9(X;UIF?(&hycKz);`3BwJm#@daC=)|BtaVJGt0Iek;>)( zz3!{ZddoMVd4q#dcA(oe3?4;Uz~h{A46GrRnmC%s6OcbN87rFMj-5gs4t>Fs&X?es}U^aT#IhK-6EE*_op2h9&5pog}x}h8E)*nGepcWGZX7Fmrtj; zl}pU0%g3iWwOT*a{x{+v5OOpCf~WodbqhlmDP~N+L+($J+KL3)@s)6+`Tf;j8N* z(O9S|>y3XeCV89lKoLRtGiHb+o>WZ~*&aohc3jdAx`*yIT}BFpmefc=MZi-TW;cGd z2XqWf!+_XliXvhVQq}#e>&{nniiGgNsask2g6$~)j6qOU3lrWO7h(b2u)at~-O)N` z0)*eIE=I^HFaK0tRMW2-_^~J3&H&8YHg6*f8ilzAl8TH3?l_9{ubZV1& z`nE`hwHlxc*B^is>BAfo5g<0oSP+qlTIjJ@Iw{ zKliF@F`CxFV)t+a++J84$;Vb`@RW0Li1oq8BOXKRUpGw>#^-qJS%khNtvQw?%1kZl z2}s465=%fQ%qm0Pc(MZfE+724X8)Ko^Gx_PC|}B*s9}$$WWk4XaKupqXaf-&=$q z1q`Ch$+u%jtMYCnl}p9}VpAP%mwk{p2earEK|AlpIJTH1kEV+$Bm=*uvv9|oSTM-; zY))~OovVP>tEn6-zm%63NQ5rN4eo&)XSsP`Hjog=y-xSf!dR10INl@SiKK}Mu+lpl z@Mc!(hZN(V`NgHvb>xSHxVEa})5ie};rP<6YD`}ZvH17nkOSI2yxY67JMa%9GwEs7 znp`W*=}#&?g^Y_?ej4KWJVxkgrO(gs3k`1V`VaAJv_jTPuyTwhcr1P7z_aEWqXaw< z;0-9QB4C%~e8^n%9mn-fo$wbTp@QwRx3YAq873chksOZo9wr6bHwBe5r{S^dqJ|Fy zNiP53ZE5*tNI{2jo0P~D*L{&lOn;m?kfjZeG&~+_55M7jx01Y0jit6{#^LonA`hkd z0NYR2t|3~Db1q($QXHkuDN}g^@Fh6oV|y{*RX_@)^^JYRI>{Eb{Lmt*#<+`IH0G{yESp2~%+EuD0;F*0#C8n3k$JdX zFAw7GHsmj*Z5Fw5DN_V+Ki%Vnp2kJHUPl7w<}(nl#U#O)_&vwowzQ3vsx*5{ql{Zi z5?V8)F4XzC+I2`AF5a-WhA}8`lko?A@Nglp zjvYSnXOuY#yf^}(6M1f(2_OL}5{|%uc}LEFyI-ViyZ4>?+aqI`Y3a9!{t{wXb%@!j zW<*j7nWZz*2Br}$NhXfZB9AS(b*^ArT?QI;o^oDf?HA-Z#2cMIRBezsl^ZnnDDEmK z?e#ktk-ZX9b7#&%*x12ytZI}|GgRCXZN`vb+*lRjQW`UvkCyAWl@IR$)lB|GX?EK> z5wbkzQRB%H1F62e5dsvRy{$}b_}oCB=-Y>jo4Zu+ry^w(K8uDv>O^3bC;Qgh0M+e11Z4Viy3+Ej*L6x+F;+FYUKoP6L>IF zjU)euQJA&qutd=uBc5XxWRMn?cWVEwk-Y1ai6 zsuh9N-^47zh_WIv+}9LT3O;ZV=Qd=Uex|D)ib^G!5Me)|f4}z4;>{_->)-&!M9C#* z*I3#%fgGT8Rew}=jx?uCtUwUrtjoR-(4`Lcn5TL*^vxoU0n&kKw)|$fxXU_Py-$BD zEj)64xdF7w7X)pC2Z-MAEh|c&=Y8FwCp~E!udEq9ZJm(O>`^meJS%{30<9kt+|q!` z^q{4Xg(~;EM=~XuUBxnACVmMW!iMvr=Up_C(!#P0?SdV2M9xADC?SJRZeg?N7-6(Hk;Yo$7 z(%Q|AJ5r9tJohop5=xk@AN7yh8}B=)I&4?hI?BB(J#v`Q>&aA zD&4B#letb?6YP0!85~o4;Aw{bof(7wm=WykewH&DPp)RPI*7Z7#)s;l%S#^_~fVshN9 zk^9(w5Va9F&lW{bq@Ci;CyXS^ol_-tqI&h>f$QEAfb~2jyx_|WPFt-yg1gY%U`!;# zPTwhROGU-fn9h&yXOcm7PoV7P+2Lb~k%~?hp7XDp#Xvu{8ha3IzXd4lwJCo64tcOj z&Thc8klbHm;F*RUbqE}CYToLRbwupEP6f!cFaT=kyR}W*c)AxU|7^IpPxjN57#8A~ z$~3nOY&<_Iy;H(v{cHo%Po)dsjD%Z=c{YDcy5g%`{zUF<2Tq~mrx+h=Xqsr$d$68} zRelwIIZ^l@AqIDewS9B<>A(@Kf#5^wdSP8?9zA85Rx{z&P){r9zo4XKo}}NNkzxDB zDm1^ojk3?50SUd4D;B^;LBV?mSpaul;M*|O8vr||Bk|-FoZGK|)5ZwlLn|W`nHAmb zjJ<^Ia%=PejZ>vtnyeJYr)}b=4f`r|86{3k`?KFIh9^k=`C~H7}0{@X+ z3~^YKi8c=Ap%8z9roW0&D3_k>!F#;VW>8L%@c!=z+jNeo``1I+Cq1-~y~>D7M>}8B zZ+TZ^iB;}ODs{Dj2+dWHJGD~PAVi;+*9Hcrwn~i=Eq9I%rcll-^#Y3U@m_#zLDiT@ zIqQXTz|T=f33L4#--#0`@tms#FH#XLL+Y8is?iYuL1X53e}17aY&7g}Sg1k!*lS|4i@~)DGrV53~W~ zV&iklp=KTj-4H`0;(JIK zGZI+znx>3fBH({0>q$*A6WE6qWAT53N4V04wu2Sngbk1BTyxCu`3-lp@`HeE70YK8 zGSHmyJVP{KJl~68=qY3GSn*mXbvMR|(S5V(v%_9XIaRt-@0AwSJMSn;z_q}p|4qou zS{=Cl4OBNL2FxtpPUoW>|1VJ$V}@SE^Lf>;m+_S`3)Eo&o{d?TIMz|pDKC(`$2NW^ zn&^LS&M&Z=^&shqsh(kGgC^mr=L*38xBg4GfU^h(>i)$-LE4%s_y$rGM^!-0XHvU~ zj>C>3z=*E~m5^`!?x?Zsiw?-cDhB?ch>H6)V6l`o4*t~%U-a-z0cSMAGneCA8Ttr68$9^gJiw~h*}%3Xs;A1ui-}|xpVP7i z`kg!0S_(Eyx*g9--a!g7Do z(`fG~K`4FN7tu{zkPS!B_9^Tm7~NS}m)D1ZiZ$O8XGIz+K(FEEwYzj)oJ)I7Yrx%r0B&(N>GL88>{j~MaD4R$#$Xw!tUz%_cxT#&`rnL9 zMFFCCW%maG&eIzexkkBDR67ImAJxvKl4=l}H1&}auBJMO4rGLcBd3%#ek1EVBW5@J zUXIURQr-VXJ9o+}8CLaPqE?*PHTdHo!)Cvass)nh6SHL{EqXz}h zD179bS=kEjP>mq+(!aP-&pz{CbJfSC`nf& zr3oplp%V;VPo^!(yFG5AM}*J{jj*$25hmTg24)3}(Y5%q z{=+EPQs8`K>%TXyi2n*M?}fC6z1GfTq`CcC?U9Qx32Vt?!!dRfR+_tdMb!pOA-__9obA$IYm;XC?f)OYbdGqU8R`+aNCL^~!xGix~~jSs!4r#ZhO}jGOfY zbh#Cl3BEB<{lul~0fMwW_ zj`X^b*-1R=M)M?DN#V#jokE+Ysvx>C+<*x8C6y4NY4C<7O!%#w$acO#&J&DV(&4J% zKmzTYo-pF_KRadh_s7W=$;xIY3gOsOPb!nLXS#b^VM&PwM1miu(rHPthBJchN3>++ zck^I<)TC`Vm(ej3x7Rr-nV%ZHOEJDlR09Ep++`$~KXHuf*jGisKsdf>R)7;K<%@{SRDO0rq3$3J8 zUw8Gyo%8%pml7AoR$XdryJ~LZn8pB1&o$N-HfjSA8gCq0ukT<|-*igrb#M{WoMu(# zQaIPwQ;C*!SP;n%EAHkQ-}S^;iXo_6CWV48TzgG#wqV$(A zl}YEEldqEzU-$x-i1>5oVt8d8R>4B4s-M=$CjMpReg*)YuD%|o{pRh zv~qr&0)DabC|o9?elhcJS$xwJDgW^N-!?{z!jw;KLKY;$ETTRhxQdZfGyiPUQ6$Jn z>n4SdpI_buXqJ_meG6(b6_}rni^pw5ttK3{(anMP(obUf|>^ zA?sX6hKHR{pmO}gCOdCxpIK|-!Lr9g)rgK8QHq96l+6$#ohG${^rz*PH79l{o-{uh~2pJwp$@H-Qz)6+!j4Zrcg=XR%HjuO># zR|wJ}hJu`>OrNDAf;h>bKR;XSOuV~EuV={1lS2}(@s$Qw7qp!;zV4v{!vsr^YxZ5F zzmK6a`4(no8LiFkF&9n~J5fz1gMySDvHPcK^giW%?oe*aK$5F^A%%_eU@J;z`;t?s zh2H};!Et2GAzTFlReQvsxSoTuNE`^G_5NF&vAl`E20ma)z>b5y(Cug|Kho#e6u-%P zFSmvOZ#h;L4aVUuG&FXdln$_5J;X4Gz5rnoH@w!|>}1LYzJ%hy?(dsSwFyJ1_Hrqe z0>we$EI>P`s74^%(is1=NB-Py#i^j4I17-X`cV=uXLQkw0cmcGkB{bTSdi_$16m$x<$ z!&YsIyPOh>Uh9V-vVoRUrKgR$>Mma3YmrUNS)HB1TH6SSR!v1CtC=v^9Io^$l9#~U zXkY<({dRoUcD4hc$=MrBLD5!3T(KFf-PRz=a1S1)tr*^dVt1pr#`rgSGD)wQ%!L?{ zLrMd&E)JS^h4(EOg7<7cC~zQs<8E@sRs)%k=2gM3aN#oN&Sq{M7Bo37sue>KuLJDF}!1PD7MYF$EGUAKA2|!t1^kn#7 z*{=v{mg892;q7MeNlJoPy_&&JY&$~N8QgI>A8J&Ow;G!Gi|`i`G5I4@aHEL?y2vLzRPqn#?<4we-9 zw{c)pWhj?H`_f|;GywUl0;l!v_eH>7xc+E?1{fF8+u7A?^Fv&28)N>kv@q8G!^N4# z_{cY`*F;|xlCyl?rN?U+Xk}F^(szi5&UOV`3cCRe{&j@OMgJCB=ceL0^%s5mjc%7e zbQT}37)N1B8S1Ug3P%>bph@vyRg7g!S|nY%J358tE8a8*5Q>a=jcLhcYb~SXuShk& z+uh#ShJU9m&}n$vHYFW@M&6G?hi$dc*!46=Zp~xSuB_m*aZ;imM`+vo0U7JJDfxxQ z+l%{PrvK@vR)m8o^xVl~o1fV8>WewK4l2mJGz@eSMtcxCp}?e6yPRdA2e6>ng0S6j z2yZrT@18Ys#urksr>Igs<*P$w)4aw6qX4Uf$NTs!j;95%t3HF$Xd|$coVHnH zJd}Y?6-n|8^yNerF@Ab=P^VVA*r0xLMoo=b#%uN`4%qT`EGbB3Y^!c(>Qa~GGIzfh zWrjM%G0<525zm#2G-%E7YoDSWn#3Z?ilc?@HvR055|Nlc2SCK*q;Wbxu;2|xfP*I_ zQ;cs#0X1dn7?Q72tQXbPuW){O-5+0Az95S}zo}}8$-IRs2HnZB;oq+pL7Z5!8~SKV4k?Ul|ZxIUnIQ`M^|I%UxBP*lh%~MV=~BjeS7&9P6RT zJP?jjIw=oTAxuRMG%gS`-ddTM0ESoEdl?5xt6CNpWCa@}CQd`jkqWIo32>TH)yHKy zcPPtODK(Gf1om9{ZWq#W2Z=_*EwmO>&+V@BqR)7Dlg=E8`q$M=9!g`fZd~ylLz|4;p6)9>+@eY<|zKhx!&SJx-TieRrBzk0EIv0>B(3*>E}y#-i8qMe))<1 zw{~CiQ(G>Sj>GePX3=TIH-9@<(XS;C+-D~1YhvIg-gAx?@&+|J$c3&mD1d47a(_DD zrj~tiF(xy>#NzaZ?3&Z7t#)n0#t6>6{1$0#M#5`fc}8ZX&Splw<06*>&DYq@;4xxs z^&7p)N-g`2FJv+^e4NiY3u~C`eBHW-IS=Z&x|=ltf99;+F9n9?>ayEh%)6(mno2%y z(V|)klfT1?_cSQj)6WkOO@E2r9oEBMFdSHGc0kGWFQ|fBI+Tu^?kbR5 z607w^FhDod6f<56hmS|Luk86LC(FsJb4gV;~LSIq?M zkca+v$h@Fu90&Hc)B5*5-7xTr?0wh?(0g7?gY?>;$-Ogy&5qgm<~JB+zF7BCIqWO6 z+qZ3yD7yy2`-Ww2ZTmszB}cZQXQVtL&a&_B_MsNUNE6OjTR9amKLBa2FwTr#JV+EE zXRyu>9{(QB`K*E0K$`dUXH`3J-`05oxf49})qNpMZJf=a2)Ti8AW<^vv=7HCPg&#X zPC(czpj&N0*9w>4ZGGs?=_8Ip8b|A8hMxo2js@4PG0%^2PWcBYis)E_5p$a+6D%z1 z#PEg4oHsFst`|$m4E-~QH})0cjz!~E>arp{=IwI{U0^cY2eUhI-BmsKf0xMYG2~ou`k5DdpFH;_s8j)0fp0X15^$uY>JkE z-nl`0g?kLc2|+dcf#VCi_Md+a6Qo$5eWcG$d?>+>!h9BgXONgolQ7&vgRZ;(XF zNv62E=bC?FTU9URFjwr2c6%&r3_?L zLU(LNQdk{-4?rAX?s(RrT>u^xyH#x78Qr4t7MI}vV!Z@2f+I&@GZ5sI*xd#8sQfo~ zOQ}MCYX1k6B+Fi2GI}31zoV?vQ&BJM?&P8Q=bf1nFI~C6JRl-RsShLepq}@l<*t|r zM((vSa*+79-%7ebvMz=iIp^lT58YB}uhtc|0}|T7NUGl+GH^AE=nr8@t6d>p++@{G z2XlYDq%=om3K<*l+UVb>cVzp$UHFb^mwsT5p^%z{_u@Age!@I0VxbC#_LJ!fOa0!ZswmRvPb5GyWuYK=m;F)X z9rw&@dh!)-0qeD(kAO9E(-7`^onA!3$wT^`R_g1}==K-}0v@2;fPQX!rVo3= ztoTU3kK=iA9yI0ge=bU<#KY`!-b)(FE7aV>!G5ip(1YaKfFt$qxA-)fPW$Q}E}J4y z1u;nicJAYC!pZ4J+KXTlk9gZOOSj;tZB-I~`tgFW{td_HuwsCF4K@dE!y2ge5TBVn z#xg3!rkb9WpE|xnM^dg&A)qUP>)Mftu)^X~)wTaTbdN@}+7FXoxLGKy65IpDt6y@k z=Jl=hyq=6M9~4IN#Aut&d=YWG+WOu`oQL$+G8v}(_VHGxit({J0)Fe)QHZ#6fK8TC zg56f#SLmYkRAykn7>kkP^XrJ+A5Ir&dqwk8O60K8Coh_ zq1rGgjmp{9jr*6)f-Ohj_zK;c3|>h)wcp9cTHwF-Tyyq5PI;`U_ID+&0db7v(Qf>@(5a*l zMpXh}bib_O4BpFgl7_>J?M>Zlf7s449PAVl4CZG+pi=m-7P{JmZZPo}a2Nk4yP^^E zltNCR6aY^DV4a^zAs)x353!lgOW4_~=&u3pe%1Rm^1XY+#peL8h%Er!xf9&}%`~>j zY34kVK|X2=mRMh)FvglYONyV{3GE^pcw7tYboW`XJ&5>#Ksszr{$D4r^(tv$8oMM< zbqBp4wm&osmx`ssjISS6oD?`fd#2QIWH#tEWY~=22Yj{tW_qWb&Mf61=|A{~L|%A; z!x)2vOZ5r~R4IgSHk;&0wocVLi3pDZdyPqYWd0_FLU`l|)2X`AHCsl!RuLr_G94X#64{OTIJAOav!{Q@lP^kdyfKN&kH&v%j8a`f^ z&4*y+plcSO$Au7F_fH1*k1V};6fiTW0Z)1YO)JO}I#T95$t~7nBh^x2BHcD4tkO6Q zn77jTAqJ?!0Hk3hC=WjcgfNk_nP5Pr2%>D#tQG^1ITG@B|Ky2xX9b^ntQlZ*bvysi zf`MO)IZWI>3YHKW&ZdNx&EL|>-+`Rk`^4(98-QnWPAr2L8pUSN`QTAQm={3C++Z=U zFp^B<7T|SZ76}2GzcM}p__p5x?o~JuGN%RGV?kLt`*mm$_RS_2Wzh`Rk2*VGrE?hi z4ENk~Kq$$(KUm_n+40vKE2mN2N!97*@ZGI(F6Z1)ulCG5i$>^~oWfu;p{d>{wI#ol zPZJ+xXOya6G&Mtj{4py-QrW@i6@6o)1wtB%;EV7^r?q17jQVk<#wxjo^jr=2)bE#} z^S$nx9n!UCC&X_+BXVtpl`#esaUEYsd{kA+dcHPdw`gr7zCZrlsq&PxA8MLe{-lIh z2e37XjYPU{A{7%nlB2>+UUIuc`Rr6zW8oV@ciF2#gk^yfXVzP?>Sn?#e) zWa@2LgW)7P?eqB6EF$I|g%+cuUo;hk+V7{IVQqdPkR!Iz`+yUol`ETPu@$gO5I1}3 zq}Us|tNiOi6y@g?{5I7l)!1M4uSSoZIT@u^9HprNaTl)+&12S1!ICtvQgnuZHOf~% z`X^PY{R`SDweln17MwjP#3a&kM!eyF?F`+n%K`1oM86x)+7uUa|;#NFR=L2H<&PzY9v`ZImdMr98XJ+q>Y>h~)Nv@DvA-<{ZA4zv9T8W+1 z<;UA^cSe~UH2P4)^Zwa9P)NvzJ6!fa{O>W4o6HBpU^qG9-TsE6;;Hf#+#dBh$}>l+!5+}vpM_QTjq_SNcB~{=7MVT zDHv}Z$AQFYfa`y?pDl_Hb{NJ4p_I3td2ZUa9#Fl15)pgJ3)~M^-VLuI+Au;EK1YS^ zpIZXGD!@#7#&6=YU-XZ3akGbqglQUO*(rrtwTTEJLOTW71HxSF5c7>$AMlo4E@vVV z82yNGl4kd$y*6qf=(X5K$wgs4WZ{?bR-U!LJO{S7`4ln;+E8KN0WkNStV!lxk;W+fZ!>Ulqf+4d?eLKE~XC1k}M1kcexa?hbc201J zOY?ngr>WwRhwaMD$8*HB=BbLJdQLS1zRI8ea#v~R-qmtIlS|{vNS9HUfl5z!*5vvv zHkGzlXvI%&JL%Tn5|$iVRgv$PQ4_j#%zf;A7FuIUcde# zBT3{+09#Y*!E9(gS)q?3FAYJrr#dqtX-9Kz>h-ehn4`{%hJ{uP8=&dEIuT~57_=dv zV?k_sgq?9S5`wBDiTFY`JbouI+%l#lQt{z#zq8V&wqxNBwPsNksA^HHH=<1+;fS4B zAz}iqMzY{uaO}B0oF-UBS#({!_U3{{AMtq=(cH*B<(E*{YD~al`Dc@ng4E zxuYqnkdT3C?Wx+N7<*-QA_fQeJq=RTzK16QXf<4c3lEgvt2T7 zh{PN}3663VT4&MIg60i@Otge;x`x3?fx?G7?|k>ceH0aF<@drC3A-C2YW;`;$t;5N z0^D$s=~K|F%s|Xsv4;N~X7Ix_LD4rCqGF&fxJ{jkMpVan&OfXd6%(nu$_(qkOYg%> z;g(A)BLb5t!*S&-nM1&XEBgdco~*KAx*PY7Fs=2Z7lIpQTXPZq&?JC+`-oI5)8W_ zS?X*8q*W^M1uqS@SZ%0FfFo3ZLEI>k)P~^-AmA`0qYsB zEg(Z<;S{~2zwcGi63`5N*|y5El=lTLA64ajs8@jUQ41W}5u5fcL0$WvaQhy*!PcVc|YEu6|Qj8wJ>i(kgha-I)a38h`HY3#SyXFr7yIA3aZYy z7tg5G>&(_OvXC!SEdjT8)o@|mY#(`){m7}x^w_7w&bAp+K(f~8Zp;_la#ll=xjk{* ziamxZKcI0fzL%~=o+O{hT zEbcD)>f;+vPc1^lz3y4Z7vn&M#V&(3?u_V=<_>#hzA{qVr5_PBAu7+l&GmgVG8=u< z8gz=M)MD8TNXqoCcpUyf`t*b28ebf-i!W!zF4Ut)F~~N0Uo7WvjGEHy?8B$LX31GD zN--hK6qRyD*@`ESURKcEKBahW>?3~VwX}?R2FXHSuTd{fp52!D&h^sPd4}`<0Q(C* zT5~cuUW?E^tVWv{O1X%6Et87-0OEzJ=1%Yah$OaIy#v2Q3GDiX+IUUz9y^g>=@xH= zk7J!pHmkI*xiR&;s6Wt%U zx=!BPlw)LBFzH({(YBn~@)YI}9W|dN2?{Vl!N7>tZsgGBahK^6GKZX_21*AKm_)pS zh^Jq5VKptw`*+BQbUa`L;II@$OT0ssiF)??s;Y$SL#GlJv^C8J%c8k>(H?1#ysPVr z>9mPA8{t`XY3iiI12-{M8(u!ZUI~-m7L|G>lvX<;WJ@6h+2fT%-BQs>FCZNL3>)rO ztPg|el*G(muE-)<8Me!8RanG+pyM;2WxOSAzp$rV)TK%R-B7+ZK^clsJ1L2PEc2N1 zH5VY?44=-1o%xV}fs{%4<58Xjp88pPk&#=iI@A+RWqDy=Wc;N@fT}ON!Zc*j4Mlp} z!SWr3oPvlW-i8ucBLS-o0>5+O(gls0Zq$Zu*Yv^)b@~v&NYs+uSrY}Psyrvw!s(VM zJN9VIffZe)t~|63jleS!suYjCuyq2JTUS%*W|f8>7iSZUrjaTiIVtkVJbUm7cA&ELUbv1V{y@5h*i zOmtrF=WQE);7CcIE2YORKo9`pi~|5rqH?{6XR%+;w~#?D6HHYgnE3Sh9=?QglkN$k zA1D|c3x&Ie6b~lr{#P{kyN|+7vufk(?WqN zB{3S{C}-p6btb1tkeK6eds}E$d!`g%Z$Xgtv^Vp^oW=CQTv0r(YI={#>*+IBUF_< z*4jU#W)0HP?>C`}yj?d-A+_aM;@o+6M8m8w2ZsM=liP)O~)|4R-5GrC)jf&bnobBZel%R`H0bvlu z02yYN3tmeeEl_y*#xt_yMp--S@$HHY9ih#F&>J+*EjlR6xfpffaY)frYz_iZgKkqY zBGSMWaJ6YzFMkR~St$=7v`;&)=t0_#Vi3%W}F67s#aF<>40e;Y6dl?6`hbbC8k7NEG zG}gbXcWUu+RvgoyH-Zk#0H!Gr1n$w<@f1A1#a++Q90r<3tyq2+Aw>2+{fwsinCUyX z)%DRtcL`M)#)10~#P?z}MMRJn@y*DDD!V8o;m^`>iBIt3`S(v4ro6TjqoTPXJa(+g ztcTeZtqQM#6xF%O{@E7(=>XeMLPB0>e922zp$QF8_efoueHx}5ooMYk56fK#$w9z2 zBp33&cVXE)^lcBOGN@O|#Z`>u)@8nRRqJ+oVawBII4coR&kpv~G;^PP+(N4r&qYFg zrK~fw%)}F^)@JZ}^&fZ&Pwl&K~We(n~tr%7FRZ}gBt zURQ0oUgrCYf3qW9HS+(y-jCld!;0Aw*vn zT{S6irtIW7Yfn?Pr-%+(~|4IF?RQD>^#-0Wi>}%Du?$7@NKI}VEb$E`d$R&#n?C; z`@~luGY*IZHUtn|#7P=+dvw=x@qN3}LP{wCPWL{Nbp)yCz~ZlVYKPt-Yr`Dnu3|HM zG>-qYPsvN|uFtDVUb(vM>S$pO*-^eJRs{o;n`tQq7d=dAbr16bQ!*@iCz;)kI(8l1 zhQRZ$wpyq2Cepd{aanGYsdhcFM=($&8TXiYx>2XsKuL zmkex=<*abE&a6o!ox-HBsEU%#PCBle|_ z`WssR><&Q5K9(eiS+)mCSOyLK=jv>wC11jhf^I1h6k$FCkG+`-*>VYLl#f1%g~nOS zgabCSiw`>5D(w0Dru*OK1(ZOrQp3n73whbH%4$2qHnE6&bPEx#oI z5X}TvGmEQ9aYkSXesY%bJ0VN+DB-b05#M!(2q?#Zwd~?<`y!IeEf}))JEs82o%~$W zc_IoYEf5e1TRV(Wg{QAYGE9sJaVyreuAS$|| zevWK}J=!YKf!rbcL>pxg$Z0@j`xC}BWX>u)1hh}m9Ezc#Hk>~HO!Th1X|$6C)l6Gp zcIBMoUW&KlKb>iGI2-U;#KNFdU{%f{5AfJz7q;$U#n{JL9^a2VrHMW|na-P3627k> zW8Yw(+_A~%y!jAycUzMcn5cKQ`c`VNgumQeH?57gzUqeKaSV+|_JTzQwV1?@R>qrPU$XIs*TVL5(!=brh2c;|N~UKM`|1 z)o?q@vrFcG9LY8!9uitZsOU1pt76tb6HmIK%hffBM^F0$1c!0PRn%)PK#-~x^0s_@twg{bnnr<0*^;-qM;#!b&WIT?)`yQS|@cAF1)twRzt$HLdiIa9O z2y^lqx*Fp*rZDd0D(RXpb>q<}NgY1F(4&XmKXtaWRFMzz6Bj#n1W!J7ks8N9Qu3?+ zN2gDN=XFZA~D zS&1%r1(A|z4_mgY|YcH?jtcgvk!WafR`}@|q2JRaHm+wP+Fw()y)wHa9 z7SN$DjyW@M&?BDR2fQlRxU{MxUWb(>47bD1OKFU+0FRvVX?b@v*);1|ulbMTrFseq zRTgUh(AtUzHgw_Mk{d#O1lY(Jc}6rocyBAhaKH&b+8f`wMZq7S><|x0@YTD7$m#rIyrPFH>wGu^v@VP8%3NyWO5piy+ zaYf&RX@ukUl}t;UamFGha-T&2(uw68h7G-yWDUI2gN7 z&JhkUt9(}ib2}_~sVkTzUi0`%FpM6ps4C_+A4O7CYFw#)S=qEKx}%tiS!}xl^pc$| zAeF(t2d4>lcm`+E#Fw*`XyCo)xBiDA$W;$q6p+A$!Oyq=KioS8frTq3g=q4;nq5lN z^ub#BvP?k1PCv8j|FUS9Z!UW@T(DvhXh|x+NWcW?409w!AKhFSYM_a6J&N!Gg5r7F~;&2Yr(uury%aG>m_jha`S!)4T%;g0Y_ZiKO7B}CQIAXxfh%AD3X`O z-srL}FS&U7%~(l1k-+~k!s zMtAH9C+9N-jujYxl6NjZJ!sk27rR9#?nWN|E*OcJX#wXf?VVb8#@dhDSn*rG5)-=a z`>A=hE?!<*I_{f<6{%P~!!*zbk{ffL5EGtL*~pYd#FHhJO@@lyyBvR{(-i1&V=Ony z$Z_U2hXpECl7a%>%lK52ki;zjA0P%Aqq@z6EK*5saa~Q(al=olJ5As zQGD<=`HZSZ{0r83H>LGJB~|*s9c7E+eT|5&+r&w@5*ny;9sa_HVg@5a@JzDP+$r=9i|Dq>u_IXEHjL+u1f;`u0iyX;&MXnE;osdYMK> zYlg+>4Ms9Xxe}@KOe6}O+k~Tacd|K$7)k_^0BVw(H^Ei&(KRzr%xoy&k$^yfzvp9a zh_z24Qz*g`_LCx?+23lNW7+g5a|)Br(fN37;jUf8H^YlR@gbNfdSKTN;UM8Lb+!QT;!+v#ytIbI41Ow}KZj|7$qk zm5-Wle-Dd|)ct5lepMQUKxvg%+yPuw64_pCimzXKWdbwsLs_>As2y3jP|N;YQw#ln zKlyRl1Mz-NL%g?$JV|4z}9w^86zdo&aD&OAtTgZtzi zg|1aw{l^MOrPF*??^qSF>I9aE9B?^&G@J-soyoXya!2nm{H@vhzNvc{7!*_dxbBmE z8|SoU^Ge}C>D=6QvG5ekYRATOC(_AO6e%Egx0g_XGaF|Dq*B$i^JdSUSK!=6kz!Tr zDV9&ooIDI{w{a6bxyMNH>AwF>iUNf9roZ$g+SATGDnkHig;RwZ1>a_t8O|F}tmCZr zmwmE0ja`kmG5BlPlpSK%{mnuT&|#XLIp(t@95YH)y8Z#xUy$$SgF(-gT}>z5-xagf zmvpsihRZD%gt2pEr7NMEQVuzI;4A?*2gw?3!;O~V9e+|bpe`N&IFsTaALw^L1uO;- zSagV%-XN3Z6NA2jT%j_X_W8|t5QF4)P@~i4)l6<`u%sFgBE6%Uk5Igcs2cChKb^X{ zslFl)Ed30QIOCAPba-Yaeez)q?D)%cJ78Qn%-JKVXw9@*$)yeoO=v6Wf<{|;2=Bku zRfFD`eA;6(FQdcYg()`uh#)j7FT4zi|FT?_X*KM(jL+JVf92MDD4 zhLJ#KVY_Q1I2#qBonPC@VTrH+bX=rIlF-!!R0uO0LOgAkX^Fq=A5xPMnZ)gP3oksf zHtonFms3I&XnlM~a3E?bN+f3=q^WsivvLpgi_poUCGb7Hj__~*GwfmqilulS!)_D? z6B49L4W}!%t+cEajyX_GZSRJxSf!T)3VprH#^H^}xIqufyDv6V(T1aoWTeKJr+^h8 z)~w42kweH&u)%ns&97ek9Z-s2@dO8 za{l$_eAB{U;BhZBsd4hkC(W9hlgzv@hlU++kF^ej6Y?Eyy5+nfESl1~E2~@TnJY`Q zqg^+0>flZ2CVkiNNUtp!M4U9lJoAWEqyXGxj}I0zixmpYN+{7{0+fu^W0iJgGF{;d z+_HW4xPJo77lisPVm1;m_h+1%kWQ9p`h*()KKnuDuE<%_oMlfHe{=60Cn1 zVNnu`RUPDlN`R?20Y)99Q^|*pPf zl_w%4%3SVc+qY0hJYNO<8Cw>@Scs&+vqA%2xE`Dv)o%1F0308QycUSj{2!xPAU|w> z`h%l!YImL{#ThI;{o|2%!oMw#_{W%88EYgAm#9>MULX*CkbQawEP1`t6XV+N8~%My zb!aS&k~z(l^nh^(T`E6hzxSrEC*k_zS`ay1i0wy=-Ge*#jsFFH%u9Uzc~)FU3Dq{u zP~i(b2Whg1kw1+odWlp>%1c=Aw}?h=%Y35$J%ss=|EW%B@ZNVfev@WtwKkK=^8m49 zJ2zayKEfc5hp#mEn}SBPPpC+0M?8P{IP7=P*oO6dV&hnz8p{d9_yAiuEb*HSA{qLN z1~|W8+;+(!fudH9guL0Dg<0t?Wy$GM`V!sU3<}m9ppP`${x(JLh6O*>r=nGr28)px z^JJ$;Xujji z(LQShyxsuQJQQ#KVGF0w$zu>5HM_o;>ZV?pKk%suIh5BSxAd@V*7Er42aY*!xUryJ zes&>Lg^{0c^2hcZ;=WS7!opAI|DVB*2mk{**n7>luCYct+150bH+m0q5zxKCw~`CD zvg9|468z)tbwIU4d>;I+lvondmAlwF02{b@>Sb9g{WCa+54T!RFDZ@hS=Hpv<3Y`%_~L@+VUOruwc=X&lyC&f9K zXkN5Z;T&i9NOe}~h+OweC8LfgYy`-|_CBN?ItKht^;r{cem%uD|FuYW!3Kmyy4)MjssfVR+bttE;)Rn8Knt)SvA}+Z zDejVT#j28njn{?hg5C9kAaqIIbcOtnF#M~pScWjGfxz{i6P=PR4@!2aRbk1WDGLmi z%zXUv3eA!>?Cv!XwaenQlw>Y@+cP_**yz_MR5?uwjoD%EONCxZm3o6BRl}DoP!&Yx z;x+#Z>pCV#m!^>W>O&~=2HH^&QZQXuHOkgSfMS<7A->{1r~emY*i!e55+UON!*XwX zxh5+!te;>K<#O>8O#8hLG8L6elDNH+c+-9A>UCJ(k!54=gfJ0;S5=HX4%={jTF$+W zt@b|+={BdQZ0I#6#qj{^#@6GGku0ojjd5OT%HALUo8}<51)A?1H)q*&?wYQIq(xXS zPI+sSQUYQsIvXw@XrRyfsF2C5bf3G(s#(rqGq=;^!WfXoC~|Q0Cv6D`0RaV6-}XKp zVr=tFmvt=vr=~Ke7e-RaX%P3c-j!WXfH!E5$uhQTaXPk#gV10mu}g=AeyM0Lt8U^k z;0w51{E~#QhYvXBN&z^J2KfrhBr}6mn%pA3*WfIo%Qo0`xz)UU*0-85l(qFLDLO0!E5IR|m)xVu zL=IT4t&4Qw3HP;X)6>m}81Hde1dF3&b)$`ir&-k9lonfPBX=%TayZy{cVeXx`x<}l z8&pq58iikIlP%8O>@R&J5Cd~NO~7f&#tmlnnQ)uL@P|_xrIp z$WAc?3F*eur9?7Q%3f<8j=GEgcFJ*)%-UhcG0$aVT8t%(*RE>MXy>qeLUL}Ynn%|0 zU>T6(7_P@Qj55WS{7CoCWf-cx1AK}!(G@;6&62xQ08-e$LV-%t4Uq`4rja=k%8&3U zfEC{H=n3wO43uB?=f3S5;EFuX)VwPg4|&Lgu?Hm8TvNCLyh$o)O%$0P)OY9wrh&X* zPYJsbSD_W=b0Raa*wY8YQwWz$QvAuO)t65F96J$85(O{vB@I1lF$O!TpW3VsrdHk^ zH!`{&vh3p-t7GZm;Qzp_i!J(a*$7S<-#szdSjfgL)GhP(Wf6$~dt^rtTIJ>-u7{{B_I7rr2SF+;-syw(=<7V&(8vi8vB}8i9Lt{#C z6}pF&MZ>YRaSjTA5Gs+FVr}_}J0?umtlHBd!AFi+;LfBbb=)zc<#s$ifNkS!{8dIe zZUE0PW*&&k7nQrbp~*^5)5tz`uUVC8l$lxlX|631b?D_HBmPd({OcWJnxE_1{QRJE z=DgT}BjLhsS}(-t#B80qJ^+J2t2&;zQzu|!P&+coI?jE5aNWYhS{P(dVZytG>D5wVz25e0BQY#yh&jI|bI zllRHk*99q&D_Ul3!L&3AF{ed-Dz+M$qgCUUk@8Up`SQjdLBE^!b}0vl2=0)h^`pX2 zvwZ3MSMmpB%)Tah^|X|g^u7OqYiw^7!ZelLp~k_=0tiVM>#L|Ze!lkZ*CBOydF+*5 zLfL^&xg2CCti``6O6c(I?{qyVE5Kp#GY2vq5rFSWOp_7o&=jkCTepEXE68&Q#$VbA zUV;p}<#!xsFNr>+Otj+Ch@Aw|njhakY5pa%Qk~Or9PjTlM9AGfhnYLgUn^>VShI(@ ziVYD<#)3b6&4zYkmnt7FzymWQ_H?R=$ZThLfZ7?!3JR&)Sz43PbP^mkt#%WLR*Rx|& zjGvQS1apy1UK53Vu_4OKk~8qrs2#lye=ziNg`*VDhqzQgNqW$;f+0VMjG?^jZwG5S zgsy&)uZ;Gx{(vlyH!0b|*7ekTO}t1(?5yFcX|?+SYUu@6B7-XeLnyaDC~Q|P5+KFp zOp_IAH^2*S#m*(-$==dC`xxmIKSGb1R8Wlt}UaSp@VKCabD%kw+uLj;hVOoEw zn-8(AEIlAC^uPb$40)uB@Zk^$D(&F8dd0WE+PU%pHe9_eR?)W6Mvs6sL{6+t;f--P z*s&_kv{d-eq{UF29iFhDw%Z1fUn<+Pb##$r9q}Q9rz*b~H%Y348eovquFc(gBUJ8| z+37zD`Ce3UFQRthHgp;?ko|s6a5^qqg<*;NLON|^V@4_AUG`q`av2(rFmp5kk?g4$ zqS$O~^cbb59tLL!&*%7T46Hm!V)jZ2bc_O;avvNyazCUww$4YWOleSqcdsetlf7V} z<<_sWkDt8n54_YJB*_y$q4RRm)}khYWQ{g)MsfTjaN~YPj%@K-cC<;Xc|&(-{`bVzPMvb=XLeP2w4L+fijE zQ-D7&{PjlP3V7g@$mpA%Aw$`7!5GC?b_2IzkuSB14%CVS1FyV{?}~Gef<0$rkXlR_ zTXnoDyU7RxJFlw74a2*mu0#U!MfhK9O%#JhA71E(IH&9=OP%nnNBy9ab}sS5{}AV+ zUC7G~(~L9G5`8YKWkH+Cp%mKWyQAzl@c@oZx(mh_SuJG& z4kfZl;MPx&5Ppx=>g5gzHUFoPqAIhntc#BNnNAMRC%9tqvR4&)&4!2Hy2jMKHKx{zPC`wSy3FVT0pObBmps zZtMM-YL;hRzh?2mPrlcmrajhfLmRbx0<hQ`tnNH+8%1d|wOk6U zcDiOml5SpMq7L;;AHCC?LTnlO8yY6lW2W5(;0LyZ0lFu8R~1&lnY63s7_W3G z7GRV3p^cLsIPAMLjenGT_c~sJ{dCE+s2_v*mz(9*O{k3v-=~}$mys#9ZB%>5-pZrN z)8H0?v84vN7~TwUvfrw`o5&^|fj#mgrzf1jQS~L1pP)iGF*wGvsJ|D}N+E8fE~4Lv z{!4Wkge>TDNwvwa$X}sSoqIIUz$-8G5-O-Y!pV=L8GIW3N3edOvoUlIGADTF1ID+s6{ixWS4D-?x5uQUMq&U)4X9yWoUR zj(eiacm{2sO({3)k#4O@4h?JWpLW1w7s|+83VhI|aOdko;sn%aU(+RKsg=AJh7U>Y zBoe?cJ?P%K_owF8AsFa{CkGEWnk*ZvfgZLH zXJZCcGP@s38Lo3UsG~>xW;h5|20pFw=PP`d4JW~d1Hw#OuLtH!RltaMYQ)`xVhlZC z4vAFvPibCe`F{g&iV`-@_!(KdvwE8%q=t$bCd@B6iZqcElP>yrr-*j9@W zJicZ@pfqAsn6lo$DH*KYxXeIB;1qw^vj+GJK;3uZnyj}KIHO^DztCGehegj5XquG0 z?B>>_`_C+^6pL~Jsi zM{O4TS+z1oEC790d*tsl-Nja4V=Le+iwi3wt?0ruzM49$${}}Kj_7~9AWk?6+yTpe z+{*nrVbS-rgL4wTDkg8#tj_XkZi@Uacph-9Qt)##)5R6XbXb zqPR#(EnXF^El(u20A-soNn*)?*1QJgi`8p9c3ySSC zJF^-N&oC#ii04^Z+{lPQ%r-|f9Nclo3Sc`OO~wH4#Wr4SdvcAj2_IxA9-(cfVa2O1 z9c|xhyBX^1k4#GMRwYwvPvg<2kGc0^ARI!-j+nUrGUXy+=|V%HLIuG~mQd$JvM7KK zve$^Aa*+@FoPhK~$rS2DOSpR(Tak%PeBv?_G+`deoj;guW&XF>(6B!M!+y~Ua5@DDS2m;IQxp-gom5s{#$2h%^s|NQR7qvRXZiwKc zd{chLD$pNN0=`M(IZV>fKjq42GiT(CT-=V>cOHN%;>DmW6eHQ!25N{P|HH=ZKtH<6J zOo0xb3&1e17>I1=$!7L)AFns;<6xI&eB(e_TA-0-qWyX&`woRUcIw{hO~;`Karld{ z|Ela^5$>-eS|&L9gFW}-P$5JEf{Xj*PB?p)h>%H1xzeje|I3ot0?atzzcz=bO36Zn z(e48NlWl~GXH*KaFNL`Hp%Um) z?WE@m&Z>qjxLbxC*caMe9&(PyFd*s}H>{82KrTDpQhxpNHg`ovZp(m+BmZj=IpA)f zXJT33eiK#L?di}-@Rb9S@qFM`)|&$IRl|kkHM+(k2GvZ)f&li2euCB?za$jN>h$uoIMOxE z;SrXK^_Yr!vtu;NtU)%tePwot8)KqSnDdbS@%*1(N956V$^L3EOaV99sSaDJW zyi7-;fjK!cB3_D+gv7FilFO=@pGJamqSk&Ja$-*?6M*vLH=}l zjzHpKHV2H;&c-g^ZSTyzhikzE+5MjD@Bi#9r{ltM&{S=3+s(lZ0;E%X%T`v`?pX_E z-b-a%c>>C~6c|G1sCDdY?+&!dfCDiiv#*-Ddcb+QAVJn%Iacdn0OgkJsd4sI@Nco3 zVouP*rp%r}67+naaRZvSOSAbrJ%ZAAoQqvtxWa|^4HEWVuR{s2rG3J(=1mD@vYmuK zS1Vx#D@gS4DkjAhPiI9H=0VF0$8E~p5-9dbZKU1z#qsmYH(<`A_4r;8tDGUu49Ni6 zA8nVy))Ng392h~bghJnU_iT~th*%hBH(h8^6I%wg5Rn~R@DGyNms?35!>M&nHF4~I zba6Z=-~K`5XS++shm{?hXRv;x?35L19#?u+)5CFP7`b8Knj_q^>Y>2!9zDFxz3*)# z%)hXJ$)e4EcJe-3Wh5qlh>a#t6SUxM`jXWk0ysGsi}VUKo!^G#wvN5uMBZQ^kMVk= z)NaLmWh8&71WJ%w4m?}Nwm_gqaW!IjrU>Et-g{DluGqKmp}6Z~T2PFqJr6UDZ0r0c zr`El`#99NdH-4psDYyUaHivf?D4hEXu&JU%XUDG1P6S?^3XxBs2G>zgT^r9bK(QAk&7Vyu0G`}aCT(8))og&58q~XMX2Ns zn`Zdl^?p14vm2O2;*+?Pq(LNlHkb8s0UGgLi(qXJge3)YkdEm;ANxuVX}wt&Qpa;Z zwtX5)RYXA_sX^*h$)`1;L`tHQZ!3#Si&Tp+^~X4XxkGQSK$cC8Snj>TY2IYK#Eal< zo{M*6mK1?|TBz_>WhpC=diAY&;SA=`u6}L^Wd$RyVxNJqWvsmAtDi#=dHvYy%cMM( zlEfb+aq(}3Gc1s8u%z``zfnhRc?`>XlJ!o;1wY2kc#KyZ3LSvTTv=qbimgGPuGL+u($@+773d_ln3bb!{VH zfTNT%2(*7AUNitj-~%tSd`7va-jtE+z!_Layj0p|N!E^|c6$fExc6_2l0QC+Uq4&9 zyAZ!oe7e!g)$x-5eUE{tP{m}GUuiEQe*M?In`Tzk2rg**fH`omXV1!x?UZTbMO3Hz z{t#l&C2ZMD8reZ{$eT?2m=Mrh<7HT?C<}+xKK>M{Pdb4pRhB*?^o-2=S`+f3rbZUB zmX5~BsiiM+ zJ(l>|j(jjZ+-%b$ttmyaHM|-573Kf`XQk7J>?MvZyyb6C^(b3ti0QtUX7(b03XV6P z=Y1(ZdTwKVJ8RyiygIBLq3D8{JkJEl-5W9vC^Q_zqUeJcFZB&4U-6r|Qmgg`JbuwU z8tqmyWVOGBp?+3)ns-6K9~07;c()SCzclwh1@B~R^Calwi@vA{C}!5zZJQBI8NzX9 zcWjbT(p}Rdhv$5Tllci@XEq9fmeI4?Ub!6flw<>$OICB-Wa2CzXyGm5`EOwo=JXe5 zJ4X@pyV4UZKx&P-xi@@iNrn|`xf$A|Q(Y5V6BS4^IofGnEhQc0TQ${n>`sh`yb3~ErVga;k$j*_Apf{R zhNl;taW%WPD>4HwKWP|(mW!-h5`|bR5BS<}wqbQ$-+SI!JpK&Yn^m-8S_ZPRD2DBE z`)_HV5s_#2gnmVB+EPuWQg4af!FFi}XBx1eQkgB4_L3n@k`(kspi=tcZr!v@GGJ9J zja&VY8K#&HI#Oh-WVX%tbnsOzhH;7N@xoTv{%`BvL?sPfvV*y%6(Z3f68xC=)BqRE z9_b=tbV1u^1$X>LGP!{biDQUxr7D7ZPQ0%@l895m^861>4-y0cZ$J@ISsXvj&7 zxiEQs$EvyIK*?id$W!)$1!TgEwoU3O=_;?J&M9QMQpX06Mxx%r|lgowTF$vqXu zG2hU;eX?Vru=IQVf27o-StxKv&K&1DkfGg-spekRzx+*IT3ogex2W+at_9Eq3pROa z?U*Qrtmzyat{TtEk^z$6%nkV~Q?Sy3zw{@*HH9_;GY&RO<#@&@;kH5oxWJAG45Bq`C<%EU*CIeo&a%7~4q(C&?J{tEnQB)d|Ug)@rC6 z?cYeTT&2K&SC^c1Q(VsSNH$+fWk~&~V)x8p&fnaFSQS{HlBEI77^x`H34ii(;IV=i zyC%OflX3Ud{o67lff`=#Bi49&lrlj}zbEWKGn>e-d`(bJJZ)7sOt@6w@0rVcLJaqX z)-m|izuO?dWY~5eA*>3k;ci8?-Mj*mv;dpWdN!4#sf8_j!fD`MO(H0utUM0?7S~aC3J)1VHfU8zz&~m)f_g^TH*;fQd18kRwojo#fzJ zkH2sT@zw+BEV{Wp`pS1A2uFBum_648*Ryx=2?SGL*P;&dgdEoufjkhAZy6E9_d?;D zY_Ebl&apefu0SdnCA)wE4`p4{KZT=*h^5A_WV^-@HWy(_(0CN_O;BnoE|E^9z;(D( zq4YO#N;r2&>>j|*`RsB6kjmMz34=wi)*L~ttnu07Ky4?RqmauCghF6q4e(%!z}qI&*NUio4* z%3-KkOVo5%L0A0i5HC;w`{igaG($rMeZ>ihn=F^tsM)8aQ>fNS`IjE!zu$ikZ6qG% zVEJ!QG6u&>M#d_O-%oFH<}OGwEd#q|>62?L`q%{#TP}bt%caH0WgZ0$ zqC1mNjJ4{Fg-W#!9SoW0g!E)nVDlsl;oV~!l0kL2LcIpTi@>lvWM|;&d-~I(g?1wi z!>rckCG=Xda%U2=c_eVbuMh`1s+)3FA88MlhvuSrYHv30&9n#cw-egPiIau=F}Iwr zI3C`?Gs{ZN1IpIat^p1f2>h8I+~`<;Q{Z2SaiI{`?%_NP`=!Vgp5({C94lmZ(S~z# zFKUTZ>xCxE194}Z76FWpolnRQ5+0?eshDJac#b3BGY#SZpqm2F&pld&1?Z+NaHqL( z)x%Y`nNb9%K!M8sH1}9km=C4`LS=M_Odvhu%4dIry5Jm1Bp8|Qw{;^L(p*d*Xadf3 z?Sh!VRu!vmDXuxcPWg9T0VeFHhMyAgl0i|?0mAP42KyKNb}`xk=7DE(IC=}-=O4st z3Pp{dorXbw_mIS_$~oSJH;TIdhkjR4qSNmy=o=p*{LXn(uarvw!Sai+-ZG-NnM9lwI`1hL?VM%J)6Wzl0ID}oOL$Yl zCo3e1a2TqYrLC!3n8;WDZ=DcaaXj>I1V&y~am^q&pe&=ZvSI6aA5v&pB``jWcbf7Ui{{?<8-OPN z5v)rZPSeHTfMyh^Bjsc4bU;G!9#W!@`laKG6te_+z=<}JST6*CvN`& z3c3#liuDf4(Fth>4teU|{3-UZ$#Fw{{BE8ev!Df0t{I*;wi4i1`lS9hwxlRrpm6DN zuMwZ4%WS9pRA_t?J@lS-%V*7n%Va)z_Fk$MLv}>Kh4_Xj7>8qz;9RcLC&kpsn7x_G zlNx0+5;FA@n$mbe`Hh_E`)C*{sbUr$8#582!AlM$cfIPg&O^4yHZHc{O&QB#K#Exk$69aT{0!B+G%3=8HBW3`m zf;u*96^}}(Iy8#?mUI%bSXtMsvh}PJGD+@z3unpL#I6bZ7bBsH6K*HtiiX|lXT0r->nOD5l6Q*l1xzaTx zo~QE8&mBEK92YPD3*^`&XW>bZtL~#``l5mfT6uBrLV^B@1uLZ8>uIN}8mpb7|L`qy z{qMax#LX!(zMOTDJkfaap@V`5C8YQbWz!dCA@=bO2S9qmohoE z5b$GiNav)Vpg%K=Oo0EkHX0;0#S}y+`N4E-)vc1=Yd)Q5uas=6T+iG)lRaxnvT3_I z5F^_|c&nq+PuON?N2>y!z{XftHV`OA)Sn=-S;DtZ{<|{4PZrWJ4RuJ5+=7)^<)h9r z`vN++SLyC^5#ZU+>NtGFhY#)O+_jdpM|(`_Iy;P6WL5*Mzt{I&tbc<6O{}nfDQfJF zv!6ogU7|a^oMdP0!#y^P`HDyP<&dIJU6P&Ph0clV&T>{q?@#-ts-N%m#$M^KPfQCA zf~oiX`zmqbKa=b4MJ2yWs4IZi)Ts24E3(0P#7&C$S#iqW9-?gM@^(P=#8Nq9>52Td#!Nk zkXH@``1)*3GH(<#TAnA0vsd%MjtO->eXeV3^dmTUj8@JzJ`ZTam_|3CAO~@%RxWMx z!r- zkCJ8W;qCLlMNT*hNi{|7&f{bJ!|OPBP#S^=0s0ye13WaD zat@P~SP!l}bZS4UEsbHwkQqm-#f>2U62Sj-w-yHZ7NLcjUU4xl=V~xaO8JU7VVS28 zM!L!(`9sY5kP)VZ1_;$6ip4L`n^Hv3%{8znXegC%EEl`>z9rL~g&fSymC(Nsu*i&ozS4VpPZ@eGBA@Vi?&f+4tKbc0v4`Ip|wh+NIbXX!T!Vt4Ve3vkg zE=vz(r9)qx>E74P;gbQtHh?DEVP0Ig2Zt^1ft6+z`$Q|W!h@-c61#0Q#Aor5xt*%} z1CJS3rqZRZc7QXF3pFGMt7JL0)9W_wpXHq{o@ShY-5lYv=sZe`7(rFf#}b)ELsscm z6_qt5j;b9&$B2rol2;3ANITOS>RUyVq$W(C;Si(#Oz~CGG<}y$e+-lyRH+yUarPi7^@ncFesRtf;h}37ux8poaxi3#7Ix?df*p}-F8lIP zoEcbAaWW+ZshkDWe5|>`$QDf-5jt7i4SCFvkYyexY_XB zRs`0QFgKArI_?ga3S(sCYvJxA{@dDpkJyc_F#fCS@h~eF>N==-uNP#n71O1HlBbNH%Ck-b%RDk|~M%2TD z)2C!^lTlJLrecz*2%HMMF5{vo8QR!VkY1M*iiUFW`R~2mXD4>F1!;QIR#B|B)Mi3( z5PQ;qB_p_Hs(Xq9*m-gMyLgW_vu^nh#5<6(1Hf++El>tEXT>{ZMAB>zI#aCaT2{$~~QOj6e24oQv7_wf|jVLuP~1^b?$Q8;4i z%Rfdpm#`Z9pP_;%;!J3ouxbf6at{Nym8Ah-8mQp^1hz(_kq_%XH_WoUVQF>&2obIQ zfVnP+=p-~vq1MyoX{JZ*h#gaTr?m(5_=0-rDRkaVP*`Ser%VHo3kw)6g?G*zH%e9h zK0rd&f~vznGI>sxU@PVkr4U@p{LWfvaa@$hjL@wxYBF}pxEHx^JJM@wMjJagWoLIg z-!rnYCB99bPJAyAL4D9)@m+`PG13V1)tjy`u^WdlC!bJzT5h;&~1)%d+X#fziOY9n@Y|@T1RUa?0LcTY(^FjY^61nZ6+>^jc6S@8K>YanA384 z%I96V#P&8+^U29b*r+;6zm^Q&&;K=+D4>M+T!930 z1v1R=^xTP(zy(0t?=qgr(}@={#XZU@MK1n(Rq;z`7J~xPACv!#`Xyaz{X5#XjA9mG zH>D5RAh23QODz*eB7Z*-1Czhqj<{KZp)>1?-0{Z~AsmFb(lp8bBWW244w1{MoGORa z``Ub0#ZV2XG910K2sbQC?y2X3Uz$SA*=zy;xol;bx^X@SxiX)JSOYc!!R;TrF*#ii ze$4sWe|ZXKKNS>MlTp-|O&(v^O|3K-lWOuo&(IxLv)C$}tP5-a?-e;dLypB2gE=Gp z3jp{^WK-PNKeI5(u;J)$aeIR+Rmr|joM7(U0(G!9!izPI+~wqsxEWTB*2clj(n5Yk zM&vfuVh)lWz4A|KBTXX@w&Wx)or0_C&FB&=WD|gFdR~2UDj~EoE#H@3Gfm?Nw%zzo zI*38DlUQtHatR~6dO2hT^n9ESmNvUIM7gi-`4P1gu9#jTHhjrx(5DHECpKT6SdvW| zwNrQ^MFqheK~=E!fWUD|^6ut4Dc}#t#CF#RUNc$5#1Y#uKSpi+? z@ zERa~~Mm%p>ddDr0KR=io?U+={{0$t&fE0ffVc|#B(&7{%8BFU>(4!qCs^{pyNHnDG z)6;%@XjL>Z#%G*;tL6t&0$YQsL*H$exTni&!WU9!YU}5k4oVqy-~F~Yg6xEN%8YBl z1B}i}Xi=xe{IQ+pX-@`qUMLB7n?}{PJ4FR*DT?S?qH`Ai_XepI1%;;nlb8dZfr87B z@hYig+ccZakd=WtX-zg{23(JzjBCu(=u-_^uF>UT>1b1PaUIp{B%0)h(g~fF0Eka# zZcRaE8(U_e?|-@DcF8m&N!hdH9wDN$)hBH#Fi&8ns`;&8mE$*rmb$Q89;dbzTQ|DM zi^CW_k<%Q0$>1Wm{_LrKyCO84Rn&^Z+rvL2GZvPBP9?`Q6C@BLWDRcgD&G*1?BG2|) znDUO<9kE1Hw0FCwaqmJN?qf&PiJ}9X9+f8B1+&H#b22Cnj4mmP@Q{vADhuY-GW{sv zX-Kvgk_j;Nyv1OuPO>4X=XwVh@!eYnA^KLs#Fcb7&r5il8;^RF;?eK{VHbJXgx_KCzx+4Tf9+p%_okEQQCIKF zk5l0+Y6~KraglL(c7_EPt}6Apvc%gTayVR>kB4X-TyLA;fR*O z7FU*AT2V6#yM>?f!`KRno4oyT-zD7Ew_Q3I3$o-~id(VIspLJH@|&B7k*CZ0@pDk4 zYZ<3vdJWB?+TwH5z-YlQ*Jqs#peD#l< zFpN?G%>Qwd)SAXVt1+%X(gUtH6K;BW2oiDc!fcN1t}dnr-4epjru%L3zRO6{vY*M& zux`rcq`TbCCPvc`=H%A94Y9P$uMM}T(OxnMqx8%?h4l+-VUMR=qea)~skD6S$D%Qb=&hKq-dCMCvRwg< zmuNO+LQ^4YxXVj3yo=0Mr66GYyrCr%lhG}6xIF!s-y1F-0}<7rHogi>j$x_CeVyJ8 zhXk|jlNGrer*=kRhit>8zyr0l}0gZCH_>OxymXRrO!fq-})yGPi`q~eG2=f_j zwXkEoAlz=ICt*1Za`q-}>{}5&?XjK)Ja-eAQ)Q5hftG6BR2h0ba{@{r4>OJ)($yeE zJJqU%RoECInhiCCw=nlmA4g|ibsw}gFk(x4C^>Nh8{grkEI5>#9^!bPuCnUtjm8)q z-CBW8EcZgQJT;B^L^_ZJXta5u2YqWmsWkTPNAriXR1xu&;VeiC|IAF}zXyPB7a4t0 z;KL+8p2I}En$N@9PKywoPTD#k!(NE-8ZjxO9d0u1@{$ms+b-}*;2&}@NS6~(raawI z*UQ5qAQir)k0FI9r1JN6s?Cf{6p9Aq$}})T3l&)xc&gbIVUSEzWSf>ndE0{TI1~!` zPqt|4xF^N727qSJlJ?4LBX^qapf(JJFaaICBof54A^wOxH#q8Nr6I2Z2uPqJGHs!? zml3jyHSLfCW(IW=HapcYLVtB(&Dcf&*d6aYLqG<))rxY3+iN&ZIAkLLN;W;zXw;59 zqckuEVZEP`8mudi##_LrAMj_U>0{zY+qfewM*I@8(h>{rs<%$s+0&O0TQyK=Ha+|a5P%?- zWMcp489a&x>oR}CSVTWIuLJA zvs3@taSOi+=shEg(%b3!i{;Tj;$>zpg-4PpW{fsv30FFQPN+zby3qTCwCdYT-ZQMk zjUx7+2$T1=yfMBoBcrakS^Sxp8gK~tX2@{wQ4mn3CfbwPD^Gb_VO@%@i$(ZOJIGy} z)bH*YxaM$9Ue4z=4~)O^#(c3d6)is&^#^=#YXJz_o0SDr<@~de$FRqqLL`O=(-h`9unim9F)&%c-Ar3{y+cnLR*>4<8-lv)6>o^M>}5J*60&S^fWe5&ha8@j z_2AVle$@W-h-9TMX-15)X;E{wV9qM3P9b-+8mUgdErOSQp=p50)UcUHo>Pd9JUZxtf2IPuE&o)pOx_@6bthL{ISuoP z$QhwwgKi2(iaRzh9WHeV`pgAKu)skZEBh5&3O)iM8nOqHyTD^7!bMUaB9kQa4(3qp zc@IBlcWt5?mdxo6J48vJ|2VK*b=|0&sD1NMn<-9QRn12vewy>pE(@Y$CzDd*`NHLo zBl2v9-Gcf)(PfmGf?-5uz;2Co<6d66ZHyAxtO^b-KzTIDL5 zX={H7ZO3t{e!1pBJ<)%iryOt2%xc|$teZk~l4O%y_^xaM3oHF5=V}WuJ=3L z33PQ>rfDhH3?F_>d%D3=H|ZMA!&bzUgKuTg5)HgaR|%U{U?yEif+(X|g~{eRX-!-w z;w`trsvRLxc%C5NLpqr`ujn!M0*sFjtyy-4jYRs@imHY@L&<~OH7|6+kD3pB6uz-d z8292O!uxTN+wYhY%IuqSZvMl-K43+1vfDSZJ9>;mfPF6o0vTjD6T&Yh!8{ zudN>zPK{eC^GUoxMu{kJfA8q$-#zKA1@jE!zS?U6&anDAU&Vy)o^9-NEdI%_o5FpK zP}{SmUR+h#@)8|hxOJ69G}!e|HP58y#BC?XVx~8=l$!#6w!p2(%UMmjQojhCPM_k! z64JDZ_$;HNn*qt!^ym^@=gv^u^MkkmvoagjIc$K8sWpJ_ia#a{wY;{IWW-FGZfy8Q zwSq5xZthsFoc{~s*^wvVpFf30V41;$dtG`{SF-QRZTgK6%A$$u5#UE^NuJ=HaC zU!i5y_ZjH=rVK~8%sd(&JPVBTMa41hFSmvBi9>^D>XuAh&-S|3*SvB-0?12Nuaqzx zk1?C{2>X_>+9TL;`5bi|`Wz|&kLQeB%9&^|3|hhRGWfWg${+;@9ZjC8V4Cuj?Iq~ z7F8#eJETRbqp)1tAwrH+?Sdb>ChYrz!QKkUR-iGINIsZ3DkKH(0NU=wQRHcsS#o$8|(SWGDY2y%J}5GT7t)2P-0JGL3N)5=OS z9Mzx#(JGpzNGq-+$NT&jew$N0u#1l<+Mm6-R@n$$xKlUwtz5AoMefYFz)m$S#w6~q-NMaN+uIHdF7%oE8I z0S{Bz(`pg&@EAH9;E+J-)T@-6Luer{~_>1G}7$1z}dVJ ztFmC(&Eb*G$&>h1d=?h7i;;=ZpAI8qt;FNd?xth=qrS}5mE+pj zL-P2!ywrCvs*&`L+x!*~@=CFCgy60K%U2v{<=}ZJfZq7b2?^n2RrYxil@5z{e!U9QiS zDl?Gbmr8->{9*or0 zMr`#%i{x6ah03nfu!kESU$!-FA23t2x=YSc5reLa_x59RD|9l=(brPWI92`Jnm4cl zy(ZuebC}UYwsEEfETf>q{5b!!l!ougv4nmESIu?qFj8Gf+-`p zOe*Za*AEr>=V&9hVn;X9y8qee|4+t`^tE9XhAIUw4tu1GCr&SVu&1xA1Z~Fp`8>j^ zgsqvoR(|0DCViZ0&wIj`6aN+LcJ zM+YUHufWr`>I@_;k(&c$5;gy61QqlY7fqcdAZu1^#go>XZ1FXo#O z_~VWQ6!uIvyqz)y>b1VMdW$K28+I>qBw&qeYP$%r&fBSO zYu`>D%8fS{6Jq|Lzw}whG+|-STp-aJhEWO7(d_Cj#~_p01Uc3;t%p*r6p(;kmLD@7$Zwj}K`GYFo-<1nc9a z*`yy>{(#}3AxlaY$41o`8BdNbapcxZQ35zIQu_~V- zYPn_Sam(@i<@*&G2HIq&dk=1=WOhoQCfz#_$Tstc2r3)&06j7nL$I+o^B0%?eSpTH zp(T^8XQ1cNcw?NNddMY1G3#>26kE2!^+)aEppS-CkZl{X{I=NieWU4mH#M0e>~773 zA5wD|9r)R}mw_ESj?cWT6?15?nt`Rayn_KFGj9v>?-)9`U9b91WM~xfWA>Ihanh$c zHX~zPBRde;A%T-`6L&}luD(^EYRFH$5>Mbr1y~loZu|_jSeblZ_uI^<%0wxhQ$j48 zoYf`JU$wJLATB%1X;#`}`m0CVo10?~xg&@UwJr>6IcTngYjL>Qo9^#+(WHVQiTC1FTr1;-+~uA7JrORWR`BaTt~oCV&;{Jyro4VynS2ly{Z!JF2Fv@3YCWY z&qI(!JsS7v0$B;A7T|a9L9GgQwN@Ecc(KQ`R|HEy1AXqJKE`m8Xm0MR1TxWc!FOG4 zf+eCNi`tSmY`6So=;ZbI$ldVifc{YVHgY8GHo57yA(8b$I1jQM-Du%G3_@tfzxpf!iQU-My44zEWy z28(GsGb2}jGQ^NQo`g}^8dX3qh8Du>TN?ydp?=>=w!z&b4IaZS(la0=&(i9A&+~Qh z&RwHgLSBi0i4WSh#n1#}+i7aE2+B#5h=91h?RN7?-g}9D*f%Cp4k&W?`kTb(MJ7E> zvoen`CCU5o=QdwI+*v4qUUxu@HuNDrlIxF8ZkZ~<-aqLxW|H|J6(ce7{u^&nN9VGv zk{~rkTPGfDnO3gIsR!}7#qZiVw9{I&#~R5dlsr4JLZmfzL10C>iMH8pswau>WDY11 zxp}6LzpI-KgBPHp*Qm(=%N@_-3J!emGHYV;z9nT_btH|#2x2}pnYDW!_jk{vuoFI?Ki@8?oqUyR=d^FzYQG#WQhp@foMtGfOsOs16zPmf%+t zh@rtgF#JWZ%~IKqu-y;C6hL9}VTrf}Ouw9mcjb;QF$qQpol_$aYftpuG4`vDdbLWK zyNdWmq{5(7{PvE)2BCdgT}Ub~4#O|wG@U$G*l96V!XV<)xFj7gVCabfT5FJ_)2SdJ z09HY8w@E7vDY!ySVtIhfAA8^u82lLE38J$pj>aJyjQ*kM-8F9b3aB@Y4^s^_9VCG# z;<|mfvJMLFbp%T3X`1X;%-jhRD_N3so$q{;;C<+$a5>JUImC-+uh=oC@;a)+G=fpPw$e^Md$5#)_k$l zHUASN@Xa1i!~2_bIY-EsB|zUcuCzR5dFU+_~NrufW^GX1?rR8`clg z_lPX{z4p{f(6bhRZp96db(0g1sd-V%kG;V(<&C`oc5-09@b!q7R0N`^CAW$CTrls( zyDYhgFCgl64m&@HESa$_lQJf^JZH$hs`K4?D2?zEiXR4Q2D71{)OA=xT{V}kVcRuEabB|M(9Qi9wo<7!*d&EoHY_)$gxAdN-T~*c%DsQ$mc_Ru1%;@?f z9mJa#ZSUnj@LTSP1^ul3^1R{%pK7ip<=6kf@DC%;_L49<7EpX6p=5g6l-B%Z$1hWn zxwc4)jY5TKv6sZS=_76Hx0ADa5x_2Lrj-jSen;gkJD{vcOcKdKX1-CTE7fA_>{i{# zo`{e$vVrVMVVV_2O8xyrfbE0xXM3haS9uATY)lP08JSjiXiv!QJ*KQ4nMoztd2XjH z+V}T4x}1)86v|X8s^SCKy-n8$U%V=!3#<-l&8F#qu--sX-Q-(ufOhk*0_nX4M)A!# z8~-PMp)A6gmw_1f(tT4f(9i>w6AOx-JDKN>LSt#KmVa;!zYkj@VvTlem~o45+jiGg zx7@#)x9)e29cX)S7slQsapWr-b##YiMXKHhvT|yp&c5E&G%;4KLe8)Wn}3RAG1mXFp3!a_#1Pgu{y2Z8~4R zHL7;rU7MFHv=~J*HtLq9>rgI#mRKTp!F1yG?cI3kQaEww^WwvJFJVGn0I_R0gjc8; zZDMV!XylY@Ve%3D_k$nuUbBgJ&cjjHg_=y65A5f1-pPO$hs)Wv@PlR&MKA_!17Ngb z%J{<>`Rv7p=ha}SBQWL#$`^eD~3$}kbfmSQ?Gp(KoIWDX;cp-`pR!GcCqh_ zRupp@mN%^2jreVS1ymftvi2fl`iL^RCZJG15cQLi9 zP?;kzHm!WHM1Ja17aoA{zOb~+dDcgs?v=VwXn20*3`#8fa^OL5t4KvavZ~VPN5zCk z{(3$b_bi#lD?>inuRf#J@8*tT3VyNch=^gfc=b&v4YFR3r1F%FlY8=bY~3@21x8Xn z%9b}jfo^$m`k{lQ(D>d|QRvYZeAyz(&@lHTewIh}>$NwBZ3lp@Sxj0{2pxOpxToBW zsffOeB)AfM8c%DL*Uz18TUYaM6{`azRJ!ofHh_soVz|D3CKBu_ zmR)_#cSte`aQG0og%23sAL3h^voROFm67NI1&82z*3@shY-){Q%NSBcdD!^O%AEv# zw^cfSSzhkFjb(VH?N*Q#vyJn<*nNQzqed84I_CMCg%IMN-J5PS@3VVXt=r{`>Z2QN zv@-~6{}hT*8l?bPZu`XLsp#A_3$MC*bOQJ#8^@mEQ``d2(w(*y{%Ri2OJp%YuDNF<|vt7~S5=U+D0x^v3{EsP`n=rWm)YNh(Hd=$V}5Yav;0vH(w1 zeXj3;u)P;jICWjBOAE_ye)Yg$)L2q@BwvlU$($96Ufi9##Mk0h?B3&Uxv&WHwTaW7 zCm+%@MdFwk+Goe5DN;`b$AUx!6PC(gO}7j~gI=4t30)~L-$SG>51lM%=e<-0N-S-= zf7S#6lk>gX(6`)1G9%0e8tdHaR#iotRhqj415|z5sKNqM@AYp&f?NrJqzdx6k2wl< zLU8xSZ_;2SlR|pl@&-pJht)^Q2aHYy-_Wo0>Y{91xKi+PJogj!nIw8X2kDO87JAz7 z(S5KfL)NU{i)$NRRv0HnU*x`%NH6r<-fKellr>?2*0(ifNM9>9f-25%d}T#3AD`|5 zN=30=FfBS?Z#-wWZ36^Mw>6uR4MM+H8qH(HK$h zrq=j| zpBzf@Tcz0M^L8OLJs6`-pwuLp+0i!faQ={e5Lp<4VU}D zs4avxJFy`j$tid*k|I(4?9R|xX^fMPmH@^j@r#M&`zv{(+nwRXfp4OOcVoE2%PYe) z(MXWN@ld-WO9bgr8WzyI9mOj0lEak13>;_P$E2?!qK>^pBBx6`Dh` z;?T+uKe@a}v@)d&m%%$ILLlG@&-d)HC|H=qL{DDNBnoVDU_>Z!0S9@(F*w2R8Y*j1=S`w$s{Z>;% z3adb)RyuE|-+z~q!}b{dMTJBaXnUg(!4drqrMaOOlOP#c&Vbl>5NR5naa#E~#PaYG zDK0NRKs|^VoCe*mGMTBjVRKo2yq~VZ$$Iq zi<=X%@D$AQYb|LKI4mcV*D8|+rodgAzMFTG8;kD1Gr82`Vo&YE#%W&J5%HOZGg~q{ zjdZie8me2No~+A##rQ;*TXCVE-c9exv6ImB`714%v2>Fn0<~_v*CiQMml@C!Vrp1- zyamqENe2Z=m99&D9kGTJC@+m_kaLa>Ma*}P(?F4zm^1Hrq(F$b`+>Zrqyc$SDZWXU!N!%2T z14ozf%D^ZlA4OdJ8ngqoAOFY{b~r zywH#NH1`Iw7s&_eI?nCYq?<8g+{x=@dhgXZ%%MT2BGiGOz2~VLEu@Q+t%ifxmpvEr z9MuS)c!li8VSe>aLk>|?yX=Mk-G zl(TNb0_c6~BN=|4$ro7^1E|#Mx8?OCXnl+1FNwuNnZsZF95D(YZ{@xX7R-3h!3`hb zOjW5v*)2{pP2nYv=Cz_0^AFcDg-k#&O@)sPPNeR?c*63Age{qEkzZzzIY!v`sGGqT z9#Gss|CHwYD!EzVs}nXQFtjrm{U*a8!8nI>{{!1#31(zckfs@iN>KI1&R|3>{Qm3i zk}U5*Z{rJQE#EDcVkPXr-Kcjo;%&WMjsZhfr>o=|6iOj(dV-zb7CA+TY7tvCP;vP5 z+r%2L4QoeLWm(iHbdy75nBF{9eh!2+1uq^{ z^W4GspGAH$-N968C{hae>@nET8J0CvTP2LG=8)Dz@!p1a{P3`Pb>0W-TU3Dp;fWZ% zH8m35WYtM^Wl{_6P4~I*Xf~^Nfr}_mTQFl1Z#_{Arje1~23CY*DPU2!h5tc3*EF?f zozoWo8vMDung+XU7Uyz|b;Wo29v!St=N6qg-1oZ+bcFHS1hs9T-ix~XNPa4D{9#W@jk;0!s~{NZX5`3$eZLTvAEw1YuZ ztLlC&T|ep`dhtRYVaZ@0^j2Y?uisV>JEvr9DuE*!PB{z+DE-a;GK=d-({3DbZ-IRf01kaR@&Wmt{*ymTB_T-m1;M=A3 ziqcCA3!IntScjBa!|l>6ON6PjvECJ)<_D{!J8X?iXzO zTPMV~3G^sB2U&F6dp@?KNl!BmP0UqIz$4P6v%GZgHb%WHL zStM_w(I)W`h)xb$8}cIMMo7;>HD$?s6vk_q*6H1S**(vZ$HEPHHsCQgJIV=wzDV#T ziWK+Bx<&UUw?1Zl&mB?Bk2C1OuSy;4h3BQ4e3_pdU)~`+VyO-K$pnfbL?1|dX=YCH z5|J4)tSPKxjmLaHf0c|gHpyU!Xhx>tx`f+lMorj2Mg_^%NAtyb0@NMaoO`1KZFZ2+ zVAS<9+MPB$tbP;b?&a%k$F)+kTdLi%yUAD6CB|G)58pMCg3@kEP1kA5fs=|367aR< zl-CxKAnr&7#O zdebHSP&3P~2RR=LwQ0q88pd1N6}fs(kcEbbxQs|+CE=|dAEt=8gye*1y z*;-C0ctk(EpAXuhSGJ3>Tpfclpgc)IXVxn3+t5;5+fsFR7)ox>hGGxDsDeLS{@x(j z47o?^*#d`9n|(MfiMH2i-(L5a2KcxsAKDR8SO*Y*`KY(RvGw90clHfLh&W<2=Z^AIc$XZfj+p+dh#7w?F?keF*k zk92_#?RvvNN_BpHrHCw+A1FL9Mwcv-;U?~@33|UwoYOFUtOE<-8Wy;l={{(iO2j2L5nJ%yA0PXt~tCNrMmA|HFj;|2Gfu5HfreUJLXvXd@iPU@_ zs)W}oca}i40N1v$tP6MFZki7KNmsgWN~ul(^O4?{nq)Fl|CTgXh-IzT&h`8`hhpy) zbwY|B$e+QZHM(;1-F}Z0W5%5I*ked7pKl?z$c5ar$xYIte|@kLm6Zi6E2tO5lU4oL zc}y22N~!r0sz^#Gd+qiGgSo2p6Ep3{;TpYfMHq^9m%5*sH;9#588xx}zEz|!)*`Hu z<$C$bFMlzCgXi4vUE8zbNr@Is8w>8J!Vu0rVLf}sF-FNJbmI)&n-SY&tGzfFfok>5`5vq?yN@&}Ic?cy zlLe={QWUSk=XXoPec8&pfjLwz(vL$+L^y|-nvQ6npH{ytDt~6uQ*$C~qDu)Ysm*kO zEYPOj(SlYDMbX_w_l=GGWqmW0?njev^Z`$1+?Mv)Y}rInGpxLRQ}I&HB4v7{fu1J}LFk%e-2gi0vG*6G z)zQWxe_&nzYKAj11F^{bLam?$8rJiN;YojcTDRIZ;jd&(sv zyNDu=WVw}^!dcXQu=aoNqnPRZd@g@aw*1RBWGHj>E9{Jqj3U6b9rl3ALo5^aDMoo^ zWd-FrnRbYe+D@74))uAYNNiok>$dnQvfD~$15Om@p7LuiM)b$%58Gw0xJxwhU4Q^9X3(+bgJR77iT7TY(=Dq1t$aXTV<&Af{S0HrQbdX zMCosNAs9KwQ}2~fyr9tP3EY?-LMKP=`DvG>#m4AA)Z}4n3{9?l+;3u;d|ytqicjz( zz&B)ANIG^UJjf;bU@5%w0(W%Y_{ZD~H1F$k7&F0kX$)JE@$4N6%%jWhs#uMemi$&P zff6rL`{(GG{ASN-@p4_XZ6@HEYHK8&J+XB+5MQjX*K@dzF4!`(0Q{Wz{qx#E-9*iw z`&;xxvvKt^AE#Q-+FUJ$91^^63WyJ4%%K2lZ*0j!K56Hq%m?WPSoFMh;l)u@e%OtQX{dOXP81<(9ik#!6k}-W=^L)LR}e249)h;Kg!_l$=*wRx{dO&K z^mRF!A8ufnN-m0oq2iKIZCEoNe!`JDZzjBoelr32+O|=LQQ>I}P(eqEZEMih9_E zU$t+8+*T2+G&EnY65f5I;42yrIqa1qMe+^;`s|UUq+>r$gMc*6yGWYJ7S3|+*m*}s z8}ozWh^z*l=S_F<(7RwxBA>urEm0z}NluEB6^f~{RA*j*-2nGgSmAXo)XH<1y%2SP zszsgKPX_YONqcQ5OY&A2Xxtb`z1E05PeafiH7IZELhO{Po2$rb`JVzEhJ7{0V@h7~ zTz*J5=Zg9F>~dIZXlPBk_*d(Og$%SB!zlJFS|?meR&gLr`DXR0dzBKLmhELv%j(;I z80h%?0MWdrZn&%@U*AjR1PBLcC+}zwoPV0_ES&!}NjbAr&ErMcACX<8 zKESx|>M?xkAV98qWH3|AW%vda_eK&*{4x!pY56@_h`E$jnJ1}~}mU`SP813N6Ko_xJeO`6G1}e>)(T3 zzVTgWdr^&l8hWKG*MO$+3!{Lv-8cskJXmj+1&%*h4;b8oC7T!Wa_f^sk5qRs9rM(-I+Pw;SU4EYF|9 z5R|kh-EieWK<7Pj49W<@jjfb_9x}JprQrwk?-XVDNBMNvAr{A?p)(nETWMZ=H-6$$ zBzfN=4SAH7W$Y)w{y1JZLf1E{OBxR|@q1?=5#4&aL`-Y1rx#|lz&b1cj`O%Zn5Wtc zGC}xVz_~Gj(SAdAyMmhrEZIsa1sOCq%6!xEVlSIB%sl*E-A0Ct<8-KeT!XFL)mIQs z)6@H%r3680WM|t1X66&Ijr0T``FCOC?P{M1jF;nzqWB4v(PJCdn`GQmJXS!C3`e3F zFdxz;zn_*^FZI@ZSwE6b?)yad@xG`=JYO!feoh#cYnFeoBSPNy60LmE^i6{N&DL;y zXb%i->V#jfjs4Dele{vyN=((o>o6xBQ(2d5#+`;CTfe$+c(}dW()Ls#nR21DpqA;= z#W4Xy!~x2ukF9zAs%1WFzSL>`qLwWPK*shk!p{m1t8xZS4UZ4pbHVZSwulCU`|ZO_ z7GXe81X*tHo&0)O%~{-V#h28fDoZ~mx?X2VN6zD}vYY#h7B+|56O~d;k4Kgxt$9!^ zljtOiOB`oTsmAP?gKfH6Bxt%L1u`eH5jn>YUKZC-#%mDI@sJKaTm+9eCp;U?VoBU( zb@f>Mq86cdXNlLz{Z&3|CaIN>7|}(jvI?0ZK1yW*nH#7$z2r52eSM~{<#;IG)zQdC zZHZ$n6+QkZzW4aUOYh-l{a=l42AEsk9AuY&(tPkTBSOJh`50iy=wTFY;qkCrg$UWf z#|OXNDyo56Oj{iCMP8owgjFQ9O_JWBl1>B$m84}uerVFt_c1D5XPIU%`XFqyXw3~{ zBPv!};No;4P8&Jx${USHGGTg zSz5t~=IT6}2wfIE?b*p0LtN%1cOGo>>M)yYcF_!FcAj+l-v3Z}1pVU8j^rKEWHuE_ zoNW7GNdaENWD5fn&-b$cNQ&;C?GBAT%?jemG8xIvUiqBn2!*4t1N65-pWp3LDM{zG z$3yrMTXG1Lz+8a(r{j(>tl8KfHO3x#-s$P0t9Mmj_Y=6A_gMsTFf)dn5>~4n=dr;_ z^UcJdVR+}QK@X#92?rzh#XGf?b`v367M`;z>+L1^i7f|W_z%~+2K^d4&_Xrn#ZR(& zk-QVT)K=n`N~>N;#h>bH7Jr2Ls*{9S<<-g_e^EqO_`#Y5pC%Rr!&by$0yB!*xry@> zoA~AD_s`wi1fZ0Bw@2d5Y!qMdtWyexR}G;LS`;e3$X>omN`JH$H#dSeOcLsm{9I^= zn5jR=$v|aKI)#;3JzN&jbi(-!B7Sn=6*JWL9H!ch^WIe_(-~NU)eEARNCPb5*{d(x zVe1GE(yKl2edIGO#n}L})lHd{PeP**LKFR{b#b0LyrKvT{ns~4 zCiWSZk$OA|Z$6;^qGz?A`@BP=$Iw}+<_l@^P*bJ!(8~-}u>>frY0kaUPW#F%fR6Td zHcIUgae#gJ26MjOA`h(?V_vcj=E2o2!$#lKIBJ93=`N4ogRcs+7F&^nS-e20-QZnD zQ}Er6;cKb&$YhPsdO6IP1tQ&6uU=!h6cQ55GyJQdvK%xNVn-X7yzh*l*NJ2^huFIF zN^>2X#si9CCUu1+ zAOo#*bNzD8QZDe`v2$OI@e6l^dty#=+E&1+YWzpl>le>U3$@=v-?`jyr z6j(xwc-*{NVuw#9(6XVOF>n0pgIf49E5^I>Pq1UV1Kj4|As~72)HIFitfpO@5O#_q zhCo62`Gzsm1)bI3Kk7ob-s|CS2K+cq;t2Mq2-;7Ld0RHg%dcu)-pR}4&Chm=fB3;x znh7Gt&)n21_;uqj(TBOzZWQ;oyGvYpM2MW2x9!f=MPwleed($Z?S*Pz881Rb%G0+K zVbv2Jb2Q;!D3UuTniLMXt()mIG5ALt+n3^g02%dBO_HAZePlw+W1(XXB@L-==wDjy z9+Ou(eJAL*$FJDkh-+hRgW8}kZLe{H!o5nS3-HABl@!qwa&ufA$zGJnEiVGO+6EL7 zvTp{7jLys{P6`9HQ4toKX$u)L8#E1l%kx@1s2R3<-Fk#!Iq6>bg!i;QBY(7b8c2Zp z;D~Q^{iBxkrZHOBYag$vgFJCWNX>PD6js^TLkb-N)qCelMVYfSoY#OdC3i|-6?gT5 z;JZG%Tg1>~Ox_Pq*i-9+b>B2mMqzPGt&(70ir${vCLRauR`|-Nwe3>mvrU!n4t|oC zSk${Sr7bV6wlo?KSL}*Hg@_|?(;^7glgxatSoRfnm4Mu{A!V8KhNde6riGS^Zcx-f zJuhPF*k~``8&;EfJ<<4#;v9!W>*Y)nyyMGW27zU`^vz zn25{yUBfO0Q}a4oY~Fy=PfP~=eVd^k!5CI7`v@KJ3O2{utb z>V3zx9g>{;l&8=fP5PY6drh0@cXvJJiQ44EK_N0(ZSh!L(Zq<}k*9j7O}JbWL60

alCV4p79`Msho!NY66%VAyFC@bN z;QF*eMBrjf?_O$bSw2RO zhQF$c3-5bPfSlTDz+Ro@IJc^c4mTHX^WC)`IKXWn@O| zCfPAj=8^#wQlUZIKQGfcHZ6*~AQT1JH)gvcy4Mh#-XZZ~nh9L`wK5H3{gK~(67W| z6Z8w&XN2D~J@0h-gznM|e6OS|l(UML@nLU5i(5FQPl0P34`hct6poVjW%D1o5FSla z;Mp@@BFt5sG;ZZBZ+5WuVh8$gSmDc8c5$&CO0m&tr8Ap1Br)7anH~po>qMLTZZ#T) zMJ8(_^aBYtTMP>p`t`h=3e!I9_+r}agv|z~*1=xrJRWQu&hGWZomid`n$B$BDU%sbZA)rG`VhdlaA^$sTJY7sERdy<@A^Qz z@?@0lJAHdb?qOYRxN28jUwq=4V-=TB{u1-2s4v?T!&;&7$O1BzE^3!w&%MJ#T-3BG zG-_GQT~++M=sdVXj~m@<=K`r9H6pKmK$@f&2A(>0+z^=|P~v-eyuZTa$Y}Q^vsax( zW-2G1|5?o+8zCw(Ql9)$?mTx(^5lc<`ZiKh#L#|(fOOnCd{U%_CnbM~>XkbD@&X|? zn=pOKbA$A&)n6@Xi}O2|>;d_wb*@z4pAVK2iB72100l+XfGnw$$n|n!(DWQ3Vu5`wSFB1E@9t zZEZ z0{fBaELkk;njH8RP&o>k5CP^eSWhHcZ_z6f)m&V{_Xj1z<&RKK1<6z@e0*!yb70=X zq86=f8#Ly$<*qft3Aks*sFBzaIb6%{P2-`eWJ;6bl`MF@U$J?@W+7IX9@8|wgGsI` zqO~scOiQ4>Xe_^)s_BV~lUjEUj5NlTK!zf^t>=1p7`<=K@}aXwPV~>cdg{PHQtqI~ zyQ9rV@AEHx&kPT{Yl2BP!sP1mPo zW9wRo-wbDzN6r+#D}0T{Htglw%?MHrN~tG6=a_}CwV{0*`vV;*HZMJeJCMp-yPnWj zGzw+TCM4Pa{Pw!8{Pon^IoYR|c9;E%7S)y4(fzgYLo4x`k)-A0l};+}Lb8Dk(VIcc{5z5^Hs zBcq`Ld1vQW0eg{n4}2<`lRelTfrtd}yarG-gMN-(~u z+IMvM02g0tHIJ&0L}^A{`J6K%sH36uiHDJ5g4vG&mn5Epha^Z8`(|rJcSGOPlVbFj zR2C8~=fqOA$w8`hTQ-d{(A`iIRCyQM#N#5t$Be7k z+cu22#fUYCX4rSMMOB4dzjb*DDVqfFxm-Cek*7GOwhd(S=btA}uODGza4XC+6nY9mYNdH)da*>d4Y% ztfys3_l>TpA>g{%y5loV!OSxsst@#4t8JTZc*rOn%q%;G_$n6h)E zXcMcDT`dU;7HEu6vI)Q7V?m-81*Yn$=7@_;5CjA(09ywR=LG2Wp4u!7{bKLMI+uv%t z*(2q~9NZnRFU_nu#}3X{yUyC$vAdSsxtF})N@L7hL@r4L`)ShCq?l4{XDZQRuTUR; z+JyxyxZ5^uy2VHP+h|kOyQCz-)wuA6V6x;z5!`^;WK#O%w%)hASLep|@RufEAj{_!@zeY+Xh_6Uq4>UfGejd)6 zfL!)TSvQcIu1s<+IU=v)n+ zjBL4ZEQdKKZE^fM%qbv@9bc+nZG45*;fkq}@-4)Wmdk5`N{NczyaPVyTcOC8>KKU2y&3oQfxARFvw@i7@#M zf_5a*q3%Yl#X^Na0o$zjT;7Mzx*)4!KfE6{KQ(~2keg~rvPr~!o7j}QmPB)B2#|JTAL|l5-KGpy7sP!D=@|1LF{8qTGXAbHRT7M@J`|^7t%7e;*CL;0 zt|g?u?3sG3f6DYXgi?NwYrTf3ERx{Zz9887EQOO+@qw*GgX;iFVPcx^v1@7xau$h> z^&)D&O=BWtJ(69eC^qjT-?3X1xbdqGLeP}H1a2^GU{eCJ z4Z7`^%6o&qkjN+a`%@!OqK#rtVlaUwdVTl}*@iT@gOq<9ZHT12vmj5g^Gbn2>nj`F z7RkC_KFnxS(w*-l2`2t^NUl2xx>rmfR-}@39bTP!+$|emP-?t{z-9)lBip{;w^P0y zk+DYnq}u|68ar!y`YILUyIR}XRP#*y&up_Y8YC(i!uUO8TJDgd|Bf z@+0_X31>S)D6#sYsX$sXc);mClA!RSjm1EBpMkYn7H2#B1dlLb^aNZ%jngq{g}3u< z1cEQ6FA{Z@6-uXgD%edQ(pschT45UzP6eV9y5&(KwUY@34LfkXw~Z>DTU5l>rSgEd zMt3i>cvf_;(5xMzz}zP(Ct zon6mmk)*Q93v>rDzVNK$``8By)F?9?8z;fit?2LiIqt`k{o98)-oqd4QHnp*iHNR) zulZuk{8&`O{$rH%E0F<+@5hZ%K-W7V8Yy%tLv?s%ki1i}E_JcoT_^U4iVtc`$NNN_Y^CdVqzo0d8oaWK z>{rQ*fAb0=9yV?jr?U|*@egbdtkcsyC81Yy$5-`OH~seyo}CYSsQz2BpYdI= z<2&5jz_*ZrkKbN)Y&PB6xnQ`-e&41GY(e?=*06CAe&AofRXG|6fupUT{s=hu4N z<%7P^XE7El^AO&>(&k3zJXi$Ox5LWy{ z4;T7#%dz!ES(qvlxJb3rw2?6&*tb$Id1;~u@9k?_5+liNKKZ1{a@-Pk18lxRvib|a znP^nqCJCAdB*N~eRVDJV1vvZDT^a4OwZ_K*Tw{bWZP$;%4sUB5@L56#*aZ`L;^aFR zu$EX(G=3%BLGMGz`%X4z14#8cV(nyTI#-ao(QwMCQXOB=EF+jNJ-p3dhAEm?5xppX zTF59=X6j=Xm4DHsD5`mDmEI6?TmSvj8ux*jjFG^Dc5`4O(|r;9tKLx+M6%*rX8v`r z406u&DkTJAmpQc`mpb89O3H6>;va-;30>jIa3o<34|pRfPu%a*Pc98H)!#C~{?ZNM zZALod`mj-#rg&d%7XaBsCH8s$DyH7(5)W^~R}wDXuHvvT&_UGZeOW*OB>mk@+8BGj zBji&4D}lt)=6c2HGn*g>LIahnqwky^xn39+3qzY!G%7&F+IRc_?479#tzbo5C3g0uvUAIc-TEoOZPH_;yxCs8jpv@3Mj5E5t+E{MC!RGWx$qRHekn`4=pvvpoh zj2>~HBP~m{Epw{KB?i#W<-%9Bp$cpGX+q92Pmhap@$dkLFD#4fNURf1hxI@XCMkIa zv%k*DkBSM4LR#r@9AP)y4T_R*ftwK#tcn`4!K|ny>ZWHgO=m%54%Q!998hV9ZMigz z4cmp=#pFBBB^eNqh-YiMcd6G>9xLWDpDU_ui$bpr&3EaxKg~VaotSjrEHMW$`dCLB zA$#aeXNfGCTT8&qfT;P^+w0)d$K@rQg8JaO^@`kj++5C^ie${C%)>wDa5Szwk^ybup-!eqH2d2CY*H0*Cfo+7$0Di?F6VqoWP z8C(uqm+C8vw|Jl$zjPDKZQszE&Ui3q-pVX0!;3t%ZXRjZ(G)OlO=Wglg1!#si57^S zPB>kT`4H$(hcmd6sV-?6J62h>AXb$wlZk3Kid?m~mLz;vhItm#l3sBfbe3~pbBiV9 zhZf>@re>p`o$X*npm?)YK4o53n`-*5&zbpGj;8F1sxDTpSfv4tUEoSXBZLsv1M!@R z@CWRYH&e5sY9R{0)Q|>o0-e0s-dR?ZIOqKQI@KI)a$#|gWjsO=V+d8qPc|to*emhB_xnz4t;NguIRz(`m@|nybnz{BA+s+!h2fHcE}MIzP*>OWAoK7Y-dKcGi9G%N>4Y zaIxQN`Z$ST-lL$Py{_vg^Uc|Q37$SVGQ(uSXZ_wy4HEx;ZqD&-FEvv>-P?&1o{VFM z)KfQN+;n39@2%E1B0^*CdPTQJeZ<0_-UtM?%ub8pl)B-ymH1PNK!4^9cD zNmfF_SjK%n7k^bAhdV|i4DUs5=L&m$bBlS%(e|TE4X;LlJFlIK>`X&M8CiA?z{(B} zU)tsNu>CPfIff|Y15o3sl|Q!t3}R>~Hkd~p{iU^#hHfJ#8kEJ%OI$A^SS$~%F)B+M z5)KSs&}{o#r9>}$DeZi4Z+=w@UC?p32wE;@=FB&jtLy$&440)OMYyi263ZoMclYCpwCt*5-`k!327V`7l%4|9s`qz} zZ8{{+wFJ$K-<92Sc(LW+07)HLDIWv?P*eoy004jk5J9K_1Q@}9TM7v64+f6|nIH@R z65NBpZvaF9K>xu2Py{0Uhburd|K$N|0I~j&g$47~gV_FHEHG{d3H;MJ8EFeZ{a4RY z6xCl0F9xOoqAo5DmVm8_jkA*_DJ$D=k_@_YLda{(zS|APxa|IzdE0ssXN zf8&eVT>$wPBTg6L{?`^bXCFX+<_`KDcfdAVA!0reD(EI=Z z9%lfc%>#hTH2`oF0qg$#`fUpv+@N8Xq1WLGpzZ(E6{)SVI(Q6R^$cJR`2X^ufW7{m zNARBzlwhyH7_b4C0wp+Fe|bRQ8UMv~;G^U(ZU%Gz#USv^e&-&1ygh*SI-!Yx*Z*W80qTGJlmPu-JiEW?0@Ot#Buz^;0SX5!%zU%Uku6yxc_2s#QFXg=KqHQK;R#S0!05| z0Fe8KAppgHKIj5UfAZ)Hp06pO{0Gy6@i##2fAOpT!@uhV5QKmLH33CH9uN-r0ds&D zND)K{Ubxu66J-K75r_|BM5x8KM(<=00w{vSe6p}rUH-GgGNC`pc2p# z5DS*h2SNdJKo%SvQgHGp!Q)CGUr+#u1GENEfa<`0<^mN!2w(+}gQY3K7Nj8fAnrgU z5LKmZlc1U`c8ii3S12YZAIssLd@1VMCwPJlL`92})+z!%U47YHGk zBMCqU`GG{ivw(*<1G>Rc`T(8@8hD0`01ki&6ae&~Di9RtCqNGI04xHlKqlY-AcAdU zflC+$zyisGszEFuI{*R#9yAODgXe?>PANIKxMaY+2m~s`2Iv)N2B-$1gVMpe>A~ah zU}*yIVTA>(0rH?+&?L|atN^kgAHWAJj|-;bfo0*qe3{^k(1YHC<0b}{BmjF%3K0Jp zCk8OU2dtTkgRQ#<3(Fh`0ul-u1{O}!%E8pyUDM0d!P8RL!`9K#-Q3i{Qq$7K+1v&V zgbBcc?ASjQNMi73kAfY6L&tqZ&B)9n_`8VWaF0P1&gpsF!FM-u`zORadL3*NOFpEh;f2N z?nD6)bv78_f)^LmKRN)k1OSpT4FGWBc(`~Zc_r8-8O24#S$|uTWE5rRVP)hIwkkc^E-H|tg38ipdx658E_Qg)!CR>!HtbVL>BRn zEees7JColCJdB7$@rMTfpb+8y4}?QTMaRS;B%xs70dOF|8oDgSNLlfoPhts z`Zoc8CBTa_-uM9cF)9yW%Aef<-2d5)z&#SULI0n#4^lHzb9+(?Pg4g{Z(9pXQgc&B zOE*(e4kk87M^Y3UZegii@*W)=8vrWZ&~DjJPP0{`$O0GO-KJn*8rFK|IqRN(G7rCf9T+- zBUpeBvETZC+j99W4t{}`=RbaM{HKTT0QVN)_FLC)|9+pjfqT>laBl%XLvMj|^gDLH qbMSlozjEO7#oyyl^yL6Z6MSAM>II(g$>08ecJ<#F|n2>;4Z}&d6 zcU676N?A%=++_g-pdlu#sIJJV2@3!KsDO755?~q*ASEKAhz$z-2>``5ba1c%2U50n zE>6l4!bF-{+C)%?01)8k-(_g*>>#A5DEs%ve?R||^WWbOi~lJ*Pye^A^Y?-uoFNhe zwvAm1o~zi5|6S_;^Mo}qbv6d(y#a3~V+SV}004vzNGrO#IQ*r(fi$`ka8N)x?k{cr zAG+`_ZS)_y^t&Qv7e*a#7|0%qwotg^p zi4MH+0ipm)fHS}WU;{7&dzY~%HI}D zfwUCB4qyym0MG$x7623QX8AkMz`DTeVd1~#kM4icg0=tvzMjv|&yN2|lkNck>No%Z z*tY*kqv8YrP~ZT7(KZJ|C&PcufdRik&CCFRKP3PFf))UPHUq4q<7~#t@-H6*UKjv? z*!=vwr2qh+5&?ksxX;hm{Ljz#0ssJP9RTRH19A)z`aB50K@cMggr*m122OxHp5*|tWuz9`(LPtaHVC99oxi2}r` z5918}iR)?G*e4$$t~>9~(yfeY^;cOwI$nQ2fs>NQ8Z{2=kfhGfEBW-7m(S@Pxgtd~Pk~jDF62-h5om=0y1|d~B_Me)y!m*L-Yx zf4Y3?r97_d$8PU^eiQGi`K$?HU!rAzJ9X;1T8#aD+wZd z_JF}sfg)*a8;SvhPT%0Ea-sRY1%%+yX4lLX%BugbTva=re1D>QUr2OCaDtlN!B$Wt zEr+FRrvD`3BHq+N-={||{XY$%gFsdMEklf+B%%?c@biEAdRGByTAI=R>hkMOf$LG-u_6~k%!p;9$30i4Z2XixRKt6G9gJ_ zf|?DrC+yK`NO&nMh7nP1wCO4Uqm^!~2{wzO0nF_WCg31QJaYd1qam1P$x9SFwBzDp zR^t2&7o~_oSxtD#A~rnQ2^U3hb`g0aRmkI9=GDsTg}&&saUPF5Y( zILdlGtg=Eqta=_Jekwlz}C#J2(1Dlg-~+I{8=owTTUHY3!kX)bf}Lfv{dbu$K{ z4To&c3C9qO%n)LyTn@45M(FW{F6DMr38eZODJ;qSgE%FD!mm%M#_T_eD*F$@OyOoo zTsQ@cs!_zuJ>3>^QvL30U`R8;T)SbH%yp8DdL^TW!h(y6G?J<0Z{I(xrIU*;NNdox zQWe(7dmVm*pbZW={P65Wsuz<5q4FnsfI6bfeSp%g=^fuPi7Hfb8l_hazjgiMNhtv! zHFx3W(|&_z<(~e_%qZBG%BO?xzg2r-1v&1B=uUT>V5vI8=k8zQ&~(xJlH^0ud6nFD z7-pH}$bwt!Obd0ls_VsW6l##Yzk)KO?j(;IMS2MiaQ_r1=^~({t8w&&$}tGjl=@B^ zf)1_xEvHuJe&E*Gw-hA^TTJXA`ukBD-Gs?Km)l>?ts4>cTJ@}Ip)xx>rJ&Ein53>{ z<5(v7=}tTkpvr}XzPfO@X6zy;stVdb8jbXmH$*CXa0$IB7@=w*u{LT8ColW{+~`Fz zBc-}W#b+dTi9>Q!@m7mIjp?~i3u3EnLQK#RD`ODhstt3ZX9BKZQr^c#DUAA49H2YF zJ`;;_#wz~B3b;Ol(73eHs{U&o|EWs%wG$lKOoR6Eg~XV4iak3KlpIul9)ug6(J8a2 zX8ipculqY!m%)%`$3x~6f1@`)*bNIFwXCwJO%nBX>zqvck_XxdWPx!*4EXN17o~V= z5$5=R#V$Igh^lnszZ$zAcroVNb2FciazWrL{c?Jvg0RuVGI3yMZ#yL(}&pOX2Bh8cXj-cssQM@CS`3h_?PvOxud zMVI)KLF_*0*D$sKS7hfBCtqIWfdRhOBWJYNxqk}=HG?Tm}FshhE)lW6EEPcEm@1woQU zr3mY@1fzS@lu}qeqbMAgTrNHc!)DZ?V=Bc=?rERf4=v@p&=t@{ZkdV%nZ9+Uz0NBT zTLBD4;;RY21?nZC07~nU2x|Hm9+GK}9I0NMng9ZfL-Mn(iKdheMHl)ki=eH4cXxEF zLVb)0qWl09tqjzI1gF1SF4C`INIITcP_MTU+LP(2V_n~Ley=$(#~DmG2A1gr)jZ*8 z4khMqck!;3IOElbDQP0Nt9*UcKV_J}t@pq?lY#RWLhRsW&_vB-WII$BNtdLQ>1p8* zG0MB{ReL zoql9Qo{9PViU+c41ZIfb7QFFCE)Ahs-scy<7QUm6RyUbOlNkGi;`1%vUSz|<6Y+0U zv5C&37(ud6-ai|dtV%kpZEig4hO+jIks^jKnVkF?6Yrr}cc=V9&x`qu$3R)NhI$rJ z3zUJ8e}&R6yjlWqSH`@s28ydOs=%dLx)i4vLZY&8Sb(=2q-iR)`fNW4*G`JAq0Fkn z{H)VLE_c?>l1*ZUYrVktninaVX`m1ddOt1oDpbp^6~m$n26G5Z;3@@08gCfItPdAR za5e8ne^jd710#1CvH{4Mnesa@6@gILz^B@sQv4GSU{%j{%|%D4q*uf*ZE4pvxD^5Oa$TBg#l*q3@&3OENE--a{O{a(Y zV;z9~mu-*-%;COGw;drhw*JO!Hk!#7rddD-$<>sdo|NrGaiV1GjrBmemZzShYBRy2 zMsl~-vYP(&*c2RiKu8>Gg26!+wD5kNGA6+AU%CsdjaGp`fFOBePD)4e}C`c zqcfFQWPGm9@kE)mHbtzPWLvB8Lp_D*54|5uW6$V5elyJN8WX(*$9(XG zl3_}nFcFJ%(92+tWi%4ll?l2c*l|F5i`#{f*ZLn}EHQ2Ap8{G!mGx_G`0c4l85+Bn zXH|~ag+8cfPzv<}6z=OPyN}!II#v?yOi8?F0s#-O8%MTc>G|*L+Sg-SR8F$9nK3_e z(_0~x7lPxIgfs&N)F&_P2zdhT2)+V@&M~@`%6-i2v$Qwllrpg<8! zSVRd*VF!8cG6il?Z5#`X(T=7^X3bhH* zB0=7G04|Mre=CbDB(ZX;nXxr>nu?1+MT$8p-(2RM5rv`yIYqnS&%PIl>v?eclF&7y z00*`R1i&|tMGL4=r!|7x3|<;RJX4EnDGjBclq-mt3|Tl}EvI6*G9OHEp^(^(HLpc9 zTuS?CH}q%amyr3DD0%d;e6f+A3n(|?4^N_GyKpGZ+7T_00^^+v^j#09;u6}wD^pi? zW6l$vdBRt56z-Z!r1RA_kActFq?z`3wP6*6VXo*e>VRu3>`CW(r0{ zr+*C{Az3poP(dRZlQ5qaaz`(C5_7(sH69xT>xl}Z21D^MA+$-8e%@S0)aqIP?s!P_ zpwa=k$C5=)u_#MkGH~Y_(SOcSKLwkf68WtyW@?+*ue>LXoAHj1l9-6(SoP1M3Fu&zj6k+e6v#~nJa%)!XG&g6Nb-O8gGzdiS)V{YHJ1+P5Z2`;KNK7JDeOEq{M$wodJp5WlN1xLJo zNr#JujhP^vTVt^+sl$6N@-JSUhp-`|HjI7#wZ*Pvef~;4axAW>EbKP62?LfXduJ3ySQl# zXBfVgGD_>2>4G)j%$`9H^Tlf&gBW_dcBwvz=aZ0M*{0kTR)I9Z=$s5eZVfDCDzpKIlBMXM}PE%4cSAkAHlo8;iaJmiI%viiGes!FX-RVDaX*8lBkB*#=& zku?%pQIgI}CIo6yrX>IK?;^fMeskbdcuPo|cL)8am04J9^XMz zpPKj8DM0V~Z^#3v;^w0;c)%z)>$DF*V|IuIs5a$`E2FM2MhIs4_G!{ed=Mh1)RJ3D zg3HsrpRc?wpMMpm2XVyIC8!(I2qgn#3cfFh$!<%s+k13Mp~|^*7Q)c8yPlj~^y93K zK*>;^rGl>PUZ%cQ#JPsHDn8+znPi$v^a5dkDqn2QiHOl3og$`P%X{=|^ozf4Ytf#T zff=WL##q~?_J!{JooqZUnY;Gu z!8(${<7n@|9jUr#kyVH2XJZp?&#bZ&@S;2Ez>QPVbcdXuC_oIzaNLREV7AA;DnUq} z$2(oJGSZXt`+N&U6qK_HUxjv&RUge?Qf)Fp?$46!bvs$FXG!b^P@xKXz~W%y$aPzE zhS|=m+W%2U8TEJrc*}E>nifggNK_RPX8eHpVt=1WKvZUAFY47HOby2^A+lr#-4oDQ zSY4Z78XiL4YA#Mx+|}QhO4oLp5u+VmWoB{Z9KB`l&CcOtByL*(R91;+nXSVI5OAgS zqp^#Fhpdq1oi%ce?Dg5izAv}>yVjrHHojqOLy*y-4!M%4F1#EFr>Ev-OgOw@jc=F_ z#YTBOp#>3YG~iXe&gwFN+z*=A5?UUFK|#m#%C`24yP9OC8Yelr=EEG;CP5GIhi~i2 z4JbP@Wu^pXEv7fwvyJUvPbBKrS7^S;!eNT5;2V|x6H)UZ0U9|D%(erI80Q< zS5`Canm)wRq=uB~Koh^R*h*p3kg`dnFS9eqDX0#u-QP+G>jzDV=53}a zw&&Xy<;+M$(Jsde5WSvuWyO6|lso55l)Jug{uel~>Obkoo%I*%S;?gpm*|yV4Xhvq+_IKXgbkGUe|rpUx#UR7P^JgBA{h%uwiL zd2n^u>+B`4XY1&VH}P8m={jRM8;Wbu)z!x$VN=5Wl=5%l*6?RY7HNiE{uXOr%*ur3 zWhAxmZ01jbh?~QH#|RF}5R2N6C7Tk_+&<2lu=p+EU6WUW9Za2|yDw0jc!yWjtvqA` zjnmA7IAwnz?npIAib;$}T{3hw%2gyxx zrQRQ^@a0Np0!RBOwUA0X?0sK~j>`_*^P_zj%u?%MpqNq=O05FD>Zn7ig{n9PC)$tv z@B1KTYV*PleB(X6$izbB9Nkz6>_hv~1gIAb_j}_NyRE89_B1zTd6lN!Ac1hL5h@qq z{>Nr8C_M755-(P`Ek7l-b)~)iK3=@;r71gtL91ek8=uvWICm zZz`6fI#Hp_K7idP>rje?Usxx8amOvktm|qQ?2q)G^RX0N4Q6Gr)MEvUy%=uXK^lPr z7cFJtNVm;Yk}*MBb9ToDp*{?Au-GcqG;xPs9&s+)3@+b9m)7n(Mn^H~tj0C6Ukidh zgLNNpcui?lq8S95gChAxZ6RNp$i`7OO7z>5KC& zkYCKW_5R2odNMQ4v+kew7w6eWP{VI1dy%gVtUR`cu|g5$(;d7Gs(wy8uIL`py@50Z zCnN306$&-P3>n9RFISM!o;yRDxsFv?3+^f{Nl;XUo^b9I=1^V!@LpG{N`GiE% zd@y7}Qq6hWJ_SqS-(xPPMr>bZ4Xp8G$}O$#tn6{FpbHm#?6NHiqMS;|`omG^;D^@$({^Qk3|JMBuWIE~aLD0eSG`Bwjgj>}wieYkS z3g?E_ShVj6Bk1jo;s_GCMy(A-@Oc#ww3|xHt1&t#pYvPVch)<)+`mz9G`^}G z;)9738O|-!1Hx4h==y&#j0Z!>L#Ok(vlb5R(RkVw2PY;{A!sTY(FLtyYP4l>=;kw6 zK15|d$;Ivzct)ZPv--q~LtTi~nj&O^9e@5n)n?BLBeWDDRf0BtuSdWU1Y=iC3W9T> zo4y!!MFG;D;w&o~FBxgT4f2=F{5S|z>z)B*aExKNZtjJWIhy6Y!SWf|%rJ%N`Q;0sC2oC%EjYYF_R%j21NA#q(s|So z4~y||Y)Yit7OWzw$T0Y+Mhde$!%DEwzC&l>%TLIB%S|e*oZqW9E8OcR`Xk;HTfCaKPD(&=tdW(0+Nt6&PN zzJah!&$sBuAbeooiKxNhQA;PlAm>}pgisG@GzH?GXx|)m4jVrf&TLCG&CMoL)Hi1d z&O%@|8m9iLKFw5UhTdZ5bR*)n9b$FO3!j5}Y!}%d{bJk@6fRkh)@v%_idDrnOpaExk?ir&$5ZxnnANsI8|_uujk5hWFO zrGrU@^q8m!Fy}PS01+}=Z0Ft`%8HZ}hSnU;^U>EDw~eARQ&J-693fX1cQ%xh#5-j9 zuSdb@v$e*$y~(z4UC;r5_AgQhx5Or_tC^Lmeb^w3@QRQeGp2 zIJzMEP#)gI`9_ zo+La-{)q2EOGm@s?JGqbO=MfWMXYq4@skT3=b`*@hSeKL085S|U1UJh31QCSZl8<2>pftJ7&y;a-D4gX6MA zL@piI)~Q`+gs=bpx=h}hoy-+x5BIAg#veL%UMyZ3ba*MpJm&3$T|m1aGixPh!Xti6 zz;H03DI??r%JzaTZu0=Gp04!-4{w(8{f6%JOLmK{#xa*Hp^ikh{vpL30rMDC3hJ;* zhM9E!^=~0K2?!GAOYaTgDw}H?YJM*_49Cm&4UhWnpH8)ks8z0m8)9~oybtYWfARON zGggcm$;Hq^V&-pUG66bfSEw#z*GQ_6ac|x>@0xic{xW;~plr}7&XJF-CKsYFh;IO8 z3TR~g7(&~}REHJU<7CmxBYlRHl}mK(^0#^IT{ha{R^HZ~gc{6v(QY>lXg`l-`a=qJ z!wHOLm4=b}@$Is4T{2X5{N6DT(%w&$WvA>2OWQhl536nxi(U!z^tu76lI0JYved8_ z{@uae3o60XE&>2;96TPe;^fw%87s!uTLvrue?{0gEe`qna(ol zxSKwDclwZIIi$8Qy=RCT9%(Frf;tEyPri=L@|R zEg5=k4d-SB=8%#)O(Ryb`Ll6MI7JX3gSMc`eg3n&*#;8G06$GkF=3^T>_+2t`Yx>osc5)_@<*V5?Q|;wXna0(%oZsXlQl@rs4NCbXOTT}k7N zJ1X2OLVqv_zDhDIm7zl2G|HJCz=tmL3^hOQa=rZPGSc;rkIf_ud+r_FbDW8vb^w{r z$QnD-5@w215P8s=FR28_qh5M>8S8N&vmJx6c=N4@>el69g@}2nftY#MooWW%=x@e6 zSrTf687D1#c+UJ1V|O=nZ&8w?fV1NlweZO>yx-l<`p3C$q@;k*tD4?nA-=9oPzhx6 zQf~gWv^gm+iUbIWUz%`j0jGW<<%2)b*4fIqqWph@%{T1|PXd)Uwm!Q07E>n6BVQl! zx;R`-<=`=bM@>_T!Ra&+Q9E`5(Z37a_o;Jz$t^X^C=%#%N0E36(>rbZqD zs2H%=SqCtg>xdUuA=8~OLSXGZsw}*?kmm{NGrZ~JR!TpOnw~lvbS(a=+0bq#@)Rvb zFSVuLFBbTmrcN*P8PJR`@?1&+&$Y+p`l7u)_Ar)aDo(G|RY-f!qcKIONj zMl-z+HMCS`*nD=c}^Rs^KQa1G7K}Ln( z)0s6kKtv>mHNBo^3-T3TxV3V0IV$8)3FkBN{Dc0XmKY@E`Qd`+D0jy44dCo1`(C9L z@uvE4E?dxvf7-XtvszeA@z4JR5OmPF6Ci))8wekUqax#vRSI2I@8OWkgx*oy!8a2B zSlV{j=na;ts_%m`6b|8ztsKNo7U}aVq3ZQ=IWFk?d2()Ug-_Zb-M3KskVtZO6m1Fx zW{qDh(ulaTiHvsATHOd0wNsYT*Z#Kv{D4TB&}G~HR%^J&3n%ynMP#E>w|#46@nysF zoD%I?F=G05Dx57wp9hv)vpa8g?kxeFSjb^Caj| zt-G=%-9*M*^>(dEeIGM{V?{gL?w4s$gYp$A%=ZGCpMu(T&K=o-@S|v%!Wasl_~Oyl zJhf)=(-nQ;QX=LT99bXT812_8wh{c|mCpstf%UTig@60d&QlQLM~kQ6m7eAc5Mk z?c?uRSQ3~1tOIA5;Arx`M6Gic#bi>a47Hd_XUXp)$u1{R)O;gPFzmnWWzO;bxCN(k^P`5z`;9_y6qCWSe2(9`s2dI80iZ-(aA|9> zy6Lo_C0N>mqa-q&mij&L_=fO6C8QFC<=kb{n5wHf&Oiwug!hiPZEG2jey&PqWpcwL z4mPf9HmIo<1Cny;@bi9*+OF>mD(`kS;nQgm^+tTJ{h(g(k8&=YLlZRqM!KfUjca{| z{!<1xX=~O4`?!BH*+F9Q>2^t(8C{ zdbHkwJ^2HIYtOc_3OK(I@Aag;hi^IOEA%GJtAWKsbNi~1x8M=VQSpkDC0x@m=qE9d zl#ECCJ+2$i{8e5ASKh=5>MN-!KO?J7gvUcoo!1R4QU{0~zs>y^-e`;I z9Oq+3R>nLv*I!s4g&cWVWVuyF@{S}i6uE(15NP|p_X4pDv~~P8IARRlSNn{j{a)sI z?eZ{LmC)%RINCZcKxZaSnQ$lT686n@YGNy-J~X>?l|p5B%TLcMksYq>?M66SEVCNt zt6TaeRV@qys&a0TvWu`Y)i9_hPP|mP(SWAUeGssQ=&@+}x35ufAiRR;cpw^6WpwAc zB3ddVm_wf7u4vru0GQ*5Qk#XHKW*_OjVJ_7H12s0hRBfKNQ=qfmqgGSC|$So$DN@yzfl-f^$Jthp8zDI9`!j8OCrQ=)IyETlzdQXRl|LpmSM zB~Jux_F?tn>G!DvyLuI;T2QT>xCYS2n@YDLU@5aTU%|(P(GPp|x_DRJAr3qfIuql9 z5ojAy-V(=DoPVZjFBf_N*=&SugV_ruQ9kNyZ7Edxz(7^mPM&vn{c%KAIJzhh%2W5{ ze0(qRhcwYQ`l2$%`BUDB-&En`Yej?Z^CK5AC83t4t@kv;g6(g2DNaa!!q=s2UZ@|C zQqvsu@{n@UKk$2lqr}EEloe!7Goa+F&GPUwGeZ_(Z3)bfEJypd!Bh%-88nvL*789N z<{$bqYw5SJ^%5P@tQk?K&Z1ia-GBYIfO_Idwj1u>&t;lUrq!o zMN1!vRur4$@%W)}lGeUh;k}B5zIJrY;XtM~_99ylJZazZ=6Xh#-V5oI^bLQf8r;s2 zN-WlD(+N_SC#y%uUs5CgiRkkqG(V!76H5{mw#q(>96k)ewkSNQ(+s&epCi`Imxqmn zt$}7hixl6u;Myne^iK33wLLM6fSjcxb)@CQai8N+*Pu`P&m!dXK43{ zZRlaA6k~!zqu5`8sM$ILe_Qj<9*zddPW)GXQGG~XZT=o;vNL2}?o z7qf0yMuB7N6hXi2Z>X-u1=;I-{B4hem!5HNrq$82H9C@TA?#DBD)2eg3zOV5-Czr+ zZw9A9%K|DiSASqY+~PeJRESoD%!cNVB`Qor#)ho?U?o#DOun+UcJ-?dCiags8y!*pno^fGOEw~WU9)5y$wW3$fYLD&5C=KBtfPgP2p@`O7$SW zk0WuE3p?$SJ;Ok~Z)qlkwvIE7Lp_ZOh?8cnR1htWDN6~J3u$QSkr|{Mhjd*cdIjfE zR}5Rg_th{~wApab+9mr_&S~e5-z1^u7c{GpE3VGQAS4D=X=~2oY*ZfondY@x@w6}A z+-!axWJzGu$aEa04=D$AWdcwW;$W=@+@BO;mSkQ>J9gku_)K6Byqr62f5>rpB#;K& zH&PKHyK?itvmRJzO%}oUVhbXPgnXE~zO9&?2S&rgK>t$ZdU=m&qnxFDH-zEgj#RoZvCz95}+Pz%s&dtNLd zsg2q=N$GI3)x@U@JL6NHpeVIS?9>S)-|pu#LJ+CXIzZD?JIxD%dBxiLMK@48Axzl$0jPieXdiT0 zW1U>VZzJh-%G5MvkbJ&q)(Wu2TFqp9bx2afi8l{(SyyJi9M~nSK~n2DXy!HDm->VJ zB6y^mwRf_KDY=bW=^;qBy8)7X6RgAY(~9IWKNMO_ySnx|r%7&&UiLx}=ZJwVX{dCI zRb^R27xbE-SoAw!=Sz?!{OM+*7y=Yj?fog_uiRWeo~dcH)Y=QpVFk$ne#u)}-9FfR zc=UERB(zVB%W2XZsFfWMx)yiDM;|M1-70E#+uJyJS+Da7^Mpa%QXCe+2B}>Pedv|!lx!Br`Ek)KSiEz8Xj-reGue=c5w*5*AxDplLCF40Xbt5y5}Jy zt2zsdeaPA2{1kAtrZXOxQ*?~-v3#7_1f*QMS)u|3pGo0FzM$J#6-1SpQ)d1ke&?94 zw7Xy8re|H=2qC{g{G1E3y3$_2N~`ePrp@rhe63L5r`8HrQW&>so)y`BcPYwD0o`q0h zjtBJ`*N`iV>jjr3Kn|GzP20WqC?q|=a&)PF z;Ny@soySg2&K)>#b-0|y1VmgP1;N^;GwG0Vl-fhx-u+)I0 z&T@~~ckAf#RWVl1FRgKn-oo~oN8eGn+bO;HWG~=@1|DN2y^1*W`!e>Ticy-*id@}< z`Jv=jUvV=}Q9~FZxx6z}8N9z`zNMc8g}UtGCN>1?S0x>0X!~%MgU@X-d}W-~#(*u! z*H4Z536f5ykgW%e7Z|`?Orao9!<*hQk@>Cj z{CR54rxVx(^1B&_k!448i}=?5s2-hA)YTaZiDDNUS9ZbR4vtO}hBabtSB)13696Ng z2!T)nozDn|#|?vO7qT^8W@>xbTyus!SE@$N!;!fy4i8t{PDA(3vi#`)m8*WY><~4N zAc*lr4ywWaue;nJf*`UT&?CW(WBbx#$BI5J+-w2#=pu>4W_#AhQuC8V^-Qf8q}HHE zfw{t8qx_gV1nJ(4XmRPo6XVD3!DOK+&oG{O{~LHV>~?(dQmSkbn`&|t0$ead0OWD4 zeY@<~t>!*pG`l7Zl(VEQw0gJ_2lZzs_X9)U?YzRNyIf*6tZq-vX(%Y|BY|NgLJ6&U z4YH|J7e;W?^%0o6mWf@Ul*eq_$Dr>^y^H15e(ey^lIvjU@d{yE% zP^AO(@_;PGu)tx8s0UxX(6V3F*y*_s@xdBhA>qESNGR^cuGKK|+3O(Ytw+R`(45y6 zok1lI+=zHbjY;F)3kz!0)wyPUd5GwBoy$RV>#7)Pfj%dApVn29yiw+LcfSc8X&lk} zgaZ!3Wa-RhAhb0rt<6IXE|Jxq3*{nWEJHLimi5+##1c%GksB5@WYFOI$1*KByx{*R z)X)VImFP6(SVaQf*0pC^TOHaU%6-ld5(3W=~8iSM4-uR_!S{cQT*1V44fNEEGSg6v~xK$E0VQ)MmlF$jQ#0k!^n>YRe zL*Gr!)F&MMI~GVK*9-*Z*M(HAYatoae3Mkm4FwChgQ*5QG}?uu{VT{QI^^g$^ys2f z!9dYG-^mix33GjF2!PP_JkWy!+Wml4Jn9TeJaz8)CTnc1 z_bf}+m+daN`TQZ|*rV~w%qzZlJNfU5ExRjG6v{%6B^dxp!d$H&dUu;yvZLwvlQ7!F zZs7{=uZ|UIFS+|5;%au>c6;Uo=pU)>9X4uZ>Zn-F+yRoJ_OoPLW)D`R&6(;=asl{5 z6Nl;FH=EGh>U4032BU<(KjC})bDD>$ibU>C9+d}r;c0yMJ=&Sav%N)efE3_;ej5TkOVrqq>+A$qJ$*i9&1#4}3t zR_4-qHP`=j*?ir(zGYgo$Li4~tKPlnFz|sE8M_@H7S0F#LH4j~t<;5=APyE((keAk zB^g3Q;CO*-1U|Ld!R8Z-Q`kI`YZ>_M-r99hA3KvNqBKbNqY4?_s8cc;QwRq#iYbQM z5k6H6Wz%wIm-P0QF&|Jeyrzh3D8^swh-Uh2hI4c4r~YitVfk}2@5kTxG$k>MJ;qmV z2+?QOKPG{CB}qA-pS$Qs3^+7bJ%DG|VfaSZIl`F^CBG~5u-nHYt6rCe3{_yX8|d($ z@OkFUYFu;MSCLHY)jKn2T#076U)#xDkbF5x zONF=C6&->6dcTrX&Zt*N_LZN!1%B22{1Fm35Tpuj8Y8sNfg}qSc4V$}E0xmxYf*&f z$Mg=Ih_Y&S>SxqN*vRGMK1>LxO8SB3mzlLZH~(zHKi{iJD~|e7AuazDzq91(`q?N1 ze4CPv4CByf-tZw1(g8KI^g);A(@|DXK5zE2iv(GGYxx?o)%{DOJptLSj%>Z>p4^RRxMDXFOahsq;vGoOrGp6YHVo_LtjMbu)%r~Rz$o2yXNeGtG zAZ0|U1b#cqK-j{nJe&;SbQETh8Qgm5UD5i;rZ4L;wQg)VLN8SlU?MmE67RR*no3PI z66ArtqL=-AanipI#yCXAahs~D!r!9GE18&zE-n5OuLvj(im#Mo&w!F z4}osXC5S;AkFK!_tv$jxG3r%I@)NckdDrhMs8;!O$g_H6PW$BdR5*;|9vr|Fk-GrF z$N>(PV>R)x;KWyT%w-8@VWaYGit$O*eM@@o>w~9tD!fC+xn$CoMz1D=0@gEv)|p-P zh(tF~1OP=W)OJIgMEQ{%@}uQOK-$>5+1e{yU??ohx#NFA4R1vsj%#5ZvBKdzRAT$< zT}8>zMsB+ppz=>A0MSyWCK)lum9vQIQT<2gjkM3!VA~E?C*r$Fbh(_W?`!e!TD~xS9$|5$#_m-937&f>gy$jhck*!FcdBz%#$W zWaf0OoXXu&m!@1iJQvn9VzTp*1V*C9+A|cY^;QVg1wXD1yh+6%i`(D~PFcvz6w6C9 z*Ber4Mmg5&f~Z)wxt*2l&(L!FlWTBsx2Xf;HNgAzbw%D%->w9YNN7u@42|-wfBfY^*2pQdFE=HLxx0hj+Ku zEDf*3fj6;zqUOOl%*Cj?pq|9~8>RsaI=TMR8_BCE$HkbqWk2l!-Wo%E*U6kv;8iJK z9L#=yfLC27kpwGZG0@LQTD$w;-@R$RY={+ODN2ROHGF+3(XAUUg<94yYhSy}BiVBo zsTj3gwCMi*#F+ey5)Ov9_E+@v6ikby%6P9I*mog8IMtS`slL-Uq*nMV7d75R3hopn zX@O6yMmFW3N|`jWJ0(G!_x=i`sHb?6xYw^{<135~eb`zC2d0TnxXzUz!ac}=TkY^V zSv}Zx`e}TRGzkpzl*{D`*DzKvkmnEWYdx3V@75kU0iK zdlAQeQTsPfXK{yJJ2}Q_Buv~))rErHpLkw2!L3D-9de)}TuZKc)y+>Jt!*Z3ibk)Y zNtbu5Ke*(__Hva(!#iL!B%M==l*`pCKybTY-6u!gX^F3ew$-BcWHip^cn12rfB~tX zl-^#}L`~uu#qIsI>vBSCBCr-jt5g`&z`(R3x9Ouyeiwm<_yV~3s_|r|bq4U$_~DcO zh@4g&r#(w8+oUa-%0zp0K05)3tQR?QV=VXnZ4lI~8&y3pwO#L;H%=ThqDu`_4V{wrK^YK~ z0mvz1C~2ZZ(Civ1$0bFnNsLQhod~ezsbf>A`9+y_SAK+T(U_tMy!CVI*r0v>Y_Lu3 zgi^%j_p&P!EU{Q%-abIc3H*ME&b&ww=J7g`gZ>Ji+flHjhcg|69oRz7sN^Qa+FREZ zf@${?{;*H)fB9(ZFYq7}t>`m-?4KG-fFqi!%(4TjU0NI6wS%<*dMiPmFn6 z#IWKX*t6+|Waq}ajm`-pz4Vs}b^XieSPexgZw=b)>tA9D3hy{w$aE`ESp55IvgOW22AD1R>Y|U*mYQqjRMXy$FxJ+_x>Z58cGPtyWhtF=!30VX3R532ZuHwDISw_gCe^62bH&EDFWik}FYA+nO1M0%en1TSr@aMP+ zoQ!_(_9k36vjUFpqj!Tsa)#BE(#O4md9QbpvYvKq><{Vnm7Zr@|G1?x6LCE&5f9}l zpHci3&Qi6DXm9kN1h@}vbOj9iedW;|rmuPuzU?cmI8lclgOxgfzA|1a#mb??F0#h# zpF+XL1`~sJNVyCGh?2X_b@H%*o;khWgxOl@;Ik7`flK<>S&pmkH@g}!-L9jY@`jD-hA(Y{r?Ua93-`$?JW z^1r{lB1h54et8p?sYn!xCEIQ)a4v%05xMkkn2k_QOdaIAds7lA3YOL?tp^r2h} zAg+uA329?n2B*_coL-B{aAnj00u%|_tasF43oKI4vz zhIzRWIL|#I=x3g8rll*_i0`KW?X2QMtuCs}05M|*%ICg`&yB11)@j##@UZ)yZ<(HO zOx(jpZvZB6+o-lOnj9myV~tUzv>va-g_(-@uY#FzIW1*X3_b)&Q&4EPL$z+WOMW5@ z`_e|945XnM5*^hjn(I3YE&C$sxDrmDwTtN^1I1XHm1qUfAk8(mq-wK2q7k(i)ld%X z&-sI6tWo0p#dS7uJI4yJG|hDV_R~R1`Gh9TSe@KtT4!yQJJC-_*vGLx5*~xVjDagd zLkb(FCPxyzD&kBnQsjat#MfqGwfGoO*o_W);<{Ur*H|1+l9$*9WZ%|j<%8H?8e`#o zdv6J>=>#2(Lfo9OxXp-Nir`HH7_bt-zZBxw!#Kqs5w5YML9ZXuL0vD;diBh7Jq+Sk zE5G;)-etK084FE54;tyuewf(qR%!|bux!ZMI6!{1p;*N8u-~|Qld20KF_xpo>LZ^h z^@@vet9CNUg~%`cEnf{!nkWJfSLJ}M?@aFRXGfuUaK$Z1TXB3NwsY-(z@8o^OCbHj0X+Y}pcib;Hn?JGV6-1i!c@8 zRuFXBB9QZ$mh{NGg$}aYBJSF0K?K8tf<1HDuv_})C{3z3zR@AP&4nq!ioSi0%cJgBFAi6r_I8SvkTgWcQhfP>XSRIT1kQ;Q!h z<8^g0BW{sCWR0B)V)muA9hPNx;e@@E04qJHsZbGM2W|bnCKys1!jo%*d(Givpo_HF z0p2M|^|ez22M1HiHG_N5hh3%4Kas|^7qLR`@IH*9q}$PlISkL8o&v5J_Q5=e=fl5+ zdu*xdmTnbUnt@=0B?B3L-NGAO_}VF|Tl~uKX%t+$B=vG$ZXor2{{a#(uox!|V9SC^ z*_a7&KAAt3y2-TuGn`k~rFJ$Uxo&p#K#-mQN^`utYAgZ6ZbO8alwQi^^n7yDgYL z<8RjROt9yG;aqK+#c$bjzn)h;*m*Cn zbKHy?$S#|9eO@ph2Qmo;kp0ka(5=>Fu)tWHbRAo;E7zX?ZUJY|k&T7ayPytS@vvh3g!I>mP4uZ37NZmIKb>3s5S?ZMhn_kFO5ejdE^d z%DA$$wJC6@o{e0pd$CEn zU43R0K_jb!Ph9KVtWxo%7Ek$_XJNVq5qR)v6`Au=nJHO>9Aq4S9;A!c7E6z9u1@4& zCt3L*c)lWiPF4R!gK_f`jG z3|kXIDFEFR0S2Jlz7}U2L)J3nVStzr)g1(x%TvKA~q{V)(yh92tv1BG&2|5k+x;g z2&anJcQXbvsD2c5pKkY-rT1M&Yg=Zh#ZUMK=Ut5;-%b`!CacT0D!<>h+iuA{oK`fs zHcK~vQ%?d6(`WbQ=-!QBLe-%fgk=>VC_PySl&1h;kcvX>GNExWPVNfcWx>fQ~HTM4r zxmiNPIr!E6guZ2Z=D7I|r=lQl`mFQ;UHH%OggQYwyXdAWwzNd~PUC+a-mC-(q!Lq3 zd#}1NbA3;SiejH}wNybP6p&nXsObTCD?Y$-M0M_e((5b_DxfqfV_U=KsGfB_dU~Kq8XXqO@^a>J zm`5;qJ0lGuR1$jCeg-lKqUEpl$S9x)SA6UYJ&_4vp@mbkLNK2(-Wljvw&W1Wtw`8a zTAweBZ_i!Kj<68}oYAqrmj4BV#De-%Qsr0Bw2Zjx;h%kq+kZ31EpP~iz4tgX;KH|Y zi6aOVM4R&;9V~7n?U{#d)d}Dz5l(T!8d;Bg?<&?j(@-L!xWY%~IcC0I6iWnOoMEzt zX}O+DDm^PkEOa-#_vNPk{#EL_Jk02r4Ts3}VH7EvDG)#9ETrg8ku#ARE$@{1V>^)O zWSgGNs8XUoW_Q$^Lt+3N<${K=Sbslqxc zFveH?0*-kce$9Y3SP9qVk!g`VMWyN7vRA>_c>c%a z@foZ~f?n1qP~)!xj={IP#3|Q)1G1XLd^b0pYX2SSQ$9%sMEasM8{c}rg0rp9<^$Y% zv<=rrFbABvQKw7nJjKcgeAVT(O)xKur!FJTQMb`(kH^qR)=V}Dh&E3n&>+E7(~9xc zB#~8P+NDrOfZcac^lOk<;k8*~v0ku$Q<2Y`cE0=pFWu1Z7$(KJ+KyjI22V8q7%NMN zZ|cp~W%Q8{b3>L#`qSUO1@``Z)K-%1_`(FDe+>yIGsEGkVNo$#Vn{XRMg}ICICAA6 z#xm8kBIW+Ef&?LtAl{v}^GU2xO~h6s3;?n}+xLpwwMi!ylyx^zsRXlMKc(0F4eZ+N z#>1#)Z6+5OwKYU}cpHszJ8rxc09-02GXD(HG^^hZCFdbt-dJ5sdkxd$(_gv?4miL! zz;~fyjtF?PPPIWigaR>#($g$msRCbxP&KvI&%6E8T9wtl0n%bT@B9KQwAt^Ip{_Vg z5!A;Qvo{C#?gE^<_36rBn_Gk=0pz^HjJq{u@D@mH9a@KjGE^OTB3p>?mas0 z3mUF&DH}~J`2dIeZh-d{XIyD$6i@YbSQ#d8h80Hkw+DvEfe%mW@FhR_0V}tM&ubj-6EwnH$ixq&OGCz zcqI>CdN@M=Mph~Qg^SkBq#|j76^l~nY(O${Q zfEVGUZ+1Z;njjj}v;gWYYpEA+djh=?DoWoOV49mSuAs=65C#J7A4&m?>qf};Um~3F z2bDouBY5!ET=y9vsi#llWX1~sB3%Qk%GJ9vd6NkRF5`@dD_Qg&-a1Nr8gsaloO!X3 z#$`q=w@OgUUO=5Zywdo9(RD@~HS@rXW0wF`vnq*MBxkZ_`{8e)_a$E+-3&C%Cc4dV zZ8?Hx2ZUT=pH-KHi^8$#zGu2nj3yuv`CXk+s=-Av$^e`@c@2TAg3F5^-bXybzAP`_-H)I`f>6gwo!!ZKU``o*O5!@2gD8dPL z8|2>u9)pOnRh4Fm1*s}kZZL8*1u&D4%eMkCOd=`@;Fl=P?Tf`jH=lF36h`lU`xz#> zkp-sf11hCJZ!I8oGX4JZfY*ASB`X`p`^ARxf(}o=OHEy;W;PMs7o%6>tWRQ_AM9LG zn&WqBo`h0hPo+>w>vriy^z%ot%&g8`n`K{tg%ku!h3!iyHXB8zf?p7rbGF0)BBdr~ zgAh*t<#--5G8?3I+ohN{#S`vMi0lPL{4mw;PW8_cuW?fNGWzmYtE)*^`H8LLT`Y%G zrJ@-z%R(^Fm*^X8Y;cfVnG)!nv?&uZ6nRh%qi*&}ZTD4+;EUSm$k2VR{Jr}3+jFD%jr>+ODocN9t6_KteYp3>2sWnG!$cz}mM z%HM5t8_3ozL(&qhxCDooUC@TOxbUh+4tbB!O$E=5ORk>jV8~KeK2vxm0GSjlK!FK& zj6KIZ*sE$(303`uUPH|=W_b@#=gy%02yYf(iegfVSMAeBv;`* z_Bp_joKx{&^h3aVW2uLqL|>onG^D0VG5as!Y1kYp&Pk}j9*Kc$4XZMA*hcoFaIfBE z6$v?W4zV9q{lKL~zC}NYKPsY=(8{ZdB&LJ#po#NE078(sJzs4KbWs!lvQnqb`Kw?u z-ojn92)hrlphIH_FKq+6F43s=jXs#NELQy_vFi@M&1H5-xo@bss_b*pu@e?~>JnXy zjnRzfpIBwkha$-v)cQ$5Acjkz zZu)77Z2Evn4Ivaz1Rk%%0@`&13n0C02X+ZM0xwRMlmjSK#l@X?Z3B@545qT{8#86k(}Y^hSIIef!>vG<@jc zpkYM-Pkt;6Uk@-&8fO#4J{SJOE1hrT8i7H@*cYngl@0sTZ5l9Kee?wT6PXa0Hy7KO zaQ!_5FQ1Z{dCdX($gv)DFED^JuWQnFARp_4i|1NnxW98};n#npQ~~$eDKGyH{G_E$ z7gybK?rWp|bAiI)U1K?%kD1IFL3Srrs}$XpnamgBcZlt09)djiMenPpyi)9mA(x1C z8RHeLD;Y=IbrFkJmyT}f(cjkBH&1tMW_VPLjYl5%@95yqF1)51(eRN=eI^>MgbJ=H zU;O>vLO(ZvXQqavXMGtRNLALs{#G<&C5)qfH^q)C^R0G>xWp6c!p1oW-lk2uDN3{N z!fm%{b+lASfzg$PARD5Brdw)i=f5tMnJ>U88!|_~0z+uO5%lEFqFcuPrNC}f$uq)M zb)o?5+s5`-R`WQw0Eel5TK-!81}6aBVnE@Zb8~ZP0)8?cH{}LKQ{bEkG;COqxf#lo zrCt4EzH|^N@Oy3=__BTN3b7mL;e%DUj=sQ}NCp&E4#JWc(%wcI^_z}9Fh8b>`q!Ru zjXe~oYl6U1Yy!WEBH_m$N-klrr?ql6H0l%map)IY_f30LSlgurPz=A6Ox zT04rJzskL)j42XY+fXn2#cG%L+iUEq#}ojWt}^!O0|qz|B)YY+?o5xsQKN2o*OoKb z zST~etGTjrI*&47)mCQg>gAO*o-H;_m4SrsJbC9(@pJGCLaR!M^6>Df|$+&01;_|V& zcM{cg*X7ft&++zB9f^D3DcY;k@XtiqxR;v}701-^Rint>70@R3nV!@Sj*sB#le!-G z1cfT6O3n}J(N7ZMuU|G%`R{}N+O!if>oXS(0?;A@xA;QL0EM<_0IA=n6-^}sR!sKV zn52=|vTKl|gV5MX{oD&Q|FZ*&=e8CgaNQrqBhi z(|psBuZg3U@R1G`SUy-b6puSk0bZ1Xh#?hVqJVmO;V+7|VjrS(liB~F_B6a~!-hfw zd#fjwQkP4xYeeF|4buETmo4MMN?pc3eUfAWI3_5G@78X2irNp^TqvLjY&bHX=Uudo z0k>6lZjXQrp!vrHeo>a;9+g$jdx>5PQl8+pYSr06eu+nCmW+HPZvb`r>e>Lq!vOqB zv&Qu8k@yQ>+TkiR1`1Fa<8fttRW6n)2;afi?C|>5v4DB;I5XTEy)GbOf|r%%lW_ z-wG^b{IPCLncJ>KS_y#MlP~)N1|!sGw-}lL05HtyQ4J&>{L=YtL4JfhYj7rG2&Bhi zySm?2iZ2==YXZ^tvh}iKQYB2qdgg9-i^lVvl0}-tOA5oP622Q3nVgB~t~xEEJud25 zu)(9;yMa?HrkN>P>9&TTF-!@=DkpErhvjY>fAyx^K}-R7jXK{V?3yTr$+fc$16Wk2kt-jfGFhKAPyyJ;5d=tBvr*Efr^0*O z?V0Wt-KUArznuh9^H7e$bqIrUk~HaTiv~HRb@Z+D$DGMi>BkUJLM0ajj*GJ~GL`%! zE>ThSBc-IVFmow(W06lX45cOy^+&IVTnr`8AjGsUHPDj%(yAD0tT_V@F1 zKqTO!62n1S|4A3FgWu^RVMU3ru}Gob0500$=vyHy*&O+u6BW!T^_hy-;9*?fgV}|| zrxAmbz3tZ`D9-1B*msMA=WqPrFGT5=0aJ8P1RkjMOSv$hF0%6r(k9@g=!M13L^!Gr zW!F*NeC0*VFtJBAObeHEWcQdd$coILUv5yoiYnL8U%u3gif`y(B&~tN?fu=0%U$*{ z%dySzJZ_j1Gw;s{^qbTj*|OsgU&dIvE})SBRL1RwXKkn_k=$oQBV>l)JzU%0=5Ga& zO%Mp7WKuT32crp~8s%}0+*^6bHf;vCk7s?+Jn7-y*TWa$yMaKp)t5C@rO0@|1xi4kctWC3u$afv7epM9%LcsRKv!05fZNMeQ4l{$7;A%wMtRz=0XtmkpG zd`JIbxI_8b1rz}Q;z%*4DQYM;u!1$6BzbD^f6Lv&t_|w9QP^Wu$pgdA_N8k?yF*3i zPK>;Dc$S|ECs}ICab=1jc^ZO0X0QA>e!%@VLZ~V#0Ai}^vJc_fo&W8Uw%$b+Yt|9! zb7%~8qKkAbL!Cw13$9FvGwPL@RK7r#u?qd^d9yKHfzZ!e$yEbOxK6Tg3psxdSkVXi zhOTfR^|9IIx!sktaaQ3{MEuTr-+w zK{9y)8Jmm{YcwQ1x$I65MY(>gHpylHh4}pdUtv*UllRoI4fe-u4a2jnV;M-NduF2< zY-xs~wLs{jY6kZvbZP)@TRkWHE*SGzPL2;)ks`cNvzow?y)v=tvX^x_sPR1dt~IKu zZ2=+brm}I$M;uhTABZABQlcT(Cr^%$BzgLTQEjH1$O>s_2Z3c%cJMO&qNerj(Oi-_ zJWvbu2aGCLF>+#Rd(gA2q7v0%MF2ssFz@FVz`-E$*nyotTo7|3nYo4x=x2=r27e#d ztJ^E*=k$+-&^6{d(d#dU#S-s_z8$Q1gP&Uw=;OP<{I z7|+uZV391h{oqzSvAb)a#pvzRmPAvsMav+fi^iN;lI1K%K9b$le4A>W$hPTIxPnt}@r=h<2I8x|t2dJ78CCvraSvB&AmYgdHAmjT0J2*h&}x*O#f8j@Njl zinr;P@>dIO$_+mtBm`iGom2o+Ba>cgKkTJM;`M@^*PrMyV`258Gbr-7E4zy~I=;mE z3mrC=<#nO3Zb76#N?(Y)b)b|WSkxpgA)!lr7T6Is#v);m-bW?3lLa3>4ceJ=B)fb&&I6y`vt z8kluN;3mIQ-_rc!+A=|7v1^G8O)Pi?bFyIhf7o7H4Z8O)*5=Zs0K8AXR z2x9mSo^n;IUG#R*nHz7+OhB7ei0C)!%@;5y&m|OiJj;Mg%K?|E8+U&>6TZ;u`8 zydM&Re`W<78!7;qcA9T(;v9C+BAdgCqK>}3c_pB|1C!W4LS5(kGooa}s8!bu`*k=S zc((*sMF5&*E9OyuO|cAEK5WEp-n1V)hUUs!Xf6B=ffG;B)X;{Bm|0|^eO$iWqJ3Ka z|5=!=eg+g!1*cWvgohlH6;1`B477|a!*C%if~S#(@8is|HMcluh4*5d zVfix~^UM*&QzX}k?eaRmOHgMh`mr%xb^!r&@QdwoOJ6E8jQ2nh@e#i+8Bb{GhtrM$ zf%<&-mq9Qp1L>U9ewiNC=+sj`Q-yf7(Qo@FhFU=5jiIuAm$oFUA9w{?1~JTEQcv>9 zcpcvmd{J`ygu+frHlF6HfD)69%MP`yrT2u%ZBFYO>8n{?RJe0c#$qY4ujX+U&z#;F z1hztEAZWMOxU3?ghhM!oH*iR@gJx=nDAXbN;@UbL?ve(yvr!KOYGqGD0fkcS6sNdh zVe2)wi-r?i9s;;vcC={)>Ber199TB#y-766x4-0wt@D?uvbmWl9`uz1=AlhkTLTZB z#Ge3~{CLNN@dVA+cV-g`iPK@hE;DK$O%>-TeECk|#J-b>85$2*+I z+xFOLSxZr{X1u$0V0~3hb-usQFtqZbBu>E{Kb;l1>bRrAE&~VFlvMH%myuz;!(&Su zqGPK!g%$D~N^FidRwXcy|ovR@L- zeP;ew$Ogj`tWHj8^~6AhM1;qM=Gsw_sHnfktR&zIF0EC)@IV@o=nM@g_1Hmgp-fOf z0Fv>jeJY)ru?VusijgE4BzM5v+qtsvO2XyH?wl{Qs^`n;{M@Jo=1wUGtMD+TC0xrQ zDkJ06vkefFjs0*j#|$xQ-DbvKh-Nz5WY+&5MWN^bu|5vdER4V}VElb1WKG7v>?a?7 z?Bpq?s0~a1M z_iaImKuj31yfn(&hz{mL2mvYXvC2V%(^MO%Bo@cMBg9FbRFapdt_J1mv!57v5}XJZ zUSRa9rU4dA9%C(@X`}IY;|@iH+*R{!iz4yLm{-N~(nK^|BFJ56-!-FUD?>I%8Wej*)%)d66WR}A)(qU(3V zRCRm-Tqwt2%7Qe>_{koUR8_sMtPAdh4Og}j;=qW|SimBEa*lK# zRA{0a;ZvZe7e8P5LAMW4N=q3Yu0(}zz9T z<^`hr6=>Q2et09u6oFMEhn#8%o%bvoun4Vj!(fQTe$80U z{}zbf(t=m_J3G3oF`unu4^^rP^T=b+GMCL})-z_Q3M0{30smpt%8vz62YONKKyj!g zAg5D*mN7<%5?mSOg20vLbS0_J^4$cj6||YmqR73u+EXWXg1DPnc)u>5i=2=LEE~Y! zy`7nEZ}r89yB^CRJ(2G#)KM{Af|;!Auu{z%(CjTwEH}KT^+KqcTN&2Y~L3ub74pi7_IZ zGvac1`E~Kh>^xCN9)mXw)VDGUqgB&^g@{4sD!CeKbzFT(s}T z*2lv$Q?iZ7fe>)vZpq{R|7J!|#EJPHbR_eRZxKEB1{(i6yFV(++Dh{tSu&SK@H9@; z;t~K{nu$EV&RTvAIh|`7J)ah*>#En9TWaftR5o8|lg}g*Bu7;GH2gnlOZCQaYVOdE zL48fxw1d3~%hE)nqX&%s!4`$TLfF4&({=|Q5`g!OKnL^q!>F>bV(x+wYHftYxTD&N z79%l38DgT`P(&CTJNo$PC`+YT&}ExODj>` zP0v$x9jXlsoPr}5*`@mIjq195o_1`z4aA(jC+Aq=PFf-)1iW~=_@%MZu#;(GRR~q? z9SSA#CAqGNk+6wNbx>3zkS^ z5+}K^U|@;=iDV-6D0~?_P)+NM?2cs%$zWuK{^-|N#Uzts{DtRUAxxTqz#j&dV%gEO zvX{4|X1zY*RWhVEE-DhX9ze~@2%&bJr0Q#vLddRx4+(`L7?LycXb+02_&#<6Zf`M4 z?2~W+*jFcX`yd}It}A~PMkB?kxf4JuJmCKR`@>cnGnMv7{g>I_V`<;BZvi$$&gci{ zz_!|oNPjIkoFFi%rd2{;i-1H@HH&|PW+P^x7MpAL5RAIGKjMulLopl256dlTcDEko zM3>i2*}h`YdOVSYykhVeJS3{+soz1 z@vRW_({)K903nfd%i+!~*`N}m5G$Y4_B~+T68)zxB?%t`5v8QU781Ax|BWtlPp%o* zZyZEalIB+kkv~W*J0ybCSslk-mj;+5L|FI)xy^XWbRw4d)_|xYOtx#VO*uB-OP$2yq**A23_RdwY00n!f)ewTh3ql}i11_1aLYdXR)zxT8E_|0 zGRZuB6tKcl0Z=X2KsqH3+vaofvd$Xn7B}?WChpMKE2>~%dx?MafFTKC)C6s$6r2NB zqHq392?s*Reep5Tp}nK%fhK@0Xr1z%vZ6A53q#Z7N&X}g=k0>w4xI3g2 zns|?_WMrP9TD%57B>Fqz2)>+|s!!CD;=Vp8K-bp0UG?#dBt^v(pzc+{>ii5ogT{Rl zp+#!KtbgO$gkr!)6;pi>TJcVwV{{9EoRWrOP$_x;+^m~_dcpJ+EnGTjtj zF`g1nKdi`u4#7mIOe=wMw|)IP!wrIhPzW-B|3R!4U?D$Vsa#|pfcrlD3@D=VCGdFD zXa;8CjWK07f@4iA+c(m_ovlzE?9Skw^hZ4-vSP`_(kQ+W<9HI#yxEy+gUHL+M?L^H zWa1CH9&U=tQnvaAo81$<4{#JeOZ3atgs_JLr|T}OoIc8 zt*F4fD9Ni8OOkYvBVn{Gwd0@3`C7ws3?xF?v+gJyTmr4!-wckz&=NsUX^OiMTA^!>KhVde%Tc+2jWI%6x=;mz% zo-YEl>BlwbN9AcY-ox`{kBA^mJVMz9T+0ns%po1VHkAhwTk_Dr?M~)UtzdQOKu@6> zb6|L#guh9~W?u(Qg=zhs6p7)}ZAUI-nrnk*@~z;%4?MC z2U_bcP0(zzO+&9gIELI=NeqrDgUslnk_*q)%0#fWu}@f}Nt9ydx7)gR3UQ1w$;aQT z{|Qb@D=~v4f;3q@Lk%?YPbeL?%^NJ+>9D0D<5EDoFNj1)WZ)0zJ?5#=$Y2P9G&`kJ z>3=h&**aD?F+p`_#Gp3aP=4#tQM~{Z^OB{WWPfh>KvbxBSPNfio3l@LEB8SJI@5|p z27R}pQn3kZ#1b-^GM#ezXXva>(&@-?o5NbQ! z`ujSicYKfR6%OD`MUCWZYAes{O;<-OWkP19m&@Mw6+!i8t{YBvYTsJ)I(`N&9EX*4 z*_O5sXqpb{b>@^E|=8+Scdc76{cy@wNBq zXlsH+dM&xVmfG%Q(F>Mm<^d%DiVC({fo`JekEljP7GbsGukHj&BoF41fUkdAGxTKP zdy>OmxuJb(Nz1X$C$M}9mf0xnTtL{VnuLK7EzKH zYJAcGx|m>CO{9O?WJUvB$_P(&)C6ti@J^X|kyr)Z{NdT*Ed>;RWAL=2Wi!yws9UOBfX0-+_m9&MmrdP^E3$t{(3)?qISJhu_C(PR0y1-gc{{Cxn{)SYDS*nZPDAn- zd3>&1C-%W_oh#DuQNyCPBw7~?B?eyf4=)0n?Di~p;t=>U4Hjq(ZZ%^C#h##ipx@Qt zSQtv-$v#-wM8PL_>EOQSVI!q{2Wna->+r}d3bi*M8Vk7|^ApdB7Y!E|Cpv;h#L!-B z)(i%}3FJm18MQKjrqpzF8Fxb|fwK)_ zI_XJ-ne$NlB~@tN!?{JUeDh73$fV^vp0=$MFj6p~mo*u_tZL>y?`B=z{F4AfaY1XR z`C6Fzpygl`1)pWTrH4C%qGq;V!8UWWfi1B=O1s6ya{BSu=5JwXf*Cvb{9L2{Opfb7 zkacJ$tdfkP_Bt@zgYj*)3i8)l&qLf^lAZLbT73DQD&G;dba0*%nrr@0hY)5toRccg zlTc-LxDoA)W5_OB9>ccOKEqBV>t9J$5^VO0F&cmP7&glU;Q2)MCAXSoqQ+39i0}Z6 z>dkJvd4j7%RUIU!#o>}_kZE+mMGJIz;YI`1`wJbPTSHks)mXGG{TZH8CN4g zYx_H-_;3_aI=Id_f^CpdkBDs!2!^Mt3WX<(kk6wgIj^F(Dwc-aUNigw>YM;Q@#{vP zct}9yf^|oVh)(-hd$B>SyQ42W^w?tvYLIYJw6Ry1=ME#K-ln-4$FG@Wy)9r^VGyBjSUg$O6_~Y2ySa`X@viQ6Po zlj2TTShMlr53j*Eij$643M5xH^MG#+TIP_N) zD19hUU`IxKFfrl>F_3|F)}+u2wlBNH>k+}|RovfKek0O%W@<#vz$Q!P!Y8`ETU!wN zFmapO-{^=(m5>OWa5k;@0_wnYQ8}$8%V?8K zraTc$Jxe{8=&zEc%o}%wkI(x7q(o8sB7vKqg;36)goMl_Rj#82h}DgrKg`Oh+~BWV zpk}V>B$G@_LA?#H3ftJD-z;2HDQP1jkE$64zK{?ak?p z<&;kh|Gj}Q|G?Y5H^cMqZ|g!rPDn%fTXFvm_q;Fd9XMM%HcT%>>hONTylEylq5+gS zyQf6UM;J4sxrSdCQ1knOXn=C4G3v)=n>_5b$4*a&7ZIEgA|7U<($}oy79mMz=Zu*x z1S4B$9%n6c9^GBA16hisfYfTXs~x`yhM~=CJZSD&-My0aA~g{&&sm>aGwiB~jxA4a z7<8ZmhSwfppf-gtO;Jr?&=E7gq2HP|Y&{R0g>e%F?q1k@uj+ zset4o(<-ab+R=0_Ks1UM)37l)IM>#THgEFB!b)i{Gzi3^cP_xAdi^j~Zas|@sRjJNHb?(4j;3&EAsD)!884Ny7lhoX(w1c=o!Qy_hSGTJ!vGl)(ghYY)lKz2}#<7$hufWSWQgOl; zva^cI^*mE*uEH zwEb9hD@6<$S{9Wai{0Nr+Yn{o&&~$XnX{Hig7!H?67%7EMtVPA6}sSdSEIWRFz>`r zSMl(GM~`+xZC;`*r3)y`bG6GDZ?A6M@a=YWn%DPHO4mgt}f?}C+T z?1PgbuZ$)AzuEC6ts9-1in91i{KBdPF^{>ebwAp8NR@R*fClq#c8@P@4QDR`UC2E1L`gjeTPCms5$AR)M)N^k{h zE|oiMjEf2Yh$j5&%0bbiu7}ZjnG_z1)w*#cg|L@QFNcZ3>&t!Y5+F$&U}00Pglc0` zX$H*dkr`N%&EVoItt5&q%V$+;!Q|%MO~M>(v@+_8Ow8Z&UTou>Xn$Kb>y!(Tb7~_q zsj0WRI4zEDAajLB`9@bcA8XXCc*Nu32JdY};1njvR4jeHHkWMEfU)e)3`{ucC( z8N;M%y~O4Xv!1ASFiIF3J;ubYbB$^`6In;q`W%-Pe;}i4MgtSO-ru$45Kld&ofgR3 zF|NjLv|GTNIW{^P_)LhqOv|%Bd-JVbAVslh2w3E3MCAlWdv+ViHwVm~W*Ze+- zirW%F>Y?ufByGxJ2FGHs_F=><%)@Yc$RjlI=j4@ry!?~%Wq)#1O=vhvNosWr_I0!!R+JEbKh=N~Zab!malzcT)|3PFSrgvsni&ioC*o22drbJp5 z0)sp4s;B>4sX)0qxGDrXa!=Dg5IPu9h)1l?uSqTee)=qUvZcjCU@I|4uuf2Ou_nD= zz9uwXWmr{R6TNhIgCHf{jdXW+Nq2~JcZYz4bW2M&(%s$NNGK%@e&^!*{qa$rEBBne zXV$Ely=Tq1dO5Er@7S=t0bixL7#U?5rko}MbXJw-7=rj?!SA)b4D@;kw5~moKbv~r zAG;w~vy{hwOoLb|Ve7iY=8$0QNMEv{UZ)$N=a`GM%u4!?7&Wc)8dQqAec1-9p z?)}Q9SVSH784>6b1J;de0(3WhW2vs2U=;705xx-VoSktw+!%r7QDCaZliGkQJWA{! z$!a04FkdrUwto6Y-W`t>4F*b1XS4JRGKtrAY}Lmun$GfBJpVnajdz6jo-_xzdv~Qs zd2|Q%bW8ls%dVhaEYJN(4nz5m@P$*f{{0J~?-ARc_@I2Pel-(rqK`eFc8ZHaw$zyj zVt?Yp3KLQu*Q|eIiUjMk62Zw3_zj=GWU!KG^lks&XjRD_g4&4yD%+Wa0*C3tO&h$1 z%HjxZm9>xEFs3$dhrWxYLT9@~61X`SOId;xj*J(J4|ghFP#d5gULKQwCbPjO%&*i( zNd*~We@Vxr`#6NR>E0q@l=Z7y%P7{AMzC%}tEA|2oDfx6jOLEcaU+_ms3w07;)KE->xea0<3T(?F15=FHjH6>)BdNcA%(w5-KK<)= zu$ha^EjLMm&=jxiTc zH-_3|mz0c(AH(VdYQFB3^yM;GzqQ_;13hXltrZ6N^QsVIjn;D9t$F-yyxK!8)CQ{C^JdT_HRKIEL_M`{pqHxzYteo8sEHX7EDZG>cAW$kBFKm3}o{$Bac6qo=~br;D8 zv_V|ifYeVi_<%88u1(G|l-4nw;n&e>lYGsbgeF_8r>?Wd;w&wpUHFaMLL~$iLuB2S|w?>r0A2*f`AIHPDs_?Fadwq?PiZ#s~n+I>?=iNzT@uT}}GxDK!%C`;X+ zyvRXO7)(E`SraaB0~ z+OLlukUk~baMzBvEv-*S{rsuD1jAAxun2cTnR8AXA$`_tbh-=_Y$PNL`{~$C8)`Vpx{8!p9)jeT{ zDh&@iHx;tnZ_tGwWHEAM61Dwc2C&Se&KjmnK2)+E`g`0PU@1lLkgOfagzWrmzV?cN zWFFO}Xwyf}T>$W7K`(~R%=`}HM1-NqIulQb1u5lyCALSqQ@>s$MVC#~0$R@3p_yxP z#?cbzNZY=tgb&#}}5A-y95G@j^nSVScY1#4xBZ z>tMOuLOGAp+%;4&!r?O(5e1k<>dd4rAh)S@W2w)!NZ?VCQ5Cs2ozj$?0D!#k=}CTA6$h|2F04se0JJ6 z?NEg>%Lyi##UV78z7U~Cyh@t_9SQO*ZoC0LyDwM#I5f}|Q=C%LvT1=Hc!M_EFk6b% zDcXF$mfdB`nLCa;Z!Fe4et);f@d%_E_@U&d_l?R)$s8$ozug?GzxO>y9UyG6PD)-= z!9LL6$C@boHPgs?ADqpkq2$NSKc*$+Iml54t@6kVlVS^ZF}2ISRgQSaq53izJR|Qd{~S1%1t&TX9#P*d_*5M&Abcu*wPo?1G+f5#Dl+bZ#GIaV{Y!J>;lC%wFh^BvCQa;HX5UfK6+Pt%MP*=_Twe;=oB%M zA)1=(rhOmB&C4#d;cFaR@9?{W64>*F;eZMvTghY&@ZdTi z@v!y?-tQap8XJ|nAgN>3`(|>KTJ<2^0!+Y$c!sXs%dK_lSz%|c(X(ewxE1yPn$$c+ z@mFq}Yo-iNuAJ!Hs}q?x>FF&JmBK!kactdngI1=I*8<87-Z#>qi-@ou{?A~kH1O;+ zSx8-TXCTW1p}M6;h0U`a?#V~6$hBAI1utCirkcE!<4mmm==m*)A<25f`MAR&^&tY9$VDfO!YJFpS(Sn4vue6%KSAAm7T7fk(A zO2BF`24V@7+OEJT?Z;E*Fg4a-AhKuP4gkc&L%+2~_ewQpYb)+6!^9ROI>wHG#dlz+ zTad_QD+M^pSkU}9Yhkkfdj9bjM~yq<(=|#Y%5<1gwXQ6`cKbZ0l-W%{o~gBgU%IL< zyolf@PAZUj)pm&Bvxqb>nW-CjpcuY4e-Ag85^x0Z6GrWKF_#^{xLw263Xs;o*f=Fg z9UXS&xMp$WuORVuSQ&#&WW$WQje4c#;*>L+iy5P}0?$N#eaV2QH6vs36DE}xy_(Q2 z`8Mzrb1vc#o7J8KO+Rd{LemAU8PGS2Wec2nhW^WM5b(TkK4?AjlyhqKt+mjLB5JsW zhm^sqFrE6j-1#>)aewdpm=EfeAwj>Hq}F{cj(~xdMIrmkKvYYLVITYA&Zu)A!1g6FIdR`w#SNSybJDneg|VSLZkN*Qq!Y;k9rk1!~tXMu~1A3 z#rLNHcXzGMs74+5$Ovy57^g*gBkW`m0o?{{q0B{j&C#&VNTeRKHur9Q3;uW8VXbi~ z<>#zS7#uidPiTZ*x>Un)-1-YbT|DP+p#a0jH|k4Vi6wuPkP^n=TXz`*3JRsp;vS~P zH!>KC!+4AsXCThAqO~_dJ!>YKe`}~CCrBla2;CnWjY-9*A*{EqS9=z{q=%@R2Oyt% zi~C7to^0^SFhU)l>^wru!Pk9(Q(XXkOtXhMnrHQJ8n2@>S$~flARuAJ&a=5A((ALP zh^uFYK%)ND2j2D#%(s0zw z@cPEykUhOQkFhPOFMEVy)ZgOL=71k#|W&Ii3qQA9M=$Z%WtiDH%99N|L|Lq$NMz8 z^c>T2!E4PJ<5G=vK)o*UFqf0^Q7cXCj|NodQ{h9u524qPWUO0|W`a%d0OV2egsZ&1 zyuVOeKG1~#O=7tUgvi^j@BRRGik~0C2#)A%IeK;Cr5Lx?#UMu&_bjEOX+2Wn{0UAkj2SE&RkGHqqkea`q8Ev?KXfA^0ZCqu36K#Smgz!8gS62) z&5~E8p-^15u-+I#0lm_gl$e0gclC%yFePZ3#&U0fp`q|9dH7%9o6gXsp;7ktJ{+u6 zyF*~PAdvVK99>C=a-W|Th5vy_C3ky6%rHWBV+2+%N_aE__CW%Yg7{0;0DwV6TmfKv zRxzd7J7GxVN7$^C4DI?F({EK`X7Lp~di^v|(kQx~Bx>=(p9ciVVgv*WiSmhP9GfUv zM%K7P)Zti#4~}K;FF3#+8Y3!D{izN!DwVR}d^CQrod#B8)f?el^V6=xhb`4Rgwdav zmZNetl(${Mh^au$3hiq&FlrAxgZEFoxB+lcfLtebHvhXXT&!?JRdgGOK06oY=}-Mk z$!W@$w^QUX13Mlf!R!wyz#PmivkG+Rf1Id)?{0MjSm^Bgr9nk}hq5PjZBpTy({*DB zycn8X>r|2gxdmNbKi{)i2@K1;lQyx96<5bIiWJ4v+`QS#Kh|Nv9mg#8PF8C_5{i;I zuQ~d7sq4PYM}{GSfRWa~{^26a;4!+t1&_Eo;Ap_Pb{OXP#gd=H!v&(7XK>8HDIXX{ z83@kX1t^sO5o3eGFV5^*cebLU>$2@eqXy<_(;Ope zfQNKK`I{Y{|5QLSw-X}VHP)GbbXBQRFMP^s=Juc3&{A#uhJe$}O&YDEPg6Yp+C&Ye z+`!I}qI+rzOLkzvtf}Jt;xE*AIqVfdM7q7zh?K;_sg@8Dg48}wMjL`#Rtw5JTrgbEr7K=CgLNak&G=U9r;;HSB3#z)~|Lma>3KoGB$CgW5oQ`Z~f}ZCgT5n7K(^g3ou#bbe%h=1e{8tzj%1cwD z+Rk`1z^Ur%jAxAwRj6;V*>*xo@;rgoG{uqz=X(`nInEjYB0vGkx#BMgQZYcoKMeqv z)#i!A9UVgjQY`9_lS^Oqu3SkVVUzVOvKuF(b0xZBXj9{ROc^%20g!-rfFCCINnj_b zLj(H}$O?lMe0w~NTYdd=L3rL{1mI)9r?C2l;6&2UoX~Qw>Qik%k*5^@QLR^#gy#Zz z#Lw>vHd{fF=rtD7YzHF>19GP7eb6L-W!Q}zrnhm_stoR%2Z(ilj^P`VCE~#fS&`JWFg{uyAa^8ejl1}`GE!d zqNpl!-R&Tvn7RyIPQ$8o_q#lltV*nAZ6L)e94M}?5NEG07v_P}|f59AV8jb38teU<} z5~&814^J$g0w7|%-z;mj-o2U)Zc`V}ZdZjqEm9d|wTc+5&ZkgpW63NJ`yUfun2aqM zf{O47oq$}cVh^yB*C-FhZdF`6_g8emkN}l})@!)J<>o@cx5ECfy1R%2G+napdUFS~d-$_K~+y`L#>B9V5gfV~9bJ9x9ffCtVl zq!A&W(#LhdAg}5JeKn3dt-);AEUWNht0AQoC;>qmyN!L{9Nf8JL2n`r39thKG@z(4 zt5A{Pw#@(_D5F1PdZeBdT!r*^KV}yoZUf7S4oH*7iy^WizF8OVw{NGATIW!DqmKvx z6A;UU(U$;g$H@f#Vc`t+5Va$A{;yYe_{!)tQD9j_ku$3}vjRVmCV$>$%G`YSNsiBc zVohO4pNi8^ogSrrFOhIh6a?^lqG)Lv3{yG-Lss<8 zb6u&b)CnAwQYp7Xh3bOSNDvUNftUez04g_c1_S0eZy@lECm?}$oc`ZDMrr$kqM((s ztN^nM9g2)F>L|I~%jjgx{gdXQMnmU2guTrH4Z}E;qNIw4!0Qp~W8Q~q1A3O~K1J<7 z);(h3naTm69HHlzm;_RiPcRChWIUQFH(||pAN?4h?kqz352RmL0RTGuM-!a=F5Cp0 zQZ$SeNu@qb;~y-p`A(Pa$Q**YHTkxo5*s8QQR5<`&rw|m&mb{djX_p@yj{G#$;M4b^Z&*>N?L^enC+M`0z<5t><$7i41`L{ z|7UONu>+~98sV>93fbZTg(073>R~lw{d`pZ&kAtl_HY-v#g9?C)I$WE$ zS@c)WpM7r%x-U>MdXIT+34uOcFKBt7IH|QA97B+&fau-(pCwC@k<@K=fFo%;GESC? z#E%4FY>X3JAR7!!07ySWP&9#<@xUv>fa^JC(aBpT`VG@jBlY&(xKa3Q))7O-+a`32 zTgKNUobYFyKc$mKAobJ}{A)CW*s+JU!cwequ`)n_r1fWD+Q$|VZ_W*>--P$|!I(lWuC{PICBH&7eGN!U-1xVqaq%QEI zbx0=dz1n>Y^MQ9=bbuOr43hH$v;s<#_Ao3&VEB|5CvTo+NeT06IVRANiA)XOcvOHn zy!!6HZC6&W9L8%-US^m~r@pRc!VVqi;IO*uBdKbl1W=`Bcn&0rD1Gpc9se_k2H4|MUSHvq2p`<`h)X5@D*F;Zr8S7R5IMIaa^Sa32D6HF;-{A% zh@p#!uZgSaRQ;N~&}`3x(F5A?j^5Z#fjPW-8!%Sl%0XwB=!)L{>sviT~gY zNbJ5U1ixlfufYWkHbGpx3vBu;KVE%TFlV`WE=ji*38m%frvsz8W4>!j`E7+T0o`k# z8&0bj3e8Z1^$>8k?mzk+MAHyn-5}?pb}W$KRLugGiUCR#>XmoabG)pSBnwd_=-{fy zKL>X?W(2TbMHq)D<*4oy3rH_};qc30gWXRg7G`1=pvQrav8V&Z(F78G&>A=~h{uZg ze>nK_o5{@8BIxx)Ecnn#|X;F*&Ra>S?d+!F&XJ6e8;1rauJ1EKf^*5yNdpP!A z!!|8a@cdCx*)yRy5U~KRvI8dPh-6sOim@ds(URz}T!=InIB8(c;h}sqGMg64;1b0I zI0NLjGm4W>C1Aa>zq5k;f51a6&duX>zqP(bs1YEmQD5(960VmY`_H0j=(K=5NnA~g z|DO-M{+Q7p3N7~n{A+-$`YTcZS}^&pfBu`L5U;TZu(?D?O%=4b@pPx%JM2~G74iSl zf%K}-?M~Bi&^3ND2SC@gb>es6&Ev6@oa8XTj64;XoQy+XCpYRUa`E{?;6L**-0i4D z3q|Ben1E=d!C?FVj7&RzBFOnlxqk1gN>m-R+cNgsd>{}6VsSn6yMxIy!@N5VIGyl7<74l=(0JA%C{syEL zJwQ%mse;6Kuh>V7wxwMPyhy~-&eRF2b9qn zVFKj9zyTOJY#E&Bq!n3*Jm8t+{^5Ql_%zQ#(?XZ0s~48M(;wDyzb#2?a%&tC{T3fz z<-L~#ByFV_A`MUu27z5EdWjDJ{SZWA8h#_AZ?Z?fH(w(!PyqqJsT<7FMNTjQd;qpw z6{4lPjneQ0a8tuJ#LGEQehgVXkydN;E!!z}Dn76!)YoCfbGxQNUBoxTR=GG}D&HS7 z^Ui6Q*G>km{P*)fR&m;Np}dwrK9f=OG5m|QRcn9uDMfbGdWbK2EW*8Ozk4u4&^(h= z-FskmR~RZl5C6Rtkg>%Z*)V|fF>rLlEfe?5v^Y7ge@znq(RPtWlt7CQ`pJ9jx4@^= z0UnKo({<(@pIc0bBK4ki@UXFM#<{M=4ABF}p7IwsNc7{y0>@tB^*+bxUnW+m!+rs@ zMMS-!C{+ey;=IVeVV4KY2STuB;U%~0sh2iQD1uW^&#%6iJ8~jRJfQ_Zy)qo+u zCX5H-)2qN#HuwcB{ATBT+5vdzB{#jMBD|C`u*)=!$pP}jFHE0$8KODC{ng)R-fheg z+cE-wCyO%!&@>4hJIKTUJz0xolXRje;nfZCqbC5@16PfnyeUY$I+;3&4|V`wGEWDD z>;W`E_rrraH9^zb#k~h++q@>2H|3$*&JC6a0`Os`M&%kTfITn)s|&mlB=U!&6Fcy^ zNl%n)XN4RlkKm^Pd^z6ZC*vA$hNoij8U(A~&;MimRilRBl?dfSEqktjg~dMI3BLl4 zhl~MU2?p@!p=5LHiUub9BT`OaK>_cNWpPM{Wj&23b|gX+u=o(%lp01-frd*(Zv?k0 z%QiY>u;Bahg`NuQ{5fwz+Y z{hyCCQoa_TU*Z?HgOdQ7DSU%2vo-aSWoHPJYhSs`PMJc1g^SIl?5*Y6oMw; z9XeowX3EKzIS6j|;p`+nCTK>kWv`XVY$`^C6R!!?E3G8Ho(Oeur z+lvYqE2`2Ds_*BffGI++X(4LUeoN19vt_qZv87bLL$^=Yek^h6;h|KDurFY!DbqTW)^V}TE& zf=qv|dj!uvmK)H%#Z%$zq(97x2j8z5)78-L!m-1U`ap)gN2HG24ug%ujsJS_gk6Yn zsjCLqgfJk3SP*sr&TDcpBL`T|bnZWx6j67&@c@iyamC}`m%qB@|9yr8xfW^PhXuHB z5o-+a|JSJUV~Vp!fdx1T)L-3kNmz^!Fak#*Qcf?9X;Bj|&frTkh>xT5Y14M);3(GE z7w^qngaZa;AR=O%wPgZcU)9weLdLq2ROFIk1P!qPaNvJg74+LsVRA4x`G4#(mXNn> zPk3`wuZ$Reg#*N4gf}+ebPQNO1OVy&C1E{5)Z_NVhLJI|$SiK9G&-W&e&Addk~%W# zz@2;C3NWMZZ*m&bt~ruscV~uVn*#MC7jH+#ArRb@z=q|hb7 z2`qLjV7N61I3%=$Mc80Ai^Yl)I=t{BDfnR}%#bvJGz^fh9=TP1@&@)sVi)ByW~#?m zYikOp`}j#(Cv{92`p;7tJUHqEee>Xufy+N@1K0Fa-`tA@FJJ=5ElT6R@ZTA24drT* zifg4yIO)FwJ5aEB(hAlvV5o4_d^93PUb;VQ@M-?xtAD^jv%m)@Ae*V66;TDR16m%p zJmp>?JgyQC|77D)u4RWZd}?zro?Fd#rCgw*=3CF2yHf!?H&&x5VIDMIVUnro^#3>f zA4G=GmIHb)B*SYo;JAQvi!UaTZw0R4b*G3(!=9;jd_YR5{%@r+UkwBZK`U=x0j6jL z5Eq@UZ2_VjO)l}r(I;SsRs53&+xO_S{;j+S#q&||RZ=TL6#&!CZe`bpgf+9sH<;QwYWYC4+mYY;#Togsl#l@oTr$R|kFX=62!yHg!%-J8&x zi~zyE_;ffBcdoc3;~P@SoDdIyME|$_btC{Gb2bbzZ{P$2JiYI~vKLC&hhuO~FH3%D zkT{IhEogkna1txt(Xw0f=LKwwSD99s=hCgC_+dpLE~F_2-i6@IkNW3vaRhTysgy%qQ| zVse-D@$cicjH25JBdLEX*0AbhjkNS0i8|ju25)(WYxre@_W(d}N-1Z~RO%hi@eu8iFz-QOt*F&lJ<&9vVFd6LU=o^uc?)V}RNYzUe=HSb{KT3K6pOXTZ?6-a z2I=^E1;6ih9Z$AfrEc$i=Hm7>f)%U;9Cio_Uv&+YwCSD7944VFbAy>Kq$&ErKT)Iqc07-K?Hd@U}Awo-`EO}a^RX2 zOZef-ZjzefECB$I)iITDKdbsEN*LTMJuLnnZfvuVGnq3$ab(Pm zLV8MrdRTJ2kV2h7SPyO;W3eKMAcDl0-?gBt2STC^s8WZ@3uLRq9YEV|W;c>%mawWa z*fNNh;0?1V+__g@SLYzQCt3~$4nnuo)tlUCGdN})BAXIAm=iN2QV?`3$R>s9>pYBN z!xk0pI|+S4%ylFf=qU>+8=JX1cXOv07ZooyJI>-nd~hg>woj z5z-_AQ93@@{xS=nut%KV+ZRogu%tc&TlxWS#XPJtT?yuy5+E{l?qww&iz~1*f;uJO z^Mb5#U4(IUav6;`2d(*GD`P;0cxkJUSp5Al^ZVCfv%~0abs}mnkCs=>}pE-`mI? zn>tDn#BTg(X9vNg?DIe{h(t2R^Z>GgNTQ=)C#qjpsguYaBPn=bjsn%S4mD9 zkxZ9j{Sgg202)MnD2Q!Wpg=YfViKNYqDg7=t4|F6NrEBkokRe)4gbu@lXWbGA=>y8 zLBrB>HI*(@$=)rG&39WL8`ujg=w4lFB=aJUO00;GM@VRz4aH4GQT*~hz1(6`X3|p1 z$}8RRSH0StZSNCEK}H8PAKbTD)o5z)>QqtSa<0Y0#XUh%%7PkF``;M5av{(wl1)rK zNgR-#NI8gGM=ZnH8~sKkk*s_-)@C8hb~Vq>2PtlaeYcg~G2&?lObZ3rsC}gtkwFNA z@w{mNRz!zzEOic3o!v~+lNzq%#EShw6{-1qq0m#Y-`nf)k)!Br)_whFE&qOH9Bo=h zwCeTOR8Ca1GwJ|Hu8vT)5J{AVW z>$D8E`$MkrK}KSPbRMKiPl%nHp;qFLyZcz)7cDx-O z)iYbYF@ZCFW>b`ggs8FbleOCQG@#Tb<}^SML8F^@w;?oRtWA zcU%VLfsLKxa&ClW)Q$6tKFY|s-i4f0D7)Z*g)Rq4T?oW5d~oVvO-5s$T;5IA6^PR( z_9CH>=gUsBOg|(@m6#^|Ssc>T2Lvq>bn=79(@PbHOENQUe#jRB0+v!nU94-4u|%*C z_Eflg##1wE5XPGc?QCy`!YxeII3&t!aLDl-5Qdd`d;Tp78lgd9c1T z_!xm#_FJZx)WoI&3EReQoh1tMt9pW?UyNP;D0}YK7l*vTuo2Cqh8_z;erBL388I4L z{YfCI`US5-c@h07|JLyv8Hqr;`3M^cW$+V;63o#{rZ>}mQtKuuBb($!52|EOwewWZ z-)170gSlf3K{0dAE(z5x^7Gsw#5kBau4&XvuYGCciq>_;cw%$j!=MV61-+7hIVozW3Qvfk7G|zr4YuosRJ0JjRV~aKpPCbZciCRS?-1o1WI+;dSda_7B66bt^UwK|IqT&N8 zbrah9m#jKnQuU-fC2jwt_nqhu_48x0>P`8V|IkhL=2_?>t4n zbBmrrL*^U=4c91|t}Wd0cXiG*Eu71g#Hb6EMlD6<9kI9s!ijY6DepR9C^gSBEosQ> zJB(_+$De&eJj2(D+A9ab;WU5@hWC!NOOC)$`v}#y8P+3S%qTUF2$2lp+^9;{V!iMm2fU~sAUldmBiftzU8V?~%S}>i7GhasN zgyD1vdOk#vaIWaIaABa3lzhheM z>H*RKP8?y;$7dK3x>9U4q10KF5~ywa-z}#~U(odM8bX&0KK~>LjXDmcYiCsP9zl1@ zMSXm)&>Ui5!D6JZ+O61rMzbvk^~d}R&BXo1(1f1Bzg|0&juP0O&PB<|~in`n2 z_jVONtsGC6$cRYz-&NdgDa){=3ns}{9VW@_JSTSWF@d=2XJK!fXBIqJ-_mk7$Pw?`k-{H5r>Sjh$X{)k!LO_p^}6QXO@ zU7A99i7Tau@-WsXB>5uX@WyJRTs`*_4Aid6kEE{mA`RCn9d$14VIMJdKO|5qkx7)9 zOiaMHLG9aji?bL$+(_)I21q>T{Y|;bFA2jOti~L1`BttF^i`K7Dbi*~g6)^R4^1EQ z+QgAmri@T*zn+0uvX!vVK6|Y9M}-%JX_I_>?xWoTgo-^ZTcWrlAt8=#>B={*5$h*A zy}ko4PgOJrR90!lb`RUcJR$xpM;WaGQR|3g{ewo>Y-s6`;@0={BO+c;KO6>&H!SfDiZSIAtNh6*%X70HebCjW4K_dm4_UfY-mrAqaYZ3OvGkPy@Ddw zfP3%=wKj23MBl(^?=HL3`*?1)ukZIl(4|M>9svd6q>F}+Jcl(@1eHoK2ZL5vX!gSZ zPi5b!kDE}ORStXdcksc^=3t`A0^Yg7;CB;`ADLTBsqq8F{c0p1KP}9rmT#Lz9A%A{=)uLg)!y6EsI_vyV^>eV+?C_5-lrq%f@iHQbx4AAkwam+B^L>CjGs_b3`wq_49GyFRHHNK-uTmE+ z{dUR=6Ju(@ajt)Bl44ZlBHuCSbFP+H{t>*N;?dABJpZ~)3Y`*I4T5#f4BDM2TCGks z2q;M}*px0sXWG@7r%2vn1eiidgy>W#@x`j0=;X+dAC>KE=pli~AU{+3g^DF3!-e~GLk7Km% zg(GwF(Ei5}`0NuORWV#Ukoi`50{yj+V4b9S#hU+1@aaAlh5p%xIFrO*lsBs`TS-#m zi|brdGiZKaGHk5<94jVs*VJY!$2Dse%z#6Pg%-?EWu_)t4^~aNR0Qqbcmr=URtES4zG8;;V`&}MXw!w-8n>^>6v)cAKdl4JBNs0h9Rr-%H+SVM zKV7N%ns%FI)HSaVFTZ$mUeibYtUNB8yv>&2DWF*LNS(phV|2(bNZ*3(z4RO0k!Rp~ zDBx*ZO=JG6v;l|Ff_KV=OBo4enUlFyX$v253cmfu)$T@q4-L2fEuC@bBSbVo%H3OgH8l@nHs(AMVaNHe;#PJeZx zJdk{5Q1I^^B{QuL)`X>y3I5G=x>a@Mk-3qd8f3p;q_Q7<@a%ITMuY$HyYhx=*hjC@ zKK5faT+xTpAxTW?uPOTmI}d)#lD0HLW#ZH^)j!y0IKE7u-NldEJ3`t+!J?7nk@Jvy zRi@e#a}jYsnU)2A5a|A!>{hul1SR`v7!j8k@0p%*e<}9G!J=fbaht95)6H<-KITZ~ z4Us@^R4fN}_u6z1Y8dL751-Yf@rjI*lg$2FjFpF$0+g=iSC=5)QEy`H>M9=}bhi{? zhkl!(>rmyte6u0{K2|cU@sdItU~%xy%cWKiug0QMP?w zGW>=o`PVhS4{h8H#}eFNur>)9+-H)6u4iZ+y&`a*+AFwWQkPtGg2|1n##~`lH$G=3axaFZz&{sl{vW zTKh-!59nq$Z~fZFKU3lJsCo~OBz5!Nxl^5dzAQwLuOW&!6cGUjqnP0T zu{=QUh2Jda1xL6=N5Ydlr+83I){tN@oYC5AD{@n7jQhPqw`5xbhv^FxU;v=FHUE>) zPJyhXX2bdjhKIk!B)P&b3cN5kysjQSB<;VgIqP_+t2LW_wV>=46e`%g;Zjy~L}w)r zYb9sahorRo3E_4kp7=-Z#4dfJOi0k6b`rDmir?UZ22m`EFS$a z<>-M%+TQo?DBT3t=^_v*ct)#bkKSyLDkl6QQ9d+OBu30?r&LE6Uq%u9c1LS*>*W;$ z@@HL;^2qM?`MD_?abD*5FYJW<+HacE&Jen-OX=ADNODAUHsgKw z5h}0aS_D6P6Zr^5!}}*w@gHDXcj4r_7P+6|F74Eh-3a?c_;0S(v%kPzIl(#>br4NE zpKl!>np%Qn70h71`VRNex{x5Ev2`E4dd#`lhHp;gn7CH!}&f zS*2{S-15gbYjI7RfCbeys^j2rS9HwUgeao{l6>byv#v}kQ6VEIeXWv8T*mv^HT36$ZaxM<`5rGC zJS}U~Qw76bUrgU`f8`G;`JeOcC9}_XL_neDKliz|GP)S!*(yoA`cT%M*PN7yS$17% z?h)q|iNusbEG@^;AT-*mi>9&3YkwnL>VG+uCUc!0d$8U9K()#Nm5@UIq{TLiP$+oy zn6k7m@%i@<1qNE+=_HCxT(9roQ^PL(<>#h@_-|-lL{{X^2PkK;qmCZTD`kIv)Os=H z932K)2_Ib@N4eV)MucKO@zzv!HOnJDslp$+ zBgtF|!DO~QY@t=jq@kS$S6qmX5)&^s2}Yb&yf4$f8N*?K-?cdzqt@DY6x%rDQWpJz zWO5OOB9e~4b}}_*`Di+qmZTMTWE>hf(?rJi57(Cs)-Z?hIJb(fEi zA#{~|ZY!H*&eoZJ#n%I(s=x@z)4gvEVp=eDS0LIsOT3!TzchHH$fH)oq115xdsBm$ zyV+@*sb#^r;z=UTD&qoq5qk_7l`-@tl#cGFM6(*i+DtdcI4kNg4l1=BMF+<*GifUQo6mblO!;ioWUZ}qM@m(`D=NQ`EY^l@oXUm*@dNT(FKvuxylhrlQ|qg* z&nIYnOgPmuZ$WI%qe-I>)zL^!%lfYJ zo^yy#u)d7Q8cf!znZwC33)c{dtOx;^EJL$Dk!H-QP7a~42@mj4iuTPUyX(g*jTfZl z*$5$nGN{f}T52lc3_F#DIO5^VBFrAE=03xNL?S3+_$F2+(o{>EE)w(*-(QUj-V#ET zFoaj!OXgML`uk#EyN6rg2tropr2Xs*vRz=i=GF+_@~>1!t=`%N{YAvV-QIs5L|B~O zK=EzfW&W#*%P7XD{GE~-9c6^m>BmB^b}915Na=J^*nLLO5Edu$l|H)Gc~0+bvv?tI zxjO{5RP*tL9dU+#ui5IS2!c&i2II#*_Yb8=6nHGcq-z}IXS#Dt8R<=-hv~xNRomgC z zxzcy^8I5uO*nL;8=sQG7Y=G51+>au(vru3q+6)BN$qyScE9XWIq}mUeZrmT&_s6Uybrv$;mCf@S7&;ZE1?dHOjDs6 z%!SPiY(8<8LhcfZ*^o9-I~=-nhIAet7S;Hr`Ft)Oh(Al^c# zN`CTy+YeKynd0&*w!($y8i9m}k8@}pl;ttASw-TTbB!Acgb&Kz5W7uS4q4ivk6GC~ z#Jty2bmQcR78d93H~B6QOjhG$Azv9F8vf1!4Ua?G#PR2iLonKxDCL`d)O*m3bB5pB zlIQP8p%8(!%g+Z$Z_NJSetKYv#UqRnO|u;N?)ueb;g~z7s8&_L(A&8$z6Xn`))!9c zWm7))U1_u5(-VI#4d=I;3?aqrD`%b9`jcv_6~@$AG6)>2Shlu=S{rnjkf+bTMJ$kA z{mPw~Bs0ETScd)37C{f)M-*-`!B+gbhS*tji@myq&Rk)8r7VCxi9*S1B>f9DHT)k_M@ISz zE_?Y}KPr>HwK#AQJb)^>TG0X|tk|d~&VN(BlfV3QaVP9hVxMl=h?dwT9+J>E0IelU zw$(|cx3IvK-kai$Jm(83KWsV4G(gn6snr?7O-26@mr35CGd{&oV>uIaj#ZpYXPu!C z=h^OOgCWR2YYss&rnFSZH=Z!0Nk9N% z!gkeNCVvq(l-}G4HFh5lJ`{J#i$dyOtkwmot}K@w;RE;?C`*P>57PLWY7b7cGQR}L z?d7KQPJtA;i->_g?Gs2+W|DziQrS1TCW(d=(s`=cJz7Tjj=Lr;g`D3L@^*VXm;)8?s_zGAjec*tvrX7GPs1uu(wn4)()%H%Ul#6WLCiznwO&!bisDJ(tmiHav1(m zKt5i0gh=u81=6<@$d|uSh4YIWZMxzVC6RpH3G_V-pU7%B8KP(+P2Ti<2$Xf+pW&*v zdn+B0#KSnw73tkKcVk0dGoa^{U4%TzCLFBn&CeN-?jwEdhpO#Yc7eT?6}S^P0JI_g zINl$`5m`uB%zDp`-L7Ns6|?Cw(0*Lr*x#2B6_0qZ;_cXvAX%Pf3d_70MY`Jk)e5=l zdbcN@KP9&#AMtTz^2T_a3l_5f(2Ln&-*DL;%!dX&9bfy&plH3YQ&rmL+3=8t93Ss{ zT?RCtQYnjEsB;Qg*`;`p2lRTpJK_ntK$<|UHiP5y2U^@KLMekbDc~-Lg8Hl$-NMru zT5@x7hd&9V&vzSHsMYAMww3=J!s-wHz?Uu02%vOJi zPLi%79z*Z?Aae96^_0}V4ExRW*g~k(z-&<(Mkqi=Vsd|LudS()N4Hd}=cV*OcsYG; zU@5kOZLC+IQ@DsL6rxSl3jbUi!`rHzV&qdB+FAi})7TkUv(fZ%Uu0Nw528 z-TR5|t)nIfYfVq*UBcwwY@no1pn?7INDz?NMV{F7um088^CeWj^UHbjF9ECWcPe&6 z#lC-s#K*DnozT|bTDVBfDfosyCEwc6hO}9$2Q3C_Wv;My5uEnN*@b z&L&w@-s;HyLQa(n8J`_MFBY|6U+$MQo$G&GSJ1CqTL{L3Cu6mPo(c;lSC7BliLczi zJSuMK)8}fmkgD4_qCXKUQlq6`K|mCgD-?_oGWeY(cdQJW@6i!?z7Vj~T&9_9i<9K~ zA-VENV(_}7`xCB@=XsZB01{zy7p*3%GzC;u>o)bGbhg3&05L$$zd&anFUQOFLA=*e zMc^5jgVp(drOZlD>%y>(%w5`(O9Dq2)|@az(p5n6T95S2h&e!mIFA6>E4`EHWeXW? zwVc?mr83x#<)pD9N!_-Xra~99lr+CW%pVD73Q;i#>G{IRps8=F>^88QPnPi+{%)gb z`o1&TvD6nbh~(K@`Zolb-mss}5)M?J3u!4Xut?XUqa?Y3+o6B|d>Ka^-ykT5cD}|m z_VA;xrIOA%Tvjcf6(pZKpqdp7cs+8tQhyhQo6N;AzVI*P-2L8~{_+czk^~!;+8Vva zKA{cV2Tlre>l*yVW1PADAk!P}RzIYO?v(d!JR3fIEAr1GvonJai_0-Fc^AhupaL;W zc-}~wSVam8ZJslKK$Wc)XPiP4<2C{4aWRFBCP8A@bySdV%OsncajRx}({>hW(E;1U za$`DS?rxeiVU}yT%eJ$Dq_9i!j%gWL>jtz8!b0J>DrP<14B|fSY?cN|3#}mQd}jjM zh<;%n6xNp+TDUBY@f!Ad=K_?s!3Byq{F(vUSP>CZlA#BCb5$(53v?yjxd_B9iw%P?JMy?pm9P7e4sY=z$RQ_W1V?wq^$;Yi6!) z;0ziwy>KoD?;ng{MnwwMpvGJH1K$(;m|$)WR&-nS z98d1mmcO){@FisjiudL3TpL0&LlHd2P8c`sv0Vo@g|mxqGph&w#JLZ~_|9n3B61b4 z?jPF0_y{+zyEBy>bJnmD#ubsqVQGrT9i4+Y;7Ng{i=||`;{wD zK7eMQwHO~}bBo#xugih*F-%=FP>;MN1bVswFerk>k&%K(dudQRG4eOr-F-3+S1NvC zZ>d0Knr!6@9`X0OX{IXPl2G@H%e)O@D3sGc3R-U$W}i;tZs4xvEa&Z>Fh)>exZt@W zmJ??WU?o&CE57U~?my62MX}M!?d@-OfZ} z_O*K&*S8TmvXvAsC{p2vd}Ld@kYjPhEJLZ@0w4Qe&x5|)<=h1p=7-*3Bh}@=52=|w z?vifCt+oP|F{R^V)mR>hZ26OQyLuy+H2$_KvR4Jd@GaC-)Lgjw!h)r6g-;@u&3Cks zJc{zz^h*Ye*c}ohC-mFQjFqjtSqpK|`3m_@>15}UBv1o-zsQ@xNkH?$lU<`AGx7%y zlF)#5szK_P#(`%hJ8t$SfVzMr(5Pqu)&@geDhLTMiV4fuOB(EVt{jYggAaVbFY&ac z#&`*rVa&XM95Z_CuD)aVF{f(LG&QR@Sh(udU^lyNdjM{6Y_su|U{n%aqx#HVqqs`) zg&HfdCJ+ROadOy!nHKW@Edqtrd4z26^n)LxY8n*Of;*#39009n0li+pt-Z;zevDMM z7W2B&_6-ipaB>dqri4ilYL9?I6}zjpi0WfE!-(S_bzc~2%huJY_T?UaP7{9Gp;O#( zYHmO?{0(sbd*^Kl1gd9dgFG6xua2_%B^fDc)@9B<>vn6ZD@mB|C&_R7`<2D8qo$ad z)e=WM$SLrs)B1Z0uKOTo0H)bC>+V-}2&d5CKfY%}%4&RIQAbo>e72G-kx0~U1Iz{p z*UHa;8R#^cBT=40n*xJ~)^cI9pz>Ds zcML&4#e`1HMfCksF}4yuu4uyJGE1HlKfrM{$ZBtWNn%uRDMrV-HlNkmfI)Gq3PweY znpK8oSKw=Y0F(wzL9qtbcM6+WaoIQ zoqD88OOqHHpagzd+>y`>G7Vw94*D&fgGrXKnBqdj&As0;y1?$%c%3MNvhd)bwjGzHb;K>-+Q&!-p%@Z_nQsnEAy|T&q+*MAH zCeGQ0IC=Yi9ut5)(K|)ZuL3Axo^S{M8k+;F=6(@s~(rAn*3#0y$5 zikjtRLx6U-%MnH_#7eoLe=uB|CcruS6}MM8Ulq%@d3I1eQ;`wCphvAyKp zyaE25VTT0Bj~xFP5xE90S4V$*;h3Bt&i&Q{J^%nvUt>+f%yG7q1K#z@X`ZjF>{Z3r z!lDWUqaNF;?*kNs)75vVc#7Miu#UR2@%h8nj57$p0A~|SE^t;t_Lerg5u@~nd+J05 zT!|e0gwFXKUmUdiXLUu`qFj2|;v0aUrYkF%b+*M$n+{&#$U>|tkI<@lcpz&CDa04b z%IH6Dvh2G(eZ}Na&P%t0Az@K>-I%m}Qggev<$IC?=1RU*Zyk~P%<`oXoWVIQVql2H zh)6>zI8z4CSt5A+JNK&_S66j}R zm2yo88Otr$%ID(RNVZO@-qD=c7(iD?^mpqkV+(=CgoXS zR zea-Y}y`noML&~w!6haMT5QMj>pH#FUSp?DTgQNZLuIk?ABV$N7Hd+>-C`!nLwN1xe zUN26hhb>dHa0JmktubqiMF2JZn5h&1S@qLX*06g)FD*JaZ1B|Ib9!4|79KSmgvM9r;gA@ab>HiADV7B4_G_*MF}tb*3ZgQ;Qg zW;v%Z-p7w88bP|*PB5abpOrzpeVnYX4rD zjpyI_K@!d(X})B4VND|~9chi4tzMTE%Ez;)R^Z%#9SShRF@d3KmCaZMjUJ+h_Gaz% zJ}feezckb5h(6}znTT}W$(lIN(L(fl9w3a;E;SpxDdNeXIpHR=pLHc~^5@sw7m8lB zEGa(EhxC%{^U&#%vqCHKCEXLPRy>qlH`A&!S)uz6guw?vb`OZVAGk)Po*Nk!crsT}x;W#L@W3TXkvL9pq&j)~)p32Rd+? z=L-~sITw4Nw^If;KyU1qS)UuGfL>{hzd>*T9%|ARb>7d?;^Y# zv`cOcIrk>`!GAS=;mEXr`1=xqFT>9!EZD8lEH@lgCIKNy+G6Fi55t@Z9#&mk z)F~PH=(6nL`)vqxD$vP|01!&rxa(^gyBx&U8XvV_Z<*Ld8&4fmVbnGrm*|J8RHJwp z%y1BHs7M8cjJ~5=*?6e7+*0PTtcfH~7o#fknRrHbPj@QAPMd7uoNhDJC z?DEW4YL|9^-^^JAu`om;;x=j!`0bXuOSbqi36RMdS?WEES(|Y z)f&bVR2m)}E^8Fg>jq3W%%n#-hUZ1_{K0XCtq_vv+b6<`bMC_(g|w3uhuas2>qaH7 z-lgCeUGY6H@Opg-{ctLQpVj%(mfoKa5OdiX=&8B8qoJ}GlBaj%Ht=VOo4*<&85~50 zdWwRm%2Lg#ND;7o0qUHUzl;bnGuiTLN%()sMU??bRUg*JC~}(aq&+A zz+O5Ih*FSC#N@!^&v>X7!)u?TzlET{tbuk2jOEdmxuNDSpbnY}V-FBxY_NKz{!5nL zUVa4-@srs`ZH`*M%Y+2iFeF}F%$`0@#UTx~O++=LY*XW#Mi?+%Xs>6z40)bX`K+8l zg@1AE=bZV@7<-Fk5efts3zM5YU{H4Fd1c88oE-Yxzhyq$Y9YKZo|?~XbKF5FX=V(0I5&)Bsu;VXl7d=K_cHrcPbm5GOvCT57IiSxySpC;krN2;1zvhhwBhd%niy6 z4vEUMCz<7PH{%{}y!zY-{c#fm-J}IOE{~UsY3<~ZSPl%kM+I5?0VkW`#zh*q=i+nhg&V`a)rrUMK|1!kG>wD7t#aX$(28C|(Pxn+(q3nJKpP|7oSkSXhTV6JdJ7n%v zW>Uo)AQ$3u(||udF75N=J=E|q$P7vKn{Br52g|&vzKm<^M^T})EaT?TspH3R2jQOL z5I?GNquP~vfi88=8@csMBth z)zv?Lg-BR)*6K0AsF6T#MH3^R$_{7{d9p~aH`t|k=kHRN1yW;%e+>EqK7o=I!!9Q| zzb-55r-8z5;=i99Tag|T$79a>$$%zhWUj&$?D#z79M`^GqjCPe4A2>A_F#YSX-!SC zc_tU4VQ6gdU5;>tFFtArX?9ACYZhvXVkFjJBCQ#x+03PD;mU2ii34PP5~pmrRbNSh z7oE5=lx^0%HvMrW{n;FWAM_>4PQ4qOGj--ZdXBZQ8_sYr%)^LU%ee)*J!_av))XRc zub--6rwLOx>SFI)-Rz)VDW{`x(CrBMgv!i18^KV zN%@+{?y<4K{o7dbFGwCB*!KeM47*~$QZAnI#TNFW;3myCCqZ5_lWOYyzJTv30cXl` zl?k*|*MkM|v{0sP7iSpoc)fz1tiSm8eA1I_y)Xkf#r&WCh*u8|XeWwquua`8)tb2{ z8rFChfbUYMB}C?Eg*0j~SaG=$vHHR)f_PG=e_WG*6UFMCCD&>ryJNghyKM#C-+p;d2FC4I%Yd*Q^ba^%BsF2LCE z@mAji`-Pr}X;fpsF1~|Hqz_&FTC2w?g*Q2JU9IYwsOt;NptUxCF0GOPbz3O;!{IYt zh)MRBmD!kvK-T{K5b8J&rB`Yc`<9aER3(<5eJn4r-S50Pcb<5J+TNuJq6U6J^qs-5 z7TiXsK}0eqajw$h z9S`(wt96Ie;cId79(fo|ev4n@WO z;FFp>JQLMJYA)W>p?e(gR%SE1r&)WG-wI@VYgY50fFy5(f}`7_jRPR3lk1WGy2vaJX2jyuH_Qh;AO6xKu8lhAqEKcT5;w-*Me8!wsQC^iTvJL`>%EXgMPE6L!mP_F{hszt;SvE_ ztmeElKlVGhY;q-9?S0;~o%OQR3JKzX0Ys#p2ux)a&+m6=a z^i&B1*#Bp8@XSXrcS>=2E)cai*M7*T;%QKUkr6Ac*orN`ZqJ&sR_iJU+j;Kyu^j{c zSuUP$2Y4$j{im^0CdcRqsD-eLdU-XRSlxh{9f!1-U+`t--of8`1l1Rt^cNSNgozQC zmGYzc{CMl06kHGD>t$ae7JG6%=nzh{gVEZ3llmiDHZ4i&G6nVQn)m@B7@gRuuVg&p z`=EH(5Azf8(7T0+c7Brr#SCinb_7WW(FDIOY@Xy_BHp3L1uB~gN~^mt52V2L;18%p zqJI7vM}Z`TU!0qHk2D?=e8*j|P)0cBI6hgV#~Ie#5b8MJc z`?5aEdAMlSg9U)fs;biwlD@tlMX3q@?8i>1*;+UZ=R!z=6UB?#E0;TA1MDL0PWEoV zozZ&y7A!e2TFJuv+HBZ>ftK!rg%pr7oQDJH3uK`#vx(g*ChGP_5vrL<5c!;ErV&K?RU4<&|h1`O(G`o)ARmnI&@<^kP5V&9q< z7A0A4{Y5-7Vt3oUCyER#0DYJ?gg;)L zV9X_^7AX~65pP^9+m5(O2@#)B>6!(h?NV0xE{-i$=;x^Tqp?G4RgX80tpYHBbF9KJ zy{q@lvG1!8tS`M9!o3%6!K)%sdpcD@WgP(NaYCeTJz_R4%O)g(bva0W=UYxM8}-v# zz)4Wl0Tn_G>waiOZ|AU>)jIDv)24`RUkO_YDCWf#H$x@w3Jqu8)mMhcp-DK?J$4Lx z_{q@RvAg%6B&SEbD)-HHF_|4!GukVYy*myk+EI5n+Z|mFSnf5W{rLpdH4fJXFIy1Q{P;unYKG6&fM5QHUu7WCd zFCYXo?hdgH7cP>&LF3^WzBdj4yZaVULcaq!rBGrhJ-pUNDJ$jN(Ab{9_82;d6xrS_ z!`BJtn|q%wmM?lC!y+?{{{5`_JLztw%=Nq@dW`6u(8!j-$nn;UMp|AaV1apNf9F_z?{RE-Bjb zQJKKLsI2P(tkISyb2?dd&-(4ZhlPdt?CRr7$aS)O^T`?DnS?-Ylid>U-*01rieTs#c+m_kL0odk@P+Z_sI>WWEShsWKl@&_8fN37ni&DTuvI+%v*`KaEs;%$6mBOs zfg-IQk!oAJmdp#MIz;I$mQUxRo_fzH0mJtty;=3c|H7!pXYI>&9VSkej|4N>k_TNP z7JpJ;O&<|+5r%=GP(=?MX(yl*fAGS}HavR;_@$amS1)|n>2V}*3`}I6&_?d|@0OJn zgt!5D(B+;ch7hghJzdlri;C7BAf(*&~*fU1xt=`LovucQb# z1FNR7tt}ueVJhmE)yOz>r0vNMm;_hY?81hl;W6(i{{+v&OemqB$_nlXB^0-7h{eHS zl=k;ZhgH6&>X||AvUfc(NW1ryy$)~vvS$!Sltf(bCM(=k4MpL{EcF{18L`G41&?tJ z_#Xe%2Yw)ZVES*XZBwf~L)HbceLWMZvs!==W<(jn7sj-NA=o(T#LWosuSnqe4GRu; z|Bq>2Npz-r{o3Pljw6Ui%K_Cgt$)HYI&zn}ITg{~T5Cos^c_#6B;I6iKnnx2iK9^< zq(*CaMvkg@hmL+j;n2sk-W#*=#&uw+-aUuGoab@RrCl)#nt0)Mu`L5DPP0nO;mwFN zg(^#EaC>B}#hBqe7Sb-w{<}p@vw&@Z;!m1nS3C!6(EUSOMOb0e6riXewwq1>o4YQA ztpr%}db2U+crd8#DH>*qAX^L0al3pp2qDx|>=!7V&nM%-3#cPRe+&`No;7x~6-Kv! z6@Wy9;uIam>-TF|zuaGv0kR}!y`Lcb{{am4h1|vfR)I4q8uWgj7f?2dnWYut8B91+ zdMSQ%KOz`85>Del!Q!@m?4!VO2L&=H?~FQg0ccn^I+vbG*rB8x^?h5sA9n~Be3VNb zwOlo?>VxaFF*Y)_duBqL10-OP{Z#JTobe#3np3m(L0Yh@pscoUu>LoH7NJbTNrzpn zBD|`tgW%4)%He32Ybnmy08;pQ9Ng=;9+frNFkXv#lV-w?SV`fiCnx2}OA%te3%NV9^4>%d1jHC8|0 z1rM~qGS8uhliZ6AJn8C2;A=VRU?ioIGZ>QKc@ft6W z<*+faqUEl~+{UXY(BRFVPQm@11BftESe9YL!BfLqSD_}J(ad!Sj}J>@SMRu_$m%f9b}Wz8uQ}%+ zX@6Pl%Hu6afeQ5tk>C%003i-bU8G<>O(cUoI0LVNES|s`7I4PJ#IsMI8y|SQcuu|l zD16m|WM?#Ma*O^Z|FFB!#^yUzHned@V2m&vMol<&m%O2K>5+?2B06RyyDBeS|Hl@^ z<}Uy{i7evW0%(Z^GeIFW@%<3T7`lc(eYk z?Teo1Qht}`-wZlvntCLW1Vs)G6~!rte2xXEd*cwT7gG8_zCihCM7bFAXt#Au_`M?&p`P8( zjkRz-xCV`W22AQx%0(U;X&0; zp{e0s1*2LVw~aXr9?q=cpMUP88HeW3C|&5>m10Nqk-BY_%0`qUGX0IhLI|HV4El*a z8)Rl9)w^xn=`t1&0l(O*vQW33hXVI}hGCJWDx6PiV1kec&H|cwk>AeF*;68h{NcsN zw(+HLG{~f6YhZ||9roGpM>T!s3NoA5u$c#b?x)p0Mm-yJ91di&XXAZvcH^iS8<7{j z?;0)+XGktDOJD71K&fEZ`Sm=s9=uk&Sh*V?jh}DILTfELk(qh5zdNx)(Qv(XE(V|% zhBUGMn%Ytc9QsBA48jS0|7g{TK?avPISe391Vij9>lV&>gxtrzn<)C4sWMT^Jie00 z7Cp6`XF~)?Y7AD!c}>4z_N9F;d&^=sxu!B$8QI_IAiv;AnW(V4`eyulzu47dd?Y|X znm8$~Qu+?I-;eO~w@3?tgHTAE0|KCRRAA_|bp8D#Bc9IicSZ7>5RJC+ka#|pth6I} z1=z<7wk40ieUv<;B{O7eKa|y*2u6~oU*RZa*(Ff&#v^R$D$OdSGB<6%RDFr*$`T#>~0Rdc>*Crz$+}*hK|76XDpvCIE(m zRa(8T7YpHP@k3dx@*9IjF!H|EE1HC}G<-yC55xolyfUv_El5nGtEEEt1Io(}q8YA$^h|EvX#G zAoSnj&$Ay4#c(GL;|Z65(=ok6*vXB=6YgnWq%1n9j-m-48q#?X<9sB(Wx$^+Ny=sm z!w;@2-9PgJP8aXT>azhL1Hho-b`^5>pZL;ds77=y9~ul6;^vZjW$^B@ZbgSWVfWxa z1J*(QNgIdDnGSF1UM?CFYV;NkIla`Sf!8_ToIeCxL8kwQFvjQLC5@(;tKV5eze=DT zVheETb6SxlK4<WlxF;L3vfY4#T zOB*mjwyPi3eFSGwc2-^6xPp{7s+P~prQfX0Z0mGvA2~Jo^-!ofgl42EhI-4>-Lj@^ zqegFCV=tFDy*ghxKLC7@3+n-VP7`hmA@2b?MWL1KX3D~ENX+v|-o8GcVfxdl)rvcw z>s7*Hpt*H?b0?OcfPz$Fn{d;(K?ltSZoVnv-77Drnx8zj4&%*=b=)6=IeAk7!>$%A zRX3+uH4esC^~lF`CBV3A>&g3Q;EGo~isQr|WzJzO_Yrl?FQZXTRVg_NXT@F>Pwcz@ z#Yrj`^JO_qnnc-^-25j?wm6H78|88kT!W`z<3-4(`>WfC{#)d;(gGta?-eM{da5I< zsOgZ9%yjylNB^&w*_sULeq-w#{_?10lDzy@+(=S*UP!sThFe?8mm;>Z1f?=ADLmc0 z1WZ>O5Bm#%evjfeA;<5S1GY#0pMHVPl@o;RJD&i@t;n6HFXfdiPnbZ`JzvnE$c9hL zadJh*D%48eSR-YW$2j_?k?XWM1VkZ2oVz`sOC7E5t8~+}^ZDiG=CNuIOl*ZLzjy#kS!&rFvP?;A)pkQhFV-4Iwd%!_a%@F+ zr-#S>(n; z9H$fX)FLD*x-H94NHZfH8wE=n?IawQbNrQmQ!;C{dOE?dJx-|C`(H2SapTGPW?s|% zt~esp5D4#!!VP|gn+GUFnwY{VVpjsr6)jrQ$hycF+gAIKMUJASb4`JvHBflV3%5q1 zlLe%{0VB)eW_No?n+QVu?E7y`kTLZwrgGCQ{M6kM_=pcFP-z%y z*OC|1-UGk+ICS1~J8!%QgyC*{B*@dC&q(x&Q2l!ffQ|!@r+p=?jTC#+f7Gzc9-N#- zAxS{(yW0dXGPL)H)H_3vt9yD8t5=PwKeWj9fi$a=!8fje^^w_Dp!=K%iY}%r{y+!M zA@OX#s%4h1*O=}MM3~v&m<*qQ#t%=vS|f)-vMR+oR#2oDv>h;G$T7-K5L#PXI8pKk zUW2eaGP`1On!|b&v!BTXXO{!hEDBErrC67+bkQ8y>!L#H!-`UAEmaC_CMWxILMz$s zN=p;9Dfg}xx-Tc?U=9r!b6J(@fS5& zaRdZK9rwF#^BQR_wE1=<<6;}P;SZJ=<01Y z^}ju~Z_aL-y#+p$5Q?Da{nl@RE9ohm4x1@qQV8=^qd{tqj94wYycfd+-FcmO6V@;e z?E=iodqZcuY}*4!smH~xqa3G2(zEh&wlslr)F%|NNv)XfX;!}-myF5933Ov>x&VNG`;E23rv-zJCEX>Es480ZcV2yx#`EgczJF)xtsz<9Hk9pLEV2v7+U7`! zk&R+vJ^Bc1@sUYZ71?Tg9VWy&RiK{Xvrv)utFV9Rq9BvUkzKtH@VHJ@R4|O4Air~U zm2xSnTo}S+x`nqWTalkgud?uAzRdO`^mE}tpDuaDft*mERNO#tj%Rnmt=?gNyO?Q0 zrHJ`x>+~N8G+M3l-0Ext{ZDHZ%8(p}y0+q+`MuDewPh{gXK3>{$ zU8Y3~sGBJfi}TH_zY8(xSgm2Nd4RC3Ar#3nWIQixIajv4sP=v_5@R|$Eu)U32ex-3 zOA6A4tT?H~XnvO7=zsE;InVB{`;42k%7W(CL{NfCOfQh@{_+csj=eR2@uX z;h}?P)Mp2cIXg(RS_xDMX4v8mn^zF^R?l56X&{W6DzLqaN#tdvh*lzuORLv8C zJn5O`vCw*G?^Opwl7P}!-FV|SUU0ysSs$;6uL-awV}GxfJkm(d%EyHMyW~HK6j@nL z<41ZYU*^LZs;)PkQ>dDUvEFzQOp(1Y-_1TC968BMsi9uP;KRw8Rkfq3;SsP#Ri>)n zXQD`v?acVyMBe^IsV8v~`g4qfn-&F7CRTGLELKW8*c(y#kwRl(fd16y4pl_$5b(w3 z8_4!!+dFaOIuBjm?S^{`+D}O5iY$pbBZN>~8m=g7IlzKjMY@;6z*6m<6hmHzHa#kB ziYl7Zxc4s7Rrt)X7vMt=C#4F(jLp`}{Bhadd|&w5!Edvr_5c#qG&HOr5k`?};w|C% zrd2i9bstu%NPc*iWz?ViCiO*xLQ-de^9AA$K=?m+B4X_%eg{;dMB}42b6b&)=7GV6 z6i0!VhM{5Z=}#oX&z+3J%ah`$>-(dJ6n=vUuPd+AbSQp5=X)KIE@~joTiXZ~eEd4{ zZjO1&DAC@>QI!}~6IM8ANn6-uj374QaB0dka*9P|8^P^tv_bt1URycWH(>G9|MQMz zqs4RIzDs5!Vlds*b{)aoN%};^CwwA%k1W`rR3iNT;fTJtEPMr+P-1=6Sd~Uy zv`rV?7Ha@)WFVp1UyRbGbd)K31X~lq-J2Nu;7%ARyxJu^%{jv=q{}!4H4BHWXN5v; z%%|;R$aWD)7UJkg6D0D)2~or$=G{nKUpF`0P}n;HY}R_g;9@PuL)o^HMlTQu!&f}p zuMDAlKT}-1FYdrO?~Kn4unf+=;_PY>i@Gv6$wPf&DkkeBZTKQQ{;Vf=r-nf6h8*0< zN$_ile24d5fZ%+_-PqeJG^IbNUPHB%>x^aaLC7O9DZnztZPNy!46$-+wzz`YDKE?|JExaZ$z!GtanWM`5QkO2zJ1W zJA;v+VQf7@ut@-JMGm>9!?(X-(Bs&Ci5u?XR~4~jn#Kts&f-xdq?qqzK95=0Y1jF; zx=mFI)i0G5ep@QrA9IEf>CeY}QwRc&ngL(()SrQPUwNB~*^B1rY?iAfE-{;waJdU` z#E{|lWjg`tq=O1Q5%?W@TlI`eS5wabY_3seytL(<_IhScSfEc&cw@8eioXLF(E~Le z-QSzG?-4g@pJlfKMcoo@RDBb)!julBFu`P!YlucW#o*0-*%jM#w9i`Vz3Md}1o+VB z3C1KcQS6gGhRXUR+a+MM5%`=a(WUKVJBV)fHl?eT4k4q#4XUve@tI{>_ zwRT?3{XZi6g_syBRc#R3G?UDub@m4kfp>VVFDiL~Wvl}nJqA%Ydh9Inel%KBm!7#; z@LeG?izxVeMMIw1ww?IGijPI2smo1CD*mc z`ZG0n%2NO?VN9;T31XwlB$NSlsj>%!^-C~-DrrJPVc?H z7vMj;7`?tx+KOXER7N=xY4&D}V|8&j=k3ili<|$oY33=Vl{vXb8^by;OeiRw;l}8LUE!^owKjK`=^xGYgtt^YAO%tB1)pVGCPCKxks@DnW`qFwfq}p0p4s;#%pKoQt?%bznDS z=8#ALZ0cK`(F~^8ykSO~`B@?_Z^bAV>lMA6lmZqe$5yX+yzF zfVu(db!J0FQ+(%{KD%w33Kji2HR6CYi!LDRj)_DY?5mUg5H9k!GIPCoB^MEUA(D{J zU*h|m6eu&y@2A@;6F=QWYruGK8VmEEDS8Wjry-zxu2UrkB~mdG=IuUg?sfcTL_Kn7 z(5B;`NwAbG=EmL@*bEN)+kkOnZCkzT(?|28hVoMZ@r+Rd2m@{YQaJ5R%5uI{*bqGM z-w0(%pAG-MZnogvQtqrME{ZQ>o4mVKT(>BAKlI|Hp^DzI{#uDVU*xG7H>*58TDBhl zHP{QRpqFC#lS)9*v41u8n2<_~XeS8qG$6(XuDq{ULm0+a@Fd_?>x!~@Q6i`>AAxj! zMSjSk&+mnwVSCNM<3<{6$Fhde9p>ChUL*980i*~`A(jU}uG%-!+ly=o+c&fW->qFBmf=*!#l1rvS012v2BUCQMO*0&Gv1W9w&)o70tHdY_oR6hL9xx#rpM zAn!}B*wT97z4E6JWD(#Ul<^@gWj6atj5mvhuNwUXTOL&?Ob%d5HB;gf86Kt-k z{yvl=1RwhSpwdUMJYvz7XV{6tV^k!i(puxnLTz@Who!)0U0nL zuVmDt80@!46a`w!3yp8cIq1E1-)r%#u1GxudGf@byAdFuG095V3+O1CV zY&aU}uuLR;-%QBr+!aIX#`2ZHvlfOCJ&w@51%sU<5nlYyBE(cmGPqVUN3c%Bi{@G> zQOs#k)dpTX9!V>kMSZG&dKI?}h*g+|DdR&H>ekSx8@Pf(iJGh%O|P7|>RRR^N55=D zALKOSz-^E@Q&*Y-o zEmJim*ehkstL;sr`gh3uv}3;)RBkXBE|$4+U^DwW>E5>)0>_l>Tp%}Q<+!cka66n? zV!H-h9%ihH8os|5SQ(D>)CRhb-q{%qX=LF0hFzE_M0kI8@GdPeCrZ3+v!4I5`xFS0 zu}=rqH&v?Cv#E;i^%m_O@-v1)14O~k(HB9_m@zbtxwshbqs5L>So}1QHTKWX>l-AA zC=`M9qDMl1NX#B0xyFcV;J$`xpEWRxu*H(WPg;$0CD}`*tF@5(Ft~HcZ$=`X2s<5? z+~H%-b*QiZK_aV66+7Kb4V8eBeTpZTu4TOLUDLKe&`SI0NF#g&O#gZAkPcA3cEtpG zso2Cho4zphkL6a@wRed!B9ED$H_*ED*kJ`Zv}IqublZ&@lN7!_pmg3kWZFJRwa2%3 zVyPA7+$QX%-Xo(HafXj=%?n}H2ADAn$%N0|+}$FT@^GQv-B2Po6kZ zi5E%CuGv)k_G^);vFZObfG0Z@N+KwDyw?Y=YaTz6b(C!QM7wg1+Twg?jLUYc`A-?2 zn}!@rGI&2s>y)Cv7E9KT) zFbH;4$_`8phTnbCH7~cFuaD9yGtKRo>e2(#j6vDz0WC(n395%VufS^WEhXKOh*jE*yommZhfor+hGb;AKoFJV>_njzbbi+_CnS-mxH z7SkWg*~Caax<(u7G|)Pe&qB)!9VZD`U7=>M=+6sLBq#f^qKr&Mme-rkO%D`txcxqYF%r+V8Gcv-)t&J7Ed{F<2qp;g=dN{X7&ifE90Kd}9WEc@aDb z{F}zE~kkLhlRb4sn{jsN|g142_H7z(lsTObBc_H8@2~B-wzh z2+dT%69&<^GMbySU?Z(rqmtR0_jA9|y2x!SeAb&rnWq!{hM2s^EQPlquY!-$;RgGQ z^6ODO3$dApbze3H$QhCTn{vB+Ai4T@kuj>bIx={@x>Vs}DCh)p`PialFqc>LXfqzM zXTN~B(PUvs1q`y`jvko*BUN^p#c5k%IFz32{{VR0 z7NAiv5Dsr6A$mK4HH&Q7K;S5wVdSOEYCqNa8GZ$8wJX>J47xzd{jN@2z3rk-=*J4R z_q!ZD3d(Q_SnQoiNx=*$W4Md#Hh2$Bf8fr?J0*$PbNGGsqRQdtKNc7LKQS|!iy5ZR zzh>K0Sk54;Hz&ewzei#L;4E*S@7RwbsXVO#;cER%QhGjcU44^ zL3}-D!_RM#8BOU7Ipr^-TojVhLi^6Ijr&R**@ zfKlUgRkeLB4f*)+H@Is8SZ1wFXiZLG;Bvh@X1bk?nGd^z*E@T|I{9rof;gDpzDk`G z%b#53$z-xeakIOombQaSEo(5ZO$|zu?To;+qN*F>??NOL(Q6WY^)Xr6K`Dp}HBzQP zvp*Oj+L9EMk_Iclf&WtT<|d3UFZm4Ycq-iJ%0*N>ZJK%=Nj3m96&(OKK*+y173SJW zhR^o9q69<7zq=6QiTzb5`=h(=$B)zVzqt>zc>zmyG-k12$((8h<#Sv$v~(%$WX%Uu zhRhsZz-;Uz?&Gj?qw=xo%Iv*p+O7M9&YJEwPYV(FZ|M*#@ZT<53K=C67Sg|<$EAuI zXMq#hDz)giW!%vqee9dx^kIy8)O{3}K%%(Agm{{&4M4QJtcl^mXmX3}_b_Z%i{YG@ z*HwlA>z_^pnO*Z#Fzun}%K`(7OhAqtB2)>%nDyz$jLB)+R=EvvVL?sBIwakyx^UO# z3K8`O;7jkU@IwED20>-PKd_~j7tKAGo|K@>W1|j!J~+ThbZa4&uMK6U1Tp7qA|rCf zS&X3ibl7-Tqe0!=sq@P3WdGUhp|K7Mk%yDWn8fcWE$k|F>lC$)Ft$2aSG!GoT11>i zd9!2#oDuc34Ty+QK1Zl>mkxd&$Ure~tqRIaXV>os4M4H|ZcR!Ov!PubAQ<UkZ!oU6y`v^0;|I4;y zz_AUp!IyIt=A5iI=ALi_0ts8DF*ObL3JzJn=d7AHiCb$A9IF*5&ETqB-hcMFV=D4( zX1cfLq2{5I2Z*sHv;aFm;2Z1 zf@TC86W>mC!tJo?Z*46Ioub;Z93CjjW_8XXawYlJ&QXHdldYa~%YX_cSEI2NuzP^E ztWuEo=M&!P`abU=CA;990d^lMNvOTB|Mo+*x;ziz=Dv}(Fw!d+x*xT$JMd)Phm?~v z6Qrm|R3Yd5G>@X$fArdWx}az>R-QRHA1Mu16CP;xp>TO_m=X@qIcf;vi+{TvnW_X- zx-@KE6aA%h$UGJZg`hVdn+7FC8QD;L4aX-5e9dA6lXta()-$D5=2%u}gHJ-)yV{6P zTX_=43^d=CXs-tuUli(JuIeqZ#NY$7GAVmv{-&-=Mh8&UN@3qY9VNGcJ4rQQ3>G<( z0He=c+eyLgoeN={jy!aY+38#Emf(m+{)v(a1M!21?2E+V?UU}Dz7bK6i~4>Kl;b$_Moe;5W< zBjLAnUE9(D;d&TiaY4hpHb2ofjJ8_)Zz}gA5q^M&nZ%KJt+U2Od>z zm2(rGJ?&uCvCJcE+v)+bA-Y?8+}zacn&b~tA!N%?hF;a~M?QRDgs6%}$`N z)b15ILE4C1%Un!8a*yS*rag#s(c9!>S4Psi^^!*d*=oC0)UC3nHd2(& zv9WH!a5L{6;7FO}v(%csX#*kR?5SL)#v|OCZ0W3m7nut^O|y?5RAOvE9>{<@_e8Fz z;mCr#U|8-cY9i;>K#7{74s_;q=Q%HczIe`($P-qhgFYsJKa+6;diZ_>S` zf(}7q8RJy%DQ^>9;k&GbcZt!LPeI|}gpa0AkM4izZ;SV%NNk+Nn_A1Q)WwafDF%H_ z1=aG&S|W2G^LT}6ncTt9)QkTXayS1){WkT`SV6l3S$U%T>2(*>G6; zOQ2!M+)G9065;tH%su`9cPXZ@Ygy zu-hoN?jD|sLp#a_OpGqqtz3e*k>9oO(#x_AkJ6ejuOx3!K=I)Y+JWC^cgF|h)b5>d z>y5fU>8U1_%mlCIb<;iMDanoF4Wm7|@^LF;cyuyZx$d6#c(|Wi+c*&sb0&_rwRh(B zyGu_ z@;ufLEhS58-EU4mtE>|`y-!dXtB!cWN;4G%U8J$Mr>rrvqF%a1>HS_jH-?Tl6dvHZ zWzR4UU6_QeO#M(m7v98ddB?<8dq(==v@+f_>EVd}3gJnFm0ClPAQD6I+!6nmBLm8# zTvW7xwf%3-&28KVy~zzAfh#Nm9M#iFiT@zNl-e9h(wTFs_N=42|E+Z@ou3jK5b<0r z{V@qEsvn}QHg`a3W$7STeM{VoKIl$Ri@KO8xDylx^IgsOid?fV`~Ed;G7wWh*oH0s zufoF}-c)5)u*o~Gb3ec9t`H4?zvsMy`Q|3u`*u68N_`?Jr~DCo={rgwp3LOLPY$!y zurn|nkf=DGY$7uY0r^3zsG=EQNR?6$#=zu}r+%`#LZr@2T7x^zD^7i#*svly3CPiN!xeuTC#95N1n%v;p zIDDkftho38n-5vsyXDuh=;K_WAm=cZ z&o~RJB8oo-Qaty;@s)oL|& zVd09I>J0V)LxZ*I3K)Y_$De!cyLU#d870_7rJiF-==#rLCvhQ`Wu~V^u0zVD{w2uw zV22OZdZ{CPtR2R>0hL&wnP4Ag2NHFypABVYFBEv6JqYf*5lH2Ur#I7<_hq zBzsuw@=PI?mB3dXFCf}la)^!+q-AJ~K>2x`>;$coH3o?h z<|({=|D-R($u*Z-Y=hVNbvKNw7*s=0u~xU&qmk+pBKJHRWjjfM)4tx9WqdKab2sTu zWdz@z4PmyNHOD1~QMU6#q`}GOCIM+l4U*#4sWp{c;qY#?ahe$f?GKQy5Xj+{_n0jO-jSUu+0i-x9N1#|s-*D>g@ zi1pD0r9Kej0$!#Gue}&dkPiIC5Vf%r9!iun!qFglz4&3$-fLX?EQ|C8 zb2@V&TQX@58OHP*nQZ4$k{c&tt(3IOf+u2`x);FOIo8|8 zg9HEV^s&(kRNLOp1@<^#1I6R|37u_P-U^xtS{{eLGG;$v|3-%oDndk$?2&J4M zgxg|TqzhfHv=fFW2~0NHTHehwtJWqjIM}>+Bs7m}jjpJTP+<~uj_38cVR6>lraxer zY(mi0zVqxvZ8`+J=J*mXl%q2&qmfqvD(-g@JVmkK7kdD7*U$|U+3ch{3tUoIEQ_wo zDmz!@K#m-$w7Iy>)2ti%?E41#+vcOqGH5j(GOCxG5 z+`03z3agujp^*5`tOLHrMAo+nXWyUU`zD_(VXkITAo*e zR&;liwGk}8a&aj|AFNE9yS{jROh?Q4%fe$UFrlNm*gAHep7s=i;{Au11c|Ob)7pt$ zcdsJ%1O#dKF-65VX~xQ+qyP<1LBpB~Mk?BqsRS~|`|{E6FH9=T$WQuZi;_<@R!a0> z3}R>S6vqjJa^OTMx5{4{m`X0SXGH&I=~U^M+eb)5;? zk=+ra77f>GAQzraPbiSH5oGi`)t~W35fcFo1pkjSe-8*!bl$u@<}3%q_C}hO@!p0q zq7~e3qY$)$k1waFDQWRzeL;@A&27BJx>RccY4Q7p>;#&IN>dtu=2@fNyO>N@FAJ4D|W@AgB4viiimAe5){yR?@>vh15M?7@8nk}4|INJ)2r(- zax;H*VP3Wp)7qzj8X<j6aRQ&ak2>vOkXDmtGgBvymQ?AvEf?(q)eu z*5^3zd^@>CHu5ENQJB5ZKnLN9R}-p&xjgyhLv>FI&QJGl4~TeLsy#9I5%cI*dI#c9 zb@-bn6kK2x2h@%YH$Yxhd9bWRuRIOo4-L1@*=Vu$4%1E9-)jw?=|ddPa1z}V6gZ1M zUHT+y*q}DF`g^-HZhh+*?9Mr!f<4sZt{X`s6)vra*_)xG4E0X(&_Y++HwGqdPs8X} zxM{J!jTWKFAe{Y_<$7=)8#Ya034m8klt!kYLd# z7rEa{gv)=n106sO#sc#Q+A zuPE@F(C%DwNytJBYQJkh%~VgGNiMnWAenqYh~)e7!D?ZRl)_?aY0hHcTa;Dhp9a?w zOXk{Ql_WaKu&S!vSBgIzLR7c`+WDoNPG%QXZ^5xjnD0Mm_XS04kkGQ5)LT zX4CYv(wm~NyeIn@45SX(;u#@9`yO=RQbgX-nL=8H1vP);s*LXZHFsN!SIkzFg@+w` z{=NOoPKOX1?C(F_=PB?ERYah+WRnU~NFe_AJKpv1A?sP_P#z-YIu!4B2SloB(o!Hj z%qjyJFue`Xw+^{ebS{g|C%k+ICD@R$Ccfh1K^J&fUQmy?vk~Yl@?q8Pva9rN96sF4P4w2E6T2dO=8a-9F~+nW zWc2lSO#!-RiAR_)njye(c!XytG>3L(Pr&9qBuX@6@CzR#Kw6diq8i0$Mgwh!<9AR+ zb+*LpnLmqZNoDmPkC2yX@RhqgTN7?P)Z=6lhVT|$Xb|j0Q_>$m2bu8q2uMpYK$5T~7hgnk$6nOq?*XUh6O!4A z!o4QEw)lVLyX$uwet_7ayo%LCoVxwXLrOyNQhy3`7-iT^}?5t04T}%v-{i>I!ue;fCp6tq8L= z_pbTXq53XaL;-tWPWmyKnR0WF8ScE6xLnzZ8eyk=wJ9Ej<@lwFg#20_f4r>HDhIQF zt_l1Axo#QQqHb_AuJt|Wt+`_=AMN!1o@ER#P<7D2(6G$aYV&;)(c15}DofG?f(5!n~ok?NRMZRd5{eJWLI*Kq2sTY-kp7l$*E-aRP?(U^Y8 zFjiu8K?2xpzrk>^JU2EGh={x!6J_t+aP75XT2EWIa)GbNk}1QOB!?Y+98fEsLO7lO zqK_yE+{r0m^(>w??JdvW4O)zjhNp;)a3SH`$FXF7-D8^KKF<;1h*$)0uh5I0*7|f= zBah_Wv8WEa5n>Fpv+E6?$)-<>cw2|=Yc&BR7scBu=A^Jbc2ic*gfhsE} z#4*u{4Fq3bO5Yw;tRDXh36*7dDO}UgZm+iN7YQ-f`$svpi$z@Y3}psh%Y;t&W~k3F zLALZawk0sNt=k-YiP3|O?)v(hfzoh&*vCdz3gOhg@Eg0m_+ZI`qtk&;JCRd`F|%4R z_n~N)aCMqN>!!3`zw}4k;LZ+jv@UmLmGXVefJ}D@w2+)r+$=(_blDxJE1bmK)A@M+ zA^sbZRTJU)zX|#c>KQbz@Xzwjr{EA-wHzr6q}UZx`k3W5ua_^s2fj=BgK*J=T_}@) zh0K-2?gFI%vnS42IH3uX;Z;Ld`79Ojm&GvWV0^bZ@ic)^^0_8kTcujTGPKa-P%L(H zj-$&JkD9UmBN%&Ml9|JTPDh>yIv!*{6}tW}cOSO$qhJ2qlZPO;p63|a5nb%q*ibCW zC)rtW}x4;ji!9{r*}TV zeUo`hcPY2_HTL)3~()S9r32^(QD zkPF6eg%+OF5V=R08^CJ$joo98`BzFQ95%=%?p(fzVqQo@^nOi$IJ2wH+vmMNxSi^h z@0k>gk(oVehh|Yq<^HrI%`$xPza7o;J-9Hal z5XoxO)^!mxMgQw&8sOVuQFpMqF)#0E4LAens{ZSS6vH>AsaQ?8DW?OY%Fl?lnlW@3 zeC4wK2ZfrmBRA#to3;(PT&fzLY0KLRdT*mh@qbE3{c^w<P!Py8B+}^ z5mN+^FSx>f3C*PLRu-|IX>1 zZCq3qW~(6M)Z}UR)LxH?FJK|V|HzWe^Tw1aMN8&b0nDBZ{F-I=K+2akiu<=;x*fm> zp1UTDwDPRKDEe3Z9aru1EV923^l03XDv_%WE^rq#Ah$aJH^CM<49K$^d?E0614c8< zp6-)OEDmVjSc+Az@q=~s->Fv2zfLp40c+L$o|B|X)-#%T+_HUZlLz}X5@)<(!jG_=x(x_d%LB%VFh6_Vi?nSeP8`Iu%T)n92xA@TQ0qF@WFiyNI|}b&TKKtJYH8)vB>b_n=2(_OTa3HFTN=S^ zWAzFXe!o7Ez9&T+S_>O(Nt!w3+O6E!BGo}o+3viGpDRiZBcEH=4^|n|39T}~Z9}`U zy8_rg`Q@|18z^4yFy2P~kRm;dhiuB4_TWUR0{h=GKZXI?k>m zgGuwB#TFJ|GjdttwU*`Z3SS{UyR-vkhf)$s2bxQ$_N%7}D|yS}=bC6}9;TdRE9TK1 zb++gkM@?$R=$kaNC1YRFqZbK0In;ECs@yw%y%?Q~E%!GTHZh~k;FA363uNDXX$bQ) zzEiZ!p2Z?@9X{;xdexg)_B-#*e4^Y0I#whKl26hA**9PBX8UU@ z*|TY@j|)CswO~<6X?iKxpP+ut428jp{bg@v8QNBp&oXDUg?P^{3n2=b5h8oj{k#UM z{puRLQwjfP4n(-lfl4PNH1pArZ_thDoD8xKCiHV<_h%ZBa(tW*>cJ={zCP}K|5?(0 zlfvZ&OB2=Dx@3D1NALhkL8Ia{qiG}(_89efAs>gYA;kE|_ZXn5kuy`o{n(De3Q z{KYGIo*r^a^@|By_!5B{*!$IMBgG=Z;u8aO*HM)0w+zh(K0rw)uCXouco zVYx#bOFxCdc`d%EyS9&P9Vtz`nKgSf2{HPl)!qT`!nH|G2L=fc{zCxg9aXCm^SsW> zVD=*iPo1$DJoKOMK($+aB<5j!lV32XqDuF6lPl?KB|^WgHKy-D|2D>-LJ%!7+9nyx z=CnvPKz=N8YQBFe6o*Clvy15xpGi%XFr{5`b#KoG-7YCW2y-8H;qj8=`4h>eUdB2Y z76lk!M>j>AAB?c#8JlwhwgEk0wfAMhpzQvY1ZGqJ=E_kR;S}fjC3TJZ?lU@L6XM0k z${7J=ff?H~sr0pn5&;`<2)|e~QS-k+`gmAdg=;}U5$)Cr2Fq@_38fh1P?7f6puQeq zq)DRADIjr;7lt%3`P9`D+!agR_PHvR46{qj^WQAQAG! zu^R&q1UdO0w>U(9zL0{48*2N@F0Tq~wmK+gJ}!DN)e9%o=7&q_*C^0uNv$jr`#V(N zvdUYqb`n$2x0&DQ9Bx6qN%n9TB?cXa!~Z1TSZ#HkF@_=7rCUFT*CT?y>t3B zU{MCHx1v^y9^Eg@4c^qLCf#MwS>=PsfYSGcA5J8%=q~vThTk2#Z?k7hAQ?K#@PI!X zJm{lmCEJEwz|cHuqR zv}GCG#a$3Kf>vMtdPZb^&pH0UV;u>4&N>hGaf%mVBubQXqa~(4E5qApe1=9t+YEX= zaccwFmJ%~iru7c92}@*<{7I4FIukEe=xzm1T52dP!+nipiPhW{B<=B zfme^|+JKKYevyMz-5gEnbs6N#8tkDMoS0u7>y#2C zX#1KmFYP$~S9HF)BzCcD@b%5RvvI7gPIgS*2&ag81Id6O1CID7B!V6{)4Y%G&EN12 zXQ?a=+TjPHE-3kGP-Y00lT4PZZCb3%Q=7xp>2GdCnf@`k9Kl#zdya*#9z|G>kYYw6 z=D&*-%yISsd)}`$N26enYWGz;GT_JqM&T*|L#b<&=TY6mt3M0wBhvXt#1n0|5TXck zpcLt9uYWU;IR*WZi0}PRy0ql?t%JXb&NLTyb5Ye%y93vC45EzCMLILF#Oj4?dhd=a z=@~CVt*m(}l@kHJq9vR)l-jgPZ7$+L^dId)HZx0!MlYgI=^HjA^GzL$m1c9{@xg0X zQS~y-DP@ue4%Qq0MYv%c4V%&Xm1eb1LLMp|g;)?`rb%zWo(%R+g#^Ct$*=xSfIuYa zfzHdV@K@TbjFeD}wfT|0C~|{P&H*VCgfb(m(A*cg%Uwr8*C1zo)LwNr7ZH-6! zu-iCBHuRQeHr>=EcqExW^#csgHC$qEPGnQ#F6C<|9!=HLcJjHb^IEoz6EX1)W+^hL zMNY$Y*}~WisMt6P+L#w?MHp3x#mf!flWhv$S>{Bo`@^;LbmW|W@>cqqi57f25{L-Qr-zA2;%0(>qeftW z<(X^LxT(oZCJPQe$yr(7blv@7k=#0dj7%yVrE zY?x+W_VA0H#XKCmb}WvQDxu8@09$g8xdcrL9*84;LBq*Ig@(@w&R4uFC)A^VK{Mwk znsk0$m2t(1=6dz(pzZ6Tn7-yN%GfHn_WP|9k2jRtJ3JVU2caZ-rx?Ir!bj}L(i(t@ z@wH>o!;vD#jSbMl)BqSVu)Q)L_4TcZZ>mP%O+P6#(rH2E&Q_H zjO!6Exe#ggnQbqwIe{m^mGeahQAukGe^>4!?Vq|Z>c9>Wr^0;L0M3Tq3cKg3&uab9 zLiUL|d3oeJfRf@@kJW^QQPK$Gf+LP~CCgfW=$g>@Az!DwPXFMaWmSukc*IWF1r17) z@Q>1W_=K2WwFH_j^JCL}3(gaN^?+scDOK_n_R^-S8*|N{ZY(h&XoC=?XXzvSHT#uR zc_g-02cw!Z%7@Y77=3>$K2-|aQYJx?YwyPzvp%DvNof&p{CT}CWqjRsV?C@x98yBq z9OwOEupZm9ogB-3i93fhA*Jb5241y&Br zt(D~GV!rk@Ph!8xw>}|?O z7M^2ZDNgQxZD3%frPj-5uW`yxWp&+e7v6 zwl08j`ng7=={7BCLN3T7uy}EUb?9*!s4Bx8dPM)Q;y!s*pmKbtL0}z!$Fn!R^8)gk zxt)B806Kc->(WRQn9I9&4FlY|3_8aU(@mRU7-tTGjp!6;6_?iIwnOuN;L11C57MX2 zA&bJ{BWi}6i^kaP562+w@>f3(q@(zRvij@vZy4w;o@`BO;5cg=wZ;YC2eSg4#ohnF z6bB1@HN{!=*+Yt?UV+V~EDjTN=hzPkHAnWGo0Tziju#k|fz1%g8up@VtS69h$0W9O zRoJ^0fT^p*}?#u1jM4AVgkoetKg{qgPDZ2k58W8 z&OnCP7i;GMxePr3Et#uSgDmNB3h+BkWg)cRFizWqoati zkWNbkHq#^8l|iReIvf|HE|lVeK!;hkzGxsa|*-ENCeTMz2kc3Ew{1N)TS6Gy3owyMHY^3f1#w-{jhES5*V7pM7IqId&i>19spuJB5s6gzR(q{2DmDQlan9m2?}_#1(7wf7I|yCZwG}a2{>` zYG%LrtD~8oQLM;1zU4npxqba8Hbb;>LA|hjkLIeA^XO-?G?}+LmPUPgUd>N8zI!v> zaFF0m*s)I=q?!9VUm27>weQpKnGy!)gS-clgnq)$E79bm1h$dBm5rXoK&u~E7GL{Q z4JK**O~UOlAwmyqe^lz5UFf^xHLMl?`(a(S1p@JLBi{xxZ5+^~Iok|YbOWi%mgieP zOXs*#?olOZ@lo)&<=Tx#zsy3IWgF&OBBa((vA6nv>(Q}kVqbtD`DS`T)5Q#U2PSsE zNh*h;~Gjc0#l{w+R zH%K&44OPAu32-0wm);GH_o!HD5c`fOa8s?^2$pev^S%)#wplov#vgQHnqs)^b}b;D z+`L*MbTr^#tEB_}>}$yD1EW+zG25Xd*z;}R^118Ks);TMj6!+ zpo}q^#%HqI-DP@}WA@7^piRUZr5ZR{+Xm7ufxR&qqGr0I6s)#uwn*v=mHFt#I%|>= z)*lr|xg2lX8Qu?!dR(^89DTQ~tCPF59vmOs8OI*kzWN8$b%DlfInVPC+e zjevA($#37`V02+qx)yA{y@e4Lh^i7+EzyAZIT})fGV%Rev6Z1xO<_;fJt%;E4zq^h zLQfQh>}YcFgeEX56(WhT)r_r%ZP+^{#=_Zx<2UT*;H?%sMLBb6^J2bt$$ibua67jY zo>}b_HK47NYH_I-U-Cj?>EU3VY^vP3o)Lb^SJ8*Y=(CK$9JvJhSu{3a&0V%uF3LpCK z!_5GbKjP)b`ezqj1NScbAkVr}i~31;7&^W&?9P;3{0;wZCKf4~+kuA_+vA1!N}Pe6 zn{s8G90@!S=J%noqV&xL*A;51MAFCL6y$t?j{g^}VAKHQy*PoLX%=e|oUfR`1j{~y z(Eg^sO}#Q6%oA?3c2wrNn7B1qjxtvsl3?SOat=Y6b4V#eUq^pm6fbkbRMGT5Wl0;F z?(AQ;-LHv3r^itvE1-DF*z08^0uj~(ElI#MJ3^~4!DDwsVBd(ew~5>B7V+YxGs}Iz z39YBYkq*QNoLnC{XvLD`H-%cueW{kBK*c{rlQrZW`0P_?e~K=V)A-P~c~n*ECa;H&|T zZlr2EpP4NPOENJL#S7HFUAx7-<rkJ-_jz=p6i$S+>I3Tw2+PZDJ6x)(+)^@Ig29 z@Ro0~uYi!Lx;VX`L>8AafmzXt?1Y4XWI7I5=FeEae0{qmdmV+^^r6D{XzwP9U*eHd zJDS;c)#4O^vly7(W&njc6F#Azh4I3!!FoMV5jCQQ(EF3$ z)Duu1`9|gT;HV<$K7@6^l;45nJtxA5VKuQ6v%}JT4lx{u-0O~&V~K??NgScD`SEAT zcC}NciCL)kRa0|2tWL?K6s%<94}izW(eHr*ve{4Ao~w?`@aFKfwS7{^*I10qiWkf% z%crCI%nOV_(TDO2Z5m0yu8_3T!uiQ;yylX%J_i4C>TJSe{89Vx(_a&&HDFC=HWVw| zVFp-NUp|vDLhw1<`C6JIQ0(Fj2PqZ6^8jS4$5EvJK_DB>{$u*dYwOJb_T64iJs7G3E&= zW+2$|Nwu_xVtg>9BpeS%U@qfGPJF!A=v7dW1L{!mjFvqF4UKFe|wI>H`wSBldimMRg?7+{~@%wzlj4#Q`W z-S(vsBTgkPO%yDd!m~mBJF;&Zv-%-c7bfe!VT_aIm>Fz`-J8}nQ&DgA6eJ-PY#FVA z7;fb(?Nj_!S6`(3#E>49rLV~8D*KnSiA33OxOgk!vhw)1)y_fu034F8^nTk2>KYYn z8tkWJJYjJp(c7+PdE(*=7%w=4`CglxOgcgOR{;HDJnJ|S zD7cY=Gu;dkx{1;|EO)j2WCrs}5Zi_n(ioJpCY|k#3V57=ev*hP2Krd0#nt5pjcc4> zHNfV$BdE+ zI;t2W%B`~J%X5o)W^rYvMvYB;|IRM2c5;vB-sjY_G6_Y%y=dLa<2?d zLPSo-IT)_n%4Fy%2;#VN4Yd=O+h+JNvLClt@~~Qs&LnLhQK4w)7XXY+briuG#j7ZQ zu}gH*(t>rU0H2ZH0ioufZSz>?B57an2wYlEGo{MmNiJv3^D1@{ZqKAgX0gY0X1WT~ z)>ZPHR!-YAutu>KH8n|CMHKg=fu^u2UYDR_f~_hSH7V?t_y7_`XAm)cXdBu7HcI$m zVY()qcKUp=+oFUalWddD{{EpIib12B9xtmVW+SO7ssq%|w!%xZ{;LW_q(V*EBB0Dm zh7B=Q6>$~dI}iOwr!T`A zHf0k?uqsxPF4QjUiNn>Aq5>n64z~2QT+i;BV6H|Y!G{dnsK?aDaw2e9_pcFa|8T!;o=SLt# z)T_0u^Po=pbg)fVNWJqP*NYt9Ss@%w*_Z0jT}1f@$v65XrQJtlhj<>3i$3{xO*Fa3 z_&7J&ZP_U5MU~Vkt7V82jI0eH5Fx{#W;6-=>mNfegYY)CZH;`Km5!n7m^C`ub%C42 z#0Rip264PT`YreG_IZ0R&~g%@PPn(q{3u)PH2Y9Z24zJt&}|y8TbrmXhK> z-!f?7V&t$Q30Vi4xaPwLH6w~N*@NMCRdqMw!D3MTXr0oHhKGakU2 zcSdNd3~lwvE6h%c0A~3v#u|$ky1-*=JRT8ek7mO6H&dZr`%)aU&_+>W) zN=-!U3q5fRU>a=U8dMf*BNlMJgR90M-!TP3s&`?#u2qn*Z4o+e!{vpS_%8L7d~B1ox=R^)ATIpkV6xfQIpr?j1W&M-WL> zPC!*bs3D`Yy*H&F_9)OL$)6^kzbjF~pXWY&w|7O7ODMf8V!bvq#)}Vd@L3&}dFdHw zhCy8OU(LgoNoyzqiCdORlnP;ECimPzmc9OtCLE!j1Xd=6G$Qx=FA&n+=28+NPdz=%&7mjOt86dBn|%47FGjTt`c z8#_c^lUnTF%+u@yf6WRx&$DD8QrdpRX2XI1vk*;F-zUDX+-@g6u9{&|w`E^Hfs);=h9T$`*1dLazJ{}3II8$UT z)!C=;ovEIOT8|UGIkhed*G=qRqP%?~L)cRJ0Sli5LKg%bc^Ig`}ho z`te}OdkXrBFT_$4sN9x8fv34h*~w|mKUU}>I|w^tIR@*ItSeY0Hy+Q0C_~9p0;|9= z!jr>$mvz3xR!#Ur#VW|5nwdkLz`kRez?kky{sHy(WT%C`9!u^JYNB#Wna9@r;LFr3 zD(^E8boxA40FhWJ=;p9XSza4a;I+j*mHl}f(c+c60EeU3Sm)*vVixh9VkYVYJwQGD zc=YvLVGAd+Oj?U_v5Mz(W&Seo+r-$)OuVv41CoNpr*P_!C9}m!h&A&PJl0K&5T&MN z#nMO#5eF=|QcWuv)Ws7{nL^Kzcpkaw(}dO1=Gu$vJ3JZhk_XXYPw zCJ&_dO>cw>od%S6dRx}^u4e2w$Nc2G947jIR!5yD0652->2B~BI{5>N!YRBqm6tbY z>w!jrJ?ozn-pu*WTSX*Nm?xZvsLz4{e=*B))Ga@@Zh(s%E$VcoN4>QA!UjRZB>O#D z^RaF1lfma%SJ;~NU*j?e&m8YhRx&4GPjQ2roU+$B7ZA8F62mfBsQV|L$0ayR4MFvB z1NKlJbOXlm1tW0x`&m6t5-GU@Vn{Iy9f%w&!+aLayeo7N1c&YcE=CXDG1SF%a)79x zF`V~6Lqjd?AW%zMz5%3kqzE5ATv2JY_?Tu8S#dVnk6MLhb#=aJb9myXj`gdYJPFZ= z9jZZDvP$?b?psX5BMP+R2l?7q>XQ7)S?(f2>P5paZ1qa<p8SsfZNAP8Y{?u{vK&bI{4MD}KZBV?!Kl9A;@#`%t82dpT_~D1k z5*xu=OMb}T1whTnw8$3tqCga5F?b{&7e6>fQvwOUBp;Y*P0^JO4nsHebs*iomU;G; z@m=?nfXL=E_kE6G;wkT$(66y|Ugwd43kr1S2@2XVCMJR5@e|>(yLapmwAAi^?=9Ix z`Omdd@WpKf!|QZC+EK2@7zPq-XZ1!7SaJXcas4ldAK_vB%Yi3e}LTtHg)~WDd)q;Ul1T{9=_AKPLxXB7IV> zhha^Q5d1BBAs$G45b+TKJ2qe@W)+PV30U-M%{NeBNtDG8`9?fM*z7_w*7upKv1J#z z*G`&{h54z1!9F!eE{(@b?{31K1{*nJi^Z_X$Uu^dyZNa|3*l-&y62HGKD5sRX$Yoa zSv@_(KX~!5=>MY@VA?7+Y6yOu$68Re_m?i^b?m;laPg8xz#i*cwk_q>U@m1wQj?K_ zm`}mK*&=j0O5QCDVDjv(9sKFIPn{V`Ei!mK0?r~vxEh=?yT@)KyO@l#!R2W#AeDt~ zGF2dswu(b>=K{r&S0A0L$#y!XsgGnxkt5fY<$ykh7P;R;Ng(*AkfLm|yi(?@<+9qw zb8j^d za%u(wUpmLULpLoPlm1S0`=9^HX4($$LPe5*B!AQfXI2>G23{c)h`VH&;Bta7Ovftc z&1YNE{0Ns}GK@*aN9TI($7TBUAhDLZhe}Za?SeIB_^m|?v48q#uYMe^4-}O$hxrbk z?K1v+obW=t$Nkv<@&?jEM{)kFUi>}<(7(Umz!1WOryZyT5-t3@NjWy}Wu%iK)O}Ya z-owm;9KFsc$KnV!)20`j_x+&(j+Trzll_Uq``tGlxw{A31u!kwfyX?XA~>oc0}Sc& zd!rUitA$Jf3)ZH@p((L)hhf4`!mA(X;h^Ao0+I;>&?^MqliH3?1kDq_p2(Acb=_^V zGLF5=sx$kt?s)qi>59qpM{YWQWKdaqsU@J=uSOy&2J1-+ZD~`jXA=y@uYtAqDO|Kb z3LS9}8Z;G`U;uvOmIsWmYnvyhv_J;HB6>{})NS6849w^)5NRuIjk6E~e2(Huj2p6Zj=<*l?Jh-scQh^vOLzVOjVU-M!$x1kGT6{2DdA z?;Wc1LL$!PF!ScQ3*m7d{ltY_3TIHia`}UHuu+@%4*$w^p%g(n?`axq7-7WEQAC)V zlb>`*527!s?l9#+&!`B<8Bnh1gl!0ll`lp|2ff6s;5%Ncj__39(Uw`0u=A zsCk@0GUG2GR_!kWvwmAz`s1)u54VHg#U)X00ER3XUm~4cXk&K997qJYm>W}gxtr{+H+)1CgEuta4ip^C1ZRk^chV=6m zLPsMiNpeXZ-@bf^W;T!C$Jt2LmT@S@$OZ879a(Ls@e0xmoU zhyyzuhxwjGdtX^wUx6Pr&%NM?Pk z**T4|%S7<~e-tC?ILcA_LSVS$z{QWyy+ndXYHq#|t;QUNV!IVi+bLvl*a@B|#Z^;T^Bt45hb+Mi2|*#S|G z_Ogz>VfK?W<&m*mxC93lLm2T1GB5+9pX+s(dmD}BwycgdDO}xVM^A$@i{$7HdH0D1 zG_(3t$xRjq;Dr24StY37)A7S$cMRA8Q@vL-t)#=t==S%M2<5~U_@Y2Um3EOxTKIt; z4T;7kO6>UE9r#0F_=X6sAOWpD=}y{Gpj}#X#S*e(oj&j0v4vP18kPA|VnA0bZdTcJ z6>$7tBn&4ss;`z$K=SmKeCjrMDlFfPUoB*5k(JqMbpUmc_TBb<=hSUFi(rtXPa^W7y>c)@Z4RcV2J6_z^J@mt>G9qy}Tc%$ICwF0>}bf8GCLf zqewUW*R)Twni@=^Y=lncFcL9z_k|^WAcV9G!<0oOVM8s53sGg;O9Warbj&%_cT&Jt zamsr5F)DyI1OPG!A_i>qqbpcVZ)7Ymw<`E?0@lIl*s9Jg&v&zs9gfl%Vx0SJHl{3g zC_WayN%V9Vs?JY%*Vy>IGMH0zTS#ZO4KvRAQFZ>#q6@8+xuqPPzrz!#91MkuGdOHT z&cgBzo+-}64$4)a*pNBjxeXMZwye*)y&jXo3noY)v?G(9)~70ET=+!#v+`ViPo@7n zXOqkv6K#u$rNZ*fJ;N0pS9Md04VoW;gT9i+6jjU2GX%OA`B8o}yDF}&ew)-di}+da z^Zd@5xe(-6qi@bi3-4@qy&?L!tpbJXnvJVOKO=m9Sjd|_!V^FM>#PX0*XK-$`4VM< zB;tc>`Ju2cJXn?b=-c+v?N4v%Cm?=L}bggat_JE(Q3>Y?hUz7G|$VCIc z3n?GyiQr%dlQQcJ6@IE)Nw~F;)Yh`ggTCXmo>7AC0yWrUIKDXX)mlyo9PW9mg$Igz zvZ~L^GFzPA+?J)Z8z}ist=Tvm!_qiCcz9BW5wkxp^VFSi94!Gza&yxUwXF+yV-g6) z^TIHqgvh>^1~=4r&4CE^7I_!uq0Rt`bcu^4^-LJKto+fr?al9)ICZC&eF79KeZXN` ze^BFI+O0>;e`eZA4b}^h0rJdK*JCu-0q;~H8d!Tt2ySe=ap^Y>8GyRXpsKT|oYCr4 zt%4I9m~{lrWONe^gvSb+qj1{&Y4N19Xae*MH=l69P6#Ao9wcc<=<-J#jc9=Y8A&_`2H zeI;}Dx))LeS)z|}m{YQDq17?74)XlaexJ{bqHWk0-bkjvBSO%0w$==uwR!AXIGA$j zpAhuZs>o8Q{^smN8R7+f>(aX1x$f8Ehvqrzq#S} zS|(g;+7K9o+^5nwSK_Ay(TEAB9?;yNzfla>8VF3cFOs!2jF`sQ5PP~(XKJ%w$L`-+ z#2Qu`_*BZkKRRLX+#~X9O63HJizaAf#D^iF-5G);$I_-VB zbCf|&4EiFX=dIv6(&Li~yIzF8s$R!VGS~X2A_W|e)!Ai>Lsv#)OT#Rbf?{y_QbKn1 zYV7ce?@+qEK7{rll#79feS#MF^w{hthzIWqFYU(}v?iYyuSH98y6ud^*`9cESK|@q zmOz-dwI4^xlvQogFn|T}v6(xx=ZD70b{mc=K&2%1G%iZVgZ{NWx`{ROh4!H)rF;Pm zNkmYz>$l;H?w^9@e|J>7-)tLY0r$N`rBn&f?jfr|IVuDVXn3!&C9UO#0 zLlu3lX|8`ld%cDJcFX2@T5-u8=KaCN8aR<{2=y&Jly+D}XcrLE(HKeJly$6m|(eAWPTtVJe@g0QmH zS;sYs8a&HI2#3dxzM7Iy+$W?M{Zlvo3tEyEHka{+2>l^kI(O4X^VkuB4E<>|JlGjV zy5Op2*3bjg!vQy=P(k5=it0CtzYO;=WGTb~K!*T*v?g--(|8QzN!%nw)vtXRqUrxI zHNEDZ3La>ts%ghivY9%}PN89M3mx7v%+UBAvnh%r2?!suf~}zZWH2rWt-glFtBr39 z#BXK2sAXvy7&0yyvH#l59)XIZQzwA;r3U5GUZ0nf&;ry%v?M>GYkiEQ*qVm7;$0J8 zU96_If0U6uRwiwrS;D4Od*t)uT!0C&q>UEBuyuF~+K1Sb)O;U4xhN8+gSdVnAZlME z;cPyg_r3pKEv7wMttTiGYNiC0*z>s>x!cP%$7XN3p1PtJy$humEjIEGVuz^NWIB-ehQ8%vVKOT^u>8%PV+c=#3&p1r>DgQ`G)*KvO zrifnGmfz+e?arqdt~xY64#E&&nvJFJj3%z5&~>X=a@Cu0X>kpclJuR7CjkA>%3XU; zCT+;*98fD67x*dv$pxHBR?Hnz9MTEebEbXT>b%Ju54eosg89 z{61=uiiP$oVJjq7L)ILR(y-~1r_XL&JYSgB@JCCU5fku|y6sS4G8}}7Yi5kUwfGe^ zlAorc#y@awi}OheZq!Gxqn>&i*;$N+7*-gMTf{8ab=fQbASuDm{a(s;6v`M;*tQbR z)x$h*){+@tj5T_eGpF&-pBn0sCu&pY7Qd4_qoNC$l7z1EE0MF@*5>7wvL-4QYZj*&0Y9#Iy zghJ_n!_)OjKfgO+Oj({Z_UXLnl-SqA@zO7>$yKZ~){WvNs`o3&SYl>&x9)NKuXgC> zJRdzlub_Emkwbe)k;CE@x(dZkLD6Q-HeWK`q(yz|b}8xdFp-8unGnn0cW)cMUsSMBMWcu}Qo_hJA#?2`Cus$@blYr& z=3V;sH6m%3|=!hk$uQ)^+er*Ru2GUXXBck)~TUjK|{e_?tE$B zLaP-Ug7?7!9Vz^v(#m-TpvQYZ0Dvt+9Gl1eW#Ml48?qyV2mM6<5%!@viXa-3lE$#| z#iB(m=EK@k`h`=|)4ylMFDTFR0L+4-PIYE4rn9nE14__!FQRz9?(arml4P5ai>i1M zd=qSS(SfcXVYt;W9cFzfmi)zG^~Dwv6B@q?N-V}f+spKEa{mP&X7%d6w#l5Jb!`~U zx=b>%(c^lai!dZ9MgPVn`xUXz9ghx4epAkwqC)ro%#Oi?a^Y5y`Bfh&kI?`Pq*Zzk z(~kYNA?8G}kj$#9qdkHtigO0zdzRk$L!4F@;JzV22xTMLSqDhvYqpv=plAY>WlPf} z>#3|0HY6ccz_??kWhV-mV?aVIXyM8#x)<@`U$8Ks6Iar8r=vTZo|!$2>RD2?&AmwK z_FvIqXoHL*4W+mWYgnl{`d7yssoLDL_VFOLLAipsU3MLBd<^ITIZZ8Ol(R9*TTjHP ziyy+&E3uq8#%9SKK&5z7tcGh?K)~ZWk2E|dvMS`%eqT+v4(2Z$X`kq<;oa}{Tm zl5LJ&B%zaSR+3oT^&6JLeAYHT1kUEXGhy(-AnZ&fYBlba!RlE5e^ z<1ep*iiV4G)OP9#c;Xb>z*XHtokF;K50LqI?z=zB1;Bvyq0P;|{ zrZk?U)C*j<1NF4zNNkE=NEG9);zcMBa9pXnp*}&E%6yTFtFrUjj0J@R247ldc7%5& z8yPnstRaKFz+X-6i#$>B{VI{U>9&^~SsZ>Duc8(2cA-N|B9uPV6y)W3!DY{BBaQ(9 z1b}?K7GFWa{R&5+TCDYtJHv67c8u2Lsy#eOC}*Lpe2jOE90}vU)}foX|2&HxPmS|q zj>#dxLLMT6YIbjUCwg0c?3nM0lOiz(=eYc|S(Ky>+gWK#)r*`NXzAm1p(yc};!zQK zUuIwsk4>xN!TRv)`-;{=j=^bBF|seoQ%{NWTp>lyBVf`3s1jTr2g z)2q(buS)>6mE11zCT9`j>o-)UjYQWdLnHR#i&JlR<@x@uDPE&4Z7RUUpM8elCN?|r zI~;oeQmK)mf`RRqg@&g8YXx5~z*~5Se9NE5jy=gvW?tOrUUi2bC}5#;*U{vYCWzllx(tZz!+2ytfe8m|*JD@tS)}u>1pF7ON=#ZSq zSHz^(#S`Tx9sK_K%#xE&))MWeC)knsB|W;476-Ums6X^Fgt=>##WqB*U}~59z6%a* zlp_W4@o3p4)7wN=?un_ShPN`$C7)hMpvj^VX^MFHHcSAEK>4*Z187?U=M)W@$q*SpYmLJ{Waj$kuFs2cOwkI&ykN2-Hm z*cqab_$fSZp|J^6cH#7-ASUW&OgLamn)TEhX%~~5t*j{tl#T>?A}RWul_Yd7(&+G_ zcT0QD)*?v(v>&1RnAT8wIe|_s627&xa#vo**2Q%`S}COzhcvD8EM(?U7#}V?_aFmO_f0oin9y%#lSeY;&RPek& z655dcN3x#!Dd2Z4&;15G8`4Lcr-SZXdPih9&a#}f5$9fEa6)qIS1~L<-#k0&j>Q-0>211zu}mDK zo$DM_6+8iU(B6>?kKrFRT{=b-`3fB!iW$XT^S;#!^}FlvKKQIwhv7WM?RNl>JUXT= zY^e+XZ|<`*g+w=Bg^puI7>O5CejG$;QbgI;U|ZEWZ%XaZBU;{BaXG6a{WNPINa*Ogw?Mt}u%ioBrNQ=&h+T1pZRCGlc{Ys(vA45*e} zinzw`|83?m0U^Kt;Ry&;Lu*N)I>*l7kVs@iK9Bai@|S1`aFgz5$1;0RZ+$lhy?fbj zH%)g0bd_{Yudd)JPDt}zJuqmSnc$Hhkq8nIKR%y`JpmI2uD5d2Q9V*nCzi6Hc$ z0W;87xE}5=&3l#G@xejNgK&$IrnLvToh`v(iI<>zRW~kyHWa5kOP)Zqr9{#xv#3@P{jf;J1l!qRV$Y3XkH*buz zZr{VCd{(L0QGdY=ZHl--;()J3J^{v=D}^7paWAi!tNgb!)#9FiVESXybg{}`MLifS z;Q^VkYXN{lv3649Y`3h0Z0KlJ6ztFwefBt%8qKxO_E^-ebYw%rII$GxC>c;l^&PWf zx5kWRd0RE*pc|AdSDByT7ekwcAyzzbBD0QA@8t3>QdrB8YuDjxP7le2e;HzH(gN+; zS6il1tSlfwgGw-_T})}+s0#O)w}25j5u#g7))vmMjj(JJ{=!%#r7TDV0ZKqB0>Jn> zskO9>cN1vuT=A@TeUVD&yn9(grqQ2Ct;Gl{nTTOZ!4%aXOcC2KGSgZ8NN@oa<&3La z5nzrWT z%0g>7IK#1JoO@i%x&}Geoact5W8UV8TXq;c;+!j9^ z#}#~|Zp!15P-8Np8zw|29j(El<3hd>^s*Wv&C5)a5796W$h+Z3A?-%^0Y70v_;Z#r zDtZ*2z_ls|QHXZ!q!9%rstZOe|8U|E=$K274anCNHD!{VysPaA>MI-?Qpdfy_Gj{7P>l?bLJQs-xQ%1L1k@XOVjo$~>_gp6`nkGD-v_ugG7BH}1ug2=2^I#3 z(Agq#ue5%icY1O}LTWlo znDZ)MCh7>5?5zk4Cje1Yp2SJ(pXd^P;M%c3d|PFKQ5RFq_y%0w#lnfH z|9|^0D1}UXqw9DPsV1X!>7h2ZWJH{LKa?5UpD<8<*r$Oc&4$4BK$RwUKLr zPF>Lm@|@@kbzGh?;z%H2m*1pflhZQ;?+Gp&qrEl=sv=eBW%sewHPvd^mrzIOJDr*bwpmi1;kLCd~trF%qN7q=nN}@$6sq( z%UV(yN?L=z+k$cfCV%yh<|0{m@#JIn{|8CtR4Sn3#5l<1u|Vk{trlAH0hoUwS)V|pY~`xwo@3k= zI*HJdM3c9#+bxdtlY+^X{7_I*Q%;39bwZ10+Zdr=Y_I)Di0TT3iEg@g7(wxxGUhq) zM^q>?tIa+q=+E72U8@LNa98r24>4T=A<)V-fd;0h-0kRT^A{cR$}1mdkR~cCL~6vc zUpBh8S`!`q$CGjN<7l)Ao&v0nh{JAD(T5xbd0dqfT+O_TXR=?OXRQq*f#0i-NS4RA$xfL)?cmZ!*I z(bhK6vedUy51QFVJo)FgHIXo{U)fQqIB zPdynxL7H%s{Sc0N%e;#e5#39p-m@x7#8&)QaIez%u>W~|jR4n!a|uN* z*$6WM1eNyeqLHwD&$j=MvzE{5=7uw{i9d#;6|cXItz080yeB7s@>j2sXb{w51FQ)V z8>_5EMVu0I5vK5abS5uC4thklz`|1QU=1($(H-q0k1>LvTB$u6p*NXm;Mgy5?;AYW zN2vtjD(tSUw{}zcW4!L#Br$ap;wVd^gRIQwmom18^?q9wV_$bbe0$T4c*HEGPi*HK zKN#XP!dLQ0)rc&u2>o~omJB%6akp5ADMq1BZy6cr#z8Uc0_$B_RIw z!8_**w{wypx4_QGe!z?H05Z;Cy*3gY5AU>kJcCjDLMCqhFtlYN0*{e;m6&3AO&XXC zTljFQGmZH}QeQ`XC7*kMtcYxUG_#C(?^gsM!5Z2sLd%&-JoCcUw4C!Q%sh9v*Sf9( z$|H3}L+&?c7kS|OqH?sH67r_l9X^@WX0uyhK1h-1LpKe{SE{9P3`ZGt!?motEJw0! z=Px3@_g~K{(ZfxHY($BfGcSt{oEP?%oiB$DaZ=p@GO=GlR@%@&&ZCrdju(<5W;y}A zkP{+4{N!h{L6g;YX9pyJ%bc4QN@bfHn9afL8k;PzYVKpSMotN z0bm(t5G@8iXuU99qQ}+*(HFxpka)SqF^789Q8+*#_VGQ4J=EB6%4M7*^c02{ziw6l z7+!d6>iD=q`Fy!~ZYTY~yQ|=i0{Gj=FjnzjZS04mR5Z~d7Rz|t4*adi=6PrgAuW*T zD!bxh!`C74MqKlA3JU(WYZp=y6&Cyhx>##WTbq8Ct}nqGIq$CRQ`7dJgHb-2tJqUz z27tROHG>*|gdjtefngMP)Va3wg9Dq5>YY6(>%N4~?Z+uvpAH*@iBiQL`FL5W)EB*^ z;Wcx8A`{z72&WDcQv=y!L&RnIt*)&OJZiY81HY3nBD720Oajv8IMQy}&sgg)DO@+Y z4VdJ=`(wYd)qiiEGsgX_hT{a%zV&}qK{yh4jDdHspejY^5FtKKmQ;??h&V*IxFPpv z5JO(RHRuTD#PfxOk0%OdwO0ixoZ+uEX-;aso^9>+yFmHnVRuJlS>Jw}MmkHJYSixed1i!`mY%=ZhOJbix@-*MMdCBUL)FFGHo$qQg{u?NLN| zbR0NW4*h0yC$caBDBLzezF0)S!Q&6T4k#=hfb4XgwzY~z)oMNVE9dF;q-@4!DL!|# zqxmsN3Z>+{YX`G0=Xa-EwB_jv72gBs87XKK{ZUg0j}fJ5_^7^WC?&ac)EPZ|03|Nz%`Ui~B!L6WaLT%&gk-v|Sv+!F_+iX}ftmqB@ z@W)J<=2$*sR~kFQPMA1#E*l*mHJzNu5qE6LbUk!D2_O!BKHk4qB$5I=?g*cu7VoWx zuqqE!vY>uNoB(RV5tTpmXb`t~Vz!4@#owOYyveZPtJVslc=D%*XI82^53-wNcIKbT z^8n*>A^`Q2lwbb2KaFIp!GwRa2?Y{>)0W}YIKMJ>@+Ohbt~5NHyU=lhDkGomBKjR84RT%8{I(ob(^@cu*wE{~b^dNnt}irX zKP1M}YYBlIgMu)>kE5NguJ0%BT(FO(8$A3iJ~B*FxwrexE5mdR(QtpR3=h--prbmL zcY#IgJ*ufZqO%WjT&Ej+=nngCe=kIc)#onWEVj^k3viVeiBvL**s47QN zvuyUjNO16SzPEc?%qcSm!LHBOcb!(P3(pEMhPt?)!b8#Y{zu#uXLDVMHQsOT_z8bw zeIL=ALzwodt(NGbEP|mSt3_RB3-QFjLdxqC; zQBCa%_=Nr}1N2?jcUwza$BNPd$VX@wQ4;tId_+|Cp((dSd}`CB*qSB+n2r}Q7Om0a za7E+`vmPR^@{C#NNKrQLEcW!VV=(31%dcNA9`JQych5`!QJ-fCLzXbu3LF4uXO4kJ z$Y>m`P+LnuSsHlMWMbY25|J(ZNp_Py!|#wCXr0c>BW`l{_p@P+Q7*v8&eJaq#dW z?RJeD->B;{lxskC=)Q*#UZqhd%$+MgXX`g&%HnDRV@?mr?HMUX_8Hl&PVpV$BOmu z_WT~g?K7En&>O;9DFz(z~Lj&wP&t|CRbHYndH6Nwrn1d@@2R|6(N z9*Q9%e6J|>SlfDn_q&IyhPs#JaJ1y~N@S^~_7fP_d5zkcuw(T^ee2(S#*;SO_}{L=$a@HP>}hL+ghK)OjMLLzxW`yuK-wOOz`kDJ$t-E>&je z1?+r_h}RKat}3Gr%f*26RV9ziwx~@B_%L)!>i=!+r+FAMjVnK1NWRyIR{wY9lfaY-r@$cY$Cur1xv+F4b!oNQ za|Fc6k&iY=YcGo`&W7?feM&ul9&v(fnCcVpeW?ECcs?+99i8Ttlw8#p8*EY<9s$6jcz_ zZV#0RB66^|KEI;(JbH!z3Hz_BnAzsrEjPG<`M48XDzZdtifm}TUjxic{04F4-f-G{ z&aEm7Z&th0^>;mipr`XcE*l|QX_!j!x~?>3?`$6VAB>@)rgplu3@-UmG!hACX*aJ zr~Y8&s7w&N$MrZOP=5@>1QHDF>Q02Rq@ zCZGf}h+QV+e91Z|piOC~B*c+L@Ssq+%-mCUx=`{WNx@R<{!}f3R#z^Ech+nG3A>*9fJsP-F~nQ`&S0TLBw`cTORn6*V=Vc@~H^TBWsJOX})Ve5&>2w4}-^&z}s zv9Lth%O#E=Pm}Htpdg)K#PB`Ixy;Z1=#iyOsZBNLj5ECEon8i?=Yb$~B>J?5C3!w-n{@K4xy(83~~hFj(#EXMM7D& zXZK2^dJ9jFBpLc%xQ~wT7nXfs#W(o+ddCWm@M9th)=RbD;AHgJN_TE?N`(?bAMJhP z1h2(WO4QN4uAU#ysE_KC?MGYcUCJaf8lEXjHXAZLBZ>lXV0I}chiF>68h*Gn5y`V@^UK3w*@=jTk2u*EB3FU*LfiS}uHL=;z5d3F_Hm zfo91b{Py2*zOYB4AoK6Tdgh}GKbUXW3si*XOoYn8Cs*ACTG%y{R_%2|zBlpSO@^KoHmVVgXp=51Yu%piq}9< z{hy+$uM_5RQ9e?Pl(=OC%M;5mLybL*sE;}_`)DZQJry52h&Ab_K_+{g#>0#7CeQ+^ zcSt2U*4vkNrBeF7Q@|+YwV~<_veNOvcnnkmaJDWPk!TDi2gl|;Ul4cN`zN*|OtCx8 z8!!vvS*%nNL~Mo~FTu<>i->U@I_wL=MOq#4y!yvyf1W|d^Ya>brh5TmZTSdMD?QGh z0WeBSrCw77w>;D!KQvdo>kS$=+5IaMo1k$r7t2$7Jyr$xAm>BdayB{|}O(Y9k(8zW_L%0N(O6qrG{ zrrQU!DxfCqY2ww*Pc_ka)hcfjGNYbM%UegWO{@`6a1`qVUX-yI*oyJfe^C|yG5y#5 z*L($ubzSw}f**fn{fHTe=)g-lsylq8MbGpe6`|1Y4qKTna6WskC(oF3GgXIV=8s{b zqO^n(HIa@dIZ**mcX^?@Nk-8~XlDYDk z_e63#1pV6y-sZSYJ4nfX%;ushst z?V~I*OgMCa1eqJe)@8j;`t4?XuWK+hVWz_s1kY$cNKsp*g36J!cO-$TP!c@Q41crJ zI1oi9_nAQ#MgR>_!&$k&fd~fCa?Qu;cfNJE`!tQP)dM2))-`D|fwpEcYj{4+Ht54h zB&~zN{U(m7JBJ5Cg6H&Y8M7zunq@i(9`bfV@rUjp44Yk78w()7o<1%_A4;;99JG4x zJ2u9Yd<|*?&%k6#-g}CfmFH3*#aVZD#bF6=cS-W62OuT-&v0g?}<%&aw%H5<+ z2TpBdZAzifhfj$p<0c$Z>R9^}qGAG@x!aDx)L2(?EwTfeWIVU-)JQA+Ym*kjmJ%GF zNa9%tt{F11^C_?`)h)c0#J*iou5OovV|e<$DhZzBo(S^^!*4-}>OX?EDq?5LMuC>% zOW@7NgV;mDSD9}Mh}PEY+QiUR9Ej&^rFiJ{*8-3e$!wnYxkeQh2LeCGW!eD`LEMRr z#^@tjO&=K9pXRF06=cW+(QE3%)f6Qr|EKiYLv{rDqY02lJHIra$RrTVY1EpQ0$&E@ zRmKD=@w5Ka_Vh&DVqi#_0;#2#fNS>};;TSoA(*{bo!9(Y5i5>nz2Lz`@uF$sSuR|M zr!cgE6tOIGBPg+?a3hh{e`#UP9)%y+-kz+sHz2Ku;}|a8eBFkMp8F}SWsSqj9O+yE zF{Ruj6rNv-9|b9sm9OBQ!)+%o<-T%Y4x}&HJVfc#lNkZ5^qtaa$hk7nXF zgyiPy<3eI2c0AZ7Muw}5&kP`4)yLDIuB3gjEh6= z!P(L|o6>F4U2^+yOKs8$!>hngYS)uHx!A8#7J80DQ}&{JaV;ue9z8`%cIe~!1788= zCIJ8_Esgk|b8fnN+a(65bH^TqinWST3f0Uu^Y2^Ej&?a$PxPW80N)^w{5aDY-T6L< zEn%MqcFRN!wpPG3)-)fR==9uM0DF;-epU9VHbt3Er@y+^CVC84ol;3V%uF^7cj$QP z6e$b7DP7&S;i`}o5pYwvxrM}b|H$O@AtLf1p<;&Uai$e_80e!aW6L>mWk2{MGQgYf za`Vq9*C4bmv#l1eRsM5-+R7b5iwcYpJi4!5$n2`Rc9sB5u6dLpqseau;CN@(pEQR9 zD#+SsYI94U-{xg2R#V)#`+O9W_6hf-w1RFi$pMRR%eGZJ4c)~f%8UtlPmbYe3*1n%nhEBd;u z2X3jNJg&P}Qyg4Hb@IxG*?6}8lUlcoYSj2%FN(%M=1|}k%&TwWalc zV&r_ySYLT)eQ8TN`mFK31bMXN;M3-NB|-bhj@{rUiW6#6LkQRz2$UPd)nFDfl?Z;@ zH-m~^HIN0hJYXy94I6PNKBN2rO7DRK?;*+EGzg5!OdvthCfJ(r2U4V>L$9GAeF{dXva>iwc6 zTu(5ii$U^ziRg178A2hVUOYLj?$32pbfV8!iQPF)4k^}Q;5Mg6hfZ4qO@L?`Ar&Fc zF2DYpXt-h(6qr%{n$NO}B1msv*4Gj%+e=;P8v!N%jJ~ZGs$SscKXMYN=W)<9@@kU( z3K?a=0!qoOrO`ZHIewi08;-Cf9^`LG2z7GA<5hySfD>GQ?=MS~+&4!^=MWP`*>U`? z16|VE+Y6&X)KFYPZaXVgzSRw4QD$b1Dh$B7wk+_WN?8ZvDB6$f+wgs8v7Cza=hP@(pM;rwHt z9a+RisVfM;@bOx@ojZET6OI!LYel6Zjt8=K?`NTJ zS1HlrKBKkEK&2w_-|XSHzmau~%a){D;?r3tR|r`6PFzP3%X>S}{l8u<%X_pSZT@J> z$~QdwXuLevV>f^zx8`Vx92E&#laI9oc@sv4Ex6=M-5=y~<$owGQj~Ur=&X0N5$adz zeVHgBAVoH2B$Ze6=aDWf{h+JRIPZT5^J0yiH$b4Dut>CpWe3}$F8T+rUM-Z`tC*za{GF#V&p9uN)$j>K5Hn} zscgySd=$S_e6RIN3u=Voopg|iMW15sidB0JusG9tA95#H^S)C^Ebox8WHoXpA=?Wh zLdRU?!jY~ZlnW=c^<}#NA)irT_!j}m zmos70*P#P)OY_7@I2&Gq$m!2hvm^%>vS5Q4{{pMGn=hth*y6X?%IsjGqE*}a|F>Lc zomDw(6^+4KHjm4*vSqm79=knASoD*Dqb85_^OkU(YJLi;jAowF{Orj>AupkLk+QMj zH@e$0XyRntxiN;*w^}@hS`&P(EcSxgvgN`nv%Md9`%koJ#kT7J3{_J~8{RY1j_mm} zdsdf1k$ouuAt41p{!9-Q%TiDv2E&3q?U_FtA2YcNzdo>=KH0mhm4@(xGGd|}gQ*$2 z2aE6g43IXD$gzx`sq4|x>H4cIwKoY}#4;e)G8P?=eq7Cn&+`X$@WpJXs(fn{zgl35pWXR;!}8!#7xQ9cC94U zI*AtHVP$DyRUHEL4{i>In?)3wmRl~#?Vmc@lT_HXICIUnXc^H7-2jC)K7oYjy zJtgmzkSw|2{YZh9wC`0pUcl5wi6ux-}l zYj#)f06e4t;9A6^+XIP`2XcLLSYRbwlfE&K!)wj@5DC|o^&+QyX$|GSxn~*AqgMZyHNE3AKn>r6?gP-F;Fea_ z#e>Y-b`L&G6xmIIkVPk<`jtl|h7KX`F*47z&nAkA!rpp+xGxqll^8wKZ_ClDq64gG zRF4RDP}9^H#MhOeW>P?@lyU29y)gAT^;ZrBF0XTj1k=~S`fpj`0^8IX1GHjE4WsP; z%r=W7cGUJF9dD$-Nm8VLylUv$W%<_iaI9)IF<<0)E}K`ckgI>ML&+xwWK1=snh0zZ zL2Ry>%RfKGO$_{Sj`9{Uo>Q|K37PKMjDENwCV-x)!7)&~qCL&Tf3K-LG?`gYl?XHN ztp^eOev64rbx`9$8G2>yGYXr{>6#_7FA8Pkv)QcG^&5!?=a*ssgJX2|fWw?U2Z@f) zW!7X3_NwT{n1rVuF3Nj+28HA}Gk!$~}Mtb2(8~`yiBx z1V3UrsT3&z3&qzgS}K>02gr4-*Tguc0Y0KPSQdZ1#1bogP+4f0a4i(=#APrzZlYxfACojWWaD9S*x!cZg8e{Ae+@bB_A}+2m zq-FPM?Nw$B#!@(4qlwMF$}l{qoR$YKTwcTH5leqaZ~0fTLjxR_WFJf9bJxk5!&*Wo z#Im{an)3n1L4iJs=(JdXcBqo4HxuT6h@`WeL{+|`Mpmi&`N%d^O$wYH~! zWb{#)v(`IJo%>vcljd&%Cs7=glHUhXalq>m!iJSX#+>+QU71vI+3te7S7LCGorYeN z7HooM*qGeI_+04e*lc<8HdNum+z5mvvxh(lA6B8=@$ak6+S}O}$y;%nv+1Qqprk^W z-ZMTwUz1B^J4~+W&{GHo(G+jQ%*iS^I^RO9Y6G4H;~dHm8CQ>te4m&30S)XTgFP`{ zN_k_?%35Ew=)3v^3JsmKOVyUSNN8O;3uBSYMMn32u^jvmKBNq8-pn`k2u9YesUVI0 zpj(0{-nQ{GEcKV$0o}&MLbgN(t{=q6IL6Zcj`|AyLYIK`^u0gi3t4e=YKHtz6TAeZ zV}x@OaUwJ)wnU#{U7igxv||87NGNH@TUA~lhGa(}AO)qSk*O$aks z-qr`C%bBHn+v2}R118MLRfdddc`_2mR02FLVxz^o>RCXxEyg|`T5yWGLx&cx9Q zP|wyx)7TwaJXO%ELw4G(k21&ZBD~cLQ%T$v!8_@}`f_8j_$?=*<6n zcpZ21#8Z(2*h2ZE*x%dY-MYo|$kBmVLp3vBGmMA8=%6W#N$*0hcscii1``dbiuiV< z7A$P&P)x{C7($30RCh&zwQdNgJea^MwjEepQkd?3E^<#TWYtJ+wIMvT~YJK)}pncwS_3@$CZZ#i0U#X zIxT!4&*(I$W`-Iy1Feh%6$@=S%m7b7u)k0P0(lpk`BMlTACuBtb4W-8^8betnP;a9 z+>V=6FZ#4mF1ry9H$?pGsY0$sFXaBLo~W+IDs0u{T=@r+aGs)SZ=@c(+jQUq(EBe- zBrQ}=P#lw1o805&2ww$H5)Us4jq;%ho_wBm%pg-v!h1}uy}h8rV=UHLnk zSA@mDUlm*~qA1Up(_72+YxWUb>fwNz3-qBZ&qQWsZyFbhBD)Pb_O}oB-GsNdV^$(; z{D$^Kwuxm6a9K)9sKT+E<6?<-=#BNJ68$8>j2*PwX|cU*;mnnEf2B4_xC zAST2X1iRmAc0ouq^h}=`*vE7hzZn9Bgy=tfTN=fCGd=0x>A>j`{JhQfUNciH%Z#IS zC|hMp$r*Ch)+&;quFLM*%AHo`XhjRjP$nay*L}LeRk6P|$66yc;z!r+uI;rub*{<- zhTtbS+HRF+t;HhlhhE79zs*hotit*070Dp$e(c`Ut(WSoLCr3zG2GQ6V1|8^*tADV z`d%5vUg}vtr_a98)J!>R<&+NlMZSqPa;;_uM&U&tjB(vZ+Hrm|jt5<-OYH+x5DjuS zX_Nb^2z1*=%8;lfm8t5v%rLB1cjxHQOc4@6O@omuN;yH6p9URfk?eAhH43-p81R75 z5H!ex2`1uBZ00n_q9M_<8Vqz#P}@)0&EXJ)%aT|`a#DF#;-azN9D0WdsTb6T+*GQu zTIBx*{lg}ztCI9Dar=Ox|Il{p4QEr!cU=y7ELhL%6X=;)QiBi-fZvr)YRUEu3jnwj zS9*fZ&6KoRR;-3$|60wt(aEx*f32mofrb`uuM>}bt{Q-4#!IZ~e*|L2sDNrIsHq7K z8?LQ(K|M7L%G&I4w`JCprI!2U_w(*@Z6%cop9^KEZ7PvB^=N)=_?qsU0l8C09WM7U zXqK-C-Wt1Z@t@Lp9g|dS2oTUE)eZ>|+~alZmYG@(k5b@0TwgyC1-^Xhi>?-iWvQ5SR4Ac%T`io;3Zq{A40{H!iqh8#?Z~jq4FRiSM@Y`RsYK>y zw$GCL1czLAg5tjzj~RXM;NbzDWa5$%td1W?HyUqW75Wli-|QC0J?%gtArvr1z%Ng1 zQRlHka!7H6=$!};IX_q>$*%$s8h;;1k~w74_tdHE!8xBhxH@KCevvRmWd;><9$eXw z{CEa4n(l{ovhez?V7iyoNhdjDF-Hl@3dOO_>trK}|FVt2Q1Zvrk&{EbnIX}bcy`oj zd^#xI*w0s#|D=OufoSUawhAoTso~_TquP_5Bn;C?J5fd)fE>^R;fh5381wR*@YUii zv0yc%Bm0M-&x3=#?T15*iS!s7nQVLpSo&+>J{W0dqDMurnYGoz7=6MnMNK2n0Lzrf zeI_-Uuc;8OZmv^TaY)ZO z@(-B-jQX-`hdWy)_hx&0b6r)y`JMc*SXjNgvFaj2O;VQju&dLuwZEtxjMv2;BT`TR zLSjOeIr6fZ{^)-~tw(*oPYpuvtH<4$#Oy~XwMWnP?oZBgPlz9pO>-gC*S~}PKMz+^ z1Y3u=+O)|9r~U0&p)J{|`k{6{R({?-R7mp2`My9$lm{9bNCu71_@B%7mKiN|IU23M z5iNx&;XjBvW^}?*gtjf26TPmC9ddLD*CO(6Y)&$zKzeDR%W(O1de0DgnK#S)&rZ)Y zZ=hqmot8+7I}Ee>k#>wt`%XMQP{sg@+9|@HU#2cK?CIg& z=LdsbAJTT?mnRMAC?elnhLl)~qb-&V5#C1R*4Fq4ry;#Fxj&T+H@?Bu2W+JW_ zw_&Y#r9aTTa#6%ylbq(_bz)zr)zD;TP!W}lc_0&NgXL{ZrEUKz15gc|gHecn37={g zLRe_!?l0si6-LFW{~==Jw>ISIbf+&Yus;g38^EZNJ1t=#_5&rdrMJ*M1s`1d*+kT% zz(K3@=;wRK`9_11bYFJx33N1P;XPj7K=vm)wamNGS;_<&V{(6>maCiWL3Ml7DuX)w zrUq+zGeUyuBBgxSSWw+)5&+eW2UhiU^AZ7J$BYgc!wEnH9sD@N57qgMFr?A?V^f50 z5ZPdZH?^p&3u=UQ7!;vCyE;iT(YQPX2#3MMB93jXJW^PC(&fM94yyE%iCdKYFv}!Q zS&>xzheYozM@NqIf-avcGXdA%QvC;+N>m7IN(gnAD{J{U#Pq~TLo|^IF7o_Sa*#Et znq)X$r4|Of)2}=R+q45!Se=f_jy&tt-Y5Jvl5yL}<$ycpZsux1>2+Zy|Hw30eg1Py z`g7HNETJM)p1o!DY~FyFU$vKQ!BPE+*jeYALu(&jBD=0Z`jOl_7NC z_4A5UK&9uVjYG=acHIozW0+Z628lI(Cx1#vxBR(9n$-My+;y1}|X0 zqSlM#WAVJV z%JK1AbpKKEQ6h2~Ssb;;c|~n;Yrt-Gge${=+#U(a_v1 zv*3G6kKakCzy5=kJS|`bymg{h6QC7LCSG|}I_Ry#MB%G-87YU?d#2<9Q1@nKUq(l|vSn^Zb^USwuJ%FdJqao*^W)$%_3${LN>@xi z5irQ**UmU!RA~W_@A8`1e5Cdi9`tI(T zgJv4(NT+?snww|hX2_5EUuxDu23_0xfx)M z6OW6jz+xnqFV$Mtn#iqdm`UfsWiu#N#)>4F0kv>)i{GtX6^U{>iW?&(i1W9>aqAZP zE-jBVEhDL6Yw>IM_)E|ba$7(|&3mt!lqYW8BewXvbaM(F2LNTe>AM14p;4%zaQkdd zT*8W2KMB1LL-MiK>9YJ;9vN((I!>s%m!N@U9Op$wxK7>wuU0prHsa5pYxOtVxgbM{ z{Tdc^czU?O?2YhBrcE)+0T0L`bcGEX01GLT+OEze_4S>hGMx74sZVv>-MWg+oGC*# zEG(f{b2@=^gLB_yqiY*1DyJ{X8W{r5?N1P}C2!MCvY#G|?r{GA79;I}@wN@FNDYN# znW_YVsJFRyIY#H-lSEv&f9dgS#uHry+PY@th(u3$GMVrbE6N@mf(OvDmBTLVPKT(R z6ZEw`_~Zs3p<|`E&2i%F5(S(l+9C`M0#7bu&X)=PkQl6~oPisis?mWHvIv}Z&bO$6 z;)x7YOp9IvN@zLLsE7YSp~Is2>&=ItS=5u}wP-1cdj-L~S)A^1mo>I2#Couy!iQ|F zAQX`dmrjo*ms@yd;fc%WQyAG+O0Gdhkj-Lt8nW-AU@(mBfPV7wj`p8afleY=DbAMd z4_>W^UB;9%1)G&^-dmDh^37ZTpco<5K+2BjF;CVUoSbz4IT%jmWf?edgz*$8&KSVc zw;4k1&vZsGXRpQess4-6T{k#UzBX}a{Q7*I@E(g_Sf9CldEMD6IBGOr}n$0g*EM4kOrbYo^-g4xDG$KHhYuB|ZZ) z7gg2;Z9Y66LDZxAGA=Z4_xjD_EmW(sJ6@l>7tig%gWfPK$_yV!Z2??7i-GJVWEGXa z7Qr>&;C%f47ZpipX#biJosn+%Xi5Q)bBgv*0k%%DMB>Tafgzd)bOis znc#Kf$UO1FdnYAFtiVOv(ktWQKOnBea3T*8)&hQaZnqv>vJx38i4YuE>$+NaEc=)A9~@j?JMifgy))?pzm@a{tqs^H-bAnIdfy>%cH_2xvl|>9)YgI%Cs>1)xM9#$^_1^+Bib5)`fW|zrB~zvV z4!SD5)bGq1wBO)B9d`<-7T)K~NZTzYhhxdVJYdew3?Ln`xb|xF#ukVpZCWwHe`!B~ z;}OuOqubv;quB?t=FY1?{Dc(u;o?tHhNvDLAIwqOo#DNsFk~ECdE}bNT@7RWbx>G@ z>tT>XUCg{!HBSL#HX|`$Dn&SEFFHTH_`uIap#)3ez=9?=DwRuFSOo=B`#XAe67s-&f6pkq+m} zp}nuRi&(>hEO3kV2l+#SPsOC#+l0QRP&r>B&II@hzAM$2B}bnR9R9o?;pk&pcFrJA-zS(|g&KEp!!TVLR`<&6(vG^u3z zDO2Y->wVG(B$r|*vPL(3LfCHTcKdk?_b#h>Z@t&2M8(>c3PI#oqeM|744LNG)>4XE z?wiuqXcF*eO6_f2atm{-_$VTC;e-=f*uX;uj|E)W2RVdcP%kgl56>LA5MQe%Nx#=CH7zd@6xYCkaAnxAkvZ}R8lzVE(+l= zz(om$xw`RFxG*96EJkxI?vm&W$#`)oo8{=v@sMX}tO(j=x0fekrk#VQ*#hT1s<9=P z;Q`Z$mMVI1W7^Q|qJ$~cWV3A-wz6(swdy7@vmnxnlm>A`{|SyKw{S&HQ9p?+#s-rt z`R~ICTtZ2d3=~V#}?xXnHi-qK{Z&q`t43)LnS1J4BOS z*na=AtCm(#qyKY(UaC+z*Z6y#_utM>m+Ya?RMF;(l1NOwGyOMVqzkQN9-(s_5#cP3i3W z4ppcr?o_#Ai0~nOT0Y)f7v_s6P_=|_E%4;JqOX?BUjE{9TJ^4I4()~EjSX9eJic3x z9sP7k#O)J6<2T$HkRZ$om`4#S%0QXtzz1iLM^HK4O6N5LCljq+Lv?F}zj^PO;X%(- zPVEB;hbOZLzuC#hD^A|?i#&yN+zsVY7+e{HwmahBHb>^rZwqh7h;n{1U_jYY?rU4% znn8?OVy8sVJ8j$L%pNU01_5WBrYMN04yKF0qLFk?t_d9d#I4w#f@buiY541Jspu&2 zasck9fa^tJqK;y-K=5UWcss*kXp4MP_$L0rz(AT*G}|iml|W-tfGy{$wU!^#Q?D7{ z_2HhcE_3$2_^js4#RYA+8R^5P8XdSi5Pp4m%iYr;3V?CW`F2K=C*}>j2R!tV_Ws?& z;@1}N7Z`%&lNx;<@;QtEB=u2H$i2`4BKIDLRy@vtls@>}(VzUV$W)7>?8Tv4as*rH zt?l`BDY$yvpO5J)0d{h^+%~a{z}aV^$rP*AdRSBEuq(MX?T31!Y8wX1}?6+Ok;~l5osZwNkaUW?7;38;O1W92DC;?mKTLL3sD? zX9kofE*!f*J(e?C-zFYg7@{zV?bo5~I?{`SWx68*^mD>XH>#?y`s_L}1kVN}eQcbe zgN|@S4Hnwj?P%neh~g3h=10iainE&+GzQ)taBjg=6-OhR@dxfggJb1Js`bZQ4EH{I zv6zn`*vHx<8jY>EsEup&(1sG1F(0Jm6vw&4hr(#3s3Vmi)-qRpf603!Q&hTUKlQl9 z)w?O#AzVBY+x`vWZot)is~y1q8gqZ`-WGZD?ESZeYMXU3LL|n5&<8L;#Cf`i!VvUv zNIlFOznF%7d`+|Qv5I|Oa8=Bc+E~Ho}xytiJQ?TG_ zQ5cx32rtNfZjX#1EH<^5e;JiZKi|deiWd2D#(u_wf;j5d<; zp0CFMj@N2!R)6Q}n6D8UC=|qF)j-cFRmIP#Yg`!-xHnJb);R!tqpu4V?@8>LxY8c4 zAI6JTWkns8*z<(L6x#LLZSs;Tad>g4^?Pf=L~<8oH=-Nx&c)No;F`_D^k^-_2lnr;qQ>T*i7<#l&2=QWJ<~{`w0P`X>RbO+#o+u(AI5_^6B47 zvVu^FA$3yrI+x)126uAE{+b7O0Glm%PoT>+R5+EsK)&ue>n{Kq`0O##OK+F>G=%h8 zl_bLFYC_*iGOf@flw$l1Rmm1gfixY3LeX}-b{tniVA1TftScToF$*{!^;uJ`(tfmP zH5-p0AvO^ z9O-Yawa1^S^P#^sV^yTigcnXNk$Lgb$n}ucjdfIL&f$HQGw>@cT?+7fm=&vzf?kdj z8W1-{^H-5{rQQKHR5RWuS8fgZ4&bWn6UM5op<+y4-phI5jCq1L#f|=NiS?p4ja;0& zt2i*n_$)F0&j*;<=Z({mBcTxnx|(3osq01;{iB0{h9%*Z?L5X+;WLhGwpN865$a9>vw7I#@FFD#|p1=Q&_GS!r55F$F9w}LlPzCp{aOk+#L!m?c%mGnxqGc+o z@eH^meaEyfhF`-{d>Z3M+Zv${w6lxg#Gh;$8h0^Y-@Bim;FyoY;vbmCa$q!&djer4 zkPbZEQhvB)ZBnSg5#EjkE&r-Cf`jq|vN&qhY^gxnxkGeq$O#Jb-y7^z@ z{!7gvT?cxDMOJx!N4!xjZdr2CmXv^veF=g27RxoN`3mzu9=f*AnMH;BB7*g?{$c%? zaJ~g(Gb`+Ag_%@hj1kow6iN$7k$ME`MdDa-E{tK;8rn7Sn*nTBTiPXlU*Htg(59Qm zDxtLnEks-SW32YRr9W-5-HYDMdC7;+6qFC6xOC$$q9IId&Tz2Qjkug6LKWN&FvKQ@ z#??*$xq3(-oostgz{1we#&$rDZyF&U7utagC4Sg(akL(o7tf-|dE{NV)CvPesjeCC zbIvTKZ5kJy8e>zWfiKCxT(?oE-}KmcHrOy^a4vPIAADU@G6%0SVgqL7QH1xTKRiWG zL3o?Y6Bc`&z#*VZyqPU3g^v-(NnI`pI{!UnO!>8Mq@ORS?J=dr?w)?THk4&wIjcn* zkGt;3>TQ(LV$zC{lS&Ye0L#*8+vXf?`X=4>M^w%n-ioE1fqh}M(zN8DfImpoU%sq^ z>hxLj{Zik#q|f(!E~s55N}3$P@wBkxB?eW&$=+V-p=hlMwtgufix2_-akdgE5C)=7 z8xQAFRhoPn+a8go#YY4rP&7fUb}*B;?SEv@svdV8vxsT;&#Hr8;v9kJb~v9C=U^t4 z(=uAi#b4av1>I^yUD{=gYX>k}OXkh&!GrUcae9n7;GtolEX%}VKQQjgo?*PrAcOJJ zd%mc~6_!2S+W0Xo#phX9orZY}mDHHbp}>v(SYj#G#Hc5_Z}s>*eVNlx;826pf!b{HrUQx zV}_REw{T6!_EhvjA{MFa`|bd1wj@-}_>tXCA+d6SWPNWOgiMo=l_`QySTL{iRTo2| zZ@_C2;ppBGN;tNF49QA^WbD^))eLK(PhZW!+(5bu8x}?8v24K5>k6xI*99HGM8?M! zI?xTwqx=AY~$YO)&kCxt#+ZmE2AJKm2nMoNhK4S>N!;g+@mwS7ndejO3xEI z(i*tPHKnye+aY@MDoN4&1J==LV6GE}1}oiEcTe8d zjGr@xe|#TRyl)~$Vd8+F`-*XbuBb23yrBHv-vmfAW@MT0xS1~Dv;Ogo$a!9EL%am_Ffgc&=NPvF28wM@m=U zfH6L3h1CkXA`gh*@}zoGtM_g3K27A6R-I;#K%miJaBBN6<=O=jgG^5xC_1H5CMQIFA?tIay0yTn#L!;tR#RQzA42^P=z}DI(avit<@i4#ozhu9wmm1})3@ zA2VdrI5HB?2pL*M3D0gn1Kip3%ZvBEQqh;gInbk6%&@z-e57+ON+IiKA}}#=Sip#L zQ~t`*gkvmYPQ=VZIE_q6PG&ed@i&KFmlLTJNJpg7 z(l>`nPB0nKY@N(b^v-3#F|Tj=5Tp%I5SH9X!gWhgp<-?3qvx(gF+mG*VI9%DAe2bSunjimtVej8gmtiOYw1ABM67v{G=4$_oT)^xH9WP=J*yd z7B$i(;DA1gpfqevNvnZ2?dVn8wfb;X+5|?~m3p3<*(!<`NrwK67C5$?(xukrwX*3I zm5f{IdG#-xsP6a^B*)8epT}t+61TuK{m%W|O1-x{=XPJ#>ClH2ppS+py|mH&0jVn{ zbh@aJ5aTzA`+IyehF;xv02uDf>&D%;I7RrC|bVbWFAkai0X%tN{V5;rc9mJmVf@aKwzZDu@?( zL#%&MHyv6nJcg+UBVd+OmigQLqke zA3~p2xj6cjZ0Kb$?#)yZVLO+*$K)-Wz7}=uSsJwS)V2BFkxlQkDI{1sDD`)=!0j%N zsG%)OXzS*E&@L40qZ zG{KqqHr1KLG{))0SKb0}V}*C&5J_M5;xZ5DRlUSuURCOf=uAj%dB|aQVbih)FEu~k zn`L*M(@_gFT(GgSG$ioeJ8!-JoVb~Xm|R;3=JQHgFRl?&GR4DyZpe8>aFM%d%(0a< zOd1DSucPy2d4x{Xjt}U{v^$*Pdu(B_=J%C*$YC$Z#1pG8OQqLC99V$-B13Qs*n?oK z96UdB8eP7jG->QfH1q%t8HQ#AHc@L8sN7fq) z6gEgNo5m&5;xc$mB;C+;N_2cib`eTv!q$RR;(#DbL*HmB8;=f3jIY(ZA8DD+Qj_p3 zUO=7WubJ9Vl5baRFqDFH9_Spw@W~P(Gl)>5fGO2drdF&Drf2G+aQtPtt)+IhYt4xyj~%^q0RWPmHnf1I52Cc}#lf5R;gH3n=r$MeE({hC5e{bq znGwk3B}=53X>(v!wVy%eBNhK^4W~WCg3r2VoI$JAP_+<+>{SXZJp$u&zNKdnQ)`VF zvOT5GA;< z?1Exp=G8*!v`Bo)W2$G=IKHUtHx8Kd*q@bhE#!!Bxj%4kmLIsk+zoWjQo6kp+K{FB zGnXIR z`-`%88-@9&A~g!`EtYsN{9;JJA{UhEP_zHdmDsXTX24upmKd(4lCBsIZ;xnJcYvip zUe;*00)M=2!7NysPpBQdiFH8tP=dyF3*Z+DFO+sNQRsRahjwF0 z`F8%rj~Sl#<1S$A4;vDoUcARvS1 zT3iZ~4|jv6oQN*nE10#(N-^wW7>cqtSyaM?uB{4`ZyABdE!yJ~^_ax}90Hx^zfvf6}m~ z$WuWO{8-UUI}@T#28>wrY;4I7S(ku{^8Pf2I^k&5F{h)-jy>U$jF09Xa!F`4X^63?@!Ucv{Fnm=-uUi^`i5huaf$O$%VX&lR=8Ei>U6L0?5 z&V<5V8|`MY8rMv_Q}(TEYx&WBAPQ8R7r`uMWHBR~@-jijBzaLeNFnzKgbF-u+dW6@&t?!*+4G*qFYkq)?NZR5O z`Pm!wmRF^W^cL%c2<(yK@Zz1)nHd21%Yy)w@d9ND7y4hq=Wm8@TVRHAH;Z6=S3?6B zz{a6|+rZEuK{bN+dPEtqR#7%x(7Ku=f^F}Ch}qZpt{WJyg;oZjgu4G*bt2qlMH1L zF=`%YHFf?yDB@My#7+wNs4wW&TSsA_0el2TzX%KBB&m52ZCl`W+H-j<{L6JMMIT=w zE{TQusuE&hqxQ~x{LN!j8zu-dNaCw^Aaj>D9{pOfZ+pHqKGEd_)qItU`R(hY-~O!O zlwA}6xv6QM>Vs;{`fj8llx@&&QaKAO57_}I0UZ()Qt;&NzAo5?DF5p7XkuVCbUeR* zV&MI35CX?(wS%&1Vfd;91dVIF6fViNK|cR~-b=$=b32!O`55i8E);(AnIAYvvEW{R z=1kAINkD-Pb8jft6uE;4sdB8ynlq?2#C^bGntiDt8scowByF^jLTtNA2Q!$r8D&$k zRWjE1AI_Vxj*2ekM`2<{90rrOfjt`kHXI$(1pw>#IWx)JX7N}Y&F?`JqV+SFcGFcw z8jEZ20195*oN27ORhkAro3ax!I`w?j%FGC>!QcvCc1VUa?%8O;vYf#jG0Hr)aw(v8 zOvRBQ$`o$LL&fcb(LXv)c6rj=SqZdZ=|=#V#^tiBF=I*)CRuC$2uWnkluMPOoh1pX93Po#7}|n3+gql_vK912)=Ec=Mf_lZ$);gv#jcL;Af0s4m1) z#6vK1Xj|h0M7|^mPX53jIpw~(xD;pNU+*WDruqMey^9f=b4RaqbNxvc@k@`6K`uTEo&QZ-veYJX6>2ca6P%B)xDoWpP_jd-P{=f2-cLcY&E zk{RQR>0gAqu0V|`>a+~qp@jm;50l|~Vaw6}9^u2sIR|}q@3i@OqXmT&d!AMRX8ic( z@W-he}<3#eLoBunu=^8mj#602ZeDi?q$$59;9~5 zNGp>|hz+V!nZ>o|@h5|lM}1Uc-5u8?7*}n~h_fw7(AI+8=A>iDjJNRGr+{)~fnGAE za^O2o=_~9O>B7RJ7d!zYeTo|o-r}Wwttwy-uQl)rJ754IBv@j6k%XTF=Gqc4esSFB za{Bi?*F)i##`Zb}eAW|IeQfEY0ipw9T+cLT4sE5u6cwKaoAx+n1Q^Q%ra`$*A+V)m zUR@cw;TP?MWnaBG3UN2UAlvq@vqBVYBibGcTItiyD&Q~OOKq<^5tUe?%$K;-EP~q0 z?g-!P1UFVn(^+oHs*|sy+i5BF4KlLa_hatEeCA+-&~X zOT)Q~P3yPpvqnA;*8Y3raLNSf^NdcZ#Vi;Qz-xF`fxJ_ZHxq@pr|wDAi9SUE8;OE+ zcK(vWRe8R7#($BXf+-MpTHn4T!_3d1@cM6bf8@DCz%g%VG2iO=?Lfg?-L;*7b5C!AlC-@toGRERo{wt4mo#r}4qtbcL zwlg3)oG9aE-HJMV!$h^4F5E1JFS#zptdFbGdGJkO4{Nm`J{7J1;32Nt6~pvQ`)r1H zm}RW=g;mVO$xSecN)52V_A~$*_+e0*CSeIVcFi}HDf(4c*)7Dy7alhn#rm8 zfNWW_W&<=prm>o|5V1hlzsWHmt}%OIUp)Xt)RQ2(Ph)MM0*WFK9fN5}StU|P@8Fk9 zL8e+Q@9sGIA3<< zM$w{!cgj-=sD5-|_Yu!3Mm~`K_~{;#`Qsks{#jM>hn-AwzAyJ27gQm%Hd;NlW2v_D_gh+O+uWH+G9-Eh2e-sNS;c zSnn*tXNx*(XSFpHf(PHrW-uR1E%Yc9Z|`DJT)9*XDP?E{igopak@rYW#(X*9Q|W02 z7`vQ+rI1(W2SDP@NheOSX@EV4tC0~ql(bwReyyAUW!53pjuX;=?_Yzs!2j=X&Zqwt zx3$`Q*zF6u!!Drf%(R7HJl^+U7pA*4E1f_Q_^^NL$L`+W-v+Vt%x_T^Wts94qwCc> z;S8^83sGF3Sp1~YUAqN3r>vhId??q1}w^ z)(g}*{7aQOAzvC)gy1|(z5oDNJYeD95oFMeH>6YbD6dvpwjpuy3v|w_DgWW|FfdD# zhtZ3HE(%NOMIm@$?p7c*W)PYc)jUoB&~bw}$0+*-?qp_Gfne7^$VeXtn5&QEs-B@i{1hPDzZiSw}9RIy#AcPpWP-`Ds6)Bz*>fA0PRZTp$p zSV*Y=xaV0unKhW{_5y*wqFZz*GAThL-)5A(IsiR+@pYKC2a&s@4IdsF%(+M}v!X+=*n*SNwQDH)ka^cM;eZigB zALHaVS4Y4o`Y;5D#DLJVHZ=;zoGY;c8bH_)&{C>1%x+t-z>tXm0NzPw>DGFfDLT{d zKXg-$I+tOw0i+*m;{9tO_Y5^c9zKRwSw9J}n*A#0&6F&o{=Yv9iIPi*O(uhAm)2#QkM81UQDd;PaG1nkzb`tmkhCTw)WZR z6J;*d7^1%%gFXVzw-i~Th!=sdI)4BQ&)@(*AZ49SO@bsERACQg>B%7b_WS~<>t;P- zCcy>(_2c$Mrdxjz$wX@!@@5)I<189;a6XM&XNJ%+@!FZuaAKzI`YS41AMYq8e@_}E zrQ&C4cn!tTam*}G_R`~MfMqzTt)v6Q1kH|nxN2r6ZTUDO0W&8AEU^+1mab^s?Hi;k zYk4z%Xtrw-X&fRe5D~ktfdGT^ts*^{OTbW7!{$u@Shc43S+VHeY+IxcC4)yw4ttQONpNp7)r--M$2n}ek= z`4E9Fv(79&F_}sYQ#6^mS!u-6qlfK1CodxLBCN{9b>cRrST%W{+M#LUw6{hQ)NoMR zT$r+4G_?HxQHzHT{H|>U%R8?ag(qJcvBlMYqSXFwi-EWq4Zy_c$o)>N9*|mZ+zt+L z;4o(G#!^&noNLg&xiOH4VUcT-y?(jkDYcWxoEhH$h1{`fDpfsyp1O6;LyYawz-8>Y zc~WORDJ-kH==N5tFV~t3nh7&Sx+r4}@a8pt!4}p`K?sw2!7|2ae-J4m30zh!e8AXg z1+{|z{=qvKK(x3K-do=>qH4yDl6dVR%;CucU6dl~6(4lkPeo{mTnt0dLq~1bH4wO z5{gepR+}pfTbWHw8H{j7Em!bnL{bJIg>P5jI1mQBv&Kex-!Fu=Xh%(=RkOY7Fo@=_ zg8(Q1oHs&5r$~+Cd;}MjFCQw@Lx!Bd6lefVU(%N-CIfG-=m$d01lcV@Z>mzEwz9E2V<;=ia$Tz;Qc+Ur!f=*Tqhwx za9=31UAi9Cm{5fG{8HI!EWuc}K&G@!cwGyRVX*fXX!bLXP@eb1hsg!?J2o%=di)Dm zoMU#Qi0~2M1=k5I#aqf5=Emf>pUJ0KXQO&`y1d1?5Lb%92+v^AQN4Eh$*0}dUnEtT zT^5J9X8%m1?CCKBAih_|$eEpzMu7QniI2zt00ohUVSfcz?~r6(Bh26yl~Rm&z6R-b zmT0ZqzMbkb|9^7nqd@LF&<+phzBsLlJa6{Ka0AitHi&eI2&tx&ja$(is0 zM25sP00#0F(8)7l1_fuK_;ZcTrL zOu^|vz(HOJS16$#ukv2VL+}-#wlT3cSsRSpi*dqo43|Ez7JL!>r?PJ~<1(K@rm6 zR>WAa=%;=CMMT5iwb#w^Lnv+xAlji_Xo^wVLXa4f&W7tW+egHxluuj~#Kwbd(uaoa zs$~((a&Vc(D9`VM@fVDY@mrb?!uxCr9LIPcV=e{FAmp`isJ?gWh)<4UyXaT`6O2cK z`3(f!4_(plWTFQqMdS+}xS(>Zu_iK_CqiZbQ|z_0X?7)9qu9TDHex3Z z$fb*y`VFtDLRpxVeRCyHU`2LYxHkp%%upDwl_a^B;N7qcAp0%@aG%32I(@Js>IJ{= zCz~t~CMjCO76{nDjcJDLjLX4O7~dR>G%LaX`y+x#WK{!Rg35B2VjM5xWjPGLmG4){^E7)wi6K$|00U0r3S@EA6E8{_ zFpW<$xrx|S9w2f^0|;%1U6okUTOU49l_e5}Hpa{_`@IJqHNj#zON&390!GS_c2IFh6=U-$L>PX=^Tpy3CvVJ9}&8Q znsZK)E^kmT<%U5>P5WT5H5+R~vl>U6t0?892^O?&E*F?@StspeIPhQ#dLqEtj0Rv| zh@dWNBpOFO<#=ELv+1KD5+}zSp~pob?HEWfm+O9RdtaRR9BH9Tdd{Yj{6Bh4#0upN98k4^ zrv8PX(Bm%$0s6(weLz6&n|oI%WD?g|xmVF4noCn?32qc8m2bbK2~H*m*CfnRRSJ zN*Ct5@NqRLXSslDb<-b|rK$!`$c$u_l$@}&8xLRqhY8?FIP?naDIpDEaln}ww;|sx zv-ZOUB7JxR>(As{q=p=kys(Ca4gC)UL=(Wz)457F0ly*yh|+vRi!3gbN=Aky-1q>K z4It#jwOdV5PjyKF6$$G@4#H3{!y?&`G2lB};%|PQEr2xL=aPGZTxb9Qehd$eKg#H= z0;Rz`TIdlG;kw{Rpc{+@wjcan{%_!J8x*Vic-E@>RCR+K!3_WqfhacQOfTNo6o^zN z8NNqdzX0A==slE6NXbx1FG4yJ-=WuKi5rXh{Ls`OfPJ^;6fR?OjN-<#vl!34sejquu_007FH z062_lcXsm95Rb5lqLg}TI=n8#?ZXo?XxXw})lgHyjv8Y@hGYc;68)$OKuoq2_kvHt z!X3a7QX=b|?hXP#HXY8vDzkH-ewopS-Y{=a$Bk66>8EgLInChM0{REeFBtf6kY8Xr z1`-akUq`6sqd_DKxT&@~|3k8<F$y+C&;&05J8Tjp#pz734`{xKRR zI@j_SVk5^NR5Ni_-5BT13mGc2?-{RHWxD;T_hHME!g&kwD)_6t z;P0{i0mp3IrJ246^)RtOWx{|1oyH_jZ)2Sbo+HMk@A+B{GL6Qm3=S27fB*>n)r1YU z?P#H4>0QI@5q5w2Ogl#phCzOt!+Fb}H`;UMEyN9MsWxV*(%LX6-0H4F*$M9BE ztbHP`V)d=#(Cvm`D;bT?XRp8j05ky4MFeVzaupc93$ihEm;aC|42Hu1D|r2XCxT*O zE65{2JH(!G*`2;*0LMNE4DvoP+R z&ZaVZn*RU-*nkJxpG1J1In|GvU)VPE_<_5k3{7Z308D|>Jj9j*ax= zH8%QR3LM{bj_Mb{3}T9t(_);jL(?F{fsJK)_e)myr|A$ZKto+D6W^IXEkH|4Si1De z0CS9N>QP57$Tx~xIT9rs0#F}tiQ*1pVuEQ;9jSQaHj#SipKGS_8l} ziP)&H9a4}`5E@v-`Ma(@?>VM(WXhv~D!XsocfxN2$ka=DjuWn|OIjz-V^n+8jx<~s5 zL$tA!vry@PU=*lq+#3*qXgBOQ>oYRH1>5 zswNV6b|!9)tQZAy_Q2TqcffPG>QC9{tg1lgTCvhF7j*Jt2jSKYuhx9d`7sTK42+w& zC}->dcl-jsK|~OwEf`?Kv{w)gg^v(8Bzfripc+m@e6QGh4F=!v7BGz2*1&5$6y?To z$DH{A`4`L!$xffRHBtsDEu%Zw{wPg6U5yQOIyo_7G6#ZU2JK_!(}jCoKzQle9^%4UBVV&*P49+aOp1SnZ}B=D{2zS|QxZ$P^i`*O+N!UpfB*nRSV=}2 g0000@O#mtY000O80Ra*K0{{R30RRC20000005diZDF6Tf literal 0 HcmV?d00001 diff --git a/media/so100/leader_rest.webp b/media/so100/leader_rest.webp new file mode 100644 index 0000000000000000000000000000000000000000..351667778f8662b1ca5eeccf995cc26e3493bcba GIT binary patch literal 89600 zcma%i1yoi4w)LT;JER)~>F#dnl2AYzY3c6nkPhi?1e8V^>5`C^?r!<^IePE^zBk@` zwu;wrCIc(sv0AP^n!GlmT6KnKZ5NT}dL1OI}c z@eS?mtzm&98(Sv_H5qYoZ5>^5_$?3=@D2GgG|MRcEf8P1m@2lBA=T0$! zKkMKzKZZA0rrYLoo3h6OKFhz(`d|JcnV32n1MfWmKdi>~4o)Bt6eDn~;_74%KK25R zaU6g_0mpIRWAi`91>j?&KgVAn=V+)&0Ot$?$K=Kqh9 z;4kn@QA}+$)q%e_zz;D<67(MA2(kxRgA76LAaaljh~s}bpA&Mv1jr6J+a2TpTxSll z0678IhykyFKfx3@mIK*>j6uvGM&Oto#0vbdgV!0j7WlfF`MZ9M|GXBs0s;wjJUuFGZ2>FF^a1cLbq0(IH~h#}`!g#xj5;ABC) z97pa%7tyO2F|6z8=*S(v^*mt+e{cKK>3!A82wUlyZ`{Mm>yiFt9XOT|H=ZVu66uy*3*yNm4%M(r>Ci?vEPANA%XvOmm=Ee*{cgO+@Fc4nt;DW@F()6E(FFdtmynr^T`O!a zqnB%2W_djNjU&s1oqKewO7o*)Yu68mfOZS@Rw2a3K$GO(K~5cs1T1l%{hh8hB$lKqyL{lwi4JF zyCMFaQR|CmZ-Ds_qq^aTDjgcT)|mDp7rWH9obvsbkulQR{NEG)vn<3BkkPmOmut-h zT?22yi%m+3d-a-|9M38FvvTo28?f?1y{EkUTl-L74^)=w|9G2GIBM9FChC7}RL?jm zWVb$iA^`5RE&c|wh|7I5RC=|~Q`!F8_IUbjBmW=!wZe<@&*C#4V<4XK3z)zj6T5<^ zw2YnlXIBt7rJ|QxG!n2N`}6NDbJHgK-nD@LuRC5*9{pE@+;$fH_q_#Q+hS5@oKsyl z`T~MHY)RY8*lNA9KO4?i{!9Q@mS5^nft2Tez<&_An<6FvcfS;m zLp4!lWSB7tz({sVJOQw%oYIH^PytLLMv7ga4tgqQqm?%M9z2##0dtpn9Lm#qU`No1 z$<;)a1`)0O@`$Edbh!VGX8`Vh){%Lh(T1${YIr;5B%R6)@ial;k69J7{5e}v&;z?` zK%v6ff~7_y0oqObKTTC6<qaY^c8pHnnkHvk$ z5X*n;r6!+vZkd2#5%~{5TB#t%b}U~YTQ>%s@E?Y0g5(5V*1s@t+W-^7XwsEV&xxxK zJxBJxDP%X~?7j@kUY#e$)Aj)y#L>OMxXWn0O|o2j32=wWJjJsxV1$YZkhS~ISpjCE z;8a~#-}Kq_6WGLgJUMWn!|ap}t*sb{+FHQy>IV@J1p#BSo#-sY0CR-aNAM>9ok5MA z_R_h(9AJlxMI0``yj)7b6COEn8vH)X6Q&mhTtM+tm6Y|bWV1fv4qzTmQJ&-p3GdpJ|`UN3(CW9g=0WbNz!S|5ms zK;~y0R|m|gh;|Ul{1pYn@^AUGY4l0SjN?UlEFiOTU8=CwQxc4TGG+T%VI&J+*@7AZ zSbokG8yEkJ7!~lpb!kY^cz-FE8LAeZf@Fk z|E9S$PHBi4x4Xi(It#i6O^`ez$NnrLCPhfulMYx0Fr$wsec-vZMTeo``ziG=YREyz zgBO^QuF^b|AS0ObLW6z80GIXoC&NKiCqpKzAj2^sm^q2~d|?kWk5vPJIBGhlWPsk)2?VUB>Y%+M!M{Xb zn81C6%nR(au6c2i$vt&LhWd^(k>oLiAYQd}09Y*W*wd-NcKi>;DXjeQ&u(s7^EynU zCf8u1?yc|z8z#g8wG#i_0RkNCx*l{#ekDdYL3uQvh01io-$?(58G0+Y27(twcrA@&1LjWu-Itw@c{l^ zeJTqjgBOCVdVA5E4x!PWYr7GskTv)s;(UI=kW1;9fjPmof1F`vTOfj%lmr-mci<)Z zBx((DH4vJihfK%6n`ASK1`JyNZVc1~M%xFa-RBANpSjO~S%TRQvOau7G-0H>Sg`+r zWp_WCQve)99WQx6rP9(ZW-QvjR4}rHCjisyU*zf>_%-H%kvpm9JE}DgZ~y?(GZugd zTtwF(1`>zoJWm8)T;M;J5CUMsL4-_V4&dx}zi0txkKMQzomcmUqvDnt@Lcqh45z?K zeu!03gAViPsw4s|H$qBZN5Slns2%K5>=25E0BZoSL{lgJhMaM~j`?3G`^GjtC+D)p zKgA&8V#iF}m0k*=0l;9-(XB9$C{`4K(L_iF5mNRYzx(*tf3I$QE&?oJq1aOCjICuB zpo=!Jc>s4Xm;0lqOfcR2lz&YBCI{1psM2f!)TWXFeGlSN;2;qzVE*NU^H7pJ#jX(K z+GBw?;2{9I6xuaL;QJAU7XX@AbY#@a7*Y`1-G8XBUn+?6Fd@K)ioelH1}uX7g^kDP z*Ybl3XBXvmfp&X#f!$i}LJi}VSw0*yX23pwyt&FY2w$qm0G4DKY|jv)gXVg7u@?`z zh&hKb1>T5Dp4t33SbI=m4cHaH5;_Vdzz`wwcIX|4o`B)J`qZC$+nCJpb?DAr;-Cx zvqO!4v=KDIGWxw;cJXw-x4QSTMn$h3;8O!7wU-W8T)>>}F<2*#F$_=$;NgI+bf$-R z$G&47zVqD!Vo>aDP&^aF;FoR#d95q#(KU2p_}sv7`a@C>E9NzxbQyS`cZA*Q-_Ar> z$phbO@Ec9s)Ob#aKO1fO$Hflf^hj;oh&+YMpXgz2=dv1(1s|2USU1Gm+ z^MwjpF?dI@>+m;Pu~RGlIt5X7^V{9&nPNqj$SPpWe-uOzgjQnvX~NjygmWJk3iZL> zMoKYxM7Ht-_IM4N6f^Ymf&U~6^;@}G5)z)*HgP2rtLMRBtx4GlaF|QQtQA+ej2rLV zxAJEPGM9i+Xp}R9(f`8h0r~>$Q-F1Xuxpl713VMHQ@5W>FJV@U$vME^au6Mg%zqFa zIEp7i>`IMi@8SOvJ^rthE!1(1qX?Q5BYPe%d?4{8h4&g2h<&IHUB43WClI?-?qoLk zc&|F9P77iQv>ETu@)*gs?L^4o?&9-a53V$w+zFV5ks*td$-V)jvFpOuPAr$R4Uh09(Ecrt499$J4mRRMFHHL!leQ+8m3`m`M` zwn-hIgP{)WDf(T>hZS{59OH6+A)2x2k>qg@kaJagi|XO>IjasTOES`|0YM%Z#V5do z0c=1lwZ0M1!MHbmD*DdRVK98W(nzkN_{0KWX=dLe9?aG(^$PnL>#99Cd|Rbyh>n2c zh81O_MoDL)Mg={@*SMF7s-o^`PYU#~dbqnAe8Y!fit)GvP7}mF&)&?y_Kfnv3^cg|0=TmKE7Q3G@C*R!7R0S*zsmI9a+ZpY!>xaR(N@0r z6Rhke7Q4;WTeMdPNul=f7=e`*8(zEtLeF2(fy}Rq-u)^Os*o%2ZV;2DIw1|p*01eK z5U3?H^jEHR^?n`Uh|qVe8yfU_mI{y#PWXPSA(ncrt?@M;eus>vvAB58E{M1?i~-V$ zccEnj@RCMa9D_uHfKP3v`Oq@UO^4gGb}54k7joz6PMieaki~FN{!}7V zrx3k0jx+qLQ9A&Mmd9&VO}4&%svN!p+C|$R>^OYbWn5$KKI84hyhPd?CiWt}e|Bt7 zBHBkLKS=aU8}Iom#$JRv8{FNPw@4obETWYfv%pNg6hp+n2!f&c=F0# z^OzXLX@FqLFxiRZync9~a5@tUoE!rrH68sT;~)S~Ji4L5+y}1HfZO)k#2QIF#f|NG z&0hlqKGHlvKW%4o>jbu5D>c6Cg6Ajp(wC$D1s1F{2EY_&SlYE&IQ!>?Z_CikR=zXf z>D_qa?a}{LG2RKf`OnZ*Xu^PqqTgHjxhxFrOda5+Z6}P~qT#$f3_fFUp7vKw4R{Mir)%&aAu8lw3i5lPt2VZ;Mwc8RbwAR0Cj8FJ`o$bzbq(3=_qfZi#jqD(x-eEF)zSFe>c=T+eKPv<^d zIVf|zhz&O-bYKlL9i~8Y4oZOYJb2-SdY6dkdXJOS3Ov)w+NDV70s0e;!XlIoEjV6S zjSq}D<7JwbRY3btM-1(EvN5INz?QQLn;%w0ICYDHpjjzu*u(b# zB@AWIn?E#f+V+AW%Vs=OO6%E5cJ)KoH#IOt+iR$4s@xFK36*8?h4a__{u5il7OP3bdao?p@wkNN_`pNmvAZdu)Wl)`a+Y}>sg0H+4=@W@>jSaao5NirjT6(a zodufL%0kc9be#`DE@5P$R-G1@Ef+w zz9Hkq{sy=sl3c})al91iKu1o)gv|p}ZAC*BRsKx725c|X2noEmo z2sAK<*H+x%u;h$iw20kBR%iySKjS?t*3TIJ_@Poiz%fG>`I)m+iCfI*nZ5frFlFpx z-b7ou1I*^nsN=fA;+Y_~WiqMrJ1uZ*4tRUc_{ZD2VblAxf&1b6{K!G_ zP4^aDaOfg?Pn{sQZ2~)76tm-XHV-C~AY;Q2t@$j0><1W^h^z?PfiHgrm@QywEyOZ= zjB>yNORTekc{UwpDEYXB+@{Cs&2VHa(jT$S{?tniLlzzayP?)mCU>?6)5}z0%^Gn{ z6&pE7xB+OpMTj;BgyS)h<@YvYKNN5rrJX1T#o=Apf?Z5#{rYSVBgJm*I{H#13@(dp zfAz-YPzzD%8Smgc0eo! z+IOmfsw0d+wMK7dqFve48Tnee&c~?#MA!gvIz=>KN6R-Q!FdBwK3Y8B^mX09L1+;% z0acqu!jw$lioZZV$r`WVTBp-R%rW@~+3HrQdBi(-Ol+Lms=lI4q=j5)?b>&M*z%ZV zTDVnFlyVaT@yxuWJel%QNZvdRZxt{*z&j*ifq?iF86dC(ZlyZ?g(;+y$p7> z5;vK7afgOGuo+bGSP@4~>YCr_lW8!(i9JQgBBtII>j(D%PC3S-M{7gY=Mq5Pch?(l zKzh4~a+C=~FBIwkvJLpSOe9&v4Dix?HvFsDKh4eMTx$qbSgQyZC0TY*egOv;b=C=t z>p;4+souy>3@2H)y<~xbR^%_Lu5aAP)ZnQggQsUoPkOWh1}{ap;f@b>d3#wK2}seg z0Q9@Y)c431LIY$BV+CA*+(6!ZBfHrR?=kF_sB--DohLXdOuZY((fMIw4J622<9H$d zs}9;Vo~i_G^w8La>L4pi>y#|)5y%7s@s2PUtr@hA{cax@z+v%P7+N%L^g)wl*eXqs zUs`-w9}uQAr6h2p7{LjWja$L~?(ty*qUM(+LW)#K=Io;bh-rk@+V=fdh<-1Os=uNC z5nEbhG4gmcwTXb1e9hKMS>ioE?gkhGSRwELoCJ>gz)}qe8*IeUSMa4Fk>Vhp4Q_P# zSm+Fql=lz=5vqZcu%j+uk-JyYU3;*#Mz5{7GPIAUz*+@JFoKI7*dLtA_KHyZt;qCC zpOnsKg#8x90IL8T*!}}Vv%($(!4nNfYDj%$f?NO?$M5-l20-(O)N~^0z99gM0*F`! zFbWa#-~gxf5|YX}N-_{}d@3m|kD^FVF*yGO9=yj?3MBdi=ZM{T*%$f_q>^q(`-Oa# z)&Mh%Bn7Nokl2e1y^LG9<(NzfGw|wm&yDwJ2Np_ROYYce9}%47`2GOR4*1x+AOy-9 zU;PjWq#p#P>Y%?n9ha`FTRA3Oy;ks%dS3_j(rYdpcT`$vKsI0$s;;rMtU;MJ8S5@P z#i3jJ=2;e`pdu`z0rpX@WpWl?!er>7W0J}$BoSQv**@?=nl~&TLYL4(M=fUoU!hFE zXe~->a03nk5$7p8NRIIR*1~~ELxkAHy&p)1>GZbW)s8I-Nn<_0pbBaK5GA`TGfAe!?rElkj?f9n0E< z3)ndU+)ucXw*L=#g4g((3XNOnsMjD6CVH5PEGizt_xp$xz~4Z>RZBc)R z-HN{{TVjLT;GB9mRD>+$(NYgEn7<<;B1}3CbH44Gn+p6DP|dUTBx|Bh)TvuMq9xQD zM^j}&?);OTi|Df_y(A~&DQm+ru||r-=pDQs72<8ADS9Ee{6)>cl|EutZ*6i*0&yhI z1Gl+sqD)2`Gu^5@srC%m{DtGkw>4vbu3~kVsQg}f+UpmERPqdar&+I1z@_B_lv-u*H@)ZNtcV+cB>9Q`bdyQ)q)uy!y_lA@D zJ^9!E;wn}-Vw`ghV|AssM|2f}bGk61Ra2s3g!g#ux8w2DvkgxVU+$?cR z=plgq#7J&KV|8o%brb;umx)H*>4!Gm8rO?0&e%Cm62^oMv_YP)7t!40E(JPjCm!n! zVJd_PAjj+aZ#m_-FXz(e;XOtZI!f>JPEkm+J75_mYD<-+P z`h_u&_z(ufnpB1q;AkL*C_qkY7nt%6pdMPg0KaF3>hQS5WmsZ1b+72@vc_vvTf)|r zT@^mmgc544S&3)85WW~pote1o9E*15EHjnkWxzLZqrj`W6Q1zwrR(;w8rPTPLV{8A z$4~XPkP{Zn`CBKQbP|)r`?M(i(N?w(#X09vFMA|)pW=IE<>z#g2FiGCkx7YG3HTDM zoLe3O4EoiLmOM`9Vo26AM&_3a?&=q%qKa8ttZvUBSTSj>AGa*csGP~50Bq5*0}_8D zdwEOaSr@aRj||XH*;rH}d04EvYVksY8Jlc4O&S_wtfZDPS_2J1bH@s8a#a@GR$L|G zy6KwDB}_BFqCd2NGt&@4qI%c6F@ZfbDWYH70+(V02z?-#7+QC6g|(kPi6+2W0$gbUgriB|Pu&LAYf7OsdBz z^KzdoMgS-`M!*RazA5uUvyM#Ecz zR)^;>QrF=$xBod8ME8--a4@#l=>DrCKRxb+%*?db(cM#{#LMu$WV&)-9^Vg)W>&Z*UY;(r}%E`1NSC+cO|lKp>R_ZTb|cmDGQa z7tz!HD+nw;&-Q0u;gmD?_?c^H&*cDhc3@kBCWyXqqe3E(QDiJU-t9q1 z^BjY#be3Z7xq6)E)6RHd~aZm+|9l`QpuNdQy&B7bl0u`#_ z**0(%j4tFiB&!N!%~MfV&l}%+1UY`g&6rPS!ZBR`5VMT<`DgXx3p{T@Xd?Nk7F{P( zQNMAmQv*4cLJ;x}1*)deOX`>2oz)YM*tYlM-g8Mp1wYd4>!u0F9N~!wfo=nf_oE?7 z1)(HMFPl@Pn_GZ%JOTf5I{oUea2RkXiuedbN^h}gQi1USC4zXsfxuy`OtpRhBxLwa zHxglVZ({8hLI~?H+s8~;m?jn!>C%BId-;hH&$a1O`i8F~L<6_kH4ckQVg++IFRzJA zGT-9Fj_yp8c*I_e@h-XqMi-K87|RP0@gS?V5)Y+4@|9bg0ItCJFx7cra2}>WL(&hp zCr5lf?*zJK22js2>VR1UYNU4Rc0kspvqz^F9r+1RZwhJGSLhr>FDGP7Q z3Y5{AeHQe-n{u*b2>cis|01II7A1lc%i%&_pv{t$y4G~rBO6VZb<5`d1lUl(*UO;^ zj5GTwja$krPPiRiLoqdZFF-WBL>!`@(|hzNJ{;hlFE*(-Fou=ig}kG6)m=Oo`f^wP zorTbP`g+uvxTI1e1buSiS-P9t;~e9raOQF+qu!rv9SmF$4U++UL{d#Keg+_w($ZyA;UBd(oC5I*T zmq(+G$D0SyVQgSRd#1maOBPQjRVm%UyB^H*!E7Q5RSdTEFhe45=Y_}+ZV>d3jy^wm zpR-VzvCOx=G^tXAxC~zDD4v!i;P?lSyJ5dufQ$iADZy&{*5AX013}< zBCN!r@U~B9LHjkGcU-$wuTKUZ~_ANpW~fkQFlxgqJl*fTy>t+%1Z2~2?(3MVah5}ASJwgc zL!h-ppsTIghf__a3zF#v8iyQYk1kVmz%@Yi+8w@=6=c<|6oa#}u3CBpS3((Nh-*-US6aM|A_o#`5Y45fT~_^n0h`7ZX{9AgO)v``uOKpfQPFG_ZrUr+d) zOSaXBz3cC_)A^{M93HPtiT3Fe4X1}f=-ib+@96O38#9+ku8~1qZaVP_o!mo!Js9_E z-v)*=N&;ybJV8i^oqlDR#%*)V{3(~)TCf(H%YpG`Vi2Z`Z?tyV6us0aKtV(+9strMs zLZP~-nmHK;gqpai{tE#LGYBomjqU3PJG<-k?ng*Dl7z;H;&E~#%Q!400I6iQ0l8Qn z4@jjSfGZDXCpZNE4;cIjuHS9{ei^N5e=S@ErSQQ(^lSdvE@L#Z@}vn7{CPg(cP??J zj3AxT`q%(i)#w%eGCln;XN=`Mmx-$W9AptyJ15VHx02_6XZCdpbx>%@!XMGjusJ9D zha#BIBuKPa8b&E5Ff@!fKAwq7MH?;|V_+L=`#}r{knQWhu4UUzem1X*BmEc6a&g_r03M4>csN#i0mHyz zqH}>z{*B*wBP6>BbeRKch!2sr16*qq!MSH5jR8RkVsjoWWrG;_BWF^l-`S5)H59Ql zn_yYabRG00C(U`U!>dN$+|7k_iq4e$jaC(*RyS55`J+|SKOyWIqGc!rdu=Tn%r9ei zZ>V=f80=6cuv831uYn?0Xkc-0+U6 z_Mc82zug?0TQ6loS)Eoa&8hPn4?>sj4bgp$S(sB6s~MkBo?7k;^b`i(I{IHp9`%n$ z>~d%Z-E|Tdy$g=pnEacqitQ))Q%cy&prAr}QDt4@r;2(&(BMAAoMccHDj(?lF;s`o ztdVCVOCcKdVdk>OUAJ4@Qzr193sHa`;5PrEHmbJGp6A z5GSfp=SiQ6pgQ_p=*62O9#6kyAQlx>ogMp0Dq5azQGNsDEWs^3;8wV07MB`7xNn3T z^CBcN6UX+q2Epg&>@2#yeBU~#+(Zp3d2S{6b$gy|v4g+`aoc6np!o}gI7v?SZBMf+X!(`S|>m|2iWkoA3)cUDC-1K`N4ep zN`p7w=Mm@077v&a9-HJd!`zCnj|okbZ>ZYcBdBZZq^2UoXmDY_+g50XYXJ@sTWaxo z70hy=(UMxAx9=NU=Q9zraTM?L;maOAx1k1#lrNrbh3=e)&dPT3Ge??8evxdgn@H_+ z&Vnt2s{@@N)mRyobSu*^PBVoLUs~o1Eh)|q?#lhm)PapHM=rI;h)-nKKWr80W91yh z#kWtz^F9=Ok`4O0`2~T%eLCmt`395p8zTO7k}jYX4N<9oUU1~7N~<}>4obt02Ia+T zG#N#8k(Y}eC0h!~a!bENDpa$2GH2g!Twi(Vf7-3~4WZGM{cD&&;bbPmsK9s4+^;Uk^KS#+0qjmV6kG0*y(%vEM>#Gres10;Rv%nK&|=vN-EcZ5wjq0!cd zmGIs-UGL5h8}CyvBC%`}U4^VjHQuX9!|WWG9J;v0n!B<45L^u5ga?(OQ(ft01X_rr zl`Djj;H>QyUpa4l-NRd!VUCLQGNvPCAYmd^_~O$2?|w~8E3PI6a8ocP79i+IGtzE` z;2hrK-_0PZvAdjF1p9MZWi4qW=T=Lbva^ zBjKxQW%xNv)%b{vK~f^8RkZX-CrUZi3aqlxaj2ab%@mMmC+2z<1&qSkmu=Er-dKi( zLG6a;Sd(t3r6xfQdvo{&=Ow>eftugc8JD%QJcb}{CUK)!VvW1^A>2nadW5e^8q6lwQU4eqRAGjxj zB-WG-MS$UlT8kiloL(B;b0w+|2G)u^uM{|~`Sj~(Dm?X`Ril~X$ha=o2Rwm{KE3)n z(?KnajyqB=)5Z+-`-@EOK@di|I1K`4BXYe51kfq!f>ZB9_M%xKeE{ zC*HW{M=6JjG@qfy+P`x)OjN$&+J9D?C-wXm+(zmpp1@~$V03ouOMf7!m--q_JzlFD zG;O+E}9W$=7npdMet^ULJ4=SjHqPF)^TJfhdj;ecPdEl0a2hIU1APWzv(nI9R z50abLR8r{NDW0POnYL+a_S_w*HO6_AYKgG>rJ_->SM3b$GfCdaa>26tV+-6us~gE> zrLy7n6=BQYQrR)I(!!UUuX@#9%C>TwCDYp4y>n){KSm{aMHaL2)+%|5*@QCGx7=Vf zERbfRi4)04I#rwO%R{XmWdgWM+^bFlovT{b-!%TNdM1|+ZS2!&S@NqXBL!TOk90G7 zeQta&P19IV=USrQ$Q4G`B`H_Us35G2%$$-MV2K{R_lRCDEsp~?cz_EtfW|2dEwevr zsCdBof~H(VU?MACbH-TdCo^F6{MIZ~Y!sQ*eb%%!{b+vy9(#bWGXI0|7pNl#s-|t& zP$&^t=zweljL&P#o`aGR2jK#YTfLSbX+hH0&Dhpkon+Csrd}i&Kd&*bdv>MS2##l{ z=n@b#Z@X0p*Xs8pO5uh>2@($Tz?H=Yxut{3+A#vwcbrP^><=X0SBL94KRA=@J`kd6vZu2D>21+mDjr#> z&^#xx8_a$5pWbIk+_aWy^EJdxT7!yCls#_R3)Mt)Bs0)On)RzD&%rvLw!VTn19Wga zCjD;duffnKwsCK`0h5clYuxRJ96Jv#Le{R6zylfc?&aXu9sK&TUL9p|{k=Tu(w-81VqzE#+Rc%*-OM2FNF3Iy=E35@(G)`D)b@L4~1rd55Wm zcs9v5;gb|YdImD`u;Orjd*-{}epg4IuX~zhDX4W@Rg9b$YY~m6$eE#or(T)kD|dVg z)JEU)@A7T~QBU1?fOcuO-|Z>r8qYo?ZX89oMeu4}yt+B-LfZ1pzQVRdiMD2(wtF%X znkgQ(|3afbY2shQzPIf`>>7&c^Sfzy$P+r7SSY?p?DS9_?wG`=d*b`L`yGyQbzAZIzm#=@#AYPJ9nVn%p>4qRu4@j6riDjzIX! za3WM@ohSSEi4~Esrj3_!-wGw}J3Bjil9a5B`#aFT+juRB7MsXy|3n>@y*{9?sh*RK z2}MHlP(gl1F>3PgMTzT@Z1SBKbgOYUEtDzYZObcy>7N{;e4E^qjO!v(_OoeQ2f@RUE+L|#xBdv&W_J6wP|t&TMSBC5|9i6wPe zaL~@@*KiaNQ#!3*V1$_`oDt^)ce$1OA48%sUWq~_mzeC8rm zx7_dx?kj%p#)+2aSmqH|w<9@8;YA4gX~vRP3(vkAY8uEst@I-%8{{ z_(fF~pK2sxsv{D?b;AP_@PihRW?n|17~4QN=smmuC4{~W&*DwaQ8!bzk`H|^V?TB~ zH?tLiGK)5rBG7>hlmfDlK_Rn;mA_ZmGZb26X(JQ94x3v05Sq*it+>4Tz8OiLXn5pj z_n92QnD=cH-&3lg>KE0YK|#`vLy@GMP_H|$()srk`GO@6@-J2K*_I*@+fb(J<}+^Q zNoJL=-eFZ+cnYgbyK`JVzgkg5JBxbtQ|s$XyDii0Or$xXrPReKHSyre^Fu*f(sF?f z&inj~zg-xqwoRkY$#(E@8?NOTZ6VnTAXp7C(#Dz% zcc)M69HOFlddlL9glpc?^JUB0WRKGcJ$yj2$7P9E-)(~u*)(CEH<&`1($<8J6%p@hs9l&xEOB5_FM*{DHW%!RGpy;q`Ol*CASvgB}3bO_Nh zVYid^jO0SN@?OKcR0jQ_{wI%u(CB0|=dt7Asv(={KTd{Ntg=z~f(kcEzl|n+gQhWN zp6i~sdu`c$zO%`b`4aV$#x6SToIwpTBIROenUC>F$4jR`DbAFg3*W}!PUC@2eA(EYt8&fzvTEQ5QG;SKI1z14uwbk5oGXBRUjOXE6Lfy3ZD{{1jR3jC zJ++<;?xWs;$R(yQ3q}|fAvLx}b0N;uaQS^2FT^p+b;F{pmz_V(`ra3ZBP`)8TYTC@ z{>Z-;J!SxkF>31M9{BSN2iIi~(EE+RDQg#6eW>;F-gW;}dtx#Z#(Eq?+aL|=ebs+H zgzqWeK`UBH`&$%m9MrSXYxd1oh(;@ISu7IG^z>EgkCQ;!v?MaU0EJweZIQ%55vFA> z|8ZZ3B1Z3^_oJyEHn{S5!SfZj8OhL;&@bv%Jz$aAudmMDVl?;g2Vx%Lx3d@+7syJ& z&DDI}&7-E7%!y#l^(9cpL>HtwdmaAfRk%Hz(nHD4$XP_haV#kUe3H0i;|h2PmFk@*Xv^!S5Glc_z6h(WVoiQT&0N~bYmrL|Fi zSw16lc%uF~+ThstUeDzrz+zKdG1(dQeQ%jLOKX_(#zNXk!)ZyjOA|>;4+2+@7bb?V zt#>}q!y*^eo=eeeTF;ghjx&QbR5IO8!JA`C23?Ovp7tevbys5ts&2x$vg?Iq;Bi)H zTk(Ccm&uBZli`6eZpiRcGlv4Xis<`DaR4I_4#|cC(dQVfHfVY?ym&BE zaGwPdIzRG8P}7Ye8N105BY5^yVjxbfhM&b-vK#k3zCog}SsY2;JQWY6ZF`&@^POx8 zxR;T?y|Pn45Uf%%BXY^D$pNQU*%$|ac9gWrA-cyo<_l362DuDGJbYDLCfK1BsN(md zx7usPwh2|7_A@U&tO|zipjB{!Sl;0mmB&0VbiU(O7RRZ*{Aiw3j{<=8H_l7C@ri7i zTP@$w3e1*n9tP-cmE3u^$W;>{#q0chC@Z2d+(s4*@+ka32FDucujHpclF?L{>0YNq zugZq^z*RhF={fz=k=8Cr*uWq`^z2Zi^jnc-Gxn7DsrKb zTETI_ym%hOFe-u6{`ZNcGm${~L#Uu*fL*-acsRUUuvuaOefv`C3w!QV40B|gkVHDre` z-^VaP`jflfX#4E{@jOoHcb$fi+`Bt$hEE-c3p+nySSEQ75@4P(*lZ5GYu23!K-}#& zJ{bkMYcH>HsF{Ona$o}H;HMD>JuRP#53*9-h(mmezn8<}i@)|x@O1J0vKAVWYk7uW zruNv)DkLizwF)RNamg)#U6Z8uv_2Tok7TsQSAKK7(g$k1Wk7&C%gN-y>D&Gjn&R$sV{qU?Bl|(=G zYe9?LT|v$P>{4)31~__OPE=%QHbL+v&y=&)LNqM6+~?PtH#+`A-%7}R%SZVGJ4mc@ z2}p8!5q^=>(afJ|J2gx6YS9Hy>6~t+AbNK1z%{KXt3DpM zxf(%V{p@|#T*YCiw>DdF^_xE(b3k2$>%4PNw~zhOZGO^y9XreB23xhq>P7grIA6)) z@5%QQwz|Nt9wIf>ykcoV!u+M+-|Xl5QKxfilhW&uJ&fK(9W~Ne>4u zMQ6L=Y4b54zK$X_>$W3Zu4}4jf}RcMz{Uh+l^A2U@Vc{XvBs!tsIztj7l^rI-%S1P7x_js>HpiQy0(Pe6X4^P2L1eUQJ3?Y-{P{B$P1P7E%=xx9^l!rBM^BI=) zCAqYdIa!n7FGcb}mmlxq?OGEIyF?`RA~@>Gll>fD)(+c+!)TbWlEe3*Q(&rz)OhBO z8eCB&1|2p5=a*|1L%)gZhj!$Ul>RbUhMihl8}{frDf4!;){{Vopx0zRMFHSg4fl zR6QL0uy?Y1`b}Lj%fU%m{pISC0ppbwnTO@ig92n)BwD%f{*R%Eh?EqymFuk`zrpqN+kN~*G?KH|5;R@XRukiET7)vrkXtDJv+R{`*higKMbghB zL*2iXzEop|=|xQUl?|!qS-Uuiik9OO+>R!q!>@jtI0=vI8TniSTO`Fs27_-oY-g*T zg?>1N2Xs0C{j%UrCy&0n=S!7*9(|8@rMydwsp3$Aqxu6Kd9bdOwNK-dsPn?3_QwOR z#e0Md(v?q#4$nTGS=%%-z{&8Qq;N2lU2+k;>Ha2u6D<2te3CRVQ_$C{>3HkF?s@jR zFZ!s1x8h=7b9`dHpzBE>HnWeJbGwdnH1&^1qoR1XKiZ!z1g#d^nS84^!`w=;Rewrm zkThRMpS;lgW==<3U3%|zZm3!jU|eZo*ydk6ITaX%^EsaWlDJpn;(23Ntnhl~?_a4x zbS{wzHZzW7ErSHwW{=+|u08_j{dYg(uDMoWsA@MbQSY#1oi1pDvCe=gTw*)AIkR#Z zy)vgA+MUI=H}N@~z=K_PR79T@b%ZJAT4r5Yl@bbumL=0_G^l&r?m{m8u~nHS(tQaX zU&(L|(KVjA;=Jra7PEcGJJH+jcu)5BH+fPbD;xAD4O!pDChWdX^*^

7AjX`Z=6x zZ{E!{s4{$*E(@(ssN1&SmZxu^*gSOb6Mj4Fv7)(5yyDr)3B~a7AWu3%%$UHE6W&oY zjIqHrcSA7K={~SNR7ZoSp><%69jHG8kLZ7BvBz4X6a-f&``sd(^lCR{CMl`PxC7J( zK4udOj6~H>7w1sf`o_Tu;%^Hc<^kpPPrp*XyG&Y0)PyD}G`_&+J4@ef+Z8}_zOGXD za&4aHE-D(DNoivlGl%7Zr?E*?$qgGGIi5;1{woRk8`uz z)HKgrmz^J=K77G7s{c7#(0lZ2^aQKzOm{}ANMgc77O80B2I-AF&pT{1(TOrMpMA%w z$XOr0rI9zy{k0%%*2hb1ogIe+KW{lZT)jN~-%qKO>uALwuiKzB(v3>H-+R}_)HbQI zV;TOE4BT`fvN^oi;iXNBn{&hC8{8K<3JouyF)x`NN?LzeYNH?cw$syGWaq}d{5@?W z5}`6($$n~SkkQZ6%VLAW#LBX{y@x*ZRq5 z)WVy(1aZBta0^28m`w+~9sGWe#26fmYLYTT|F($G#)(7MP=GiQ*YgnZ)_5db_FX%Z?xGjh&Dg8)Cb{(kiVh4bxVz>`Er zhD12^zMovCy-fO3cgs%J_1iCIeH4OfHZSlN=dYTAN+mmII0IQ|Lx<{>w(^T;Gp#gx zqkrF`4C|}0cRDu<^ynh~AaglGZpFk#^Ka96uO?iu5Z_n1W7$sn?)fv#tsQJ@-wkYN z-y8d?&fMS8w7d0Vpy8^`ET%rGTKCGd@@*Hb%_EsT*C~nZF*%)@LLVi%(uy`v(H(W4fJP@raI}Lya#O%LNeTZ5dG8o+US^Qh{Um8ekf6< z@_&p`fB`2iJ$$n>@o*!dN_Pqm`Nj=Dcc$oW^W@oJXK5E$tyG1Uzn!XM&vQL76m^!i zy-i%Vh`z5~8AY(w7={jFPC&FlFm+H?e9N=kJ)-WpMQkYDOJBB0e~HDYX6%ssxE4=j zLe$#VZI`8<2gO^JBB{tyH<#&pl_=Lb@>qMEzUZFhrQ|fMEU3e=>r6l~zMC!+bu+ig z2qPa6KzxMo(qdhCz&kGLVuCOCZOt@UPrt}L&ljohrd5|iXEiY6gW1o<|p<+mEL|u#0G9Wx&wv zyr(dKf%bmc;gxgn!2^%v>)0zkMgOoy3%4t;-sf0)_Qv^MGV`Q#30-q`yG;Ck)M3WS zh_r=pN(%+Wv8CvVGKAqCoSU+vC!t?1#JEpV+;-cVEy7j^{iIBHhvUN{xbnBs>9@@b zpffk$*}lmSJCZVdsx?)f=rG<)wCb(I!A%XuMMppK+Pt<4zyu*D)mU8MT3mmkF!?72n4rZkq7w^P7MuOAlr1!9D(^p$&je;O6 zYaB@ZR$cyn4{KMkXZoE1 zZtsRUqaue@GXwMf5d7WA+e>K!n%_mt#sfpY5EGTtXp<++mdz*Mn$&GgVu#((jm)F9 zo|XwK{rE;Ug;E>a}KPA%R!!&Kh6ok=+Z1q2k|b)ci9)m|zH%M84ef zxS4-9Nc*uzf1qqOK7}BEU8)es)?jcZdHaiD2&Ka8{G``xFdOzW@>iI)>{)jacndBk@;4sO{U#>Tc7|NEw>eT+$P-D+5Kvmo2(8}XS_Q)5t$FxO+{W4mtvTy_3m$Wht5v%u zzQ{QcSIolPvu$u>x#oV!zf}C~=Z-7QGa|Ctxhl@}q{};(VBX?o$_Rj`*!qhTdMy(p z-LsIuPx{)w=Ms*KLu)-Nnnd=`DigcCjkY?rvZ9rRe7OXYeZlq@zmNz@K6BKB)Kvmx zywgcX|7z zzfs_+Xm?Ul>AJsTR73HNy_sfLet><=&FbjmOv7x8og37VP;Ws@p zrei?$ut=p7u%7Q?r2K{M*f~zpk@+(aLQ(esRuss$1?7^tc2mUqTGW$4nnqWi1J8Ma zfEsm!SMj}~(U0@^%H5Vr&n~%-!j~t<9b@7Ouc8bW8Bg2%&s93?gcgCA5vDX3XZ^NY z9Hq-cXaWicSs+l-G=^TO`&&>hB##qpqcEru2%?oDId#a!8+=-RU@v6lOUL8vR=v?- z&|Q6-C=m)h)tPtsr8Xj(Lb$a6QqzM1Uk!e9^;p8VA(*aGT$5oa%D3n7Q*~EE3%Ebi z>F{^2e&|Hcl&rIg`yo#N-wogzvWwr;W%n_&T3^05v@mYvTjW)bI~u_Ru0J^xqS>dO zBaQ;}$5|{Rp8zI?SxT4v(SKK+)+y!uUnvdq4LtJ$DM(3c8ow%NxA zv_+RG;(9I0mmkl$Y0`~#YG6kyZCQwpW62FRta||pozVQ3j<{_m5vIdsjGuX1LuiBR z9H5TGe+#n-ihM3R0dL|X8GsuAJQa`v-37(p$+1n)FLw?u$IEfE7t(EcRvY4kZXqHTY+W7f8~h);X3{|+j7CwRhg^a}wvA_#<4IIy zgFx=?$x4mhj1@f~(l^ZQUcf&{q7qUWx1vrAV3A`QH;N~pebyu`{T*Xubc9igN~B1VIA36lqEZ zN~x_K|4%am$h-oWWWx-M1o61yyy345p`g-|*r7*|fvPN?Fvn6V1Vk{;EDs_NWltKX z1?O5hy$-iyNn^tTuEO%s!C6X}6mnaR++e(<5pz0|98R-gAF#(V$uVwvzv*ybNtqLd zfMd+S>t_yAFgC1L+zE7xOlXR~?!p~NL}c!8;z;H z$s!92D)H*E$<5(;(fyde=Qp5omI&mn`_&_T{uoq5%ajH;^*m3>l&lPNmpaawld7UG zmAnq0#wZ_(W7Eu)gC;XgN(+^>!O#6@R+~5UvQ4iO*6mOc*@gnYP{5wV=_8tL{X0f8 z<9L&we~M?%20Ip1=xM9dXQ zg8DC1+Enrln8#B@0Pbaj?1;$g!OM!D?rjzg2piLg^i--ipX>(LIq-xtAm@!7oDnJ* z<$Sb2Nh2c7xO>)jpU+*<`BZ~(f{#f_I0Ix|2>Bfx8kzn!Hi2tW+DBfWe*W@dkz?_x zeNV4z^mK=113}QIBI`7VN9*1!EQrL66fcdqxss!Pqr<7# zy40wJAD6Nu*AH)_WzG`X1FQo=|DZPx{&#UAvma&hx*uhb`GEs9v!5vnGS5!>*}edC8BjQ!i36s+Fo9{zN>avCHAhay+mJk4AG-J z?!;ZRRI)!U44Jf4b-BI4{_zI^c{%2?OG`fZ*ibo&M;GUwnRbK?`~dk5fH>&z+AORK zbb%FBB?DMDe)YKjr94VX)x%KDmyysjV4uTzE_y=?&bQSsg$BFH<+>rl|1lKrcSRyR zdXJ%n3D59Qe@ga?q=7TPhPp9PTOTcziW~2*`U$jOnXM_mIV3?1+KmzYXzmroRHn4# zmh3Q(Uq!J$nLY-!UG7add6ZfDzf=~WBbrtJ;&v^50H6UgT%C^^+KrHEC3rQjy%PK8 zT-c!#iYQ;FBf!p7;OmIK8ef|+joif19qh;D&2VO21t zNRmuD-q3ChW-cbBlMJ8aUi$}@f1S!>#rQ=U&=gt-D;XM50uV@UlEy@9HyYtJFF{X^ zvt58Csv~0_C$iV+EbBqCQ`hqWn|4L2aw8uoaRTpMG?SO5WP_Hvu=D#L9=c~p1Hj1u zya3|6#k+o>7));i=C%*X2)mHCHe{L`Ssk9JxpYxDF+my0$p&nF0ZhWp&|h;_oVbYD zbl~33!hjSLSi4*iZO3eEBA0EXk_dB=i{N`u(vI`j4O?~I-1608bi3=Or?21O3g7ev z{Yua!znBRObG8-Rku}s!XXu(M62Q=|Y!9d0DQ+XK0>HBkjGDvBWp6tck0rVd@7@)J z51iwHDsKt;AIZBk_PpGfBb%`Zh$H9Z4p++w0mEv5A%sKaA7_0#X8u2C&*;d6Ps=1A zQll!{H}VCITS`%tNSX;rp2;vC+J>1_ey5Ym%V4NqBaTa=t2ZNX-c|s!;G7^EzPMQ; z9bLw4Rb!6$cJU4M_c9W-ta!Vkyk+u52qmb%zGt?^_9-O<<)gbUG*82j6`aoG7(-R> zS-$OlD>FYbw(94OF|xG6bbqreku!Z~_zAxUZAiMU6^ z)l92|scaRY+MTv^fmeoX1w9MHf>kPS)caWHm#R6WU-SOr;d{#p4nh{SBDtIj_fXti z|9#I_AAp1Zv%LJL#`>2y1YwPE$0}q3#QO#I&yNe;<#UPu;-kTxh00J}VnHV(QAJX( z{PxariQP@O0iiPeTTwM^e|k;L)^C<+FG#LkvJ7$HoAJol=8@K&DfL$-;m%cX2n=HZ zH#Kf&^xSK#mM9V_#=`RTPy7)CZhX&OM7wQPne$93WKMSs&EoYaqJvJ2w9L8Q5ZfH! zG}~NP|N5H^LNy_09;xQ0s5*dC)2kxMYN}mPOz?4npWZCPK4iq~fJU?wRZ*w_*fzt$ zJg_c!jToLqI=lk97PYfKGL6@o>6`IAlH_i;awQTs#8H(i8tH$#4@6HwkzkYu08Pd3 zCC3Zh*wqN9;OlW8Ro*mmW8s^Pz!&%FYEO3K`my#{gE6ULiAnt9{A2K(8SMAzVHy;s z%f%A~b;XZ|vxI}if66|94$}cONzy~^eTxdtLtp@l>#0y+LE$S0(Hi%tvlPq`vSDp6 zt+ZLf{*h79kr7YZIwqlrWxB`)6^y#OV$pBY(ydI0tW*W$+Yn`terLvx-_>NT2d|?` zJ^qZJ3!yb}`M^-;XbLA|f!jLHU_e-3@SbW0=)SC@#Xm0L_EH$(ld(=2E zt5Ek3i~`m$4&tYa{{j8~1|Cmy@_!C^@=sZdp4a6vbo>0k)?-+9ew`-qD-3ze0hpqG zS$qzyJ)&j(xr5b}o)up`y@u`Y&H$x@_#Cg ze~r&ypaWlB54L}fWdWt??JZ;|SJ%E`I+C=~lr?R&%+XRzwUd)XXyJ868b7oU!KK4o z=A8-3v_H5m;1R$D0n047j4xGMSz6{t#L`L{V#suEziZIzA_aVL{uN-6^q{fAJ&J5|LG2e7l^5~T=u5lZBDD^MAJo!fs@8<({Et-pHyFYU zmEuPS4}8TKNCS}UJM0{BIG$t!@EVZ{V|Cm>8r}C?RG_F2tJjR`a3m;3mDvMULM>0%OUxpc|;uqiRznY52GGKL(?Q zi~dn!Gn$Kf$2h=E7J#oA=~5;LS-Zi_R-T)23P*3X94Z+GwMl7Gk<}za5=57)HJdSN zE%bU}Cq9QD@8Qz1kKngU!4yNUMrdK1N*MPvvJ$1u3*|@yu(B}Zpz_+emd==0mtyda z;CR1OgB1SYTHfc9Zg7u5Gl5tKV1W=H3I>rh(ohGu8XTJ06+vlM!eg{ z;!9^g*ET+JoeJ1w+Tt{H;0Lx`v!<9vjD}Qn5F~=A=@ALK zg+$Z90|NE{ofa5)%63rae|Z7$4O*N|R8tjGGO$D9ytx7tJq^2309q6p|Qs0N5!)#{w;VwJwF7Q~l`KuECy z9u9R5A_BXa!Ud<)s}>zXJ&`-4V3}c6LB@=D(D!IvqOC>v=&P+T_G;`HHCy`L2xb)WJ|J1a9sqSLVQm**qKwGB~l=9u~3-{2#mMIO}i`MrgZ|h zt(YO<-KU@sD2gQK^XgZ)~Vp}R@Xg1e5pNj1DF%>U+*3mE1!SkUbMeK zM8vODyI`txI+`*Nyr)bV^9+1mCDhih&BSQq{8-#fzIG?!mxW2!)1<(qXE+9JK%ayD z+s?o6$BUaSO7P)BWV#teFJhA;kPwr!_}`GxKY&vX<2@+vM+*p`YM1G#JMlRCMn)IA z(w&B&j+muXNFoo4=#C90P}6<^d<3iSRuK&Vv!^E~-k{)C4G+-RZHiQDU1HIq9!z#; z9r->iBv>y3d*bK-4Kc(qzI;WJlKnwV7K>QTodstAdWcGMo- zd}kE`WqLK4Z;~|GeIqs7!>+?Fsl}{NnGhSlXX!7=Xm1p-tU8DkLFi68o&0JPo_#Ao z?0udYHcur-C5IoHnGdQpLv}b~&5H$EG)n3}N{Z)=>~0QC=%T1 zDvkbtKb7yOv8ycOaJ&5hz2PdDeNer$h+av> zAXifwJYt%C3L9loeJv&G>Rx@yC<{!LAe&D%(})O+EAn!hDyjFl_<*M@YoWZ+QYL(Z z{Re+CQP}QzfilL=Nt+lVk_)5ui=g+jr>)Sj)HHo|188k*Ep$6?7@l^8;NhY{d}NdM zuG>IjL+3N$I0C&D_(q0m@uhiumBOme!c70^^F>6=J>W>Nhq3l%5LpN{O&j%Me2@hX zxrHS3N1+VNSI$1g${RLHK#b(smD|jHP&%)@NTqJvA4B8!xFm^H#UW2^Bl{S-eKe_s z4@7$o7XXm6cjx#HznM;TVN4j4lSF$d3vD^5K)x{BmVb2h_`87#j zVp&QrO0?-B0PECSKnFIuIIsx6?C5vC8RXqw`#OpHL442B_gJdqUB4?-Nm3SR#L6nv zJi}Uhmd2a{lAwj;RZfA?j}@_WT<9W$ zH~kpTW-tLwqs|=D9M_CX14L|tE;Vv*7z&&WaOMZ~@dw3YeSn8M{v@;(*VXg%8akRE z`>FxGTvF5R2-EM9YxzScv(&AZdg=7oEHVlOQBB8v{Z#)K&|m2eH!s{y;X>*H2*v6C zOO&4v64z7I7FuS1iUA#;>ZU$qSJkWE`O(1$TSN|PZ38)Wl~?zLQ6sdFz%#U2Rg_e| zFv*H6Lj>+nqGo^XNVvp~AGCCX!jA77e)Yc7vKJ@EHQQSOr+tw)IFFQ1fGXHgBrTEq zaQf?HiWRuSDCZs45^HTt&i?DGB%n6vhmZ+XE$#%mG^Dw%k(G)8yeh@2Z;+CcOT?zZ zj?6ZglDlp&M4+uLk|nWd$fRK0ziria?bN6A8J8SX+Q_Kb9Kc)W2OMZNAb9S$PiGXk z^_Ei0Sm+DoO&Vk(rBbEB=2C#m0W zg@B0mxwz-OVx?UP4g_+hV!hSAj56ZgoXV9Q>u+^EATK?rIBlOWDtIz5qN^Ej^H95b ze&eV%adYtBf=By05cU;p*nNDK$i|#Vxr0|h4OoF$A7dWC*>%4!({dgzV$TD7IKxgMz zF$XE3ehup#5mG}8x=J~`w9f^_kKX1Ifb-^%Ik?^M2kpbXg_f+i2O-4!HF50B zhj~SdlCO}@mNOGK0~ZMZDbC~q$!tr@Qw&p|#{~5oe+gIp?svc5mfOc!H_MhEsr`rV zI#GqTh9HZO+>;8M>$ES2*v!gr6vND-ZxxAltp#elP)=WTeriOUq_$P=8Q*pxdH?H; z#+jg(Xiw>@(`FJW-fnjL)Fi7(;nxQD1y)9L`o-u);x33S>b*;LlV$F}KIRU-@p zpVmaOjY}LbmL3opy=-xX(;KW>b4&tvB*NdVCIyBK^)en0hU1ZiVU?j$fLi8PfV5@q z?%nS$CwGPa*I_?Q*Pc(H?jl@t=MsSoo)vMDvgK262BmPGE(L~+yRjEX;2pGtmY<;x zp)j+?M?I_QMQe`GEU&htAgo|c&@f-W&6@4Gy$QQ2+qO4S6|WOO-0)DiTcCcg;0=%c|AtEYTj$ul6EC@;1q^x`KR+J>36WO42qmZqW^X~73!4`7WWW@T=8wv=M zpAl&Ap$LP9GIQn|CW3I3?X7+meA%;nlK65#9`&&z=+xl9L#8IFieh8lwV{&kQI9R& z>Qr7SFmz;aN~tJ@(e*YL2(W3mN-Z36It5Ax(?AXMdyPiGiYgD@Xi9_O`AAZkVBP=s zY>izNlKmGTy8a~txFHf9BXDpwav*YPZe5@h;;znKJ&iN~Z54pY5Ad9?)cDt=fYlXc z5)ICez#Jonp4?I-u}&WkT!*bS|9rTd;4rbrc$GC@T5`av+Q)E>mTLF%k*>)iJ3hNH zT%P@lKO!^jL)= zAdBw!FD?V2;b#bI1)Ts@230LiLHQaU{DTj^Uu zUpK}k)bAL(rY9SpDdt%-`|xn8E+$3ID#^xh5#QLm8Ti#3#URRcVUA8?t@Z>f+al8R zTo`sk5RU=A{2|D>X($ko&2f(0MbkB|q6eZXC=g+8o`ZsLhN` zcdldG=Jr#WZ7Kf!*$V_s&owtXtJhG+e-Lo-OT69d=hI_5cv`kf6q z+ReDW%bP1lf7GL=p*?mY9O2D%7<8u*mFr;B4oOc=@}iu~fW^#I;8y}`Gd}x!5T%kP z`mrD+oi#K7b|S%&--Yww>$D4&=2YP~UV>zKMtD*>6=X!{B)m}Im+@u@?^=;e8wjdc zPn%Eu$Rm-YT^=kqbh9+%JiSR(q>W@mSI5AQ8CfH*A~yN?;%aOsW^AZpjXU}xflHgZ zP5^LhF7fnvh>Ck*_a^WsU?+4-Br6y+>#l9vtBn;2V5r&mBa?p-v`hech*E5r%BKCQ z-#vJc81};CGW=fm+ffjTlwABQiA)+7+uN&%Tx*$9VkIuNJ~U0etWnd>W$7;Fp8P{J z&Ra!5#0%VfOW=~O(&1^I-db(M(^F*WZkayOeQreV30HaHE56G< z3#8?r>TNUzov&S5Nv#Gb%=XX&sV4}$BV7mZ)z)FgGF(Ampet*M9m1$Ao{XKmcNrXC zf{yF4=O=dG83MKJu?fyR6)1~JWyhZlEAL^FAU|6=Ls*Hug>CrDS0i~5sRy#lL$_t!@tdMNbLi>1INctES9 zW1aIojNM;?C3=}R!O%)0;(=MA1B#6$({s~gS`wXEKi~|;Zf=5TI9d6dmVvA|%7s5T1!o8S3nhW!(9OLZ0iC#6yU629qK;xWc^l@)PS> zAdDv35#?+SQwphriiA`4t-W%HpeW^>zdhZ+!M>V zEsPFi)yrLV>8B~a8&C2(+EA}_wg2Z>uU zkX*bYktXjJb>B+pK?;w&9(DoSGM-_9fE2CtFYnB!l+58`+5QTjZ9*)IBawO}pMCHp z&|ZJTlfcp-dPyf$)0Y;I%6v}_egoI{lP)cic(V9%!!yW6=X&U?XaVcfew5k$n#IN# z&bCv9dbHNexaRPP_2T&faKWEJEXDu@YVOMqXn3n)f7|pq*p7P-fr!JSOi5VId&iy# zRA*HY76n;2F8Q#@Gj+5)UU~h&q_p+~T-nQynyV1v^>B0KOeX=`uB<9o<7fs5;L_&q zf+nm&1vHwR-QWs?j}#^G#Z2E3Pcg4+NYx{nUG)-v4=keLH%~(@s*_8p9XrsFav~}Kb9>3m# zr6F7c(^bDmE2nQssLC2%X1*7z5wQ=J;AJr=ut$Kx26gw%Egzm+#U-bp1Z->%*u2Gp zw%WkDCP0QpO)DRo?~-m;fJTHNUM>xc{R=7Shn{{{rXetaoo8TN*`FyOGAQnK7d3U@ ziDTw!*DZ!I;LYbFoSa%y(0D>Mp?xU~VfHw8X{g4SGfvC|&K5^!0>3+S*I)h_OM_QT z9V|%LUa+gQ|pHuoL#6iRQtryWa&|8dMJWWF$qc!*{v1jPfk3p zAUbd*ynL4ohy{*Q*d0dH=4y9I^&*2O%{6Sso~Js60Qqj79a5~Qq0jL`#v0hr?`%Y& zEgtH%6C1f}@8jq=v^kk518`k=F|22CbORp}ex?VL0fwI_p_v=iBpvt-QesQ9h2KDFqzdWc8RINC z`93A$CM{|`vR-uFgW2(sB{;3Vw@V}4wCN}OkG#E4nFlR*cG8Dd@hMRY$|?~f75v`9 z0ZBjxPj6$DB{?=o@zZ?E;_}7jY7J5O+e^r#!HseEet53i@U_Usu21v+21>gp z%{&KEYY2?x$RWM%`g9T9#&-O_dl!jz6gTnJ9%ZZ})6{kumQ_0SHgpkOxmfAvJkpe> zcV8Iww2q*E!?^tTZsyFJmyY0em$0u=2uRM>)&~8dG!Cb?sVy#0gt9{K=6%w zx}>k^3C&Jiw;pF=|gw+8|U-hzRT# z%0WIeLCi?%JYNR{MU4VBTc(p0bhv9+n^i|G!)VtU2&@l8kO20X;k4J-*qb#N`b>hd zd-go!+Hfd0rARtMtyHnthr9oF9<2^5M5IcvewQzCq>Q75!P%%LTi<-gf->4dk zJRV}n=QQipf=lvoXPl3J8p9+bwCBXU8XB@7U=^hcvZD6~QU*Pbe~~z^*#Awy2TZ7@Ni0aJ?)+83fa*`WW7WmukCJF7Bnzw4pS4F0=Vf74=}7 zd6cFbKrSdL*bm`vS2X^4M8=fp+k+zbx6Gg}&Y)YSIST{Zu|`s1(Ad9sQrJjva+2H} z))EK3EZ>9lDt0MqSI)msjA~$F9OV{xoFd^@sJWpIGyKZPU;8|5rIxRXJrze0P$nOo z+P7alw`FjV7W%GY4Ir&gAMl=Zter2pGiQl}oJM#yI6sAxD&o2B;a(Cal=l$Uw7$kL z73oOT4op9e-kaPLR8cHVgYP}EVwFgwgL$Fr!uT-_6ALhIBJIWIo_0)vp@YfXC%&#$ z1b<5|-k5q5`EZuISP2}$_(pf>tZ_Ep^VO_X_ISL`>m8s08(~1EFw%6sNYa6L`dag( zAukPPORKaGRy==-fDWZ$)i0{Hp%d^V7d<&Cy$aSj*P`=H;rGPv@nP}+mBsVOTKA~j$? z83}cr#(^_2lsLo*nwR)lFq-l8#E2#eCnx_YfhT)~-`foKLUJ`9Uu;}V0WC1DNlnE} z(dbb{^Hv(`k(jD@R&bzkdNAAGqJCo)(*4qVHMh-k zrovmd=$h1CK2>aYc{_3wsuoPk$y;^VFd?muS651wHIC7)&Yn6-n&$x0RkHAtK^{Po z5E&L2q8$CPh^3_tv&Ii4_qvBM2$auh72Ptu9)X*nqtDyE_%~u3>S$jkZbL2i)deCK zDR4KNh|>kNC6l^u^(mP&@=u0ubguJ7E6K_JW{rrR4dv}jm~!*m=$s#!7a7z~i@*67 z88wthYb;OAmgDb@KXk<$*M(b#=@9S;+Q|>g@mU?+w)lsvEptEE9q_<07;Lp zLraljao*_hsP4bG4GDxtB`6M!Q&`fZ&<)kN4YV*oZBSaUe6Y^oS0=^%+XSCx{EN8- zv_^p4EX>*7#!0H5r^o1bJ0^nE7E;INAlAR)UdiB~7-Y33emN%9J@`|)!l~TZ7DW2!Du1Ba!D7pH72U32($y_{~TT@AQ8qi)wl)lM^>jXZN6e8QJcK%NAO}= z393%~bWw}l-nxaDDJcwG_z|-!PA0~{vS|KcPd@=~^GUunNO6&bRvKZyS?!N3{|4B@ zluZFMs$!u3=Ld}F;by?akD{{Zpc?@oi!50b_!ecTiV!$SCI}~1IKtcPb zKsc4-p_9zTVi5QI=djB)UZqGb2a2IZdi=y%vfYD=PFghH z*{sTz`>=`U5QLN+!*XC%AJBZ zEPq1irPRxgB_=?s$Tb{BI@dId5lI{ewFYJC&|uaVkz{yuuP%0YRLs@0QrDAovng%L zSZ6lootRoopKhL`_P(|29bb7T==K12;SkB8QDqg^Mdqsrt_$3g#V@CJJQ+ED-=!Qi4B4%_+uBoNVr+tdXKR3HipZ=^}}Bp%@KHIxZKI zd8?+e(kURD3Cu4dP(p>Lt=J!e==_t*1a`7`dKBx$s9D9XNgfu}?0#D4o;1Rem~O3v+tUl}i&>Q2=yTEn z)%e|?NEyi1JRhg5%c6mfBJKv3G}Q@|&f|4s8&AzJFy~0*A$EEox!cTou@A4JtiCiP7pMIMqcz#YHJ#YOpDw`&eLAY!7FKMik-*Z`>O)c;&1QBjndJ zM@!Xf@9U9FL6wNJ#via%+^iYMfbiBq#E{AVkr_(R#Alo?e9-Yn8%aYeiK(K--6Ctr zu1R8loEKSgVH=HAiAAc& z9Q7A;Ia5(Ml?{zYVaAG;JJ4UyYo1ZC5YUIsM}eC4|k-(BJt?%gfz zqO*$}5{;*l*b~71B|h*83}6*d^VTcxc($-y(IEJT{c|Dw>YXU+}Y2bs*ivm1a%fCM;d2?3J-_?jJ<)8-!|m1?fdb59 zA>a=AJuoXc&VDA>TzY|6A$S15QiY3RvvHzp6B-YTkxh>a(dZH*iN+Bs3nG(F^V|)` zgL)@Y6%oF9aL-?nl(?P5%`{UV!8Ojt)o1I}B#CVM_w2f} zyu?hLW`_=U(}#G65{NgS7-?o$+jMD6Xm}N-EL(|3uVq&*if6W-52u0DxQJWlrIN~# zx(e;U*EdpbrGbAafULj3`>b{17@Q|7+#|!IrRB#%MA&5Wagm&qD1k2r;J;6Rf7Zev zUJd5Qwz2*&R||x@#OG(Kq)Z_pW3u;!wi(6#!5u$Cy1$s5x;{s2g z9ojuIqCE(RQexlD2C(-Gdd+aBgUCF$!50j1n|K*IU;#X(iS{d3Yo_r~#irP)96nQ! zAKPHl7tkvRMO7m78H6B0I2cG(QTgTI2|kyk+zrcnPmoYvJO=!Dcx5q93|h7PQXe`Q zZte~tWZHqPGkbb@xFE56au&@svGpRbae`U~mp=|iFhq2?=h^-hPFW&2`C~XTT1foo zrJ~?eNytJ45NooAoW}bA(en!%Ce7q0ck1Od0HJ)|R6Hmo zy5vZPa&n#ga(s>Vh91RX-Fe^zvan&mZWFcZxrC>=J~kR{o?ks#-d}Bu%uh%vx~(sQ z17vS^x0W^9!PIYu)Z=GZV|wXB71$SJq?7_`awntkn^C0MWhWoaTyvysNy; z;1RC9!-on`UME^aaq%!B*K1_(cjXHN=)^g=L53ueTSsq5V+U%Au-IHcHLYrHlvvhN z1BC`1ujL7Bt^z67kJT+Ku!4%J2eb`P7^J1oH*1-@f}kAi?3#_h$s{Bay?M5RBHd{} z={UK?d*_gQal?P4Hrh}<@jTD9qJyi{_%c?K)m>Pc-FqSApFgu}~{6C5O z{XfATqhT>Bh)W!Uqi%@hk4UIz5u!aWxn93E*1}a(avhuQ^(>%o<%7U`^<>M*V;wbE zL6r3}l2VS{h?CXxlm#JO+l2CwYv4R`w`1|5%0CgF?CP?)%~1mhx7#~$x6F5Ek~Oy} z@whEij;bu-dw&HkWi?J}T#rKQvLDosb93lr<9nC{z+#_3l}MF4ku(X3)AmI-8=P|n z3NN`~tqVywE4jMfH*<5D1BSV5Fl-I(R^fn5j_c7AOkM_AIT_Gdy575+J+Fq}z|db? zqHO|nw!ZJzBsBIN(nP~L2p7H4J{S@m#>&W)O(jprogcZn-xn?4*2%79wZZclAL0(> zh67M&WiZkddF|W&`_rrwL!}fXTTf^%QGb665n9XjO(=dM#gR4I#5D+ryuFrhrBgtU z-n>45z2%{^YLcWhIc{&;XnfI4H8rUZa0XWCy;vJ8DCMzlv)znHI!st^ER8qA8Lw@h z7glx0RsjF-gys&Q&)*7{j{~2U@bLjZ1uUEh^SY@Du-DN9Ni!t+v){btV8S^+o#P2n*mWVA zPeh9`63aL*vc?%4>{k+nbsN3vHq?X8WA8)2Y2Z0Ekg8o zuvzS6eXrGiy9spnQ?Umly_jWJIKa`NC7%zO`9=;XptLb2LRf>@ zT223^J5)vq7FVH;^ooj~!M+r5-~0(KYi^@}Y^>|8L6IWW4#N5uvsX@6W(A3-sT*cU z@#L=uYre_BTFKef+yGvHnCB}6od0gPCYCW6r#0V|+`!{?(0!`r=hnPBkY6ejNHrR= zy{a&`5;Ajsrm+aP*|T7eMAwSLY!Jsf z_EB%5^2+WmiM#kA$8Vn)Jors+&)p*~dsgKBQBkQq5yim-mEq#j#te$62&xM`e^gZY zwqG>Vt9?}%HmHp9yy0o*JkE|m?-7A^;q8kNfG@o#6f&S;1U?Pj+S1qn=%zfYsQ$RQbnK|iw5a?z5Kmd{3 zPs7eu5uapr@h0&`KC)uyHv)#`lVG3}!tK_bzFC?#=S#% zA0$z8K5_(T@{R#pEA6rLXqGzNNl(g7N1i`_qFfD%GW_u#MmkDVmIrK;Du~N| zr4#(yPnJdIUHe6pLbCQ6HUpi3#kpA}vto#$$5glrJlZ>9xKnDpVy)JbK zr{CT#T0kYcXPU9;e`hI7$)K{9@OZoDs6>t}S9l(1ahaET?2t67SRVT(-z8n6{Qd*frkbv zwF{X#yt7Hl$#Io$Aq)&Dqzb9e_CEZFq6Ia2hoXZ0sFrkGIyiZy+tOlU`(F5Nr{ zsyb<*GjPaEOYN%0B~0w#lB8#ndEf=>e!5nB%}ZW9-DxO!?F~dRx`G-hZ`Xh{+;m+( zaY}q(UUQOXPtzMx2@+(25Gf8nrq!kt2<(mp;>vU&(XWAUs(}q>NMc@d&5P`Z(Zs=g zE9U8@lGD^J_(!8RypPc#P#~y;`us?#H!8oR(ZA%}``dCQ-G&Ts5c0{$H_xiMe7rQ75O?2*9wDl=E5`GX6xx>9?c<=kZMn_0$ z4rS9hkRNe!8EdGkCVz^4_m6WEfW%L6y$>K#M9#F>e)~rYiBc8XrT+v8?qi%{RR&32 z6cZQ_Rt#%kMJ}$jNGZKfWhO|pIKT z+;WM$f5{4QkfxnYyv3YI8Zw6aVACHgI5qD)gv?+h79Pjq37kN?gf_XaXAIVPwMwl+9v5*nie;A>L z8j4(mo5)-h6=M`}U>U8XQ7uy?Fe_ld)qMQ-up+0y%9B>@|-M!UG9*?3&trU`P z5f=jHD*0{nK4VBe?TJvBhKMT*Cr|?GDNmUqVuSz-&g6T=OUjmO)105hLLUNLKaMAihGcD zW33R!icUV?l=DfL0nZH+jk}47z?bG)l5sDx`N~8G#|qux2CR@1(-TL2*y)e!VIkgI zT6sXcq+tTy^la*z@2u-Q8!fS`IjZ9*fFx;f7e>Gw{vy?!odI!#)WT(DX6A~4DiBt1Y z{wP~S-KPC)y`gNs8a@tr=?Jdg%(?y5CxRO0BgKh=<9a+z33n2Y5n3=1&So~0sTK9U zP6A2_V#il%m+o$H@~J;l@`5PtUwc#;}h4UF~ql(VKI#C!QNVW9Yj zM>IF3SW;eDm3fSk{v0rOO&Rj|tW@%~*(APCtyK$<&#yG-^fx)U!LS~oqa@AdlL^M$ zSO#UK1Z-_B%#pT(!Xz&Aw-*vsm;rE7qBb0^|AYq*b}J8+5*-Wtr! zYVh~Eb&VJ11l!=33 z^FfBR78W|BMCo6suc-s9j)iE!@#Ys=U{Z>&QBo~)|9(5>TqeO2V#;kIVwzB}ie1*X za0Nir+?3vU1J`&%k`_`0%p1av*XA$d@7UObc4S?VAhuEgX>u z6R098Mq`&uGaRNsA>e!3OOQnoUqBU}IjqHY)uj%8HR>|vs7Oa9(I1=mY-_u%2kg_i z$L2d*#F>ATNc4A_e?bjT$$5htAn@)6N|`XhEkWR`UBZQn;b$(Iv65k!X4}v z=<$CneRW)v&-3_m#{oxo*U{bG-Ho(#mz0Pob#yl(4HDAbNE{{Isf2W+fQX0!zk7ea zzx`uh&vU!a&dxluGjp@g>@WptkBQ+9j$pXXZzPjb_GzLMMzbQbcsAdkTa;*!$1}L{ zE_q}Nf>Vt9ac%ES3eOeR?C*5u#`x1$X;sbblxi-DXY>7!jz`r3C;s_Z=<5!(9MsEb zT((DjS*o5DAyr9G_P*ravHNwbh&?a0uur^JseS*N2(70uqr^7AxQW$H^gizuf5Uvm z=m>G8v=%A^MWM%3@-?>bKwn-en{?m`{kZA(cl6n}AYmz9mR}*bk~e7$nWg**m^RAa z!H`}apGd0PWt%%TJaMF-`jPxG{-H?dd*6aCjyQRk#*d}&;BR2^IVLKyUoOzHpI@_M ztGl$ydM|@mS!QiYUbPVaksCvGVsZ+D?u+G=^^%OOWC*Cx|CiH7y!Fg_vKiV~B~C5N znPC;=`Od*AAV2X7eYT@Lu2xuwLfSw(C!wkZPEOKP4%^79?~dHsJ@vl7+Eb{=>Fl(W zN2itIs~RycSBG)Gf~hho^c8OZDU}u>|2Mu@*3ZTqk3YzSQ+fVTDa_z(QG=b;%^5I+ z2OwPj$!5M;KA}DuvgTEB`%oxOGm4Qe+VWnw^#CsHOB_w_7wY{wQADxlfJr>KLJG|- zYuUlMSPk_so{NU_+0TvZemPbdVd#zBz(S*xaef5+=}(k;i#V8FUr1J#G{n!zmy2%( ztcn?@wxH`J%b=n>e`^zOu%Ax9@bSp%M=OM0kXHvkjNeTx`fSlsVfn4k2DLJ&%XL~- z&FK;I!OwxQsFwuUQ&8>qZsgf{h9qPs&SL~rhPmk6i7eou7tFzsFb{V=Un53aF+PfF zdSOw6!}gf^FQ^N0cl76lujdp&c^j=3okCbS;Um z@Q?S8=JKn7RxYje#!G)2R)13QIuO12xE`tHChij=+O(X&M}+<06p08XPXbBnU}|rx ziMRZz5NpBI#>H-utBG$^)X~j@zLaFOfq>!FXfw#

    iE&nL_k7UPtkp){(Nz7U)) zNz}PN=JV!|dBN!6m$y+Dqn^2$Bj`QS8X=q1oe+7sOkGd00H^-u>)Ng{W{>vcAAGJk z6_-~rIG8||aQ23R>B`q{Or!DI{bysY<1-4g(6^~HJ|?|VnRqvv%{u|Gs9E<>+f=6( zK&KsgtumlwKi=?p+-Ea5kd(OEV`ZX79Ic9B8YIK{NgEQC7eSYCJRG!NJSMsJClbUi zi^*>xfU6oOw~c>#Ej{VWrG%y@CZfNGK;II047YSK59Kyq!_N;$qP#(|Dc7Wz&-0A^ zgW-Z10|Q<33n*}`Je*Bps)|BenDmWQljZdsctT1}{h7<`Sxcz#N;z>B6ZLjEmu|qZ z7eQnA2#T__(YP7yzZnlwsPHzPJU^EE-SBR6`1aEDzyT*#4WEHQDRz+AJJ%Qf`v_*TnA+OEk|#C57#|jfZFW zl6TVDM661t3C>Y+)IXMnDOwVee_eY0(P&$OhSgmE(+$KRCN?jH#-2cqV<$}vBNZw) z!W8E3cjA<|9X3?k^EQ_#JZpOm<2r#Pi*3uX?O8gW-ka^}k+|Z}WKjgu^+`b5EmibEz{!nWK@!%JZ4)Tl~mvEKTGExFd-MGL%a;HC+FX%75^oCPUU4D+_ z0;X z9a66)@KxN3BweNGy2-8g5Ov8X3dlCuF=LGYwWXHg`6_(ehQ^EZa(eIIins>V|bG93Th9R*zo9BMs@p8Hc%a)LCc1b5><{-MUrdS8uYf59-| zI%X(~35KV8P%kN3Omx=HUI(Wzrl3o|<+Wj|VvWc^{g&ZAX6g62{BBGs>=*F}#rH?8 zgsr1VYu@EPf$%i4`Gk{O3UrY&ZL|TW6dH4AMAF%xGelVZ-R4NnT-xNq*Z1~ld3rVP!d8lnQu{Qtww{&oYVX*<7osx*_9HP|EOn2o22?- zCVPa7%a$=ds(e=2J9p5xS8wN8i;~9WpqOdLM6@P2+&aS)KB+ximr<|TW3VhqUGN=} zK%7);ZO)EAQGtYj$LI4bkd%A16)+2ZQ{fn#i&-ZCy~6jNz)LF5(ZVV*y{4| zUFd=vu_7_{=0#zX+oOgVHZLqTIaC(``R)6P-tX|G_AR0M*o-s8gHA z-B04ofc>W1B(T1W6~hBgm_;9Q-%;ksiSV7)+0~=-#FM^gr(+%Qj%(0bMR)&B7?3)B z5@%-nJD5CwIq%kr8oX`t>EXS?@Dpc zeAVnr^te?RbE8xapBR-5C5Gbuu3iehGq6*6^yw+nfS-Z9$dzjk}) zo6CQk*h543aZlBxT!~7YUjLmEEP;j~oxwh?N+(r0X8%i12X-jUynbBw1pLl8FTNagRR5;V^7D-{I^QPQ+ptrI(pM@1)myYD=tFK~m(k7&}! z%szy~pj-IQFIG6V3di^MDAmbNnl`)Zu3xR`=szD%kg`Ha{%S}6(B?h0Q}xrv0^Mcp zU!k+Eu74DyW(LE|j8ZIA20c`EP3qe!K}U#Gpxv!Q#FgBzR8rk0YP&M6R@ZYGcyYrB zDFB!tUGb}S<{OTgCi_E@_~lC-ZXP&7&$`Je4dBIl^C1UUh#x&;&Wk1`%ls-q37M6i z1D9R`bsGk%afWQaGoZxXu9^LtFnx-WN;g*&^b0E~mv(qmzM^k+j+(&M+?5a~Rj9kAUogA0<&p^PL!(d7DrGTAaKNhtW?B|927seNq^? zw-6aOT9dZ1HGFSvWgZtpS{j#%#Bgyj{Iu01e^lk(D50X~FX)sHw8q|Cm(gPgikAp~ z4f$cGa8@U4wamSLaa?O-v$Z78sPZOr^+VDw<^$UY7oX+ccUj1zHh=02Ne|Q_cR%@C z+1{*;ApO1NY?<3EDvh~BH}-F^i>>vF44@~gQjVdKJ0IN>EU;aJMd+do?gy@uEaXW# zFsaDT+-;M8+5X&h)f2wgHPfeacX0Uaf#Cu281fQ~pE1ug&BjSgx7yOW)Wx|5w%(D$ zz_p4t&GG4PL)f;^6RF^41e00(ECEp$y5@p)x@fOl2%N8&m5OHn?Wp-&h>K){I-H>q zyfqw(?&19+gGeP@F#BPA$O-$FkgG{6h~JbdNSoA`Qp03IA4Qj+F!H5V4Y3=CxVxx= z#zU@hNRkfL7{^C+>+kH`^_vgf{uxz=n6HXKNS_ak+RgL*%Wtf_-sIx%$C_B>#Ma|V zxf<(qjvbJ}h@`SUU1xKM7}m}ddDc(c`giklY6Qmp;w3X8&0td2N0t45ShuL-t4Ttr zaWyg}LKkRSu;Qn|gQokr<>j||ruV#EzNS*9?;)@Z9kEeDru%Z%fMk>g`k@N437eci zktdtRd`SP_>|!6cQ%uDSLlWu-IhCS)S|*N&Od@c_5XvFvHN%egl4!nZSbqESw^%Oi zUn2TKRMBl+z0W}ZV({aMS@aHj!`3}$ag@+U@+Eva2#k{ggLJY~Eva6j&MvwHj6W*~ zMr3MIlYIpV@yHbhGw6-PhzXE3to3=rU(J-(_i~O`IP2UPGu%yQm4dw<(VngrBN&zl zYa>;&qDoSa!`b%PvkSh+is_VbGE^K04(*W`j~QgQ0j_Vl6N54{<3=C!cT;F$ee&7; z6AkBuAVHxH1d8S|nx z1#kgf5k(taR{P}_Njl>VYmpme;S0A}py2^QPz6%mniajnk zRayqKlCS8=a1fdIGjADx({-~YhFN2n2pV7xBM)D3T{;y$vodR5d_Gh?*uP$YK`eAQ ztLBmw)|xPpb&%B-EqpzAinhh@v8vTIlr%X5Xa2n0EoCW8Wddx8j(sjb3SKTlp7eG5 zDT)79tkd2F8)1W~iSbR!`df3ZCW)*&SdU5nM-@Ak#QXR4+8xttkW#!OX4^A zm5bM*po~Fk{806M1Ivro#H*t|IIYE>_FDL4{weLBn`}o(97HDkGV&v&5S*_tA`b1+ zyvCpQDO!i2Vjr80CJ#{=H=)y=tPLn=*kznYedGU*{X0rwhP2Ba=Fx*E#S*OWtD>Rqb6mS-(vK;yZ|HBQGYMHe8!xz<3^jNE6d(>VB=K}WL^Lug zdHLAw?49P3;SEoXi5vfTaai&^`5(Yt9U+3{m$E{aC0a1(R?<^r9^gLoB8Fs?9cmC9 zYYt}D6s7r^S2B%LUG*@AQO!s}cjx<&;h4_8(I;rJxx;Bd;CL5WsdCpyJ1|l#D*GtV z8U7Eo6@XVOy2|TnqwQ)me;u$v?>0M8iu{-$*2?$kk4Bs`4aUK=K+T6X2QsaI%&^f{ zFJFyGd@c@YeZ`_Pv?KwmDN6h|_N~ymL$Ad&pp&|5hB&DESiw(!DHt;k zbCaCe5kh-r5(w@uFi;yNet^nv|;k(5rLVV@CWl|OYeOB|P?dW9vuK)CGBjr&J} zsSTZv$Z-NKJ`Bg4Xt&3Iu{$A9{?!QziXfhA;w=NKa{SSE;s*Xvt{m=O7c}9gWKolW;xMChaEQT3Hs~Y+&=Dli=DwK9h|#V z_IQ^?j#L6frgJK>hs0{HMOz)K`o-NlHmZ@kz-TuPZMJXdv~8}vNAuC&D>Db^+a5C^ za}$PAKc!!qLdU|lFpir26*d%<+~de+xBzGcC!$;bnp%^o!P2aadD z=JHZWM1!Zmsu+T!yS@V?(v~O;70zR{X)pgI%z<>3@!8_djmAH`ArY6uH|!tL&WqLj zxbzOsB%hj;7*9?<><&^SYZi`1LNQjIa_PCADxz$1yR9@G8Zh=F0rs(kH|NAPo38&e zud9UNuX|=Hx@0Vr_u(oa!Swcl_mwSQG(P{u&XLWvOS9YDS|WkEjpchQCQawa`|l;E zV7)Z9w^4b;EXfed)0!*_FVNnsE~w=_chBec-r0QJP$m6oIEr%r4o9WXnE%dnzd04J z4n^Old?!HdSQm31yeM^QM>*Dm{(adyqIpRyIxS+q8vn{gb~_vgpsh^|&wd)&#h?$F{$`3g8!2&P8mdSV^*# zW&PO6nBf%sSN1PGaEX&gKb?ytLL{Ec^zjGVtI5`z4@@{Eo8eS_@s(;uCtt$73-a6W zl%LrLTNGbWzxWmN*Y%xQY%|LV9#}hUeUuXyu|Lz#&3I!i$A%ysR3ILNu|7pI)%wU! zaz%bU`XUKVpuw2EH6S_FD!}1O^_7Bj4N2neT}I(Kw||a2Y&{luW=UE7$tX3NTZZeY z`N!E8Eq&1h%=$Z_7n=3`l8O=*=RQTN{vVIf9n;B&lnn10U~9b6n#FlHBd!V~fsy5 zFUVbdgYs3C;_%Ei$meM+DT2><40`nS*SKC{O=U8oHFQd+ibE1p z<15o}Af?mOg6*fL7pm+6$2c8@fXN?$uP8eZ1>9(hssT1aWe>ZpIQ)kTLD0$LrZ%gF+z84KsFvJ()1)*&*r%lMpBSB-rRh%Rx zClONA$g|#Q&yyvX?SzKRFgnIL>Coj!ijmn2hSZet4SS{i3 z$(#c>F1znbCoosm-l#1CEUtn+r!^B0!Vyk~w^p1Q{~^%7X|;_jqBP|Whdid->~YWv zJRRj<1JwnFNPk9&e6YcaWJ%a8npDDMF-5D08Gugj*=q~Bu$-qj#|7ovgcSx<8IP5P zK^|HCkw=qNwrORcZacGhNDqE%1g-MkUwu(##y}gZm{D?=Qo?hoLkJN`H>3#~J5&=R zIfp{#!d0oamE&cZAsoj6K4x-CWQGEzr@G+9HY(@C7zuST1{C)JhD|&*bWh&bAb_fA}$JTMD>}w zV*4Bp0nJv^*hePW*KH5IO_d5@g#g2sqjPjRPy6f$>=ZT%Tb_dm!K`^T4IF;p6pdwu zI)ZXib9+YlNsw+k>dBCV`?TWo`<)P)EE_%258TrCKZ@guEYC&w4bz$#seCOi9ou4W zqEo+;7UfJ?22-Nsc}W)t(kCK(7@l?NxohtzzVE*_&#XRo_`GmNWYgiktjhf|H-`03 z0Og&52N`v!JW&I`h#Z$_TXRQ%>U?^d^mE~2A#z5yIbtGWf_gd;YqHe2Zf1zAbNdEY zNFA?_O8mb#bOy71xY zQ2Yf~cSRJWbZP}@S2KJ*EA~TvJ#F1`_&FD^Inf)$xmZE{LzK0L3G`fHEz&@@lEojF z8{Zs~)R+68MT@ILu^|3p^q)X-JWE49R^y7wj;D<9X`2c5O{rU@K^V$c$)V80d3BPc zr@h<~b4qHF6JEmbZ@)rui7LpL2mZ;58GWezv}M)HoBvGfqj1O6-S*eHoh45go_LDx zDa{BID(aExIE5ihP!c<;$EW_w>-yM;-JZK%VTQ*SVDlQ}rq@W%oWrxf{u9-=Z)_)k z2Q*bvAC0)WSi3F=+^{78erPBRxJVB0ydi|;*Rb*Iq9^$Bv!SJ7!JjRr2s z3cfeGQ#nvq;-q}YfMdRR&st-9$3A~EuDf+CdqnjuRWNbwK#ROVDKwttPrU9{%5X;o z)(@lhgkF1pf&3s>99%WKOu}E34^y#*$h`^ydDa!b!<(rae#YL$%7daOWb6&ig}igO z!DcKQGkMugQH>=LX)Q%()BCdxu2&q~5!<9iG&fKDLm7^zTnw@W3iX;P;u|&o$xZdj z-N#|T>np&Rv#C5^a?B=%6u~-hgbG7-5;*+>w!7>9wUIHqv{dDVRjU-7=VMe&U1~%6 zFB}u9eoY);B<*i!%ighkIFYd{SF z0MLQ*rukx`uTgUVK*1P@{1uH3B@D6cEk=!t4v86ZJNLa5W0IljOic~49Xj@gW7Lf& zY{M{82Ii-|wHC>}0(FK0zxq>cEjDfqfsS2}19-sz)Hh`KXX6FXZ>eEk-OH7WM2Wxn z04NpT78?(;Lk1jKHDg|nt>KpG!NBOgkF}H;bzI3ha`4{Pf=EywmTfU;7$5eb2VZly z`Qylee-4Qz9SWLo5(1zkvM~aDNE%V!{!q%^xyFn3JB8B3kCQto2fmMQr^TY-!NiRU zBfW(JfDX~Su-lL%@LZFQuX{BLrxv~;Y@40UV#q090}h}?Rk1fYIJlZkvWq|f)Koy6 zOM+kwdhxRv0Fb;`lF2_!ABLPL&W~qtM8!T@0C32RsunCKM*S=cx__O{1DNDms38&Q zU5xmeN=Lb^I7F^!Fb7rvz-R!zR6Y;MoE)4Y6+lK;M1q9nq-n%21!0PVuPodWTUZ;- zKOhO+y4?v>0EbZLpU)$jLI7d}fM{-QP+YYM%aI^m4Aa%hGjIbjro=oMJcim>FUiC!{<`GjJBEiwrh z@odGHg9IV*18-Ai!Cny8oAzXsugRgLy|R!8R1n_SYYfHEoQ%^~NsDm2dF=ZtrOc)m zn3XRf#AL#*pmC{>Fck9Yzd{d5v657^0M0oqCRL8I*bV%tktMQxW|;o94NBw^A`{7h zdd#r5Gas=(X}Rd|iqb^?UZ7e7fJHcuk1)2`uGj|l-B&pPxNii>K|P^MB=kLM=@};n z@t23D65aq9n>z|FEmrklw}C)>hoVrzVq$Qv4(8Sf*?D7h_!t(``i7A>008R)9GLiK zatWaJMs2CV319%F`W*ihpa&Qj0RZIYV=Hi8`>#o((M6F8+NKIafxSaFjT=xY*ucH`#Va%e58HVQ-v!*zB= zJoQp@cPhr93kR2KrWDxP{nfe;K6m5Cw7UT{Y03cti7(N0P>zl4I%RKc2+3JrwWJLX z8H_LNBj+LkhTv!-9(Up2xW{#nkWu$!s?g=+fV4ri1=OMOp0HLp$e|o1tl4HNtj92- zpV1Tm%uhTO10;4x+Lq#DD!d_t&`AXV#2&=t1T@GhBS7yeNTXl&gaPbLi>WxA*I&^Q zZuI-b(bxF~y`C*okTYcV`V$MW)8bB?lJZQWMR+*#&%#72kk9 zxO>Y1xHfg}sQ?vG7OeLs`kqn2<|RH!835#7?9xK<HUuCZFp8DC@`8J1T!C zwk2_XykG#iddN1r>T;KfL?U0buJ~-?m;xAe4JZL*!vR<^fMppAyo3OFt^kxZl1nlE zIv)F&1p?ex0xSG#iuM0UGz^4lA+(%20AvfOm1EGzzZKqC>Fz9mh=sqCogo$iO$L$} z2Z=^fnTw;7%gr?k7h~7%D*<3q3+2y2l-{MNFA)v$pGkS=a={Sfd;t)_3>;vLE(7Gi zZ;^@Jhia)|SWK(EScO1H0}90Jt`W32nxtBF%R>x6R>@at-1{lO7&~pPWac^#0rB z-!Qn4Ko&x6DjWonWq>>fGJb^}O@Z0fV6)%&PsvmQihgEGWY0=PFQhVvp!3{fbjnAvGd_r? zp!fq2K|6&~()}}^4*amE!wpu-Z@^~(Mw+~%Ym9hBjPyj}V|%(xi`nh-=THxKfg_YA(4#NEH>}U z?BNM#_FJGS{*cH9YgPcrN{l688sgHzi3JniOv8b$RQ&F7Z@Gqd(QbG)XZDZ@l7?L4YON4LHSiat;GfbE=35dRqaQ3=B{e|NRde8!vJylGObK zT`$Q}O%7%wcEt_gMjZaKd5O34dChQdjorP!{NB!SAw@32P5mKyha1;6EB;RZ$NQN# zvoc`R$}kNZBy;J*qo6jFFmsaOF!Q&9-B%!3Sm)tWqL>LBRN^`>SP({2@%wjkyYbrL zT7*wK227qYrNkKy2fd@F*{)n81_SQ7P||Ift!Qd9hz*Z&*<6K3FLL1ZKJ_1E5=_1> z6&nftz6{F&pcz0Ro{mKV%#0cX0Ffs1<_%Q@2Dx*Zi52$iZMpf+Xq0n>$oB!TQV$|9 zTysSj1~M115cmee1g-5#Dxe|>FgP4v7%E3`!-jzzM*xNtwaW)CfRlbaQHq+;w*Jwj zf^1e;n2Z?vQnw{VrY8sV7yuxN?heJsQ6UxpwL&g6ouc&M+AU5t$u7~F zsVGS@RE_;4G_T1zETj-p{21#w}e~VEYU;;sRam_$UzT?|3-o! zNq{V*#i-Ii=2#gVd7b~el!y-i_>rd6|1T(Ou}HlowCzQs1ZX2bqyR<}MA8yq|}g+TU@SOa(_=in_)mP6T*Y&+s*-0G5hW4reVs@4d%^b&OARvIX|HuDIvZ5%a)X^r_XnTm2qLF#oE*caI8M8Y z(hHu{apksV#i(p9(T#KE#NhxbQcC@=fLj4dT1EaopBrj)=4AI)ZX^#<&L}MY$fFNA zYS>uQ=Nw88^{&cpNL)-**qy(gtzPW8J8YE=L=xo}^?N~K%jKQcEUJTka%1sdui8I6 z@920zLfgA1leFhMaF6OVq-Ll^KN>ZiF>3w6EdmJ=g$MC}kc|weU?E@>V-TN15yquB zB9)3C(UySaiMZyzEnf73XB82Xx!by8pwPIm8J#j{q)#}^U%4DaU1lC1_f2n}lHE$z zD6r6op^o{EM)nIhxb&Aw+Wz3k3BJ_1{67f)tD&8k)gTBh5Z2|%0Du{I<^M6O(mETu z8cOD8{dhyMJ5a$xA3uL5H*gRxLn61{M2OL;q(0eyd6KFeIKc!-^n_n*g`2x@dD^{L z<(2QDCsqtgD9%cr-NFkonuB`(2jgZN;Eq=S2(v?NAp4b|G-87f3#Sx;-#CATP0&gU z-)m+cpt?Qyx@>ireXag%pK<1&M*2&^3{Qm4RYGpgB(5{&Gt!Up{X&P#Afq5LB@8M! zVaswD*Q!*^>g6-&`SXzcj*JHYkgE+@kOn_MNLCD_zy-y5!QfvB)N}%a^{j4RITl=v zsrWD8#NNGOuU;<}7r)zG%CcL@>Z1+$^D|W0n0KbmZ^znHsJ&etZDW{^|7cMmPG_^J zx{Q))X(&dO@Ev>(Kt%=6-o=ss2M55Q(!2sd{OEV+1j*#lcrHJJ{LTaPDvtxw1wii# zov~l3oI20P|GnrcA(|oSyj;Iim`Itjc=d1|GZG*Y)-L^H=bFBov2k$%HPa`jVO{Ee z=B|eCrjY+`6d%QQ!>~pwI(Y5wq}+bVuBeynoz= zyFug^OPa#nT};z%dMwS|Ib6}%oD5jJKXP^Ty`lZZA{2a@k>-3DA(A3h=Sb!@Hf#D zYWREu%BulEE!*A;NkBsj!Fo2hC_BL&-H~Dw^N0K#|F26cChj5saxo;9?%l8xfW4kS zoW7|xsF*@4Oo16V?elv6M`rZPe>@Kv$$+6m#`+RA^k-qT=|>o8X#2r!C+=%;uK1ZZ z*jl1Lt6vad2!8M4z*MOOK&^0eJvji}0~qOnnTuUuXa$B-&yepMh3-0qaj1T@8Qk0lG^t3}&Gxvsjiq)>spj~F&cIH_K_ew`uvTAZMP9djaP8$tt=*&$%;dsyy7~M-yLP&}w z4g-H=jz$&c^F{o#0?cAt`9A0Ky{6E-D^h3e!bFnZi%p$E4UMucY$S@!Ddk zmR-D3$>L@yuO$0*(T}Gc#-XGqYQU{}k`qtBo| ziL3jvGrjZ+h0Ht+Qo0w_x+?n0ai7jy*8cRMPB2d)`PPR_k3aBvAS+_^JJn=LKrM)k>v7 zx*Zy6c80ig5`U+8NGHYTv@K_5jSAgmL5p(vp`BPQES-y?q#hZakcatqx%H;cGZSmy z!&llm{}b0^;f+?NDDJT!_Fh0}WJT$PykokBaX(a_{;+BY7j7#M%P6-U7d76E2Hu3n z*1gk-jpH~M;xS?ssuWK(m2-$OxR$BKG^HFvoov4ZmvwvfQ+ z1nE_NpCh0xqWLi-oaMFJa+@0PHfI=vT<}bQe~Spt(=Vb7FJU1x~!pkJX(zl-Wy3v^N_qGd#2>gtF;#J_q@BCx+Inbn=izl zqKn*w@A(GCyKi;RVB{L#b{x^6X8(K#t!#KAh=yJh_dC@v{uP|;`8g;W97^fQ;q9@Y z=cjVnu7f~{{-0$BGRj>O0-GO;hJ&m8UGiq--z*$lGbgxxb5DxjmN&|qQ)o{9N+HPF zF0h$nR}QCcz1WvkAF8k^$E4j&IIj}(D(WJ*|2=wPQ$-%{Ng`dgDVNKk|6aOdq)+Kx zz|p_=lk3n9>1>(Tgt>};@p1EQL@;8`O$=d3M6_%O2~;FCrOLV&NF}CczqNeoNiWr zMe!usFB!tRI?bq;r_=a4O=pNbJ?i1fsxwmN{%+`J)8MSH%HRF|wY%aOes1_Q_vmiY zv1*wAK|}#xHKX_Wr-Ka;%bZ8vA#zqY7?PV1@LC=rHBMY1;y~5dFll$C@x(x)HQ}qM zj)_LtwGyG#3ajqtPJ`<BF%KpoF_u&t+e`vvxn7~ifE14MtXFRQt@|#O$0oJ3NNARK<4M{%VA`II!xMwn(RR= zZmaRds7%+igM?#FSKx1$%?KmO#7`ccv8M9Jhm#JVllF7c-@8D2E37Hm-$wov zCy}=#%_chP&Yy)|aP$$RApdjXgVO)OK6DKORDJJ=$v!>J8%z20370RC-HZkXZO7Ec zo~P2zYM$*laaO%vqjNzuZNoY%2gUz#>xc*;U-HaKO)hdt7I~lSm8Q-Spa_qcfQ5O6-S*AI8k%H1z_hto}&2ExC}vGy!<;d-xAAw z_e)FGOb0are?5nQqfTfg$}a1D#}S9evv)7*Kk>X*A*K2J#hY>ZS(s)sRyEk^^%d+N z0ItoJNd7JR&7Lr}=i^NamlFPLap?#ajNwbCY4KZv69Mgh9j?+O><@iV`Lr#ypmJ8|ymO_NL?gq6(e=H&!BUJ!y9^;@ z6U(?SUGB!Td(b(HiJ8;=c}5L3@hdQ=T<@+=v%FBv$RS?VIw~zK7lEAN2*1pH1IV|1 z-XD9s;1P?Rg1JITXt(qS4t1=sIwguQ5H`t`<0j!XEi8#f}7l$@kkB*%5^~IwZxz`8Z7vOc1wPY(EKx|65C*T z>Sfem_Dw@u@vihm);fEh5Z_^TN8>@?$A(e7^c|Z^+YQ|WWlFfpO!s)m;0%iu4U}`WGRcX#QyFu#0*qRMUQ$dt$Bx*R zr=kAsq{fN&Rdcf+Hxf^h$Vp2+z+58PUZuZn^12!~w>_=;fr*F+yEabpq5@5%tAo+? z3g3usG&9qz>;>sPY#dX!ex7Zu9NQ9+q%(5p^n@XCvqV#dOvLl>dr0T_{ZN$q$c$n< z)aKm_W9@TC2iu=JB%Ko!epz`^!e|j-!?yYsQm#rBTybGPmwnigB*8^?)5PSsQtf67 z5BHUSHa?-9cXu5JRyEV7HQwEmC`xh$-W;YMcxkARF0OzVKQ4@|qZ0&F%b}B_5Vnv{ zd`KkF0ia+NnD%Tq6`-Gb|4}9cz?0{tx3`R7vUW94e>D~7g8ck$J?D>_j+0Z*tHLZ% z(~$cE*#o_dG5?r0i4U{as78pFJB!30qNz^ryr7GA38V#QaU>zQH&dOux1G15e`Vj) z<$+6eqxcF%^C`dSa{sojD+FRIvR*|)N~4$`p@37qQT)k^zm67GqvMs<0#?;5qDJa! zLahr3p9{;{C^y`oc*i%D4D0@i*rJt*h6+gE2>>WAf~UZBq%B@%xnicA8t$i}DRS!! z@sPd=Yr{oxZPsvd*Qa#S5IPT$4X0R=7&%*v$6 zulc?}BJ$eQ{S$)QgMrmRRL9Y|+!ogN+n4*RWCjKHVTyKPo(3PbHuC=3b!t|;k+sY2 zBa8M}@3zizF%c~$ufr50@jMccEBzywXY~*%ubD$#uxdmmH8%78!Tm0^I=QcZexn%XCLy&8*jmI5R2_*kP4>&e?LkE|G`W zzKD{mFA<9N&PHE(1<>$z=YXNA?3_miA>0~cQeMMf(ldOg+?y6OdFovLo=|z6^|l{} zCAn~eF#QX~O}R#X+mZ-d8x<+*c*<=y$d!13%p+H_i|d*qX)1VSjtpCJTG!9lcM%kF z%q6kEM_kIhZukDazyY^oNLwkm`A&I0_aqO&W5CIjcCs=sO>0(n{Ww#1N%o3K!U2myg3OJXj^|uevcYO3|+rg7n-uVJ? z#&;P_=#2QJW>4nRXZZw`=+<{A`A#Uen(mC_Y-184&}4@(Zmp&qVkd)T+#{-*nV=aJXYKt`eD1bYXnK!Gx58u*N<|c#jR0&H6z62 zu&{P_`Wi~N>O(M=jMbIZ!q5Seg!1HxgKzP4vYNDhuG?yhF zt?8LNzbyWh;fRxM6xkCA9JRi?+^EvZn~eNn(<`t!ZLut{#FbZMZM|~8M9V?Qkx?oP zLvdradf+^&d;drAv+GPtc8@*14?RU_hQFpbGFi?9;ELt|;Md#Jn36iw-yY1_?$bg+ z%C8lmQ~uGOcO!sW)qX0S57ehoG^mFt3j8X9u`v96{n*&}gB+{FHQ}y^^Ew;qii(Dn zZKh;VpDAU++hE8yiRh<%^@E^l%7>UQmaJ+jH+AuGj(B`5AM;~}p1;bwE4(#=ul;d}Ka_VY!@Od3AmNcE0sd@hGfy08ZQ6T|FI311q{^EuA6_yf<`IEUC z?^vlD!M$Rtc7|=cRyU`-;~Sr6_LCe-PmxDpka8K!sTA$vHokKv=BSRXLnO+PyQ@loT zyZKT3t$dP^Md~Mvc!~oGkOZryhg?*@q2%k#*@SG--Q~4?T?&Uy!rp%6FspHdooq9p zeYo{fOq22DJsf)c8}y~cH>-etkI7MEU?`g40^jMt8f}Ahx1yz>C47BVzc#gkHalaR zdBhe`7~5Z2*YGP|+5^aQ{yn==)=H?k=d`1e`P@U4@VN;^v*wa zy17mjR9j6wgp+fvrpNK)T(sms@AHS2?KzG~EJk<9$VWy{4T?Zfa2QhpX3;Oz2g_xO zq*=w&*=zOkgkL)w|Y5vQVuk4V|ON~gbD*HPR9-7G1)_! zvZcbAZ1W}itxczm@lBPo^%x7Yb0SZ74|*1wx$o2Q3AGg32Ucu)+O3Pz=g-!R!|lkn z#D9!LTu(i%SA3;8b0kca;RLf1+vq!|ZoY+Ga1AB~RBl%%d4@YP`dPCnanc;k97(84 z$RcB48)C$WRh5)7<~qkwm=G17h?c$jnK_EUP){%1ct`r`I>t_-nQp?@d0uQ- zM+D~0s}EG=i`m))Zox?BtTF`DFN$aWIB=h1^ZIJtQ+Z1?Ue+)CqcW@ga6k16mIxRwFTRI@0sRVxw!}N9}LqeEjK;@yrXM09K)2` zOy&OhO`4SH5PEkJ?lziNE@+^xIb=dO;HE6Lk{tvvg7Su$5Wv}|+QcjM)c3C|4Pt3) zpNlR`qexrz?ydLJ*KJ33&K*|-TbTqnRH)*iuAlf6bU&B(RM;iZwYpXD@mIeeFLT;^ zSX$F~qkVGL>hY{4J{XbHFCzMlyyxT5TEhs1MwN?yz$}`huaO%;PeJeP<-($Ghi#@- z7gj+5>bo+%JGwM_oe)?u5NEf2H$-QKw*70`$d7@?41u41?}8$A!ijO8At!q#A~*)Z z43%Z0C?#k98b=sp7pXOH$tju9#2|fY@R$07F=Y{vciO0rsY750PkgitvlN zW#;DZIe%vC|3FH1|9#%EUCBKAX+xv&t<}Yvp@pvUug9C+ZHs@S*(6!1V!7A)&u_${ z&eif8MWS{7RJmWR;{%Vi`j^OHLm1F8pNx$?_WuA{K&8J8gbA=2tv0M&D|jZb0Pj;B zMtdIc)n2>9MCZp2^|BkBV?MX6xF&WxTb&3dpk+9gHW@tX_8SoN6qRLKkK84THkorl zLCMIIhUM(CBD2F$rkI-l>f4HX6&OK&D)%8X6{hK!+{qEAje#y8z1gy;YdFgcqK@2+ zM?rsH1;)icWL(0LtZa3qfc%^G@-8MrLztKj=Wl!-NRF=y)`HLZ7n{zBc=y}*H2C7E zaWc9ZY_z2QL~i=M=X%GaqRQWz*|-^u2{S$(pd?KkWcbpaCRO)LGdcRl^;6#EBQ*Xd zT%ylUeTDt4OX2UO9!5iyj!GH$uO|U>GmUsIbzN;&{+nC?P}jQ4Van{diM|?z*8#Jn z8qgn5yP59^{eD=3KHxZoIYJ3D4PT7-58e-wQ|JQSlb|5tpV|tciML-HN+|2)dE+ct z@UtMnuXq%!Nps9OWht#kvBC-Q5Ea!}X9CV1ajx|9(pM9$+=NG7i zbkp;R*}@BAvgVsG4VjpEqH?c{`n*w(x!Wc=r~^@7_(B}YBqpZgR6%_I8x|-<5ASNc$PX!PTLIsMwLnFSlH)~ z&>~K1&4ULZKEItf3Ha|xz9>BKg_{OQf||ds))tr#`I3eU+9OQ@SadH`@omPT^+u{! zHTrUXgL1@1ZP*4{Sk0qIXaTN={kt(7;$v71@CjYk%5U$tF3Qhmod%D!g^VDkkR~lc ze6%)+LXdz3|1=gf)FIcjEyj2IYF}@xZ^b8C;mC&auRw{ z#`%w~{dVI#3x4hXNv`$`gcea}L&gb@oV>LR-|D+ncRJQ}1_F=OqZpWhj-_(*7LqR> zbNs$UiGl4~Dk;|iAI}#nX9jZ5YpL))xvaC&jYlz)+}0@@^@=(6;mU7Z9@K-1 z19jR)lZc)q&B}|^0HOok-1AIo+sI5loNH}?*`}AbDqm@`Cz~$cu5&WnW$j)B9>mdc zQP-O!Z9XQ>+4FTAULBfs7kx~CBTFINPg8dnBg8O(&}Uv^#30le_y-y2H1(^X>1fFf#A@voO&;1XTD9OJ6@@a){y5xS;EyWsC@Q#q!m|Xwc zCCX;w_{p`sXzTGST)hqTfi>V7H&=z;>vN}gcGYAEOU*BouOSvifFoFgiV52XpS8s3 zC3X`m3@s>V*nf)P0OO#)a#Ojn$8$=2@%z65Z88W?nZ(adT(?biZTiH z{9$FbeCBQ5MuhpAcYBd7M*>i(26G@>tk9eYxILW>*Mm#-1WZX{mF6_>WA;rUZlpT{va}Mv0aMGM& z;{G;xsa?k3s(En_6T_W=xZwQ+K z2sv9tnW*BicvPme=SiCeCCZ64s~GcLa~lD*jW-8jE(Q#81_bBZt~|c~_M%pVlUng{ zpghN&$x&jz|9@)Uf~Adx6bw3SB2F+qeH~6QG7~fcF2>NiGioCH0beCG@L;=1y` zPXbt;wsia~z;OO94n|D5HN{#cE8MC^T)iAtH1Lg7&sHF!?zVAl9es0djvnp46T5~a zhDE(ER6SOZDTdSU#A}c1^adYn7YEc4qEj)2_7V)QhAaR)XPLAOLJ4{%=2VVQvy!}k z!8>X!6~OYW1On6KInEy>kOXHbbAOT_%`%*g3V6du#k!m!r3^+sD4XabtsB$|N~9(K zqlktlKErDw&lN0Kx~(%y^q@x`-$DNNR%72|)!QQ51YV>gfHAUQ-Fd;gG6?7{_9iBZ z9#ZEpnDx_#&p1;64&r|?H?Lp{tiTZMv5D7pZ?Q5GD5-uNQlu3nxqr7ke81aE#Nm7 zb+wna-iYe5H4$?j=H*4TG^`>6a=)HqeumMgY+J@NPNjiTha|4Gc^Dzrs4RX=yQ|H; zzFG7(#?Tgw26}CS7p_fX8TX6GhePFm#=f1iKkBE0h~2z8I>uCgs-cXFmghY)M)itT z^oQMNTeg8~ctM?H-xrI>wM@NrxhM>wt|a(K|haR6eid*-!{slR$s~01zlq`HX;icvckOF*h4y^PFMiesRWj z1yb5|GSy}4Bxli^n+*0aW^+Toy+Qea-GiE`4S5@?e2Qq zT6(MgWlvyc0nw8;f_^p5o|u`{qIWoS#oxb+KD)+}u}N%NF8d(oPjvCo;>0=pf!bj> z6T*U{v%%?A@|a0k^;p#L2FkwJzmqfA6_?*H#}RfMY-Tyf?I!gK+f67>NIgLZzny?r zGDsMa6gMWuX=pUpnqYzioCeedzH-pO%uyC;l(w!)`mmosu8!gu^I`5<{grr*~m9 zD!S=vWn<$WlnXWhCIn%VN&0D6?oxiu42Y_;x-#~E7AW&##s|Hiv9wgtjAfL4;Umdp z3oiyjxU5`1fHb}UY3&0m2DeyUy;C(x%}=#!NfCo>T8mNEU0}A?c$G+; zjWr142yj?8eqrLO?cCKq`aYn1lK-@zkG_ePuI>(mp~e1^Go+o@uf{3O4ir+k*pv7AHK9jM4h!X;5+rXh zfQ`(Ta8{C&PW8cN2C_R6Ld?GD70R)P5;ayb-~bX4j5K#(nJGO-A9*fq056d^x?@?w zZF@iEf=LYZBX-RIDBD#E9ZKO0o*`NO^m@qPJSfp5VVbX-Y$?bJ`Ba>ryp9)4mq=i# zl)*TRLcjM3{CYrQ-;f<&%Su-H3*!r3XTw29P_$ORJeT-`+{%gqtxb#SkpWiZr$~<0 z%C_7@*ObruQkkWkRDv4Ca?U+t<7mlWca(tKb4+E(cP|*pbu{Bz9IK5*4<-p3g0+^d z>fT*tZZvLtrqq{IF~WX>mXJGIqw1xhwLvt7Z_;Xh@W$5Bo%mBP+w1H3Ut|QwVTVpx zr;xUx8@QL(cXsJXMAG?1D>PqPo`m9{{h^xC z3>ap$jBwMzH*1G1hf-!2a>~^Iy)ta8M`MOkoH20;<}e|p`beI{e%a+NAaK|WqiQF@ z>ifDI?)wX`(QB?XT~P2cqzb2=XUbuf4JTDpDir~FJ)sB?2-NwKgZkcWujzw94D7$! z$AjwGn=L;MHsQ+Gfd~h<0rT<*n1qt^pvE4v^rDElu#k9M4LR!lh=_L=p85X7lFJ+G zUf!1qrA`s5e5od+hxYTQfnWg-ZBH4?nW%Z?6SzEfAA+hhv41L_5+g@oLY}4ZW!zPK zL%FIm^bD0`+AhaT8KwHV0vWzmlr7g?`u0Jw9L%wKG`o)DQd_~NH-^)M{Ql@LVUl#D zSN#|Rc~J;e&q{pN|2)7C<&VXXk?6QvGaR7moH=F8wRQ@UNo7(x+X{?)2a zMwTY=^Hrt`>siKNEy(l3>L`#TsMoE~k!m;k`4Z7-NZU2^+430WOk#4P#evFfG^Fp7^GnbMCrErAz4T0_gq*)>Tu3HpG7P+mPhS04IF-NB# zHoF5R4OigL*Rfg*=;`qP6_DB5?W2P&yv9>TXTqObb>GQpCrJrn?>yUh+Sw>AE|+!M z9`WQ31-}QD3M|_SiMxU3m{N#LWGDQkIwFfT^u0qHk^diUS|dQtL<+F(nDJgUz8(?* z(0-`i^_Fb*(>kowzH#_o^>nRr5sIT%q&Fu2h zjyb}{D=nO;J3aucOs_4A^Lju4{1+`MiO4}=M0^4tbI_(nd0896vga7+z<`UDd%T_r zGPwaoIoLEX4q*F%i3AH1JIT1SSHG!_X2_QlRtH8-F|+*Db8(KLntk(C{V~!Ay(}*R zKFg%g(g6-Cq1Os3s5H3VKymS?k}^L>AUDzR*Ovh8fcBRzXigPBYXj4Fu+FjU@t91}#-#N}L~NtkQx z(DU}Oc7n+(F$YNLxpzA5!m}6VMEXpq7rsThk3GkDeZ=400IuALCQ_+KoFGX_35FQS zDAQwUfk2IBglN(NV)=M8ez^!<64oCzpe|Nk*?qg7$4-S)Sn;G7F;+2Mon z;Eg`~Cec__+NU(3u0eyx3GT%+Hi>@cvQO0Mf!*vMmz-(3a0V= zMzv@&Aq2gkx6(Y5qdvqcM9@0*u_Ec-K}P*7biv{(z^5UpEx@BCr>%%o|YmrZ}^^qadbc25rRR(tu{$j)oVM zCAZb06L^AXu(jongY@PQE>2p+L2{Y8knCMpa@&<*r*{{#29x$;ZEEpcR@IjK47*OQVhmzHEoZ4mb*T5b7qOG)fcN`bV08=`i9!7B^n5k*V^m^dSy! zdXw|{4fN9+tH!2mDbj&zzP}P4sbCKJZ{qZZ!@XzR76X`kiqA_^YHb_c(%*>9M7Go? zG-;X{X-)b)=jbp~_kU8~eVKjPp}c$MLaFH3`8JA02jG)XUS~heofsFeYJHrtXQmi6 zqp5G#Q{>kU!TCHd$MMg8;*4e5cZFD z;-fv>7Ik&r=4kOcIWWvSqtZtwQgG}$=ci{qk`|$FI7e-H9vj!Q2s2a!s-$8k4nm{o z+24wa;J5RW4(>{_Y+)FRVMC`*0iF=X^xKkU)jK88ZPB}^(k2!Cacm^gx$sXTON*QakHd$)`+H9B zjYu2{cNj_ChL)1(PU7NIfVhc^cez`t2=NW_4ElfoO-0B!L3AkiQ-FH3YBEZXo~L<} z^T)o@@ma9HP>JKjH4A1-wx~PM{`bHo&A(ectdY|0Et_c9az_(MN7-Cp2gLIiu8g_$ zlnGJA=*^YI~aB(IXO9ux6o$fmTMOkS(<%${uNB3SzQ$k zhuX)x0ZY!0GYh8$`yzWyFsCPX@j#(m(KT2|CZ(S9NH_5GkCQmi8Oh5`>{3ef>P9<|G<&@IKj=3j5UsF{v&S_{)d{O9DRxXdt z${FOWvLJAcb?ZS&cHH*hq;nT_Hr`c*&P!2quWh@FS`-Dqfu6wt4f%osS_+UJkM>{< z#gXfls#tQ@j_JJQ;B=aKEEJj-;);*83AK3%n|O6pK09Aq1efS7#P%w8T#@<>8 zwtLP+{{{l0VyFDJ8?e-%rqSoL<`y=7SvNpv_Hxr^b(d-1ePP^g{_0inUbt#UXbK+1 z!Xk<1M~JU@-qVEgA>g#^G;|*vY#0xlNB3H)<`3H^T9yrzX4?5M1K&$+E7wo}T6lMS z0Zn@bPEBElpL$%_u|CF>eS#q<3Eq4G9LtFo7#) zFw2Yrv!|M!u%P}klek(?EDzDxhQ4X4ccFUkW{i1G%R*@=&5lH55VkltCmSTWwJ1lg z1RleAaJ|mgRYVzQey?HKDA7N1NO-Rh%k@YHV8+D*J<+)cL)B*k>@U=5W=4;fLg^cO zRgt2Lb3op(l;^+>i-1M)NHB94ZcnWtNT?g@A`9pNBL3cD^amAdP}O3k^2Qz93AqeE zyuXneV7_)ZPp&=V!bR`#A{!>E%S?!3IuFF~ai05GkV$wlJ;!7)TiTLkj>%Q#;=kfz zV^7|*ReW)4ye=174xk_476z)wV~;za7IYPbz%Gzb{uVKrtpozy5PiwjF3RXd#;<+g z8^EbyM5OfxO<=wc{kEKxlVMwmi7pMFCuR%2h7KRu_%#kw+aw_Wk+>OtzErt8t+5S5e;4gI{E@P18@Pu;Tz)qO* zmCG$#9!rc5G%~DTST86eP##LZG|V)Yzoh%(@Y_!uiknvkn$qjW51<^W!=DZxZv~O~ z?-V=);j-kjd4B-#NLLFKSzDgWJA@2a=e{z?Ei;VTXmt_;6Q$dt3TVT0Kk-vCXfL|& zC+JodC!hj8KPOX5;0PdpM?MIAe$^>54qN2-6+18m9)q@mqz4M6Dy|Hd^!!_O>S3mq znKd;s6Jrlkw(@eIC`yg37z~ZgT8sy(ApLgDY0Zd-ye*= z>Yvsq9+C%$lc->nzlNn~!m^yTDXrqk%aY#zioja3)xgVU=$*pg3Sb1jJ$1!uM@%dL zLf4Ob&uS+st-ndTcXV}-1SN>lG8b4>8_WwVP4x|>MSnn5hWpw~K^J2X(C&)VO)T77 zlrX;9ezjCUZUN3$2|&gY!!zL-+SMVpD}!U*OzaUE;0MiA{$4&EDbBq7q!T4OL;=ll z>^9B3C<;eTJ+$;Ulyuf2eV zZLCUV70JB`f}bBJN!4)!%WwbynxB0o5614=O@{5t-(bh{jyhW#r0pvar7Pptv0*T4 z)N3#Sq@p7QnWZK6xkG4}b3a>u8PoQXBr`5xjsi6-D$#=oUoux@G1VWydZ7KsrAfLI zHS5=wu5+X-P`oHofT?TiM#X+Bwc&6yq7Z>)HmQ&9Nsv-oHnA9kvT$32Z>_t^PJULh zy&4{DB#VgbX%-$=5PKl$hODT~R^j#_ij_NhtK zhyA}2+z;1OYW!z0V7e!j)=NeDTUWPGWXP-Mo_!hM^UYAp5OG+#iQ}6U(wE5Egm>c= z9MUOxby;19nm_0MlI{n!@g18l^lkT$!84%#EOQDqMc62m`45R0KLZDVp}}RevJCs6 zEvXFv0dOVX+5idc8%~d+D>b%A+An}(@8^pV4&lihNQTJ;j!nK7j-`R%zHGB_*U4)A z?M;9kIb@1qrxF-$H# z=@L!Qmw)k7lvuI4JDc48+Rs3bGHnc23rbekHrKHg)O#;GSy=YqIKhCm`rk)ZYHm2JDx zbD%`yOVIoxxJ5#uhO2cGNdrcq#`e+KN8_Tkf@1yqdACokRT*bvFc3j&i0+bnAu5>V zy=^$yk|KRhPc|1Jd=m{re2Zm8^npu*AYD?_M7wET|3kYO&^-+G@pUr#Lh(~|5ad(5 zhxZf5@mjZe3tFtv%i2N=;H*@x;2?Oab#pK(qHnGR%~`9b8jnagwXv0!fD5!#(EB~3 zW|vb$6^Kq!cxWUR&>wfDf+1}AThxqO)bEv5f$a$&S6P;`KPSA!JF^C&nK(>Fh}*gl zRkg%`?V=a)v+anw&^~6F`CI#~L5Vuu`u8jhkE^CLk-Zl?uO)dk0=f^eVFL=Ru1?Z5 zB@;G2QBBM!s4ZZV{4+g;_(dtfQAgU6vOy-ckO<>1Q#6$9K=RzPl7eI3VZ&n%4+pQ| z=QcOs2f$G^?Td1kahMUHWKjLZ&O9oct&j%Xdvson!sG!Q9HCs6k@XK zLJg3kB^Y=5I#2g;*rXuL;IV<>oX1%<9bs}H9>E4bCE%yQJU2^R*|{_56$Nm8g$8GS zAjt|$8Dzg)wOH6p0(ZmuZ&c}=o$nbS-xFA7(!G!j z&1R-GH7Fm7Qn#A=j_&JSJOm|-b=j1++6ByqNtlg^6!a^o_zYnyH%%1@j-8HgrIRj0 z)t>pvJ%>*i8$`qc0sy!Jl`_B--*a+?yRXF0;G=ajhBviQWh^uE?Nb<_mbT_flKcK9 zq;cpax-929UI#I4+n5gWClY;^VU?^kb~HewiRF&}iI489KVdQlJHT{DsiE5s4-6@MdH1Z?d-?=9Bx(aQ|B3Ko6kd#!Kf79Z6Cib||!% z0Js9UCB@E~G@ld(U>R(OGUd&7Yz&|b5tO5s_yU3i4hGWY3*p)=8yQ+SAXNq$Egc){xoO;T;|VjycBP;`t;4PuZoJ%=#a zxpV?rP{Kof<|)uO7l1e7M{<_Zxfxdn5I{;;aTZ5LOd;$$80Ju8)@wP=OIR-|oh;N0 zSh$qny8_MnH?T~FS|=g!F5L_L6Gj)kQ-b+Xh17uz3&IdL+e{MQl;P?6Cg0xURqa!g zFeU6)QQ9G%rgjKHK$5G4TW@PqcqR0zmzEsp_25!4%sya>EiMQuux8oX7~TPwF-Y$K z$bcIh%oYd=@{{1Uz$?o_j?GI5KLR;ZEr@?vQ`PoeGJ1|9S-YPxa%1Xv$L}px<%y~` zqQKS{nG+nVno^kp+w$thrf1-1K(i|6E4oE_j9m=E_RHJZ^?0SavUuj1GptxZ1C2*q zA#>eJj=>2*rx{S?2eljy*J=?5>q&=g0Y@}_f@(D<4ji5jpnp$rKPL^toe|v&R}yZn z_%a{>YXcK(2jjZN3-jVy0AAR@6|ZoT+EjH9DduEJFv$b5J**}L#*hnr_+rlsQ+{P# zxvPu*QU84#WXozz!PX~YL^-jni;C%tmqE1>HuzgfA`4Ztb?6O&bW zuG$ia>L}$6r!$aje2#-Hw69e(nZ`%uOux|CuZieS`Kwwr(`1~wh-mvTKmZgWCb^oR zu>@(m1xgG_fCvKp<`x5FsqskZQBcUv_@1R;3J{RQ2W!K*X|tqv3QFghpQ2=nM}M%zX6O+wR0Nj#$z>Y*1;X?@DEUPVAt1gMxz4cM=~oiQHG|(&r;b8Dc$hPy=W$LoZ_cSOwaLSvKXJ&(tAo?o_@Exs0$D-Fms? zPTC}jn%Ld;#q55fbO*umY=9AbsdJ(=2ACFZ3iu$wa9sGrLTAMzPd}2KX{AYODJpc| z>1J0)rcS9+m=ffO+viYLY68><@E2FDC~4KAR$F}Dv;sTbDhJhdYI7k@>$ZP&b2r4e z^W}#Q9sA5U8m$WOQJm6(^g8B`tinogH2Q`I$z?wlo3%Qhji|?C{&rr0??o8%0Qb-U z07fn|MYiLFC;-F8UFzgf1)~R{*KrL>c*U~m^=Jby)A&#Dwj1GhtVO!?KIeS~JatN- z_6B4d7IAM&8s2$0tqE&?HRe~JMewCel(`-i1wDI(A0I+-GiR5BYg=@BI}IL=%ZR%l5O;JCI}SAZWqVVK$|7jT)cqZ@AG zI6yvfTFS9`MR_!7qm_?&C05l4_+KNsbYr;TAA9FY{cBP{*ThUEYqBPTX8CABm8(nl zO8(%I4=wFyY)jFhEO}c{h~)0aWa#7F6!HA)bE6WRrj&mHYjGX}S(?Yy5OgQGHX|YJ z)U55>CF%4dRwr=V(SF}n`L8;Jsqp{nfd+=lTZ6NG|>T-J*VWe{m4G;9UHpv^B(T~z897O(uV ziV4q;m&lNXIhU;*%TNE>iJN$+Q(B^O#(~YPN)AJaN{pYs8uN^Z>yCc8#C$5ud((ijcGb)+SA%ZWi-+kSa=Yk4YGn(aTE|q06+k+ zQAuzsAQDz}qVVw*Wnl=b7hJgu6ozqp}$}Kxu*ky-xyG0DZy`A8rA`s|bxh zOD?sXItR{SDPj@9iWXPJ*qTlpT8t*S=&#vLV{^`JrBgup%U#%{K26>sr>sTVj&Lz& z9ny$rvH|`O2>e^&1L(vbQ}|*<4TSzK7(L&~>B+Ldi_twhQWmx+Zamukc) z7oLTBb~yj){Uojr=wO8ly@6~-1uz1Z%*!v>#!q|zo+S~YFF-Wl@DF~^;jEROk}x&~ zaKEFs$~bffPPDUIyO?bt4ze??D1tL_@~c^h??+)mt8l$hp2RUwi{WmS^2O_=HDs5* ziH@H39a?%R#%Xvbl}WOC?H68=OfItId)~#(Yi0>D_)@7|)$%^JkAjS)QC_@lAmJYb zNoOttHRZ{rj_m;Meh&8Sa6AV%zQh0ky*hwJbT@zxP$5ht#1FRr?%FUsa0JmB?$Bgs zVlpNMNd;JMY$xUg3@7O8+usV#gA`^d?wNlgC3+qeR7BA;)d)&r#9;AEezlTZy*5=5 zg6T&_-9SM0Xh=8tdjMAN7&t+~%>vo-Bi*nA#PVx<95=Quza>{^`p-X+rd{=!Bavs&vbi)w4N+JSth%KMEWLOpSJ_3GG&W6U+FkaZ(;- zNRe6N6F@}yHzx}9^MWzXV8*Fs+4Xdvt`n4rusMDq*z;dvg`Mt~rq6h*_5Tfiy=Tt0 zoAd%Q$;#-^dNz#rb?ev9V4iUtsn&A%9i!(kJv`Cc?S?D$^I~|B&p92~$ z*fllo;)VtTA{y2r;8QU`^8+M;7~u^zKqPLX)>n*$z4TV8E$i_v(lZ1|xh8f@S` zQb9R9oO7{?&I+^_HS2LmTktb@TILy(?Y$%}rBXwA6y9j!dxE?VXf-n!}rM z%U3m6OhRr2;v6345E|^YM8_VH^K{><=3Q}wb`uvtWm%v_bS!sBZ`X+h-29KGT%dnlytpORH1=aL*Y<6N2RSmX*0t8p z>Ddp0?YjVAyqrH2GzKlLa{4u{vC?@eonH5}ON=hfpM z`PbEk$w*0!(@8Epcza>b4v1^q+{_M4*0J@m-1jbn5`YN&P~zq)oTCw!S5t#As(o?l zZIuto9vI-Cq5eG1e<|0N^hC* zRv=z+>2Na1_~Z?@lV}Squbz>3567XFXW1UoyNf8*z@%fUBIs5GLYYifZsZ9nGyw_w zDMHxPyoV<(PPU}bVtUJy^6J4Q?1+jx0(`mhe3D1*Jh)G01y&cFrVJ{O!~!vmpX&CD zuCok_1<#(f^1v$18(~b8pp6J6wg<5wgS_IE$6JIl5u~HUVc!Xf=*po>c6yn@1Hk8x{8y!}Zo? zy=&t#*!t$rUF531j^@t${I(TH7mm7y*Tk7=_;2*Z0i|6l9B=RW1HTP_=24%ztx*Zy zs)$SXmA%!02qMtY7xDae2s5kS>1dTZTiJze$bs6s8qGpYy)lNAQT@}0{9yY_c@%#| zz)aQ{Z^;C55CNYR3z3!i)=I7{b1R>10OQFatB~`uoXka9DsIIe| zVsRA5cT)IhyG{X;bJjc22X`NX?^m)&rkg|@u$x<-eh?ULWTe|rbDdri`DrDsOFH04 zIO2p9OG!9>-yfz+jPRjHtpNVZ;@6d-{9Rze5W$;B2(=<&jnU#0;>1)1B;NqSQS)!Hyf$N<$lBq0C_s>pzj z?ZY}#H_tou2%jwO$*Cn>2L~J!btejU8z1w3@8Kf+2CXNgYbmgT*Lt6oCF8!j!d2^0 z$EGE!!b6l-0QQq%HI(yQI<9RCRufzn!`+>>Rj9C-Fned(rSIlUNnmnhrOHs3vGC8= z>n$84n@B_r@;O(?M_-NQc~Mu-vZl|*UH;C182+Y0(wPlqTj)&>K(^J$&{zwPet;-@#7`0f6Jt8w3R~tt53S1 z?OjxGsEU2wrNwF(8Wp3ijF*6@JBz?K6&(8p16#6*p(@qoI5EzWue$<}KeM@Dp~eVJ zX#rJJM_@Sf8es8E%qPDnor@$aps)b*6%1>d^C%ZlrgZ>B8kLP2rAs!R@ykO8KMpEi z^hmOK@{84?#Q$-lnu0bxhUI2p(A@=*nms?KKl)7v`QwX~NJP%lGE;48A(EPie;9I- zbgA_|nTj&hGOWeG8@i|*3UUsnGDt+FudgY0j3Ht4$$Amu3K_x&;IuiK&lh zU)^Mj5{wfEYoS)=RI8y`8xuyX#D=7o`9zT zG0%SI zL@lRGdQHO&rg~)$Of0ZllCCMvQQDmD!(psYRO0)x-}o zp~7A;H3U=~pL+``iRCnIU+Pvd&T;FBh!A;|fu?GX-ZZoUOD}rL$d|pevmBOyYt-#B zEcrhuRjni($Q=X~iN!9FsFZcsAh#6_?&A|^pZlad;eHVz#D+~Rd7H*&T&-7^H(r7- zy%B6ah&{HsMgzo93bZKaezqrnZwog^L+1j^aijY8b}jmStNvUo+4i1xej_sfW&(vQ z95nz?1tcS=#9}06q?Bdd+V2|8tjzD=k#fzJjr7A(N-$7!5n85m3yZJb{uuHgy_5GO^=k@R z)J|I#4M?Pu-BZwPsEBjh+<@mPnO2H%@iy_Q|3it-u={=`{ZYtUL|^5U4tc#m$+%D$ z@5-HBx#OMszJvmEd4LaZI}!!JDtf0Pa-#7-mIV3Z-#LR+7mU|5VdOJ{bW3jlVvEq;kxLP_l_p*+$Byt0tTJO6vSDVu#+L1 zHu*6b5qRw$(}9_fRa98;MlT0MW3s0MYBq}p^~Dc;ry zp6~<}T86rS6!X)DQyO+a>M*&YLi;$ZF-RyClYjsSDznN=u+7HFjuMWN07(&t07ppN zREL5XVk&)_Skjby3DEZ$eoz`cp)dddTMO4V1t|Y>NOYLjjB`J?3HBr>^3$F;4rJQz z|NKNRYR*hSo)t9U>$r}ENaS&=RT-M=etKHl!f1^ghxbnEQXU`MZk3zNs`O<%WN23A zuMi)ABI=ue8S+^~xlfz^u|4GXh+g^$ceNax$$}-2EKbw@MRVD5j+SH#Ja2_}9#6x< zBk&g8vV4NP3rv}IaM`nDfNhFE(B6~F?9YrgBLHZM4hAq7E1H|w8r){@ff=iq_C?M$6 zP#M32c8IQi4o7Vv9Bx6@sNR4xKrL=E6N3%%j4rAW7IG}81Aj!r!)i3tk{^%0FGj^l zUv-MhA$k=HDKQ_`yW?8_Vs!z0+b)QHWlQXtjI|9NHTu0{*B$a+M^V`Ud+p*)S@5;T zv|Ce5tLl}1lH$j!ldTg6O0tGCV-&g{@x=Pf@FRjKIs4ZcbR<9MFC@i?c_L`42^W`b zlSfv1xZSCE6r3lN(fW*Q0j7`$zhJ7ORQ$ceL({0*o*P}WGUOD*w%A#!4Iwh z$!HQNq?Hg?8bp~CsQraIKg1%zH94B2RmP9I{jhyFmCP^G(f_LHp|*Yx?Pw%_`r*hg~YS@;?KR+AI8n#LaFM}Z(25=r}TQUS+NKR-Sl2XI!k+-FM-9z z(D{?0{PAjBfFT*#y$nfDLQhE_G%?k~AxUPwYfy?6cEvXFZKp%gl+GB)fot(am;Yn#4X4lD4YPf90?PT8|d#p zCtO81-%;e6+(}e>^#vQVAAPf@togRyiF`safpZ0LmL_0Hakmd85p>BC+;USfB+QK0Af^IT~oWa)mNIPEpKe{n^((+by1}H zyKJ0D42CYCgwvtQcm8=&U}h~Gb>qAP{X%s7jHMnF-K37Ck^9j>8NIf-in3t~H&fDN zs(*b>1>-*K$fm>N!gJ-iX*wSkJ#*aD6$oZXq!v=t_bPAhgSXibUd-3UT}#e_Fop?_ zrT(bANt<=D-*tb1$4_`FCM3l>coYC+pj0&bp}$hH zFG>NAhu2TGniTvaDshc^#&M7fdkwnCm+m`Cb?$F@&wjg@W`543@H2yWLHGTKK3!|l zCq_67118fSZi2nFh5_fpa;p9IkZeQvy>vUB9U$!Mk7oO3!OY7Rmt3SHfvJ98!s5cE zDm_zuZXWtp@0%eHU@u+Ut!F35jqqin`uPGwG;8m-LXI4mg&1IS+bwyGralqA0;4wX zE0TLo+UjH}&Yu4x&qa($IS2#~?>;K}CD7C0uFQ&@qczHp<-Qb$nn^$a5S@EA!J&44 zQB*{vw9MR=vq)}rHJD_bWUhU${l>l}0oqQ^^nZ-MP%PU|b-@H|JZX$KFJdh9<-`@y z1WaP2JjKe93^41Qz)@I#AT|r)@>@AD!7R;8pojAy4r(%s4t;Kd>7We#QzrU4kKc8! zREi)s)R~)%lsTWOkS5~EdNO@*X`DDnv;aFm#J?s~kT>gp7chuhSPf>=9%LywRlCo* zm+$jnAkSo_Z5(;A2Qih44n~<&p8V7FffisOJeaTmfG;hsVvmAU1X++B2@f0xo4Il# zK+8(OZIa0R0z5bHNG2oTjOV;(3bSgBH)e0c=Bd`XRnh|DV_ekEoGn_DF%s-WM-c$O zy9VKEQsWcEI5hE(M!@!caPH*^nX^HwG@jFm`7$c1`&^RlY!7D8)Jq&i^T3EyPS`2{ z5AfIS=R$#T1Xmfa9>v!W&-kw~WOZ4Er5)K7A}Y>QHTNsGT~0W5Z6On${X)&wfQtwCwl3qD3l8^ua4*5KY z1RBu9DS+u8#Vvy6@}Hnahy=CE{2f?1E9|DEawEQkAShrI!@~mSM(plWqNn^!*GJ0} zGDKHQ)D~RqvsNyG!atP0ad&eaI4Y1n^{&xTqXhiDw$HbZl3ekb3?O~HVG-YdhJuzb z%6wx4t+A*Ql;@$k`irpt&O&KpQZ5RSY-J4j;lTEd(8!3i77w_I2M?z>=+_=ap=7wD z-uFj!8iTtZ=Lehi=pjoL+(}DOs6sMe5Zb#1F|3kRo)U!HP#;M^KQOWxHFQ0^<6@hr z#5SXG9YHjg`A0-Kh1;hZq5Oyu3$lw}d8Mp)~ zf@ztt2r1o3^ck)+1OY39bIw^1D15y7gghkJ59ogcu976X16d*UzA_zU3^0TihTJ{u z2H;)=!`o84CzvN0YG&2k$2>~MQDn5;zH_+4CfD7QCelNE3IT7@CMSLwYPKV#jJf4; zY9d@{w+D;o-rA?}6%`z#K?J5H%X{p!Tcd@U0Py4nh9ipf+mS zFbrrpwJc$n<}(tq7W^E;u=K4zZXl6SESVs2UrkhVsk~NP!PE2BxpR*~mue1Jz zQ{nE8VGo8Jm~x||GI)%HfwlXsX@1G~7<~nC#Pwk(wK5r2eg@E_t-K^hxvVg;^-Xx~ z-dXa+E>WGj@#usHc$wwQVJh!{0S;tDVMq~& zaGHyxr&^oet{OY4)R(lILI*)_M#T#+?eX~?ghF);0#JkhXxgJ#qXo0QSLf9r)CZMcGju*~*tpGXV+~3GZOHwu$=r(3 zja%5jt*}=}jX5VU=12N=Nx}PBc$hFcq%_QV>(}1qR?B7j6ockC0S%m?KNL-DO+_OF z=L<2b9=MpY3Da?2U0z9WikK717071*7*mM1!VzjgI;d^O|6ehUm4B? ziu;OVMigzK_MjLF75#y-k@`yI^B{~(?6U&ha!FQiJ%UG}dzzh}YIJdy_8C%8^E_MO z&W(L78d%&AtZY6DzgoO5i*;aV98$u?{%p8b%Xq3t!D#H|DV5zq6S@HesR69>j*Z^Lb?nj$%KxjRnxeFuZ+w@cyyWmIrNDkXVBqP8U14> zRfpwTF;eTsC%+o-no<)6z>!i8#)lj+ZLcD6jgG7>2pU2})ZQC!))L{LxzkEwzU8Wjqn<|0MPX!$6u(~00@c`4HuG^RX896oLu>Ecn?JSINH_YWB?=i+khmY zcs4PrZoAdOoqsrJ%7l*nrVAcP)Z@78CKmM!G33{Lx@4Lx5CGHX|4#EH(g}pz(1%g{ z4pz7}=b#B2+8zGr8TPd9bdwH%JP$gtq%YA6e++Sa503P!OfH!2XRJi~j9mBT!7RI| zOZIU}p8K&TUz%Vm30ave(za|Tz6v2-Hk~)8U5)7`)czJsCnNW=zjE!7lFa8?*2%rhNW>q{t4l7>jb1@GQh82aygPEjb_o(xg`ug*s6jp}Q;R?>D@t?j^ zMIvX~f-Two-s%-rcHTsMeBJ@Uw#l(Cd$ob&X);@UhVn)S~n()1PB!8OvPv-8-}#tK0owb=X=LUcMd`GYac&_%ty zj*DrNxS8M)^q1WsXIZSx?Bv~2Os<}taS|clNnNe9zTJW|?0z=N-A0}!ET729<`C4f z^VmZzGjtoi6AO@2Gr1q_T$po>zeRLg!K}cb*m$WGQJDBCi&OWFRfcmDH+HoSBm;F4 z)V4g0UE#lRy%p}IN5#&d@{vR)#NFC*-fZYK zExuGO1m2tVs`Wl<9TOQ9x`xH^rPPMVfX{O4#g*>SoKJ_rDC+|ffAZhhRn$8KY@m89 zFJo!((b!ce_7IijdSQNAtAkB|8X|EDfmpbmPY3pi6>#W2Ds~T$+O_l<*^YdU7(BRo zh>XOTkgsg>6jBt1yC;PoptXRnnLwBT!`$bIBW4%683s}aNgUGvN+3WJ_%y_b;z5Ge zZ0wsu7aPSK26h~m5qU~%|Bfd5xAoslE8VgD^Zv-OvoL316cAsmNNJAMQIz&CS6{z~ z@!8?b=Toe!?W07J%X`S&GxE~tPNNaIj(TuMsvwm&@PERw`MF@ZzSChYOMu zsQwWyADWBwMQVS_h;@4|Gt8I-t*!$%m+&WCZd-ufQ}LcMX+j064J5XAd#8fv}w(iaDv8)He^@JG~S1A<``fNTQQ(A zG8xt*P6yO0BXGImoHo0P0d7TMPClF^&pQ*7_>szmeEGVi?nwnDqVNwX1NWev?ka_m z|B?mi=rxTkQ3}M@&pPI7P*uN3WRKmdsNb-!JQa&u%JhJoYyV6KMb`W4bYfZZt}N8H zz~Ik(1|sk(cP8A?fgdAMuqA7@G^t3jR!RD&;Gc=+JXTW!RB5oO^EQQ?q zi z;~fXYHdL+vIwN8PcY^JA_ZH-cO{$zmt(S={9+gWJl|yzMx)7f#cRbCM&+ zt^t=b*dNk?jPyN$;j9Zz_O9-5@sTDNxIPnaAN1IGeiSnzcrOLB=)PkwGOH)|5qF-V zf{}mMwG5KXO33qUSK6{39D`4sN30e(#fc=o8_XY55oS;u<&hKDno!ho&PdR@@e4*J zD28bZjnDA$Lu5giWp%r;f}crAe8Q)L7Emy4gAHVP_K4RjXdW{&^mMCSM?qtia4_ki zyhSG||8M5mLD_B{Q9`y|WK6noi`yEGCO@+W8t1ioemA9cq+!Muxg9-@_OdRn`5$))w;O@0m}UZuDviB`s}vRF z+yV<*?)ei;q(t?9bwbJZwmou7HkEGRJ=w4;*p}AENq#xP=QU>yGzQCE4Rgb2knSuR zYuk2snr=k+yP(F3t*_PBHJD5Bab^p-Ya+iSbinsk^pnxnXjABgqjT^Svn3|q76tR6 zl7!GuwRl|qB~AR!r*tk4)fR!9aXFVuB3$htQ2h{MG~`G2oyhHwp(**M)B?Nd`3~Rl zB`0{_4H>T#FC6$|7~Qk^pigMQfLPjTo|RsA&~s4bRahDZ=r&x^W#7en34UX0e_z=4 zYw@A$4=UI3rZL>Ic%!6QHTSWopAMa!niy}Y3Li~0L3lr=L^~9kfxF2 z*9b3OJ#JZKt*kvm<4OVx^U$j)m}lNcQeg?dF_zbO$2pS4;AGFOE~ySJX1gPfuO932 z39)d67dB>nL&}}W*tp2Sq6tKD_{M77_HC#*W6?G|ME3+5CRke5tn$jo}F z?)r}<1K4=bw_56;DEhTk4mY1vMBV?yU~@;hq^VQk_U`X2Ti?wW2rojZ6VBQ1SBsMx z+osc}^SGi(%@!n%VEyHkqNr`hJ0slTAYE!Zfr;e}R^y8kY756Xmv$#34oaD^af41f zq)@^xUrEuK+eor)oUc%~k8}0`$cxX;tLBIZS*MUX{J~%YT{Z}c;m|_tS>K%hK@Y@y z;Ff`6S-l%Kzl9OtINhOd?>EH~)3fDn1$&Navb{?W)?s|B4}!`DDp3%mqD=bbZdICx zl9O+;w)>Gb0wwC2TDPJon8c7UDjlSzMw=-@%{Nx_HLt-N1CX7$E{%^EFK2NeZ?-x~ zP@o0k#!9V8#xjqeWDf#nMR{;t@XJ1$*N~!2TAPc2(6~)=^^yj9C$%>ji zt4yNEIY!aFPon=M;Fu%`dv9jv=$|Fjl$A=>aZ{+xlaQ+ei zIAHPVq7azs3B4>};wwEdKMGLq4bX#xwSFWQ5;V#8&IMe@_@|ZYrEMK2hMi#&m?L8=3GW298K%nU#r+FQ)^nNMB z_<3$Qx46?pobOx?4W|Rhs?7p&dy&SCDkrf=!`=x?xeeVhk%(z>7b|g-70=k^Vx7MQ zowwslo;X5YxA4m<%1E04|84Qk*6_;bltKa)Nz3Nsfz2Tt%7A3i$Cv%Nk8^tgHKw zH(3qPLzWcmBis4kIIpf5VXzC1u(!niI8`FTG|O)qZT4;FdnG64w^SJ^BuGp(dinKR zye$dyRNYj0cYFPm0ENabZ+)kl*BK5pq@)r21rL{9pmtrdFrMuV_!hB|l%d*8N( z1-^ZqIzSMHuNOOObEKDjyHsi(ZsLJ}A!JJ z+|^q-O~O(!?C^09Ezt|+lIa1L)n$Kpr>ze z#$*WLLo}oBo0Ij0WZf^y+m4Rj5?xESoJCcdrz-j#vPjKpGu~W@A`z33&*}6e8H4n&JXc&kS3rODDY;;X#U-q?3*MxS6ZOg zHjvyFPKV%keuLM@WOKl=bZSMKUq>MIsGZ8>rZNxB3ts-c$NxYN87W*8`f^c z%3~oshW5n{mflz9LKo(esDPG#7kzvo%(H%9s6H($H1dpw3XAI9!MuFq&KcS;RrYk` zhqT+bg{(=+EOzW#Aqcf|5t=@1&)o8(5}y?+zeI%DG{q4?ek$Q{f)7WRduM)i-_Q+2 zladL95YK^OO9)_g_}AJ*q;jiT>@liyrQi$rMm{Es-lyKB&;G?Ez%c7OP_Ac=I-TcD zh?z=nFeWmvfwvPRqc92h0I}+vul}Osj;4W*kQg8)6U29XTR2mSvkr<(H*g*S)C0oL zqs5kwm-`uaN=?e|C~Bt%*H@yG<1|HK*g~Te0IIP>BATyU9Rc1sQtyNlbenF*sUdWT zdqaH5G~^n1k#z)dTed3!#)v@T;C~*9=>tdyf30`08EE8!CBxGC3Kl3ZS{nF+x22rj z$%URj?T-2bk9|o=R!-Hib-!ERo>5n)H-m7uWw+{Pp#c+PXEs9_UqUtWrjqDOkz1e6 z?NKmNaB|{i>Qs(S#%yy8r$JG-V?%NN;=ZVF3yrpu>Kr^5_HxI0JZa4GdKG_UDZ18uXw(_4^iwUFV6@j_6tA*rOwD#J4_3W&jL&VX+ z?c?CnePD%KBTGj`1P^;^=f{-m9|RQ@eappk*mhk2&!q?q0xOhIrug5zB~7O#IA15W%#JL-huWB)GGQ`~+_;mL~JsX3+-eqF%t0xMZduHRd}N zdvI6rbQ5O;8dHA~T+*~vjJhoBK9PyOKZ|;~)cyhJFokr!kV`;_4sHNr+YY=<$zeF& z8QNIliz1I(0@;|dU~d?l%{d!F6XEXE(LX)LuR&^R`TzJ>bs@+BmHmbMWUozIj~=|_ zIkkBF<1a)G^KJ6K&qzFQ&U1n z49wq)l5I4yu$jnNMw3kQyYt<1$g(|UPSAAwDLl9x?Tk6BQMSL-#sOU!AW5nhv_`ir z(o)i9KiexEwd{;@4%aC>{V8WW=WRXjAgfywP7rgBICX%QO`9895>jR5&uiJ3GU=E^ z!XBs(Uo0^EkLbt%{I*C?kd`w|xE*%v{h&!`neMVxUdf+`evf!4(h<8b zyVp=7MlktN9jBHCtow<4M9YZ@kCSt_|q=glztp8nBq3iiVb`-dA3U zYR&8mQ(JfAJ>QdSICq-?jl6Fl#EJuIh^WLGotc7Uv+sAwrCy6OQ=30J(N40iHocpm zk{6j(ZNeh}3R%{`;KCjx292TvR7;kodEO-59I^9B-#f0EuBQQ-aQjQs4Dxc?2Py)s z!`r`~G-vxRz{F>ebl6MkDsA}Q)2GXIIfL}u);3A{>&OA1-8u&LM@Hn4Mb}uW-*q0 zuxwCht=U*DrHm#R(fsZsZ$;q_p#dITcmS|?UGBzoc7Mlt(p1vvS=v)zvtN1&#BmWg{y`wIyjzeC)7OoQV*i744Wz08bYY z5bxgO(ZwYRLgNcBH9D;&v+li9CidcJH0~A71LX9;^>>mxbP?_r1diMxlqyqvbG+xl zBpCJSQ%$UWz*)^91hXQDBKNloMpAFl+E8bWyf*8nUn5+tJ^g^isffo2<|Q*gmdP$_ zIMK4P>8d|$iTZtmjv@LQ9`EP8mc0RXxkD&*DpLvvVaFkM%1#VN>-y2|y+F8~XpYq-!jLj zvXUDw^JsIE!ztH*XNf2GMa%^(z%^kv#N_kcjIl!C#oo!IDyN@gu)H7(jwMmADKAW| z{sc9uN96%C*}+jehJTzp*B*DuzlB#FMLv8vrqpWo6|CFFvcvjDv3j-#AlO z;J{uVn`8qs_4LAP@TZU4FToz~d)SKhQY^UqFsk-o^|pcuF9f#RvEq(<`>6HklZF1Z z5ZA(T^ccG&<$Z?|f9MRoLCR%GZ9Q?>dQXlLzEQjTw=0p4=MmTh_7f4+v`G9`b{RyA z;-xoF2E^T~FRkrTWq+RZGD7GYc^nPzMe)51z%&t*5ZvfR+}^Tnb$@P_F8AZW3adiZ zK(b;y<$(Db5Fn8;f1o0b&PcwBPmH~F8SdI^hA8gmk+{2t>U5y-LHmR1myRsTi*H97 zLH_V|sUg@Rh9@4a@tPEU0@kZWFKICt;yrQ_Z)6TS;>_pYJP9+_=t;MP) zIRi&vHswj5Rn1}6+ICfURtP1A9*`XtATi(a#*Jk|ly&UfcljobxH7nVOC*1nXA3XF z0a-lC`?wl_i&9BMR+}_G8PGK?FV@cu%`#2p{%~&%GZ_d1##bjb1d%C=?@oVcH zsgT@wtUjT}QjwBDie6#2^i#%Uis~^#C-I2~hms&+Xsf$RxwEaNSLPtSv@%9l`50Ot zU814c*@MpPtAeVmtRuK8Wp@ouPBi`@UTu|7oQT6CPaa)BDa>{@$dT&Sk0f;M57{WrG*@Nxr*dX@JXtA+ezP>4hp7t zOQqSoi8}I#usa(evx)Bx7yTdO3CkQZ?m0Z|&G~7GDcv>Ak2)L!K|82^ekVG^ZBsE=(={nH|py6X;xry|)q)f7D2| zf`AVH#Vyl~N%J1>cnuD3h^v7k%q+=oAJvYVb_SgKwA?L(88t=KTe=GBm*20sih4f; zh>fXE5=K+5IzQDvfA!?q__M`S75v1z6V3&Hdn1?4hwp(5<^);I6X&HdiJb{)obyls zQ%oFhL~xF#@K27pgfA$O$`tOr8(aLqcJotcbaxS4EcEJ^Oy!go!5)F6J#CEYSWY9uYJaK^#xj&pzK%CBj9f4gt>zfU#0mo_mGE%qAWsPq+MV)G+RO0r(D1n{hUc1-ZEjj+0ZrjmKH;` zkbs&imtQJH&YeyV-@Hr6p$1c}I5alRO5tx>tjsqa5;XG=!=J(MI#H@91I)gVKTg>B z+ng@kF83#?&oZLeLq4cr__A4idPTR<9)+)5pIl)>i;tDPc{(Zk=YjI*>M8{MZj|_9 zBn<^BvJcyr&FPL`Fph{i?;w#wwQWlBWijn1BfWejxC#AbVJwoEuwD=)w__i1Kyy~~ z;drU$p1aG6dR>yJJ|l`of-Nr$_)C{aTAtPSNvSIERar389 zOOh*n>*|S0q(}oG6GOae;ls4Fr1Eh6%AUvY6-FdDGm>x)X~DdbR=G2_8GR5(PPSFm z%VoIyIundVvwmpQx8;U6P(@|8R%burxbyE)26TC9E|+v}YVrSisWTNsY?tgSmKi)2 zH_cdL3F|5cC4UuZ@7!M2nzBDw$bk8>vEEG6WAHP77-%!T1w3H;gY^5AHyExXKdr0` z#wH*YiC6Mr>RfPb*h;d=H*v#k{<4vjtKzi7B?SWsU!AGVFiC^@{|itI7+FP@IY%Y| zNMQ7DC_*2F$WN%Q_!mbuw?1w4X>{-&wQdxhFfoWO-LGg4hrTc#A8dQ};kMoz@bA2; z1^9f;9|};<3Cu()x|WG0FrMd;$Jq|ls7C#Ks%A= z(E%cOvCAcrsT|z>qx)!`r3zUSpWaF9H)%pMh??nWt(U0|$ZJ0BjZc4`A)5dRry^wD z`0p>efxR;9Hz%UJ7iDa2Z4N$McYkMP%X7c?iVw>Fgs-Eb*M~HHYpT#jPLb7vhu+urQExQOD z*g!XqhegGm|BUdXqDrX2pXtTQe;6Z+eC`=~5;p|K5q#nu*2PUw+^KenMcBECvOBu;0fhIwBskP3=^40y8V!MZu(EnK0Q|*yfd+RdP^{6tgXFoWmpUi+&V+)`k}&|7eas##xXeyNd-M( z2YUGFhe;c{YGYf+)z2PpHFq#1Xur*VnilG?#t{OeVPAa#uJeq$hE1Y?`Yg4yABI`j zkwD3nWHWMn?hnKm$ZI~k@l1NHD;Ai(&7pyZK^DX~H(_NqT9ybDt##8FhQ6cEpZld)<$DAn1HZ(K5me)- zBCerhV$;YnT9lk&jN~SYE#QZ?bG^{s<^T?T(DMn#zc}>vjZ`r)rajCQ_|e2U55kZZ zVx4RkA+OWTTo&}uWr~!v^w1}BNuw1}*ek)cNI!?dRGK`5%ya*yCA+jV`8!nxB#lF= zKTrI+&y|B5DO^A$?Be-33$450hvgqaE)jt9v(Cd%|F92+Y&%#q_b3mgFb$Iu~YX#hix8Q>6f?Dwq6 z`(U0OdW{`FB47abltN!+7)+V~ zX~i<`;u>{P#Y~kXCs8ZPQasuDm9uf9LD1sPAfChK6po^=1Ob$#S8<@a3xx?43ACt1 zfAo2JN_?E7s?!}48VF0hpPcnDRv5V9qijqt<-$x7y$FCK*QDdHppZBgB$fJWx%n{j zDQ9q}SNf8aJ>NH9`!b-2?kp$33(RqV;?t?BWr#Nm+ZCqAgM+~cAFJsl;$wY-;&Ukn z0)Domrg0<`KnD)v%jG={LCQ_z@NPn^j5}O?BUC=tLVm!;EQd2<>@{9$lnO}`G`58#R;x91JTYHYjamBPf0c1kjt}1 z;y0MZ6H@@K$`{sX{J=9)6bW2N>Ua59S@{`DcYFcK_KO5$cIdd%OlPpPo!pSy^hG6R zN4!7qf+y+9XawxUGcLRUv^Ahi{TkjiR$_e;1Ca}+;F4DW>YBC^E9^|-x#FKZL6&+A zQ-4tLt{f{}-?PUSa`b&q)~>l&8RQpXs0?(aSAz=uCcAKOYh~sB2#a<|4N$$bqj4lT ztX}vr6RFXl(0?FCp_%MpG+(tBn_#?bMaKg7$g}CDPEz~b|Mi=zp$~g0r+*S>m4@7wm4C=Y<4f68JeF4|dF*36-fMj5 zz+?-*XMIz3z7b~X(94{}Z_o)_a}7)R0Frn7NN61Wgw^hel@2b(APw&$e5J6fnnD1Epcf&saU2c z;QZVsD;gkOV)|}g0(g(RR-N_r4fC^^!Fr8K#Si)qGA_^;Cta~UYR6AF6ZDPiKv${f zTvgM$cCG5GROicgFxPc|%GZv_Xar6;Qq8nqz3T6zt~`Vv{Wa{=SJ2v-)RP$-Q|!YI zbYt5jpOl`uZe}(rH$&7K@j&{)mFUyx;AHn})4cjE?>8#qBxV2TJ3bh$+$z8hh-h z9H|I#e4COTdVE>ztlq(W%OqiyN-_ZJ(DB8MZT=v2jg zl;9Vq*mF@z+(&Y{P3-gk8g<;;zLXcN6~}_sLjA=8NB)w{%T=-Lwj3*(2g3*9GJwDs z&*3TI9EGvX!EOwFk&mqX)aHVf&^(tWab!1Cy$;gTXGVD{9|H1Or@58wWEG;$thk%l;g_Q!J3YK&Qg+2OUaVJd(*=|xIb3+E+8Krx%WR9UA348J^O+B2U{Z7Vw z)>1U;3hN1uY4h}t1mYQXmE2b_#+0)-9t~qQm0Aa4OpHqcy9{zOcELrKpl=B!!e2VN z!dGHa&YTkkp=0G^xSCZo3?4#Kq_z>>>7$Bedukxqy!wRg@aT zb#?Ha?;C91B1D&iHSO2qJA0CPZoMUF=$BN{qy`d;(O-Jp^6yn5iCQ~9brV;-rEV$H zfdLcwcunwSbr1rJ?UQ6hh`=Xo7Vq_hN5Y{3k3+(6{0&3OPHU#`YL z5{P-I*g{;jU-V^938T(wPou`@Gdk?I zjy~1ONGv81C@sXd^Fp^&)EYDP^fE22u?Zku@L!(HaC*-F4ZA;QO#K5q4^X+q3H-4n zu9x9&!vgE7K{4nilVB!FU-=G_l{CA()OQxQfD{^otyIK1!FXbU3`;C*Jut0XzeoYk z;LdC)uWO8Ocwy*!p@%Lmd752T@XvsNBSW*=G09m-sdu8+BUuBV34pSta6&vjP`Y`X zT?#%1Jp|B3%{6CK0GCgKuzAj?{^@eH^^i4?giC5hd7XZ|OL=iy=vKM3q8toS_an2c z$LUN+*WhJe4|ti|ab)Wpo=7MxUJI%_3dcrl4G_9t@sP=}JPQq6fB#IZ{M;TVh=bOp zt9br#gis_JYWrpg(hwQB{r#7WnPh(;-$!zkBANxC{6Gvu_f4v5NYYevC6H2D0m*mX zmR{e%bJORqqH6T}FQr7qJfHs+RGv+7B8hINk;;duryn|VAua=c;*DFA98(!n$Oy(6 z0f-_A>=K9W<3P!Aj;_FUrqerc`8W3l@r|Zp#^Qc0`fcTa#Q>6Zhe%MnS9-AmfcU>w z@w)~SJpX;j z0U0{Oc;1{?tcT6H3^G&$+kA163*^0;GT|4@+C|!JGX)hltWPXDgvmNmBVVc0e_(5N zXLI+%y7?laA<$!}pom>){y7*mg?WRnioiG$#%ja%d=~ zbgj`+E|T`N5R}G3_K!>KbITHl25?Xfq?4Tdld;UN;>w)WG_2(y@fe3*X zIg{5EABwG~*lZgd{@Q2A`8RHxo=V?G2@n-V9WgrxOYZ5h9~s9hRZ zD#A1Y60Rvoxg-jukK?ZLXmupk~eDFRXNZHY0d!hqL!p2L`#tgQF{7MMWvU7SNnfDh+^EhR>HZ}K5 z06fnJWuTZmeC%2)tCMtvH#O;)O&!thgPFWU=-&1htUmrWH|75>pJb=yp7CxLcwOKD zNua9dYefZGa_EC@9qq)EuAV$K$MFNShGp{0D6NO-)onC01xis}TWJiw%Kq~`XFC<| z1n8GxaPT6W_y$-AoLizv&J_x<4I9ud-Ia;+;=#1&2va4w{fW9ENKFJ;qdWtQK3sz@tbvsL4V_UUL$J>Ps3euxVJ zzq2k|VEX>n-(k!+PsA|1hRk8&j^b$Fc}j(5p;(~gG+@6R^GzA=T(PS17mL+$)~yAI z%%*;f;Hi)}-7By>H}}!MkPspU8T!7`XW7NMsL#Y#EqhA%OvJ4!W7Dp&^74$J7t;c# z_JJ15L4e;<_tS&q#!_O8AT;9I42Jtz?1c&8mEr>%P-@ZiyIl5QWAkGVgw4=gFj5=F{qGT5dc+GD_@B?M{UiemiVW>n?{_ zgeA(j4C)l9+-LXyh(li_LJ#l1FQ-4+eA6iC#MgFe*6j~ZPC#{Wnqm-EG?j;rG#yvc zA?{GEk1oOLBO)o`MD?PbThn%%2i~CR(d5ll<=`^0sbVv-`COF&&aBqT>E$9lJ*K zjC%Yo8Y`GECWHp7+h6L1*^&zmQW(XE`HQfSi@Qtj^MZ8*xNhpb*7_n%dX!Bb4!y@W z$vkq1=SFg{_C|sEJ4K5i?>XW*JGU{1$#525y*?@4R(r}6V{$C}wtCi9aGLy&X&lJ6 zjw=s}kn3=H%@MC{+=njKy2BEcuB;D5HBHzhCHsr02)j&P2mIA?bSilK-s=-00%*jf*?nMT1} zG*3U-6GclE z!`;-Wd|eYr$SSByag#6Y-<4@=3BPSxh_Y;4e)K}8j?Z{|2PMFn9A8$&k!yHUK!!-Uox>bMQ^| zRR=B&wmPfOmA7<9UIt{x^J}eDYV*H=k^EWX9&Uva_PL_{02P>&)DW^(4ox7<!q8ru{aWG&UI$>eg)tHy@Hsemn~K)b}XN^TwT6F4WPw|Lvi=w>*zolGC&6n zVaO8QxLdx5ppdE?IwvS9Ptu=qu|746L8rVPC?IWT@^Nhpp+BwfJ2g5bSz1NM3Z#5nd75ubWP(qT3^=l0;Z(`m3coX=0o}s3X-@J&r*Fm^Y(O&s;_zr^2JIv4@;u(+~Bv1?Yr zu!RgYgJ+s&-+_IZTc{ZMAYr5`HnnGM}xi+IWNToQ{E-&UiFiedDmX(vQ0`cX_d`D{*0GR01{qeB&_0NxDB zWJ(y@bwFGrp)<+V7JFHjC}n(_+W^pM%>kQRk_7=_3t>*WAB>h-hLXetDDmMG;3iIp zC)v-;PZE=Lbv*0l>HVihqCb_4St}xvGS%#$?S+4bcyDdA#aT@hMuBbw!w0TcHE<%t zcaEBh?=BB>tTF3dHeUtnA&J8I;)>I35E}5q@I*KUS*V6x_YS7KsMBPt6_$2dap1ou zZ(KnpejEUm{tkMe-HAxhryGk-$XL37WYNUF&TOBAvz43>!2-O`53?5qjsSdS=E*xE zc_#*#RAJq?i2p9%jM5_uU=}M1MHMnY17md^L30LAT?C2lXf}qbLSA-@wPO2UK_F?~ ztq%hUA(+xFQJ#D&7zs( z&3EE8&0NeXT30Uio6q9nPQru)-gLh0}U;iD&fO|i5L><{5a04;6!%7zH} z{)1J2$-Q^F>FP&T)BgZ6s7X*V!SQvr*>{QDtG&oPm<0=4ZIP~n7`g`u$xY#eZ0ZQ! zO0T#)Ar=O=kzGZF-mL9eoJu#NL$Crlo=4O=yzB#(Uf^<^I$xC$#W(7(;UxPg%p(JV z-!j;N!skNLF$(`1l&2SH>3l(T$an(ttpPR}&$0KL^50?k>ot0Qya$FkF6=CkIV^w} z24D-C|80^jU5Wl$(v2ejPZwi(;-Jk{& z1Q53eE<{Mh5Gt8)_##lDF7M2NG%kg>VxP%97&dSL3mTD4`LtB5g@nlsXlM1$8&hv~8_m`72pa#l2xZvtfKHdguZ#?A7+I5OWV?#Y zGS08Wi`X&LmWkhiO{1gQibqaKT3F?5C8u z%^vg%#`05=VR<;}eI%I^Pk?eX?8b2r)^piZC>dGqSrS3&>ywS3&tUmd8qcrio#>>3 z)wx$TA#kOoFN%r=ZF*f*L%&F5kmLKuJ>J}OF(C1qOt&pL-0Hav#$?*+Jwr6cW_nDl zfZlHqO6_%lniZT}r%&dM6|=eMbKQK@2$l`Vi}z&NB7oZH(Ogl}>Q>LZAwwBc6lJ8N zU8MMrx&qj)75I$Zj()onrYRxwMgNLmA$*n-1ZpeCEvrPl4A2p&j4+VQgoa2!fhoF8btuU2>nZrx^pX$cvG2gD=cu#;GYik)a{2*sDH>kzgr%|rmT@Zw+(28@ z1`Dy}pe*K(4rOIQDG~3zbL`Gdj|eV-QPhBw3Cv*X)%Lwkl&RDj1>Oe14((3`he`M) z^wT^Ec3Y8?`^@(+2t`)|?P%5JX?;SwOPswz7KbVnl5xAzE5Li~dhI8#zH*=)Y`x~p zlu?wULVBp^S181nSck5D*et zN!{h&J5!n;T%%S(I-FKB$sB4~+no~+yW@o6Xo6++MAemOe0J3#4Gzahzp}|-)jQOp2qy| zz_H!}EyqPCIC^SATPcASYrmBQ#%QYMfP5d>Co|dXmgE(|TkDG=VD^yX{r52)fuzDY zZPv&Yp6>xSq0gyLEd_bPQ$d{a_Pvnk>gr*goR59>-sjuHy*EFy5}(2sn*FU^7Ta6x4}9Nk zzRo_;w@LDQiF6Yu=ZJ4ZChU#)E}@TeveNLy=JQdfyT+yt>c!l>{)>fU-tp$#&idug z4A+Q!+FjWh_m%4+8h2OCx#X~IZb!(hn9f-_c2E5Z;%ZmSuao!7IvduTDGNCBo~(a4 zX>iAaU%Pht_A1%!F)MpMj~#M4{^jg2zh}iAUZYbIYeSFiIj8D76`Xf{gBK&=yJh2p z-q`MUD?DD$@b8fe7ZpAcmKffxo8MK^a`?~PuVXuj zv8>Hbk)^5$^ZZs!ytT&gZE3J{L)K)2pSsK}KAcd?UOTvX@Yr9WX;$6g&BirRWq}dp z2YTHuOIRoDil^+DSh(%GjkiuMB+xcK;!^m(H*ib32kVxuTA9E0Mpk46cgRJ4_)oK& zjNm%amQc~QdROt|*RKi|SRT7jp3R!{FRN5l#bd+3InH0)a2fQBf5_mve{$t*%|PDs zzB3i8w{EzgINI|xF@Ilgr?jWke|}Wk_Pc@~w;tVSr1T5EBkAU*1`(j_y!4Y#e)I52I5RpOSRU$|z^5sr9aNW1d~iC}rYj zEgzhXx)8m!d{W$|v&HTE{sQHr>EhznQ>1WF_`Vpgso(5Aca+VGTK8DwTpxaOcj3!v zF(va%0q5>GX(cNv&{AUnug&p9FH(@zE)`pXqhj&^$6Rn*<V9`US}kpY4+XD zsM&u#Lc`DtH&~`e();^QwqFj_x90c@+ePJF?uX`HXpFgaZ+n}#y(T2g<3W|9W;>(R zHKQ>9(N_J~c5dEh0|U`2`-7b?#XY%`4!hWYRZ`-_RQlap{Iam)SnUDF`_~697I1z} zj(oiOnrF_7eZKn50r#(-yfd(C>q^tjyOOWn-T4DZwisu!ycVs=Ve@AM9-P*4>tyb? zYv=AyZFN z#1t5aM&VQwGaBPQ>>wP_!O zpTBHO2j+;MTSZP7!1gKP*sgNF-mYtQ#6$mL&Fit#ucolfNi`@kPLcUNW74W4( zPp&{D74fBf!TVNrYj_?*ksAOpKYua3?r^QCs zs>Y3+h0%RY=-3IB)lYpU_{RZSyOeye;JO*8Zo3{D>!1dv^oSM*5aFZm1yxV zsIA2WBcp1M*9&tquxX4=nblyd)0qe+I*h-huEPX|`^gFQ4`a7!eX?O3YSHm9J7Bz4 z&Sii#O&IgeybrcoIcjogIpyb1z;D(Zwq>!wf!0AjEDLbb`eaRj$vRs-aMtNNf~(dK z%MEy19pfT!*J8||hYlwLUuPQyo?1B;PNc<{K`$L?_ge}K0ZW5%WLVP734FinS< z5TL^Vp*qZfa2gp*uy22jC!19}_ zjB5fmIki8WoggAX4|Zf5Gy#LG!sxB({jm^7qA)gJPQ}`qkmv9LwvG_lIl!b54~tcq>C1EZ{2PR! z$7GEftsk=_GwH+SF)NZXKT3_yO;@HaPfp5AjY(ByC#RW_F)&Kwn!mwpFUNORD_&9h z=Hn(h^E@Qev6XNT>K;T5>RNt(_-QmxO#xmtYBWCw0*H5N-s}kg{UYpDEFyjD!f*im z1B4Pq0N+c_lgky}Jdw9d#`BTM0(n6SnLs9!@dIQ&UbJIbBo}gg`1~y3dj<%^L3}w+ z#uvzVA}^tU7a*6&c|uu$NG_Bqd=v`Gq^cXBWjq3FytyD3YM5;SJ!9l!5gH`%@$n4s z4C46&$vt@@g+z=_0)u#BvE0X7<|!5`@io4htEc~OEWp&6-S8Ma{- z4Wfna0-Qnz{}AJ4pQ5FM|C0eOQ z%}Y;7D!Y4EJ1Tc7wue4lF$(dTYp#>s} z*f6dUa8{VTvYz;-ohPDl(Y>jm~v#`r(`CLkFu9MHjet9Ri(#aQK>r-+g^q+zk z66K#dOGTOEz}qv;Lo~cHVsK5tN!d{RsCRC-nx^84^0Flu2zDr)D{6nr@IJoM`yS>1 Z#eczQQ}oAj)~@fK>Xh19tRH*l{{b5!&cy%# literal 0 HcmV?d00001 diff --git a/media/so100/leader_rotated.webp b/media/so100/leader_rotated.webp new file mode 100644 index 0000000000000000000000000000000000000000..1f770f6ce72825f85e34f0601f79c246439dcb6c GIT binary patch literal 94970 zcmb4rWmFtZ*X=-XcL)g{T!TBoEx5b8OK=J92?P!9?(S}Z;1&q3!QJilkmq^dZ{54T zA9u2bsp;vduCCf=pMB1$iK3*K*qI{)NKI5oUR9n`9RUOaQ31~}L{JARNK#l>9uE?D z3xdQmu(!8{0$Mh<&W?)WLd5DCn#8c%APC^!%frCP$zD)i{v-I!zpsBk`Sz z=)rv*Jm!4i3=;3Lscn<4Vdjm&Q?DK#$SS&-dBS&yP7E(5podsM8ie3^A)I1PDzQD-D8X z9I+EsK&5y@U!bF-BWqIf%?VAIh3#UlsV~=1&AEs1h_mC>H-o#KvC)bMMx! zk5YWGpP!TTp6>)wWuDlcD<;PVo`;`zpUx*b2A<8H2kucFE1s|H&N?3M2p$_Ap0w~Y zJ+HG>m!8jih(dz5iM$o^YUCEU-}ydYc3o$>sFUQSorRrDj^2vgSeSWbd$HEEEAZoM ztWaej(;dgj1t+);QT9mlY+lY18# zz>WF5+|9OcNve6=^~|`DFI5KrcX;ek_Q0aO-VKq0_Ki)<$pMI;P5tR3YMc{|bT9L< zZvf1ag<2{CUGgStCnBFkzQFo0wbkD7u2WPP=-)|u>HF3QJdehx|4yMcX7~tuT z@GLq1AIp-^z&SxH%Je`qqb4*eVm9HXS5Gmt^OzwlEvTe2$}02jdj!pwggn8$lIS^z z%~oJOrFk~L^s`EN?(N`wtgV&uV(YRgXs;9M71Jhq;MrGZaL8^i-u$0Sf6A4}d6DP` zT*P8{eN_WvM+F$Ik18cTIp3vI6kl?=LqQF2DR7VAL&dn96TphROy;@}(5wy64lXYG zj0f=<=LJB#QJ>^pXXXyHwm;m8JXEbvb>OaPhm-EOP0K|=f_PQfB*|A5t=bj%=y(q9 z+!TOC1tZU#o*pCpuH_d1PZ{XEYzuO}>$e1#t|QeVARN~}TeDHSuKzcFIrzh065gM9EP|8ud)0X;A}f7B-W zSvf@k18C|Glk+y%kmiL)u$ylb@=-sIf2UJ^{mH{9p6?dKM}FS? zXDa@kAb$Kyjye@-p1WTFCNx!cUTL#+|6_Eme~|?MvREs<{>9ERi^}-i4X^9y0i0^E z4TAfgK`ab_rphP!uN}Ss|6l9eZdBk0FqC!%n1PJ>-v!^oTtBJ&$DT>_bq#mTyov|` z!=`r-THFNCe5&H1AP7s+?lJNHkE%a-eYFAHKk%F+=7qd8+shq{ho!-X_KuAJb6Qo9 zk^T=w2+;k97Yf{D6B71@VqOU1)Jx^=*h_nPKDv<7b6E_Xv99-tK&N|{p-ezfm~o_`p#qi zj$QW5ik`tsJNPzUai3qCs01?#cMQDPJ^g95{nudH+xl`V(whuVdn*d{+76g8mUYC= z>>uUA(j0<8(}JR_09a}BnDMoV?hQ8@)%d{FmRVH1N1P3i7mC?k(~RJX*;MzJ_3bCy zyj4{4RR!ZY(vzxW=k#cRtH1^}Ap`{=$5#t%puF(#C*ZLIz)#zp)zqZ;rnCYO5B+Q( z!+&`tos#**+?=AYm&-rN2ZsNB_f^vEoph?j!K^oKF>5Pe#)VzL=l~X9t^8;=3m^@c zjZ>aOz;H1#E@n03VM9w8${0{}r{-zNC)|M9TEXVK@4{5Li#IWVFc4}APU7Q*E zlJM(#h;j^p5i;y#&_KF+{D)?8-%S~)BD%*%0_`t|79?qEi8r=?B-!>FNF0Q3#&>6{mwQmow`7T2ueMf%w^e28H`Oh8qZvVX> z3!W~1eAh6d2eqe|EHGYP?DIt>r9ZAWI)Zup;IEUS4q1J?tLI?F2`+cYvDUS)_W?L0 z!7Yd7c0Ji77?`7fmg%kuxEVyP)JCscz%Op+z&Kz3aXYjdT?7n}74CnVK-c*2hilETc6k!_IG^kEC z(T6{oY9)B#3KeZ&QWp>_#sD%dzx;&u;+7jxpoxmWqxxsUIatwBmT5!CU#=pSt#rP9 z)^-u%!+-8)8HJ!ATgyHJ$eMWfF2FxVH@gp7nA1UMZ%mEbmhp6f>E`dPW184Dy7@{=@&R3kwr&Sf-+X;UuJxPV1#YKu?dwh{KCpqHP{`2S}Jk z0dLcg(~n+?gV{bQTJdDS6RjfR^fOr~Q$wZa#eRbD=!@?2(hlyK|(GayW~Y!U1(~o@KcN|F|HT1k7WTibdphrVw5sc z;HCh%5^()1g&4sQLf`a#+L6VDF3w-F!;)IT_Q;YD8`;V;9+v89)T6S)(1r7sL3CaA zSp%;ZV-Fw_UX%ym^j`c5y&4T1Kt)#k!O^e|wY8P-?6!a_;4xo1kQ&SWGyld*b;S!H zjF0^+wGN92lv`ghzk4f30luMlz5i?m7Jfha*B1w>#7+L4UmptuN64SzeAFWjBt z4I9G|SXq~1#kvr@ORKd$vE7m$Y?mF}Ye;H#-RawfXGHStBCvPgcGksV#RU{}r=`Ma zw$edP@f;8L%&Y8p={%o&UxM?!pMLta_^yHEEHQ5Cz$IM++ACxM)e5jkPF_8aH)%hs z6P;VC-J6_x{(&3UnSd`V*f9%O+1>(1?G@?ih<9t)-2Qm0dwpmL>le*8o0TW8V>hw0 za@H95#_xdmYEfERqztf@t|zATI!8x2zz4oic}Nr>3X7o7Gxs>WAUaEieAl_^7i9w5HR26Lr3d-H}&+1ON34-#y?@aWnW^k^30F2Rs zU9Y-3s=LJr! zMtHy4k}h`uG>4xvRqNtUUTb5^_7FK3C`4_n3J0)vh~HZ-Rw1DMo$4? zwHCQ!U;BHgyH0YK-mmi2q{CVM{((TAmvzVdwP2zyXAQ3?=OZKT!XmOmW^>pn5U+xr zqBHt&oPi$T&%pZbFE7UcULuAcpa1>xy)^r-8{>Y!c=id+4d08R06U1>cg^aqGl802 zf-5o11Knb(4h%vR{_^5;j7L;(X~k0@o~~84=v&KZuMX6Pku$=(Uc@)akbGx(vjsYU zP@NzHdjx|u_pdh?_}(Y93u-?hw;2d79eI46OR6ra9j$PpzeOEF(j#au9x3p{dBx#t zG)(P4&h7}BIOVy`pe4Eq=t=v*KY(=yKgSz${SK@hcfc)zt-0wJ%_eJ|j!Q2#pL(_o zU5+v4ALnDYGD_b$3XP^L(hhHet|EM~KR-KqG1uS1>;+5-#k8`k_>>B}hOgVx9I+K1 z*|Lqmo6xSP&oTxo7M|s8MJP(V#N%%Id6;YYAJ+2`Zu@kzz=X)Ljnz?PDMkD6G^2G&|tuuNu6}<1V=r*0Wj^Ouc}UWw!wMebkL}W5o6dc1vFe z0>VT{Af`O?5)l<2jtI->DEegao1nT7$bYC&TbRd+knNuPkujS95>e;Xg#Bc@-VS8g z#giC9M&h%sjlv*7^u$vFx{*spx%9|9%SXn7Z(T-vrHXQ&AAuNWxNw$nRmox*1*~jO z7~C-1y?}nTpG#6T-ub?pio!_#6C>E13GhaBeq(ghe9$Elt8W<@>+h10NS2Roms-0S z&K$;lZ(NT~qM(v#w8H9pErDn%=#t9o+T|K?Xg9=-;}Y@Hit2zL&AG3#f3BOoOh%&t zSXdjJw=1`X-#=vq$6qw;cxAESe}g}^TXLM!kIuHKB9OOAQ_Vp4_H!9Ujv?FDE+S83&Jb_x}=esZuH7gCJsnqTnZ!G zV^|P6P{r~G0lAZ5;-ZquUGY6*JQT3YxfP(ZH5(2Yig|>_Tn%ZjJZ-1((kNsCphIBQ z(K_0in`4+aIeM3a2z}`slM_8TmMXs9LI=PMH7~wZ-{G%z9BJ;i+P& zNfV*lk6Th-?-=irTS93dzh`~6*Tf%8<>`0L5)*?~pI0_c=9RQ1B;AaiUr9@~t||zO z1HdcJOUdls!DrGLU*wO`r2HZf-a6!ZQdtKGsbWCkDPPb0LxO<71jLzdK(E-(G?uL5 zHwZYPK@lMtA3u&?i*LC=CNI5b)$=hrHMv9#6j)m;+x?_McbvQ?zW0Hk(~O)2h~zOX zItlkBlQ{26V(x%gWUy=skY<d#s=CZXOt^1#| zZlo};t(!kW1Cjb-E*=oAC({#W_OsN}G?^Y7X%7>eC4cNuQLbs1PoYj4r&y8urXP_F zWVLAO!z|3>bDo2u@M`}?`Gva{;B4F|tC|NmVEH^MjF&nASq9{Q9xwV5(x5%@ZfB{nEC;?^_wS{>|4@60A?-JJmzbYOHXyKeoAOw|5 z$D)qzcWqd-%e2+(R^>;QQX zg^&EMo3xMG8xB`L5nWsz05H+wH7uiHb}L($JA<{Pqy{ZBOPA7V|2?UO=aPea@dSc0moJHH^mPo zvC=!A7=UEX`zo`8;Ivh+yY(3X_(tT0FrIC&6^7=);$X(7I=^agkm z19nS!kFb9NxwuEEi}(wp;nKX%ur#Q`({~9a(a_JHqRA^{`y<=?9hW3f_Lx#y{^AdV z47Bh>IH7K)pZ?7D;fC;5uN=7* zAeLVDc^-53|Fnu8@Lo+jo9z~)`{01zD|;)-biHTz#bKB6+sPNM6(GG8v`;S;2nNAF z!Q_iWNLmJhN|!AqabDi;HCsoN#0K)qn{sR-5r3EKsy>&w5@GQTQHI1+_n&nQk>7Mu zQER=OC|4p@Pa2n@L9U4wiZK=$8~4^6kVd7>8^+qh%6UKHz|BhpDzLAIH|*-`I_Rg&jQbhEZzECtHpO?1YU7 zwEQDjUb2YefMGXid@lMuuaFe*(Y$E86Il^z>&*9hq|<4Gl91tn;yXqNJSIVHBE6cH z2Jw5m`5OkP+NHb{=XMwT_2XB+WLJVb;xB%3R+|&M$7SPDlS>O9py7b?AMU>eG;=KR zUFnqTM8r${P9VQUXl%zmR^9-<4@i4v5OjC`&3qOMf@NA5kd+U~*H-O~QJHsX8$1}W zkcBSZcLmaIYJ~mrh_7R~aOmi>0LPt+XW{tPZj7rAlKU|^nrbTG%JoygA@odMZ*E~^ zgwYc+^k{y*xNmy5hv#%U8~4wd?v~iv>Qn!a^sCK!NE4nwhUG>ZWlCw8o-HgOp2_y& z$^b`YFBz>Ek@VMoHyj^|SGrrPjoWM(zH!`OsIl=tSo){w6HlejGQCProSejTMp%++ zcTyRIbM|NGIpM78B8aO)VUEz*SKV4JWQhz3ej5MH3VrgKmeS^JW1?#fnRC+|0&BGl z#+aNbkVLNoVtX0rlEC>mg`=#eNcXQ)os1(zFX}zKw(mp>HXj&2PdpFD- z{i*8b;ADgey*+R6P0?|#{t@jz`5--hRvDq)y4M&%Wjv&IJJyB518TNYwUwz?7iG_= zim)Vk@yDNMVBUokFY85is0m_JTJ8-?i@N4&(yD5j8X_o-K1Q$LUL!_WbFgEfX)cK| zQ^UWlyczL;njIDL!$fi^dh`7CxLaFXILfUgdnb5`Z^{y8Y=86=mR}+wKtrwS`nGHr z()6qenH*M#KCuXGBW)2JCw#7%yp3D9waN-llcL5Ua?}+KrKA^BUbaF-U@-vw#KouD>mwhbY1x;AX0FJk+&+6C)lI$j*-~& z$r`Bxl_Po0_8oGT=%bR+=#FC=E$_$q_T-XTO2KMRSSY&P$XMRi1L|C9&IirY-m%~7 ze<%}X4&kTp*rhJ>uQOilzOqE{Q%XbN^sdF?= zB-ldLZhx!SRj?6$Wqt#09L3~@3aZm-zc>|#F6HJs_KGT1SeBXUl7 zUe~UXd9OT6EIk|W(JZ%Tyy7oe~5;Pm_Kz0 zhjk>q&Njiu?rvZ37`oZ|M-6}Vw}g)pa)k*d6Q3|FuM8VB{;Hf}fc0O?JOGL2ChHCr z1TH#Q@vy!AO3dda$`0GJIp16%Emmz>sqrOf>O+^*AQ}lW1@`u}kM=Z5VtWzeTb8?v zYDuKWr*~^;u2WEOm|ex{RSTk577);l79dpH`yig+zHav6j@mO)%Vo_@W;E*YP6ut< zV}~ap>!#`-pO#~JEXo{YdV_xWy5zzzTbLHFywmqARas3M%dH~mo8F~uUBSk$#7Fs; za>I|!#sS$N3X!pWAfP5l{8g@XLQdQwfU*4h0CydkJ*69~h|03wOdICCk;!ILxor2l$K++l;Es7PJy{o&&1+31 zL(WI&Ju+CF)eTGJIEeoq^`4Dz_#XDwsJrWe^MB$q>=7H{d-~mzP&=Q?$=O zDg-3TNs*{t4>~9?-0@7%an24TFVu=h5!SkHvoWurB zI@l+X_>r07!I>!cSDZH;`cH2yh<)<9v-Ze7F>(FiHOljj@L>uQna$DM@1v_NqiTGr zj;%c#*IBQ-ICqtF?xl1Q-=(#ThrDyKoG0rki;rlvV{2Cu4wq#9UGm@enJm3PY((ibe zX5K#@)(Bo7K+t;mEWYE~WLre_hi1tQ{SEiI6bqZm*Fl$biZQN4{+1s4@?9wtEF($& zeLK3I_X?av$9|yNSlZ0+xZyYR+x}S2oBR9Yb0*KuB->fJ8@zdzsPpEa7g&Vnh zzLPWIQABDCjxG3XdR?w%mo!X_)ofSMDCafT*=2;wygKQ=v;g-k_e9p!{ z+r#ID{uUMHYF}GB1V6XNU<9rI*f#m*yGE^Qg8iK?qPHB+BAOq(x+_$jLw|skmKbKf zx8o06lQvkk3TCFt%qF+ABWI()a5H`*LqhRTj)sRpiWuWh@GfBMPtuXby6%+!mBrw` zy47BPX-zCLfpN#ce&IZ9#^uz488VJu-0MMstL$@a`iNM~<>1S1Y>kY2$l!Wr?m3^y zwuuK~kOM54&GM$%4~&)t<9bBL)JB|&0{XDAm2ASPoz3- z9__w9{LePrbGA?0p9hen$-?`Ld$3ysw`U`|2!wL0d;;v6I*JAVjX*7n_~jH!zANBN zJFLVYyq|4}!=Od>ox;}l`v`+loDh#oM-rqnc0Qt6BMV*dlr17>bh)=<#knK3zSd;o zc=S`P_zxe+D6gV8dNc~tLwe0PQfpllT}@3-$t>5;wNl#%$4|3umSS9ge*wxoUX%t!740=`6TX?A1kHXbz8=^B+K9r zT|P@qp@+e<>-#%*ArYN zR7oGt;hluC?z*hhO{{B1rt9A)jbxVvnz^G`GD?U+e^=`X8Jy_H7uKScmY*AM^;Gu{ ziz6C~t+JE76*HP((LK5seUhomc;F|!wT6iwNJe7#{1zTl_9W=T>(954lc3cb{sB`b z=lYG%e6*5)6EjM0aO!6L{6|9AVzw9P-J&?!RDaGF*$`RyKjA9{v9;rNbfO*xT9Br> zw9{VZcwL^<3|Bf&lXOpu*a+x~J;Kdzo>I`g>ArlenMlY>3Ab1QrAvu04Vv^~ph){h z>az)4x_z5ids|H11VZe`yHsvFjfl)sCMht+-ZLom$!?L>iFf$zVN+%M18)>d%2JIb@8}9vM#32;LBqY)Z65d=S7RjuU0ztUNO%h@G@rYG7(MlO5kDv<0+GS3B-Hnea%>)XrJy(qQ(swAv<ILcg4lSo8kwS(g)emYr{WJc3H zWqM@f5VqRGFB&b$7=5^Tj4J*fP$5R3SRa$`e+Ng%o$fi-5uIp$2U<(@@>gd@nBCnzwP> zXJKvZSU;djEr2(pHp3OKeU0L5*zhx=(0kgJba z8@gSQ{lqxsX&$m$j$gLd$>$xxXn)O^By>uWS)^%kV5;Ak#$ffePBvszcsOD!@YRro|uHO2g+?^!H6a@6mbKH=4Xj zYYoqj9QP>!N}@+LJXxe<{DJLM3>xv5jc~5NF`v2fE_5Bn5h=4VwptmucwFfJWT0D-pw6OZA)UMuuHrvQ9TJ|Z__vkA8 z-$Z_|eIMkLu_W2UrpZYCUvDDf%x^YYY)eVB`b=rR)kG7098tJb^pIIp*LjyOl&0Eb zqj`LKvv}{Ov9Bs#{k{b|>?BBN+IaVV#k9*~hjYlvB`$VE8n)}u=IghT`Q5F0D_v_7 z!pP2k)*JtqEuG*!Pl<{SE7{aSHbg}kD!Na1tzU&5+u;ZwmLVpB5 z_J^tbfIxm$Zj;uqr!lC(S?RZPlIKY?g?aNOaXZd4O;;xl`>ZUz*JwL{pKW}(z z7uoQmM2p8Fm7CN48wUuMeGCoA&1;gvxZu3e-W^0H| z$R9N?+kC9rN-uY=Z(n0 zGGPLHPT8WO;eUAw)iT(ZRY$d{_2YzQxncfeZrrdwDu?P`X%b*P9PT|y`^xD(3<_Dv{fLv5wcDR7>FXYfa?{yXzb~ld6 z-)9wo!1n?4q{;iTs#CzLp;}z z4+)34WL4!^_rjX-o!!Ou`-t0oy_jJW#0Dn@kqXWgsS+!2->bgJ7^d{|xCifLZ`SCi zkc#UYj_nwP^eFT^d~S>$vrWO?LVi_fQobdTq?6GSy(NfH9K+Qv_Sw9H3aeF@%hfs) zS!?{aa%s)$t9vK1^+jfN%`(+DcOzNjshlEv%GRnBo(x;ZVNj{)`qJ1#y$E~l8*rE( z9=z~O^s}0?=zbPwKe8uf<1QAISdY|&CKY-4fQHO{OV$#;m7YFl6HLWa{6=C+_PQl2 z;~4)A9i2*8b$TGScjJY${t*p^&%ti=E8UUf`@;B=U^m5dHIlsabsDCMw>2xuZf6U4 ze5g1S5XljEf>Lr}1;2M@NBd9KRm6fK^<9Xg=H=^$KQMPxsmy8mRWnUIJH=?E)FpSl z+k`4LL66qdsiJ?UWM z+tMPp3!s1=vlB#*RQszs-Ql*1yN3NMx`VPQ?Rx9;JXV#N|FX0oRX}?C7tT6)3Th7Q zkany~ztRVD-h>}xuRl=iYe-c<;9U^>>3I5DX2FG&X}Cy=CBCj9*~km7D_+lEfVWNY zK|5Wb9Z-|?Y079l;qYBL$~pFTyCx(K*l}PhFU?AZr&A2%VQ&9qarzX}Sw4r5?f`>( z5&kamaQDoMC-^`~f8=Y&Zrl?$i32)OPJg5z^Z6>(^yk@MM&XYt#M|v8`1E_}LzyGl zCjtl8TNEuVrp>o(o7akilL9lK!+y%&_Fsf|1<2iKjk#N1iARSFqFA`$6wkuEGkyz_ z3|x#fpZfi>YgR(${Y=x@g3sU8NYdf%1(u_P=E$qwlV*YKND7*%t~ zce^)CUFh>S(;6OTSAowIRUBfu{OIT=qau)Zjizw~4(@Vmf-4djG@*SZg||^01p4V0 ziz>P{*3%huOE6-SISLt%rk8k&(ENG_#Zz+@vwqk9;i+r}jYi*);Oui^eJg@tRMhT< zh7CV|J0He<^s7>4W6f0fwdc?u)Non|aWn7>-kAC3_qw*0)m=iv4;t)&Pxq1SFy0wO zsm7Nn26y>UC?tz!M5%LEBQj+qGt=L?e=$`Ar&0rUAN}G!-CIwUN??rlNk1uK4u^f~5?xuZJ6Gi>GO($X zD9z|GoK@;n`c&SW=o{6e#{Sj)gC9b|SEbvk<%bj|U^}3~caeg(5^9i-(FH2y9@qq- z3U>5?l6)G*7)lo9_lNi`jua_1HuBAH{zyBm8$Y)PRX;p_XSs+;v)0g(A`emR|53Gw zAOY(wglTJ8^yCa*-ERsVtden{Y(4kdrxDs4n>8TxTdb3vOR^5zQLPnFN60{{WTXXl zh4-n71*>yCfBz$~Ncb@~Zyfa?8*)_@h8wGtdXiZ^EU}PLQo10@1Ohr|FNc%1Xk2Ft z%Gllo8!iNb8IR;ANB{o10jdqc=ZZ`Lhue2-X0k4qN3j-+kO4W|T%lFbt|?II4 z=UkRh=5D3QD&Y|fw<5QfUw;z~^qu$ql;hd)87Jzvx;4_#=1*vvB@|stgo)h1z||^IGmylk5fe4Q?r5)L2-c6IH!Mqt1-J2MIJ}`D-mu4Sh6< zKo1|td(9YjNUxM`FVa_0E!R@H9&u3djlGH2OuzW%EoZ=;kH$?vxg4;$_^9SVE9V1& z@UL1v=nu(McLj!Z423w?;^qy-E7aq!!&(Xb-eWj&>TlH6HA=K2(xW_eMo-#-d)oKRM*2->LQSn%$sUW+HSOH6ocLzH!^ua>u%3fq&?x zZ0@afa#~C@QET(c^P&1NL+G11Qr8deP9~B8bzAEMC=V{*^hj$@gs4H#q~Qz(qZA+HH7H?g%(q{CF1ZN}F01Ifr8B>eoIH8P zn~dn!MD{w0OoXaiem*ed-FRKtTkXkx8$jPFpHM-*#uQQ&C?vMJGz`tYF1J6ew7gtk z5&`k!4G3D?%4eIukL;=WjBT0I#!3xjux4LIguLV`7dGFVw{HbM$3k`FG1u}8-Zl!9 z595?j)6V?Ez7Rd{jEglDrqwNyA(6(=3SoGpDo$7-BV?w>!tJXd)ADE*iR?}E#jX1# zO=Fona>ysf67EB8Qik=czB0xY-&r_iqup*8HP%8fT>D`e%OGgU#^SN54wnNip|ZDQlgFa;s>!5n?NlQ30s3CYC^`z^-F6KOx(ooas>!-wcJ zh*aB!s3-aN`s1hdzjv*U8@h2K_FbaWu2G0kb10K1TSDl!e(CSw86Gr$;A)}?-JLGU zR<$L>`FHcd{%{QSkyl1XXJ$R8$#xA-eDzrv?ZeftOFdf*31!(<n${D$pygm;Mq- z*bNazWr~W!!6N&v8cm8df(5?&J-8!CxjgBy3f`d)Z#N`bx}sy()oMLI^99f$VacQW z-kYZ=mgrr+(VjxC!bQB{k9)$V^Lo!Z13F-uK*Dr_Za6VjpWY+fNmayRzNj>v&w+eK zchEhVuA<=Krr4BABY(6%?=frc!h|o|M)>`K3Q@1YgCQRmqh%bSP*Z)fUN7*yd@P4a zkJE_CdfkXTNU-DSyfjGIBE0}&hYy>z8N+T~{+H;Jh7?TC>5-%wg}yhkJ$5w_GaPuo z!sxA_?lRKr2PoJuhfQ40@*dPX`bK#f>MN`q3oRSkuZXo<$PUoh6si~u?~$WNeXDG* zwHK|qHrUUl%6yF0&gA(lgSM6hY^g{o;aIgA&3O^|N2N9hYM^C_n6o+tjpDZn|koIr@-E**_{iX$*?&f^cK6kLT@d zAh>qOP3Q7)q9yU)4*q4&oDiLnycF~x2A%Dz>_AzdiY{4z$ye#S5VvwMp^ozy!8%Ge zl!2wSX#juTwC#J@H17YX{a!)))z4#nj^r=gbGQYRL48n{#eYU+hix<)?7qr>5?xh} zNvPF@J*`l{H;Tjiwnjf`k&}x~Gw!srZ*E%j8CuOllur9=i4`KTVjr$T;;Fl6Lxmaa z?+^xE-?N&id12|AbED=i@f~sDg`eg^JfSP^ALrA$fz@Bqa}jy-$M;+zlAWI3M)p6Nx}Vgpt(?HZ$MYCmQ6b#8kz3~0bz8n%kIP4TPCf37C=QK zoQjuN`>RTm?EbL{i$>XT6f1S4S9;LRmZ9uv@(9`UNlEy}{sKhj^HpF3E7Zhun;Si* z23z9pjY*%Pj|ly_N$^LylB~snrfQ`mFY{(~!QrzFE(csi8{}#lA97SGglAxTwdX1q zbnVIoSw)*}Fep#qljt9}?7?^M4C23@lXfmDtb=ymGnC^XU9^T$)y72bJMg8|63O@$ zos6BZtd=~-JPWm!5IoI) zhRk7{_S~j>qHacE`ynH_{}^g%C5Gb7!)2*3NA33vg;Kol<&7Y0?9yK%oOf6K?x#x2 zCaod4X($PQdnhzb>`6B#Lg(xp zi>T1V%u6SwL#!|C?|9dX?gxM$_&q<)|1j?!q@A*b*2_YFs!!oh{`v$j9Dd4@m*I9M zrNA6NHjDS_BWm+5hvfX9qEfbFZ_zo*sNT8L3?FjmRc9JIdag0P6}w(Wp4o(tDhTW` zX9_#?nFlOx(}=A8*}+ifj4D2fmx3fd%Dr8e0WZE+xR0+Micy%I3ubS@U6*i+#Y>LVdvYXSUlF**Ctown^ejPKuf` z${u!KNVZxFrJGdmoKf%~+Csjk9lfP$A#?Y15L3e8t<^N*xR~ScX>Mjj)JIXPw6^sOT0{iv#GLSIX&4E;@JWfHV8+jJv7qat zvND5vM?b+I38>8xIvb42enff7eSe7HrC;CTcI;HjA~eX8_6c>yCkp4S1}#O@WmVC$ z6(wm6MJ`830&j9g)=;x~c}=Om6H_{FPMg4)CKhxIj>)|u`yTb1e%G~(wOcT(QdEbH zkWKBAnA!7YXtZ(ZEnzQ#6`tSu0DlUSLzW5>?UGp$kYZ&>#E=YG+u9)Uc*c8$YqQU< zHl`qiyprlEIT4je-@k9zh{(~KrgsM!aavSTi|N&2exg35-aK3|WsQ2t9Bh!+^#FS; z$Zvqn8k?VQWYiIB@ip{jI`pmeYkWjV-nsTizegAGl(faAFXX^J1OJO8Vw~S}>xQb1 z*F!woByXWMk||3OD!zZb>x@3KO`WY{Zr=DkAltcw64p`0{lhvR8cr(AYV$xrlz`q! zR=#e$oLCEr{Q1yWh1ScGT=4qtMABj#&DgWwrV&e1?OnZ8Nu_f0&TSOq3`5O36Z0wO z9ZVH_*KS;l$r$$}&)l7FIgd79D1q%-^13=`DSL$5UiMtbqe_~#dGj2Klu8>5$Ovpw z>`{tem-O=2yj)Y{n~5^DUKxY>pTJeUCLr6WQ+7OldL3hA8HL{p<9HS{FQ%Z<>7^f? z9$m7h!m#LQGiTcDuJ4?PwZ{Iyo|96tM-=7cfXP~>@0@|tU+aXTYof zJTqDVBIHd!drs>{TJFW_;P|ydV%wp)3%%psS|L@)%XzKE)@H#faZI}Mi831aq1jKB zIU!_;86szaObqjG?$oy436k^~we)tw=N7f}Q0zfF=;AWGFzUJb*4OIjDKyj;+x)ui zIEv$2YWR!4S{iEtJCN@iv+%7U&^;s}3@07)f1x6_Mq^gPnIbpx@)mG-iUz>u*)gRV zIQnFCt=totuUdFYYWc>{qQ3U6?ysio`Bpy6!FpiPaK-xr?YP|H+h)F0jAxVHYKxh#JwPTpUOJ;iCwF-?oxT@}AG6cOfL6XZ! zgRcBbJBa@~A*+kn@f1{f@u-!oJ*@9I>{Na|Wa&MxV?Rr)d_0P&LmFO+_{FCT?v1@= z3zY+hkzf_?<{t)d`$pKDS&6vsXg*ZK=9WO^$rLthwP+ubOV1(A&{AJrWS_dnAy2#V zOLnty+ec1{4|`W!>dP4khF;M#*XuHd7)?!7M%=~1C5VPO&{)Ii&=idqa`3wto%ms}t{`f+J8C^PNcTvkPf; z%qNAvg=Wic4}4=9>pS&Jilo_7l<7<-{(Y4^`ya8qgRT&B4EAUqC+%F54l75?c5=?f>&}ex)jY)tc1##DXe)pjA%j~ z`m=~U1OM4tr?bw*Txjhe`rak7Mz3UriMF+c{%c()Oua{aZYTPH*rn!ux#c*n_my;f z!)YIUwXI+MuH7FX3i3=BIgxi?DXm}KM;8q?4==JEFQ7b7$V~Fh>kU>8DosUeBQBXz zYDLL7X|^@og?fX;kG`lY#EJY?ah98voYtk$QRVPq*?002GLb4W{&w*uGq#VWJ9|n3 zrA2IxKJS5Cs^Bg*n#rw9_v?oyL!?e!Tcb0rgNp32H~{nJ)f(8RFnUQU3Ki;(GFx@p1MuA_Lf{7SMeHawWz&>w2;(+XSc9 z3`P|$`~~h98ch&)iQ0&hBYVMZt4&8r>TqNH=Vr6B)(?6fuaB?;wMw^ZyPQQgp*j~@ z?m9ooM@q>E*7sZGFPI>Yx)1FvsQsOv$#QQs1_hA#}TZOK!z%3HS!k5W);?Z8gz=#djX(aTiQrU6W-; zoKcj20q>n4-h~&)N#JrsRGYES>4%H58fxcen?@9 zJ-KFoKyPd%XDJJknxZdX#2^rQNA=l56 zhF^&fUqaqyhK4_c3N}N^9db$OQJ+$GisTP;)l=I1X+p#EiW$OIi=TFiE^NlU&cAl! zTRwOga*^}6IEenNcX(49Da@0%>x9FqDjz`=5wwY(Kh>V4z%~>P56;e&d4k%*p_IDq zvx2Cc9+TRYp(Id6R6LiPka@Eq6E#)9LWiOkabgh&uiIV<4acu&bc-(VkwzXXU5al(R|_AA}=WO-m1cqi2dS z1C)m>L8b%)_+|NZgz-l|F1>il0yA~uf1G-C!=5_>XdzP}gq4YRc_$2~Kr6%;=8WzA z*J=%TuwRQlWJ1XIBU2$h$vjeUjzn<*VO%T9I)z&7xa%%nf|vbgRSFI8%4 z4^Nw+e8znA!zv8NJ1!CX3ul{k9B0J)`y3y6y??_g6VLH^-+zWjg~p_>lU3cY z0uC;x-uDMay!U@-E@{goJLnkTV5}7oI~R8_DE@gaT#Z8czGaW^DME%-Mc zbwzyWR3P|^{Vz4fxx;&KM@=p@Pv*8^@?C>KCXCS8gpJyRBc|Oa-A1@tv%|b;`yndg z8~Fogv|69en)(!{GWA&nSQ5dl{2!KTETj1GxD$IlUEfjDahQ>Lo_>iCFpyvX)S&~6 zg=t>yNuBd#EjVVKkufS?vSNth7K5aX(ZUfkyR_DwBu;IK0=w2YuMU;EPAw@X zeU+lv@b6JK+4ZtBU*f~FWp$~H2)4T~yAO40K-4s!cl(ZEJC3RM?szALvg+!w)kZ{3 zW}v*IX{S{>Vw1^5)s;oQ3^^NBj&K6!)DlDkjrxDY8Dha7pT_Nly*AX)InSWkA&uvv&X6_q%x}>@!T=eM=t9V z1WilJO?H3XJIUEHnJEv*x+RO+eyf5X{9j%h8;i>7M8nSHQ!D~A=PBjiTi$>1skd>B zj(&v%-vpDj8pQf52Z%e9*wx8^%fm+E;IXVYKOb9|Ehy>cyu!*$iLW3#mbh2s)M4j6 zn!fI}C)D3&NP`#`N10sm{;2J1SV1Ix$0a@$S0~4B6I{xwrk!lB^rZ82jFXT#pMHDI z-d<}G-gd&_Ye$IwD-03HbBp;ikCsd!GatF$f){R4X^@oeYnZOQkKwTpgxyyG`WIY5e%Axd;Y@^XDfc{YO8MYSjszqlO zp9#-t@o*Qn-?``=%l4Vn3re+RiPD=`n(d7ct2SkQxbjzGCVAtdI#mUG80U#Isjd^T z?^2!o0c+6tL(e@s@3U{m1>5W!PEyK#t8VRc2w59JcSvOWfSIY(_dyUt%Nc;y#(8Xy`=v)M?=RTsdJs7JR$#ZDgQdBGsIKTfNS}j{~tzJ zqlw>IX!VdP>}~^JlbM{LBidXnuH*9jIn(4D6}8&Tf=YO>7pZHHXkPBw6@fSrL z2N8NawrbdG5wGYzf(U1zI<{qgKu|X`hm>1tK?Cjt-6^G0Oa!h#{XsI}FP2p%$m`~- zu*nLoOsaTcQ>6LIk$!f#FJfWThOwuP-VDoJo?03!6~7**T5u-FP+IWP5XWOw7B)th zF>oH#Kd$U8_%BP~x26VrH#Y$p09DID>ho0SZijo07#u+R)qF(#7k|=#efLjg#a6wj zeOl;Pbzp_@qi2o*Hx!Tj15M27+j-^_o&i{5ZdRAxq}P$jgaCNretq3dK9<&b%$ow@ zS=tVHU^o%6&L1|ix=@;o1ax7F9Ffx1Cf`-5ajI2IklmqyER+Q#ZygQu=bRA-#tl4~ z>mRdA`ww+_tOK3swC(#{lC}|MV8Y7mOEB{SBW^56I6&Z`%5h)9-Xa!a=&f6)$x{1G zoCd+*2yW(9oa|ap4zb=fQ4rnyQoL{a8rM3To4$F zhlTaP9ys4Z%jx>?0x(K0<)>rWNuJEobaHrqz+W-k7KajB^3MxI#R}sq&LjRvVf|Jd zkc~v>wjsdZ-z$|k)i+N}4&nBZ`Q@NWs^h2(oE~xHbk0CXZIx{68nsBUWL)uJ!W?6~KTc>_i2LnSu@zQx zBNoPd{}mHjnF$&t@=j<<{iABkQh$LeFyg>hG)ko^h6OK+8N>Tl#fI15WJ0Isq z^`-z3o(CVHf5bT0XgZ+BEw5 z>Zpvsow5uejZ~Z2FSH@ZZG(RHNsm|_%~Dj|x+IQgFt|H&mD%i(i3m!zilPSQjY?by z8sc1lJJ^mk51O}S>Kf6$DLXY22?g8rtXfM<1)yu{xjYk-zDbQp8+q-*#WcgITc|n4 zQSz0vp+O?cG@rjQnmi*eGtW|h9Q@S6({t%{H+A%LW3WIKpHfO|#)3-Qg7*v3rR$AS zkQDx_Ck=t8#X`~tTbEezW!nF$BynuRb;DBIv;$R9V&Gb6Oa;KiWwSVHG~XkVsX|CZ z0-UjZLwq1tu+*b(h_W>v+ocIS!Rcc5cf^*%tP(fc2BA>za!d1gOLk_l_`5;a6@=oP z=EGxI6)49_oDR?9L!-SEyOH={)PCGE()a`itkiO=Z%xhm0T}RhjRYlR9%)MyU8@AF z+mUc7Bp2kPKkC4{U6$9ZiJ5{HL-R#mc~}Cn-C&D_j1}Cbjw^q=-N}N{a zLfQ5CP{dYYlQh04CV}hAdW>t!f)-zy$XAqKm2CRst89lRNG1TupDx!Eem(2v$WvO& z%5xG!cJ&*Jk4$Cp?X=|BAR>RQ%pYsYY6Ag9vxIGh4N|O-Buui+7)Ps3NB^>!wZpZ1 zcLPHrn$YxK=M9&MRQPNQI$(pyS`qnp!s@1-VV`}qWrb>>h9$5JkCgQxYk(TgHCISa ztsC&xEBV_X59fK4Av-(u=Sv42MkT%-I|bm_tLTDwuqJ#Ved!VYTc|#r0+WZCD&sdM z6ipSP>{5QtTpA0_bV0NA)NR|zw2ohDWA>U;w(;Rywa`?zVCbwlKyS$Nb9+x{jDZQu89g0IuJ03(7bo1gmvmDr9D}G=a@-AUBZw2 zvOB}flc*n-@SF?j#*5!PGeE=4CC(5^qf$p^;7=Tcg}kN5VZ8S3cW;1tPU)i-rgD}# z8-_Bs%BREZ&}_S3okHaO`m3eF@A)Z^7pLzL61JiO94t>7M_W5`hc5B?6qrm1FS`Bs zZX9>)J2l9E!hdI6XiI=&NQ zIS2E{t1V)$PSJ7Tt0Oq%4zG=)+cI@~ZV~(?mI&xceo}^ANVgLp@SGHh_`VVmK)Zn1 z4f!xdx-o+Y2rjb5`U$RJPNQY%3o}>IYQX1E%2-+G)7jq^d*`?-OqSCm>04FV3a0QM z<@PvaeCrW%bs%Mn>&F@+xokGv1UY5+vS->)n))S`##)ps<2i)y*0p3q$@P10C;WO; zV^V-VQ`QI+HH`6B)?dZ5JBd}FOj6i)O|3nss(JHCzh71#S>rX)oBHvfD5!E$8cP-G zI${f=2OKC(dl#~}I-LD%;40}Ws8Uqd26y4Mvl(CaU6CFgdETs5qwZqx^TIP*i8I

    yjwT?tk{a@u}TqQllLMDbJr&OqV2$1!a5nO}xnD|9Xix=jQpqZduKdP#J(M4zn^ zKu8{X$hf_$lT_PK$^>JVG#R_5L))-9&blX{qFKiZtb&$U^33*BH9+u!uTrM}oID`6 z1t5qx{1{ZshYFaQu>`-zQ$qbj!&EGoDn~*T;H(j9!fJzyLXc@LB$I*9o2mLPo%LGv zBs*>faCMjRh;a>~5JCab<$DC+iGM*!Z^f_7fJxonAhf^Uwf7ALzXI3QVp!}I?&VH3 z%-@r@o42JsS2kh+i9$#z9h}b@pvs_+2;*gC<}!dTY6#1j??r!4lYs4LBR~k`E*26Z zyRNgHmC)mIG88cpE)df?b_$%v)bTM+PYv>mx5~%kIh%#$vb!;uWi?j|$LpAqy0RI70X_!$oruhf>$i$ukUCvGOLacvl%uUuqE z*VAJcOX|T|uWAU6Co5U-7l4A4#^-b%+7(qGZIX@P$&e-}yY~jPlB8Bd{n#}bR5`0< zOyf_>H2WHb(AHy3+nBXz*g>?J5uH(`;o^-D&+bg=t8Rvn$xgDm=@rlgyRNF9#^#FL zrzCg~?kj%HoE$q&e7Xb4VFQVV;9m98xMYSt;RDTw0+%CAczqAj&eb&S-mcoyZE;#V z$`2VH>wtT!!j(p>USUQ$K!$5|?&}^*``R0$M&tHk4iiMvah@o)s|_>|zA_cYvy>`S z@YWOTFjZq}gO)*o;`V}G%O5+kiCF{3oj--MdCC6Q*YeXRU{DvN;mf1c)V=+&UUww? ztM8iQYT^C5bJl)@jA)KoDCD4NoG_Z7w6N0SrH2-i8b#KUW5S<5Y1xA~hrjWWE#bco zdSFk4C0(D{mF8jvleNUtI~-M5%UsOM1*)g4TngC2#kn}`6z{E{Bmw>uF)sMksr)Y#(V(k?(3AW@qrjRWxMBaKV^%0$ zXu-n%d1|LBTXUpjjh;&=pV&winT74LnKH@TD<2tl#K^uG}3N6iYSl#rg!%O=rxgrz-6LPDX3@d8abTG)f zRXW+#T!eTK=P-no&HoFr4}BUX3g&j#pzZ5Px;q#c`Qg^TzSy8t(!ik=JoMBAA}r}) zzQk4?W-SHgnAaz)<H9LlrN4 ziK3OuzEYb4K9-Y5nBPx_Xj=2cS$ZwP1QzoGo7u$nN0)wX^v5G?HQpy-HUa?}rS83^ zBnUJP@DaUh*x%zY<9f8I#tZ)so5Ty0n%PaM z978e9IQZXE1Za-{E^YRC-(gP#{kbC_MV-n1gn=u27{3UNwoG03er)wkN6!1}s zNV3RjWy=@ht6<#Jfu~Q!cjhyhdOtNM8^+o=CPJ?VkHE-7kR4f>e>wwD0cPL(G|+gP z-t8##(tLk_WkpvTkl^*$VY_4bVllNJQgM<4FF%MOZea7kY+PQ|eM$&VdTglD%by4ZU9y4y8p+4qdoQNeD?rkb< zUCb)z@XEu16Yzmu^^M)e^2@%1p5*ZO@S?nS1y%?f3*?3)Ft3H~raIzPA4aBZ>wS5v zS<$s2wopLb7F%mQir)&g=;xR(omV_EC_hi(Q3c=Xu>`{wP=uL=4D@Ew@|;LVM=0t( z%Cfks-c`TE0blb1Efc!UaD3;m&ju>&%s5@DJ7=ad4W&9TKx(LkTnl~CujH?L`37;2wKid!g7 zoED-`v`q}>+B~=srb2AVR+E;YG0wA<9QM&zm!>$q(TB&*!%3;MuyPwpl7Q~bf99u% zwuZcm;KU%YN$&q1_&NIi$msAZSsnS!wQ`z>K@JF`VEGRF{yA8g70&b*CSh6}0gDkI zXDOk@pL<5mWWJL2nmgL0?nS(pVSn{?09w>Q$_c^&L4Y=Eh39~+Xn4bWZ|m{^-63*( zj2=+GA7!85fDEX~Bi&^P<%Ua3-I~S1>CnXZFjD_Xjy<#$-#5rVHyN=yoJl)O1xM9q z?9wp*M^+bTcez`x#w|_8st%gMF}WIBG5wtLte-!o&`p@foHIpfVt(ImDtXE!C0qqc ztX|HI&4-3suKfF4u0dHbrB6ZN?5O3IcQ-H8#6pwiE|rP}7IPn`@3#zH;BCZuJ$u;? zuIH1DJlbbP&`XK7vKD$P}78ATv z?6}xFv0RW1#D-m!y{l7RdJ4$@?7%k*e?D!D#H3*sA(4mR%EKW=Oxguj&5(m!uDH!H z+E9Dwgbwj#EHM7-Zh!dY34^l+26nE2|0^gK=K90p*M1;DC}_4dirc}5*^6%Lb7jxQ zF94aBjK0QkxI2E;zV8h}%fxokBJF4ncKBi`4EoBIh3omo_$LK^ocK2ft`1R5YVKXM ze>_K>q2vm`^jL;Jvp}jSG<TVsIIZ!bJ(z=|p z%v%A^NSXi|A)Zilb@`ugrkw%dY&r$X*LtI=MwTnuzC%uqXba~d#i0mg{3>wjtmLk- zn*8=K0lUYg`%?lKGIM>cv@~^{=(Z>QKr_S0_QZ#Q?%Qq*4;+FU-C7%7IG(}u_4y^- zLEi}rGR4^(=r3MRIxuFMTabw51rAuwk0G&#(uQ?^G^WcRh#vXPes%_mNVgT@NZXRV z?!K30`>zH691kEqQh#FQzl#^8#4F2J^7qI0>wBN?Cf(fS+h|n$0g8OlF4)k01j8MG zzpac!R`%@9ZWsDd=Mx{~EUZPp($g4r&)_9-?Do_ZC)i7JC`BYQtRzEP0n8}B(O ztFS5lXBitl^Z5c879@s%5WH`8jau4pl0W#_FzX;Rx@B#LL!68+R-SidA@#R)`-7&~ zd4eN{V}pq`S^;9Yf0y#VxqDH-eXl__KhrWqM*c#AA;F&NbTyt6e`RKiP=;9N5}t58KAm;>H?Z~CiwIJB)o%I zTZHm`E|$qCS>Ljw11GG7jRPtO!%dT`VjKhN&W{9uxL3Xdr!Tg>#Gkj$I zjLf1C0a&NKCz>19gC3fd_e<_e^1TyZFU=qoE!yx&+xuq;2rdt+)LX{-N=7De`9itU zY?m7x+$T27<-dtuAPuPMw+O_Zipyw(QwWw3ha7Fcci+^|+$L%8IulrE7XCV*LU?3o zQTx4-MCgxvuY4V^W3gP6+I$rw*Zfmw!(IJut&D03>if1PvgpyjgoCj=DI*@BJHViH()EnN7B%D87hFJ%GIMW@5Y>QM>zcEKPdS>;EtFea<_1U%Xg?+ zQ4n1qQb@LS{}6og7BR8$SxbB3$m;y?MX~*sd%HA8iVydJ!24vb)Ys+T9i8>Y|DU-m z=BXNk;8b{s4Oe|eJoTA>hT@-S7D;etf>LwPRnTGsXnZ5)2+Xz^PKrZlz-VLAXG2s5 z3raZs{n3<^V9LUlA`}LO!g|gRrB;a%6qwQ91q3K_;(^Zf)~pET{E!Vu=jPibPrHi_ z+rVJv+u<7?6AwV8*Oq%9*bX)W2w@_k2m z2O&257%>$KK@qKo;6^Q+);ep93s)h@HsX$|z*a`CF&Zwm?t(|CwA1{soz9cH>X*a* z2R8SFXJg~1`Tnxd)7ZlQ&0PBh7FAJLNk`rQblZ6%3l}WQbFq%<=0g|QYrjg;oWgMa zQ~P~mp*~Z*um$D?sN&O(niYIBy1T_Xy#oL7{ts=)k)mPm{*<{m2J8N%KO!D63p|O- z+c@(bJ)knN__4k`tr^kQ^(=GYUN+gB?5wN(CF9dcKH*Mvc`^2$fv_?U>^}t9BAkzrIK<4TpZ}K3 zL^EP(VxaSU?tzJt%f~#7Em8EhaM`>~w?9xq>3j;4B2pe1r^()gVaWgzTE*JYs{aK% z5IcnQa;0W_h0D4vPU&#wxB8B8cz4t&`I06?EJ44bAOH88L1&Fy?VCM02EpWf!R z?>639-uE>FV-GTyQK_*tPU5;+E@k!n5sMMFj^7UcijvvzOHdvz z8qsl5oDL0CYhEGgU?=-0K%*qJ6paku$m0I4kReXN z4q}bk=3^rC*zMbQ+-ts0M48a1stL#5~qjfI{+RvezO*V zpFL1y%88sI!v|@Ny1WRAzVABn`JR&MZ0P+b(N&Lf(`W-EozKMxFkEGUgIn#tpaSo> zQsl9Rb~f{WR`ys+HQWn%Syn&B{9j=%MkAm5-KV|G-yffj8cKQRN6;ckKXJf4AnA$% zT{;@C&@|_|L4N8N9j%1?ivXxD!wK?>o)V70u=4+u`@!*L&jSqv{fvMHX&5EOHjccl zmI=Kk*my56oaLW3xzdlHm(aP_NwjTYW~W(Q7?+ZdBjvEm_+5ANQzQ{8+W^Y(#=q+z z!xUjZ93n&Kv%~bv_8SH(j4)xryib)k=`-wH`1aUW09%L91(6+%=#67hTe_6DD8}VrUCfslcR(7Ra7n z2Kqr-h=I1380?Wm7-mlpBrrUq5Bq^Ohi~{TMEljWRgn>TT2S zfn43hmHq_E_j?NKBZ_LB)O9rLI)Qn6HyF*#^K!gt1)Z1M4r^|V19tihrl(NDvw~hc z!lf23vT*KzRm%6!;cAj>?Z!`)r)ohOW<9}rq5{4aUqi*Z%YHTt}#4%=}+ zUQ3nHn0h03u(4TQ~IsXIG8(>_Y+Q?Yw0$28Eu+)JbPoU!lGW23d2gQF`@+%S%Jh|5$ z_4HyjY2uOyuJ(C?{4BZ1dq~z(_-@K3gvJOmW#SBg;$$9bd+|FuE6ny`bz5{E}Ze#Iseb|#^yVdw_ zjI5+Ir#(RNR-QukNb?CBIG1UYS|$c6MfFYtBi#_ZB%pX0vn{375VHnCZG@4QOcPpy>U)W+p<3(3LUF>d$%qCk;kQfWx`?G z_8jCBB#gTyM=z_GHXiGkvpgXQIuffgJSHtM%0vpGq8=>3GwGvGcN)dxQ+w>=<>O1l zv5vSbkLwOyYA$85gjXIR=q+k<*;R1^eX4J?LtO~pYzM$6slMdtpJ&OVghq@$A+faX zfNxKyND72#VEjy%&ovO6+|t;>d-AreC6ar8k&ya;z8PCiP9F=cbkO@TP4%*);N}kV zG!FQq4gUFgNS1sTaW2>^Y`yS3{fEaA*Wo^0v8=ZpVQCgau#N<}>hix&^#9@{PBDQR$q5ng>597ELPra9aV9b_&+LD$V+U%B%6nZ& zJ;+T8gBF+*Nb?lYJb+`r3t{s=06xB{2q z{*M*f2JrIaQjQzx?^zRii{*Tob*>kr0R6vWBG0_gMH9?w{U0-yHf{|mnJ4icSMQ0R z)R-?oNkM@A3)X%bj+ZsNv2_1a5*_*%blerD&-ZdDfKypa8CPE1QGgP>`+$Y+l? z*#fneZR@aMV;-J8+rY=JN*yy>^I&@}Z%@ z-&VvzBMN~FS~BQ77%Mc%Il#?z&`_Q_aESnOo}278FX_9rA@nzIG=$qyJEUeD21V@y zD__$tKvNv=#s`&yYN7ZsMWtbqU^QwTkyS~>340(1Xji9J_QDl`}L|CO{dUoRxu9K#bb%0IqYOcb);IP+xTxS^nMY(qr)O z4*P3^6js*nh{?2K9?k7MZ(w=EQXGL_7s<%EP(BP<9U?3U5`!2>WGqvGXE(_y>orO5 z>S1FW%$Ow9X#q)3f%@F~n;8(#nQ{M0HF@)dEtx6+z`R*Y(tdsw#&EFuQ}4wH*`3N1 zIRf4#%~&oZ`minox<7x9lHVYxu!3faBAxSWsWbBCFlE=v3?UirE)O|3NZXpfLK z2EDI+p}@m0)la$GT7JrdF76n_{JXi77#f^z?sSs>;rD$Z+)`Qru(i7BnYw04#P8 zD(lGRkU9>@k_3!sFjTct|9Oi&Zo(gh zeUZ5;tM0kyD+JP-KJ=zb|1+e3nRYqk8nx63%TqBjtv8wpQT0kfGaiQuZeM zYP?>>4x9Jf;EY2+g9zni=0J@x!epBsIzq>ex>BCS6i?3U`CD;%PA$J`NI;b&SW49H zZ4cTPm##oR{xV^@@HLI+#Q5YeqbQI4lVPu|LUmC4Vydp=)=FUp@3&zGL?pH%bGC_X z=uq^NYM|yrt z8i7RpwnpK}a4t1<03W6Imva_Iv&CE+w(-NP37s5>=CSetx&pUVsk zAk2e8L+_l_L`P!@=jWPj`))Yxb^IqUasq+vQVa9=uW#W# zbm`hu5{|oucz{jrQ|@U)N^uKX%6pTGky^dk^*dR$TGc3bx_Qf%ZwJny11{B8eV@y8 z$vD`%$VIe@;@spzvj&0RYNTB;EJ5w_u%$gH$O;7tcT4k2R2Y$^^vhuEcHfxmzeK&G!x8lZ9v}qOVkB=6h($nm0znLUli}X(%vO2#S+=nqf5Raq|;N(JJ^XLyKDECu)SB4PU~} zUTxDQZwik+X*-;fS_wQ?bxvg8c)DpLML}RT=wvK52Dd52ND9b8Ys(4M35=dzMf5?> zRE6vQk9R*mIKq|TR$0jvUCa60FduzBUW`X9ZQ~5e;aT=*Ts95XQAccnxnp!)Xe60_ z8NTRYpoUw5oJO0bCW=tm6#xoacli1?9*c3TOMrpj=5(|y;h&0!T!IP$OX9k3wTgh! z(0ICvwSDR(Dci2!Mnkgt6H&y<;yGkr{xDc*3Weu;OT%>QVox+l!|z(Du%`Dckk#^8a1 zQ)&EclGYx!Q}eYwai<+47FIe<;|fgU^H#*cBH|rLV(y0b;^8tOc(J_XQX7oalk)hH z8yU67l{7M~n#{Xz38k4(d3TYqXRdMwnf7DngV;D0!{Qn~$1Sbd=gwO;&u<{S1?vKB z#0VD*`&iZWJgXo8P$bZEYGJ31_`lHL1+kFW%ks7=QyS!>=pKn& z=3OW$**zlo+-csJ2FrEMT9>S1Rqt+8bfg6su>~Viyts6O0_o4hcIZ@8L-2OM_vmST zorKWZF>^9~qZ>}7#s7M2;F-PU9Cw?iib5JhlH>it2f_wZ3NFQ9Z>$(p!`av;N~70x zs^nHT9nT29pPE#=Z`U?PQL_Kwn6u=IeCnh*BtBba@akLAgu`fGLkQOGn_hJJE1G%xn1Q&hgO;Vj&687HSD_rOfSYdR zPqjut8=P{6G-Q=aq)fBfGYuA5bkwm$% zNH0Vy0^*-{8$JiSRQO+o(&6#!VS=3FW-TX4?9)E3+zxr=a&z6D8QD2FLgp&;0Ou>k zg;`hwFx_k01I!`4AMwj%z@{-LjC)1TqGajkgHh90&S-I~GGALg;2)Rq%XF8UTZE^1x|+blk?Jenel_ zAYF?+v#RwfKzi49z^M&pZFm)8bWNX`V>(hCYXCc800o&d5a zHDN|PqbS8)gcH32S{1VmL7xAY{dwLS%)VAumT5u8g*=&K97O4AXqSQSD1I6KF-F}} z%OM6m#KdlcKF23CmnAAgMni&h=H>I%GEh=_I+yGzsXd1QI$B3q_@aRx1}zuyzN_l% z8?+e7z5+HjSkRT&j_-c|H8;A|PoZ)DRnx$2!ZEMWR*zuWV@#P_@L>tOXJjIqBYtrb zO2x!WKEsf0=zA!4@4{%p>s65C+Q(n+hqOjy=BnHgi&5L0~z_SL)mX#PdTZbm)~lRNau!bok$@n%wV$M1n1tE{lzq8 zQoq<9S6VpwNqsEp@?7ktX0ed=DA;Qj2%diu`+)K~>avI%!K= z2l;m{3z-$c-R{%RljR%uIs@xnW~>O!6^NU9?v*bJhlU790Qn6t%|$ziaq#2QAqy|* zCo56I{J;?w%&FmO$j{Hu`!d8sMZbFdpE}_ye@Vn-}oGTYLWTtvE169?q!U=J7C&VoV56<6z_&0JNt2?pjB z94!g#4k2l{_oHjCy3aU5Zus`>3*Te%h&@e1U%N`fa7;LTum7{`Rv9OD=K*+h+TDyu z`F)i)QyYIIU@qkQ`NsbM%wWY~jjpQ11MU+JPT z>bkxuf|zYZn(0^CS=)S~6B4Ift2Nu2mbq?*XAb*Y+SsJz+;^_*gvS6;DU`J_Bu!m+ zP};kST|cE(5c?DMefnqv=wZ`r`yjlJ8$QKXCZ7w8c1x!b5{0-0H5>EEeI5)4W=55& z0Fldcbl+A0P!9(lMY+Jn9DVvNSjr%WV7pDn&o$K)??(4zJ>SqUiTkxZ?%7yXnSCf0wD=c-Y{2%R{f7|VbBV#J;0lXtI@05%&!y~Bw)62e$BO#LCX4? z!3KUJ#9I4%2dcA^+0p!q_1JQq&`*kT=B2W35J(1I7|E{C-A5hPSR z;my58Ek#NJBS%jT^6{aAfNport+V(ZQ#xi0{F(jEiq^rC?9WROz!{Wlps&fb#EhO?)M9PFos^bjHSt3>;lA&a_ntMX0{REu9)H}R*6($3{A6lmtIG zTm+_pE^XjI6W8-2wtSff?orKySAv&Yitl=HvBMfzuB+NFC4OF&CW3kb24T=t#C0QS zlw^x8?A{C3X!)%>b-SJ#_LNu1TpGD=6n3Fbh-H>^;rQC{*28~LbABqTd9g@FlX?jg zn8-c`u%1o%6u7Z%7LSOhhyMV{MUxK!ct7I1)_SGftZ1n#t zDYF8#wZ-CX?_9j{jnna^p&QSqZ(ne%(G|=(th*!Gu)X$Zpe{JQb6X+P37`DzBOH0# zbvOvkk@Mri1#bT1jOgM0VFCKn@DDYk8wwOIQ_wuh$lvxZ)zrk&3Vt5d-NPSbi%(vE zMvYSy6x;NRLP|e6UnO)Gv>; zaCRvnQp$>RM}(INMOX8F)U2myW+!{Q%mmm9e2j|D;n@v{Ki`otpFJ^qDz-OstXvB9 zc32t3q)pf=I1vVEYY10zXkitROLW6?BHIZ$#YhXE{QB^v%bE?}Ui+*R*c8ZKMw*sP z*RRZ#KZJ?;o9z}H+$Gc9viMOc-LE;{L5CXm3V-rrs71h@SdN2Z;L{+@q2*K^;so46 zu~t@S^iq??a*6M)L-4TfMJ#M?rIJw3v%95h7>x4FGI^LXen@zrRqXn7&BvJ|?g0sD zt5d8dfOo;5)Nje4p20oWiNsC2$NVFac8I!r&&k|$clj+ia1trSS%wKq>0#9?iS^SVzE zhYKO+OoOW0D@U4hfo!IAzc~(h9wzb;@NBN6^#QMM1rOX?{f46NDJAp^nweKC51jgx>Vabrbw2Pmm6_6qGc6;{{ z_``piq@BbDLdZrRzuVdEKi5j>w=I5I^%M}F6`}T3MJpvjL?deC!qoQZ*~eA3w#`sx zx&@QNXLBx#F&IYTTh|R|$nC;Wt@Dn4W$Or`P;Qv-si6XXDRHO5Hd}PQ=3yz;i)?+R zb^Y#V9668mR4DRxH)bz&(IRagE50QH$H1?O%@aB%OKvcm|)pWy>XTEj2MKeb?F+L?{>cS!mBr%5dRP^%30q zp;v$S;fni^EXl2t>4%)Y5KgDEDaK2^cb6}U2KPP#%G4~6ERv~<2%?Gp1 zka{#=P_zo^>|k-9mQ7F&+63*(*FDp`rwwTzQ4YRgQ77G$xI)$6ic1JhZinn{e>aVM zh`I^hvX8h~OHhWIP{g+H=mvWI&z-W1$^US4m0?jmUHtAY-QC^Y-QC?FB_J&#AdM{D zE#2KM2uLhl(jiEfqzFn$zWaaY%k1tw`5D~H7Cs*#_x z1gdXx-lACdPa%6QDcNhRv8JEf{!#z9BkwML(m7>p$7NIa4u+;%=t98iSVy^ReoQ^l zg_txt2G%o%mWVC%u?E1x-$e7~lUr|C1)6Nk@`QE%`qXn?BICKU4v_#rcKw(b$d9Ph zsR+-9k7G(Mdj&-0Fu^Xpk`s7CW5=EO<#y>UF^7&EH!1kZ#J5_IHiC*lXtxsVM$B3mo)UJMlql8=HmC;w*lg45W zSr>v9d823y&sc2kCR|Ciu$I>XuI+Bup@KOr$a57dI~6=Km*L#lOwmMY0#PxHMzN~b zT4MI;GM$X5s@Hk0KNPIdL?j?B0mFVHvdJ&sM}Y3 zOp-0^O$?@Y(K_MbPW?-tlKuQ(69`d^OKqV2A}m)k6PP%$oAzg^=)0a%J`OUtG2{#$ zF(M03U;@rp)D4##*w2K}PtP@3kYW4Xl;V#wFWoE>ZuMKDiqt9_(rOQYzgesQy08aU zZKn=amVAeT_L@reQV{Z}>W(WCR7d|&PBiiDpYtF{U&*l=0VZ6thtHT?3zx5VrJ5X@ zjWOQg?((S9RTX&*qHm)Wjn{~O!jJg~XopSOR4rF750*o9MxPpy8O}i16re>wc;;+@ z6`DVD##$eR!rJHiFHBce&ugz=M?=-2Pgxh4rDCLVM3NhEvpA=xyF0k49ovd zYRiI$FGW#Zs{uRkdi{zl@HLzXdFBYA z`J&6?KJWehA$-WDj3e9NLrYe{!nBw;(=zG+g@rs@lYQm=SohYE5275>sk4%Z^`l(} zfYSPW5q{9lQ8=#|HTToYS%kkVXfXcwPtB?*_c3OJ^$uR?W^4QoNxteOG2CAt6!*7m zGlzHfPgz*xXKVWxdDL|Wk6DZ;D?N{L&8p{)F_iHdY*^fDzGzpJBKZ$>e0!FBGOsn7 zHS43a@-^OT8s737%qhY@whQS+(1_r&8sJsjEWs10qbmFgm6n)^%mP`3_ra*@B>;QC z*W$4O`;`+pN2_6Yj0n^^Sxb*H@_^T7vLy63yBZNNa`H>@gyN&;$y9iVE#3q{jGWey ziGw2~FTObao14Qe=w5FA_KSEg=-{b$zsj1m)av^)G8aED|3NPAwUwuJ<;c*v?TGf2 zv7S{P3E=>_$=(MHBTFasP!P3zZ-Y*8A`s1!g^1pY*?6`WX!z-Z|FTr)oAT;K-lZ-U zLK?uBxsnA_h?!r^nA$JlpZIE}B=1t7#R#~jTIo`Z?_FNgd3c~=f=IxNe}oARTAay) zRPen2K_!_768|t%FeeAt@!>ZuIlAy-&6*#X*5WZ=|944cAz>gJ{L4d!W#O8P>~HpC(|(WDlvwWr>2fKk5= zsP=IDyJ}@A%`ueF`qahv*E&~INUcw;gi1Qa+}9KG2!pIcdu5SNmg62NWW2`+lKn=% zoZ!f#d)x+djQoiWM3&*blpWvaMAtPT>7`fo59ywA#H3+WzC|Vb{(Ej!Ze#r$ug5=nskkwQCZKiWv#N ze15yzdnq*mikx=gD@@jXq_xuJB`tn?GglCeKl+QAhRR|JQSQD>?L;;S0Jtfn3z>z` z@(5k`#qgp6CX*Wdknn}vjUR;=v~*n=skrp~@s)Q?=S?k{Hw{jtVomTi!Iis-NI47JzsR*z~? z)^2!-sO4|{t4^gxPTbZwX)gQ%%8}gQ2~&ru$B?^N;;jzqts!HM*|wEoax`X8AZvn3 z;5B2TDw9`Eb*B29iD0VwpO(U&)Bex5WVL$FE(B9~^z`4^ga}`yfB*(kU6!~j1ths2 zNp@nS1}^#&0VD~0#27sStFfldG&E!re2WPM-y(ZvF5fa9F-`#Zpb!E8kHH7&BQ+S? zfYK{h7Il1yXZC3dmOW&mOZnP45Fc%9RSYjHG@5l6P|#wMq4|I~Gx@ZwFUbi{kwwWc zhPkXar2N$pKmnVk4lne$OavU|Ke=@`+FBK>7lP4;%69^8`6caLfcSg3jLNN#8d+MJM(wkuA5AYw`LpW{Az_bn)Y_-Aw z>B^^0{Bod3L+NQ2Vi+du4|8CtrEg|*Vtjqoi7m4)Z-^T&xM^bWrn_P)z!H%F$2MO= zk`gC1zBS(J{lnrchwYJ^^vFfgoE*R@*Ju%TqKWp5MTN<0>?r6S<)!2N z-P0a4Z)B}i*Ez>tDR$6_K7sMK6cN=r)Yr2=8O1>@ZngT`jE}}E47Guq7wx{h@z<~! zmoeI(*mG$*CCL z`B{uBtD{D%CVWa|5I|fI3O1Vc9(?fsgB(OUw| zo}Uy}%6k@@eKUhI-F7}aStXSy-!BYlcR_yO{TQc!sSb$*%(^&b7KuONHV``b8*ByWehH^MzAs0 z2*%?%HM`z;5_D@t*0x9Sp_#myrI*mqeoxBAe(*`%2uqgDzg6%EDuHbw+D==Al9Gzt7C70O2B0$n^-gL>-3t9O%Mh zw;^{aWV#c~UP`k645xVgVSSVOn8uUR_|5i_9|&0#6rxG;w+<-*y(y&he^zACerTeP zRm*5qi00XH96f$o;|;|{VtgxMZ;}UYEOkFFL+;Masu+&P%at znVB)nxi8425&q!$LlVOnaV@Hm3tWVekZh^Q z#JRotlEuKbzDPM2MLW3coZPvaa@BOt$0<-OUueT)Fu`&w3VgK33l8BNujWIy%9lNo zkeErif^mU&Q!$qQU7~D4>pe9vn=O9GHWkmBCA)bZ|9K-OMy(tu#fOhd0>F2wbt zUeodHIp`XG@s2&_(0`%VbAJiS`I7Q5@XA|V1YYC|JP>=xy*xkc%+D`<_`2tH;K;{% z*+4l9N-%%A-*Udrm;{j}U{G@NQVIn@bnlFUHwuZ!@_V6CWpu_gKFx6zl#KG*iSa$5 zYB9<@bv1`1_0?AkXtmy z9g@}4UAw)I}b&zeTmw&8MuKKPT~wuxHr#7nph z;SI9afBs}j1b=Me9Of{Rsh{zhohbPq21L8j6J{kNgCg(T{GbxLDJ#VW3M}_gnCg#`Q48i+Nj1MOH_tl`j zl%5w?!Js&q{6ZZR+NC&gFl_{C4oxRjCfW>#?hFC2cR!tV%6QCyqHwPFCf&hMr7cvM zM7&1~UESyE^Jim^epyV8bD|Z`hqsel%L;xmQ(}KVPsXNbr_esUT}}_F=PW9F>lVGX zR_tE-Aw(tc2Br|brpx?-7aOHu-jMgX+~wONXyN4JL6z1s#3$k(j&4dYA zGIT5Bdz`stsmUQCmS*-mZ9_d?a*sS87oJD zt!Hv@^u_}A(%9p#1?04(75Gi-L2?gLG7l-<-e*$Ij0uv8SC9sVwJh9oamR}l&v$hx z;~HNJ`Fu#9h3%1l;6eMobd+~{zJwY%)ctcFGTuJ9c~uk&GE^%iJwkTiFjzWIMXB?7 zz4@y>Rx4Ux_#~~PfPE_e-b9CWmK2<-YSE`q-6>a~P}+aT101Eupx5ITVS-3ov=GNL zjODuOzqu}KP?7!}tO8m&e|uTJ^?LR2-GWX;Jmxu4$plh4Zt4S~w~kb8P4L1fL0d^b zsrzKU2dya#QA2v&0SF5m8Z~sn&foDN8pxx8!&he%9<3FVb zo%{17I(=NvEPK|vy=QzbLi}I-1WRl}a-8oqzopf+)HZ4plIUzHv!}{1^2J%V8I>%s=HYzn0YBjqfE7AFK_sT%r_i1#rxBVa8#S$1 z*W%d^jeEV@9#j(53?|JIH#io~4d1 zt-z>9w34s#+SvN2h=DUD>0_i+bCKD7ftqBeI$a3z6k<2D|BqRwzu@3w4b`~6k+66vTLPGR#g19)7Xv1Lr$SXb|_Qv-2#en@x8uHH4Wa5BH8-^+i(otXyQ2!xpD~o1Mc4?APooIV8NF4(^gu zm_;=@bj^5!_}LqmP1V1fy&!JhcI0v`Uno!#Yb`+9;-V#s6_d~2@+adS-%H2;hBCAE z8<1Hr@q;S}uqaP-R)3M$eB$lW_ViLeAMFFB?@7h}svpMqW8bbn!IIoEL?D#MqM zM$pNQYb`EEp};cl)0G@7hos0=o-O|yS5bt#X$R3}bnRuX1P39n4JOH`aF38%)_{p!x6fnQF<#CKB}lP-p~Jl+=d&+qQ4eD7RI$;ZCqT*dHW zByGp1<$fh2qHt!bEd0A*;!eiKxcSm~yCtz$ib#Awhn7@XBPP&!=)$Pv!lyJY1EEW( zSl@DGhHg_cJVwvbs2s+jMPzUblE$Vbu5pKq5#m9stWE3kseXHwb#|S_Q78lMV(W@A z6b&9ElMKE@M+1n-YxyAC-Gh^ID$7CpS;F~bUH^R87%mHXBnrs$?9Oh_uzCa5)EFl87E1 z`XG|hQWQ<5?o45(^grlJ$X7;|zi%LuQ1ds5sCta?&azp1?ELN(_HVXjzy~*Zl_1I^ z`t|saHTgjtKjWys#C_40th!9X@|8VA7&}pAgqK3E9B{+sJ(s+Tz96u>(1jSkw)#rh zmVc-J@xAmk3ukLPpw(5rv+<%@QMDOp&3{Pm+D#!bH~n;1HK(X|j%pA;A$Tm63J|Lk zGaHEV#w^M^-kM=H3{#Gpmub_fu6rwmx9vw8`~LyzqI>g+dvt|~C1ygt({wIh>TfA2 zV)rVm+cj<1pv!%;I<}LzHz=F8ZNAAI!3JJIh_00UO0%?D^1?SGw;bsoeby)*HHSU!5cc1b$tuT`ETvaTTmm7E(M2S-KaCav%3r2rEZ1_(&e`a}Sxp@3x6KBb@^c&o z-G4>%t@!SJ#!{o}br-?1%|BltcEL2a3QO_CD{vC}$ZTMgw>ZpENy$tWr08JIH-_;1p~&{qRi-0yn=Z05 zUFAJJ%-=Ks(|+=tuk~=e@hU@a+j$Rnbd$L#-bt+sU!>?He{8rpS-1RY>OIr}kZ0@}^jT)dUeRe$RHp73X};G=I+2W1HH&dM^USZ;_S#ptZx#vEoOX`!4? zyh)gN79MBszqRJlgU=1i(eXa9g)sKECA!E!o#b+BOj|qj>wj)P57+<%{rQLIvKYHQ z`C~9b4o$I;IM_@z4{=V>wh7Z3MU03wrtHebiWH$piTY?x5G}qsi`~VB5t`T=`sR}{ zPAT(fh~V8W)hG2MG(4-aRR3eACx}*iqw|e^C&`CYntI0$D@R6V2Lm4H-2#6T> zTgv4^ZFZ>b8qZ*;t_G}fzhj6MhTWncXl55nZ)pn%)TjugaoW*We@H)BE@Kbuj1|}h zH+66duNItyhsB?@ZuVb*n}QH~B21ArMe`P^FWr|@$qBHYkyQmM= z{yHuYiO0wl-@WB_-=T)gHoJT(AQYjHO#scDspE!Rg$FX#5qd>b#FyjncWi`qvqwr1 zMJ=c*2!4!P&63I*6*m(8Z2GC!N$!|)pZ`d$d*FnTpo-1*$77);&Tyt+WbJXDom%RT zCiY$q#=hBU`aU^;R8I&1sEvg{qTWk%bX2~nuyztwS&Ej=>E`dJLsA>@GE1Y@Uq92{ z>KkJvJH+QViJ}G<`r}yL%4c4Ugy)aiNI`;kso?@HL%%Yp9=ZUb3l^eZHDS{iG&%_S9q#Lrf<8 zjh<;%Y6)}-OZ`~7{=V~GQN0~|c+s}Xn>h;^m7c!_YnHksy?!58^j3e9;d;8Q>WFd( zT+JUeH~Xf~;k^&e>xdnSakWFr>+^ke>1R|c^Tf{Mt(?CAC53fJ*nzgQpdAkwLuyI< z@A5`3Q0Wu@%9B4l=z!9ln=F_kX$y7R$QoOt-h!G0*2h?NU*2SSce-vTRoSSMk&a&= zx9rbZ0iHP_>ecJ|P+@dmfn}h8Kt87yhVl!Fq;;UWvvOQ>^+~gG(}%)`29Nwxl+FBD zXb|3NTw5Eok~~FizDI_y7TVPOn-FnmpM_r-960M!$SQhBQV_-kx1Q4UQ_ln@|C*nx8m9|Dc5@xz ztGWh=9t<98qbHT~G7S+no)tMC24Y(Lwt;usbXJzOJrJTNBm1{lF0Pn&-54;rQdwzb zm`A!q;aJk4IC9;FO~SqUomXnTp^B!HoCG}*%?#8JRxOlF;$1_%ekC)G(Ci;J5O%AHLu(k@iC;?P%3CMtwuS`wxFc>lW_xs zpM71wNhk_0!J$)2aOvLMQk;~^yPWO6JFa-)ckYPoMh3(I6Y~)inJd^Z>@2%$B9kjv z+1)^Pv61h?_-EGR86ghoyw$Hz`P@)qB^qhI@>~7mVVCzOkEoja!<=g624G30hQqK^ z8eLza{W?JR7~O68ifYFtH-2=;ciFk=S*#kyupFH!jFfH>ygRDWTrVXvp>>d)Y1P;$ zSOge^K|B`7=5Z>Ug<%uDYjHQ6y&G%+!ye1te`Y&~&wn?fG4^74#*ytT=gaNv# z1XCHBjwf>>05TaE7KSR{sj7=2YptlC^h2Tz9ok<}oI2l}8rYb0H0sWN&iBtbu(~SS zXuFz*Wa@f)bLR?*^wRS2>InF+P}l&V*RtY|Z(93V9QP(tUH?=Bm&<#RL@VNCW~Uy> zG1x0(D3Gpn;2q91zg|pHEN67|x^%1l2>@CvmPG)PO86-Lz^g~B%k`#hKrk>G&@H#OW(2<_20c^9dAOOEu_WMb$>wS@IAJ7z!nak4d}6i%M63Zc zq$4QkUDZZmH@zo2ky=;>3?Ky^k@i-uv6gx#2~cF zP&)XDyK39slVmbsRHxzviz}p>c+u5dA8vkSuX+Wi0;ySAi&EWf$yiF8%fOxU&w$sm zctoW7G!oJV&BSRi05Kl`S<7Hh`0R{w1_l9Sa;5KmtpP{|r3!V3H5dxhW<&BoKVvWf zP|gORXhtYt=o$tA03fD2o9^lWfb4cIHh`FG@ot&~z+D6Yh_WwP7)$a)d z06M1}I2r&Tp#i|W4D&|-Tm$Es_8xpWf~rb}QMqK`#9Cp|0D$>t1OS>fWWeRypn{cE z>?Q=i!veB9U_ger3agA%fG-z8^#w`**V_LT)ber1*Cd}|2on6sgbGde;S&Jbf2*K) zodw`Pi-f^Hf=${0;6Wh0;ABFpywh1};#JKs1f2 zPI=P{4FFa;NE!$SghbWeX#>Eg4E{Bj929h_5kV^euM6rmfVWH2&`v&dpY$uX>RLm0 zRBHVyQH1fMzqCc)QKD$fom3oMrk@;jG$h%IhPn>ts?r+Zp$-@5GKk^^HUNSyO*kjm zDK|9qS61Z7TBg4$p+9*xVmSQ;$;uPUGmzAEm2&d6#WV91M18T(#Hnpkt zB|;*AuX+O<^G7f!TTu{7M5+Kq)PaH3l4+38VSw~oXj-rX%?BES43%XMyIBAvZ;in~ z$zsg6f+D=Fy!Eq5>iC$F440k{Al3#dn$3!eIJh;}2*TS1p4_W{CpCdkW>0DuFM4PD z4HywhFftr=mj<%FmAiQ-DqMZRLHzcKb@?s$1vA7`W=|ytlz$KX%TP^-066g5>e#r| z>{~pLB_|u;syA1kf;V$i#ZaWM+QIPoKq`UIkd6W9Y$&JwP+HWoK2J$g86h43@VTr3 zD#Q|=@y&4nBKQP>Uv0xD8eS9hC;P%M2`E(r3{3%mrU>&?bgs{;yx2Jvz%u|)$$)hj zpncc`s>)qm`G$y?T1H+XDRl)U19E1|WFXf#3$#z6o!iu9KwJ^x5WFD(l%oij&O3m( z3cz|qQV=efp?&cz4@=EF8a<0lGFHDM6ac?dum(h};go<{GJ3Q%dJX{KFfgQ- z{S=coJmD<+Nq4M$K{uTm58u;)kL{|&cl533Jy0C%jEnm1D1f^g!LlTjRr*))r*2um zVKQ0E1pWCI3b8Bbh07-(^}!m>OBfU&Wk`7h1xU&OC{574bP2quE@WIP01z*h2&Vy3 z?%?bh#r?-l0!c8RM}R~E04pj$YcPjHW0+9`lqee4Q1e(i&MH5`A;F#ZDi9_pVhDh^ z@Tg7(tWrvVzabKHfShCiq&L9}+Ym@PkC%iS91|gB(Ow1sQcAEGtSou`3<1C>R;CCQQKJ&A z&DmB+j^NA|bA+QJpjygtw1h(efWs1ihLPmnfj$NrD#Y<#>J7hehojO>Q(Z$*nhB=nfC(O^eWSa6vg==qtj@|S9XD8WTk%4h&?RojN{74^cLLRKb->* zyjIhj;4Ao0Kuv(ic&`@ ze!AEORwh%Z8GQNmOONmQV)J$Ohl8rMrQ((chF94{BS;PAaIm57q z5fFz^zG6hR;5;ItxAt2=7VxZXeE-f);lr{aOj&rCAViU;_3&Lpn-u^cv#=WdR2Caq zf&Ul49rdh$LL{c($Zojw5?$;FVjMW7l5&#_y zMKc0;A4|&L)$Ny-y-dpuuJsopS?xEBdnj2c67Ca|*rWzM6Mkwk@ODXGcLOs(?FD*O zmB3IV48VUuaL3==1w<5(I7JMNa zh^0l$-zOAr$z@z8ybkw|L#usldTR%s?C_uZ=IVoyQPKd=6!LRn7po^0~vq?*0~ z;>b@7$k@|>ut~pe*reU!a5mLXY2an>g;K=Gl!)9t^^*Zws31R`DyY8JTi~lgPnUf# zlc7a%#%@l+?h*<1YDT4TlogL#cg=l*9#fa#SUYhy)3`8SHxdECJx7MI+o3N&nGEM4 z$DkZ06kY=&2~4*9>>>Cw0k#du$LYD+x;vZ6suidD(4qdH{s!A*e`{?Gt+N+Nx>h!# z@l%I|lvDqFLQ#x*_u9T)Ye^y`;%^0y64U77+*|2jX!8)%3z331wZrHE|}-*j02 zuSl>&;LC?8I%$OIiRA>&dPkCxls&=+o27KR@*ghvU=|6Mwruq<}NSv-V zT*j08!QYk9h(Z$m>&z9AxbdNIWO#A4#a+*0n)WHb)cM17@qlyiA(*(Js{=B#c-yyl z#DaPkq6M1guWk%2*U416%~CXt9oZPvI*Le=Hfv$~Wov-YCe`@5{EH|03LAz4-S_Q( zO#n`#)z9PL-s`X;KJ0aKjz!)-Oo$NH>x%C-bi`Slt3PpswtJvc zsy*WwwPisWNfvGG+Aj5=>;;-Hcp3q~!xy?<4M)g`D8IZrfp^P^xHb>klC;)^;Wl9@9C)_`J2YqI9R!M%Z4Z|PWd+BNtUccuaOe_o9Y4;v& zdaK*>7*kj7{;e<*@p#eFMdnKklV?vkL2K$$W$F%V3>sKe@)a!j6*`BCF~JIX;vG6! zN_ga6+dFAZY?t3TOe3GolSfLwHZf^$`JX4*d^oNl zkFc9AdHzN7;;^e=QGI9QOrG{!Ny?F4S0G?<$US6p>nVZb7Pn!=4$vB{rkHzzRG37$`)WD`r)Z&=@EuF4)!j2X|gz8|zwY(sC zz~TO_E(?<_9V?B$ww`Um*3K*lLen?EvA^H)tKOub|V30@z|O(1fVEJpxpa=)@&Zq zlcfigg(!vg{vN=o3a8_xs#LFDI@H9vp0aFe7nVrRrKB`M@hed{@1^dm{B%&UAhO44 z`hL-jYi?s_d9vqqZmM8n{JZ?|AZrZ!9d^clZ-Zvt6eES{4@<>)nx`B?7>>)$$tO;xSNlqp8nhiZb8Tie|cD>@!8?wqk${wGZcsqsaE?XCGPJIC*p z)LdQH(Y}?Fz{7>V_~i(nRfJP$AjC$z(kH2XTWO2;iOt^;f;ocPfp=<29z#JIY&@z< z=`T=0m74*s!YMR3SX*;xLm%dFi2Uw6STP@f7#H2OK}8^gMOUi43{xTf{au&z6=5Kx zks>;|mcfcE;zRcb-I7`SOOGmzK%1CBROoz8iyf55af!Br!WOA|k8QwJL7S3IwC9c2 z-YIL-D(2ni81%$FaTdg%-AS2}c7Gu|AEjt+W+G=17%N7Kk4nnB)tTOyHGX`b)KKr% ziCx-3R*&))wCL->B7D{5x_p`zGk?BG0b?Jd?u?`!+P$;+p@3|Ga&i<5X7?nF;9@FT z#ieL;QqreHXxR5pLfv+*bKmq7YotweE92Ho+H~tT zSf;D2aFvq(cKD3U2$jlPk0zn=wJkC8OO+)Z#>sEI)GuY7r*XIwH;tcDF@5JLghAeN z1{dgyCucu?_1E#@XtjNpjr2ns1e?e&u|X6667N1x3YAT|9Hvo5(Ea)$bwVXusPvnS z`z_-SNkKm99d`PU%ds=<+TAWv2cg{u>j6$Ym8}KHqz)c8&DWWY5;ctt1s^XO{7>;I ztzxV0>CBRT)wX_Up8ADJcF+RP!4Q;fZ;ANjeei9?R!`nredOfQ-=!xRlS3>m!#jsF zORYVE6yJnClN~(L#K4a(6vNVCF3XpSRC^zb?6{nO6LnRzg`>T+W2XB*0VhTppY_DD zG5<(vzClKhX{x#+boXwTf77SKZyQaI;c;#jLIiUU1gDPIRfZhf{mVCq#))Fm zoZmeWN4PX9KvlSR(RtsuGH0(p{<-BD{B{sD1jvEW(8&*2;zT-xw9YEQ9>{`hERjRG znHvVcue)28oJDwI$&g7y>W8TUSo(J`5|rlEUoRqGLurEVniuaY9F!h< zzI3RX`nSn-l}#}n%_ULEA^bBkp}2mMN{wA>0FpH112V}M7W4P)2wzw`^fz@#2%0Jx zLU11Sgg?)=@^k6)P~(FPiD$(M(cJ{rHIDCo=`*u^kwmdCPAm`MGI@)cK=YZ@^Zv_t zWFg7L=-meu9$#nQ__Hbc(fLM#$4Ta5n}6;>nG(Y*9gFu^?xA4iM8bwSj^a-lVsl?t zOEI;5Ht5Qeu9y(>ENFSI4)a5Mk&*RN=&{Yq&si_D|EvJ=or3x6o57tQ60+PTAW0wqz=#fh-f1Vz$#2 zs1yGalc^@W0f8nj2dOWL{yydsl8W*v3}fJG<5drK>FxKZ+OBP#Bg><#xVIysp;>K- z!`?OEcRAU3YchkB%~{P{GghvmZTX(=`nez{wm|Hk9DZv!M%Uyn+fNf-qwuJ4*Ryu$ms=lyYsx2c*;}up1}gQ z(g^mLy)0lgq-lv4wq`}je_>0fKtA=y3pre$S6uh5qOeU{`h2n)oz|1~6Ycv*VT^T$ zB?3tCG8)|sMsOsW;|md{Ad$OuHs{sk2ts#y^9m^pO8WkxnL#|3H=QaH<5KZiC0B(n zDzUDZbOt@YF?ZxZh)brJYkmzo)8(9So%87$IXbPdC}LvO>J@(INeYm(E!{)Z` zDX!=5yd~#QQGJh`dV>?0a~|$0v3zUlM2S!ILMht!S&aZv`L2dbkIh?P7LDB&jUw`p zfW@hB1H$`yA41!=BEs_agl0ORfeq;;sXG7D&u05YoUx(lxa=jC%=AiYodRnBKwpwJ zJ32aI=GQxhiH>MwxjJNug3LXm?rc-_w-{%Rr?`KfxvG}QfhD!Xga@~Gg>AV+_5H;zQ7 z(-})~tr)OULTBn%OPQUV7xTQu zsq{uVTKlO77>nM6eLS0e)zDD&}_85{ti9oT?3D4t+X^Nzj?)s=YUY)xK}w`$2h z%SiAwfxo^P?Y?<2rpeXPh<;>t6@61ZotYj3?vD$G%7uu+*tLpBF+$f)d6RfxZuE@TizJK9@GvaCf-F=VDJlN=a!jo3Xc zejE0Tpb&;FTWTUF6^>s3&JXIX5|eY`k^5UC_YE1ah}YdrZKf3cX6`(UPP%#jt+m$% zy=NxW9iq5Oluy8GRpTDlu1EO&#anWqowo4w?ksU__HBve!)e)X;^BhuxKYM7u?0CW z07(CGEr6&D1tJ&9$;Z!M~9i>DL5C%iu= zx2UFLTnYSY5@5A}N@E`s!p6Cpu^GJ|b!xsVu=XSC=80uqFQXdm1oi#*jxfFtMY*mz z?VfJkw{8=whB#R+@9$>5k4!!!KyohT4ybB7qI0orVwmE?Z#c(q@X&|jWX5eL2-YnV zRXB9qBC5+yWYmgeEX3*py_UbP2-VSSywD|@IIwq{*9ERdaWJfbak*w*MMF3OtF7+ zR8gRA+%JSOuhf}lY&lEnO=Y~}{qbYbqbiAZ_xL60EKHK_a|5*s5>&9)MSW;+n(FG= zWgC!RS~j+51vc>`Y7sfC%Hq!%=K{Bwj&=lc%#d+femcsN=hP8iFujxfwuoix`dys( zPv%V(`B&?!Aej4(z81<5fBA7Vjl(-cL+~5yBl>$Z>5+n-_P*mWBSo};S+Ev-|>sQ=s zYib`CdH>N@vK#+9Yu^lYK4K9XUUi;5i$z7;ZTH7lj0{6yQlov)6mR8dyANd;lFZ5A zvw5&keN9j{T=ACp?MyV7$;_@RagJsrAB}-_3xif)!19IO7&ZLNvo{QNtr=v9f^3J+ z=Gt}w7)Rt35Bi`4DXw$=<5SuT#b^>f>`Q?HRArgatl#?DI3C~Ls2qvWv6$Lt30EzUdX zpu`gWm}}(8i7@3UP`YKV+i=21F3f?O1WeYCFMKVSQ`m(sRCMBrR%&^RzsR`LPwi&N z${UifQYYypX5CweanB8&CMvC6@mK}sFV1)15Lf44S1c59;;QK{D_p!;oPF3WUbe0@Vs zf^JKr^D5jgw5eHF7!r^v>bhMN`0)nDiCnMsLL_IrHXfSoDK?8AWT@HUZ6maAp8v+6_)As&epPiL40^!i1ltdO}MGJdkL8Kb%kSMV2<$Rei$UbG(=L>+_KG8Z)^7=zky&j8e9_ zs$KDgV$c(?OqwF@ahiLGVtyM_09P!!xlf}zvypdP?K!S)GIy(oq zxXzR8TW)oZ%>{qphb69iwaxE{2V~x3STX=fq8CZzdL&`2Ufl;&GLxF5m8jjAZ+;S8 zuAOK5{_Ay@2ozPakSbEL$U+=XsVT#G48FGg`eOVbWPTi@w;6NHh)XFUx(_c-9;M& z$9;)3e|Be6<+nkYl`s?l5xGkM8nvUP|F+Fw^3`ViFC&X9PCZw9@%(k`8y^?)mzR_3`&Q=Uc`4rP}zrs zTOwf9nPU^a#KymbPpdD28k>NWnMn;jyh=m^NGC){5An%8Sr@Z8A;(xyu~>NG9L-;6 z2EPDfvdUR2s-S<1RGbp;A75u_QX0GRW%}ng$Aq`%beje(WwZu$+{38S%I%|iWje>z z2Au*OIa=1{Q*X!+*5k&^mOa?6!>02!?XRC2MiS+WqiHchNC+?1``E(ZUXGc@t1<~s{MB#k#Q(3&G=hX(_G37l#V8}xFIE@f~NU!Zy@=f>in_j_H0 zC;R}=KguF^RlSh=?*?S6B0FgX43;}sAYVNv>2Yf z8ym47O+XEkfoKTeU%2kx1WRHQD)ES_O3U^Ymv(Oa#G30%Lv`d=q{y}U+({H#s=c+u zY!z{xlad;B=Td!TchJ;{>R~J0F*Ne#m+v7*Y0HgApDQ``C_s6mtt=1R;5x1Sxti;M zk<{-9XyS}$Bbm#;(ckLh8kIY29SBINyP;;k>GkfPLkst%OD240(**6CkluGj`^WwB zXX{~hWAxSXeGz-;D`u86TmH=Ik004g34^p#mvr7Rl~^7QigL~gd7@2Pd0s@pc<@S3 zuFRVyUh^J_TQ2@-->rE}jo3QDsxs$j#9I%t9Q%Nex@D=uRI(Bl7`mfX!MUUmIsK3yA6I&?CcD7zDuSH%tR&T%$| zXjG}Gz>MSo6&CvAXYuGGh>Qe0FNFlveVzXw07*c$zi?}LJJV#{ zO+=)n<}*^K<~JwE9-Gj`WkrFD_MR_k*gjd(9T(PJ6;k@^{xD*;2~*Q(E2{8h`k{fj z=Bzc8F^_71>8=};TKty$n}Q231BV|y%>8H%3Y&E@&`YyFlt>=6|AsGGSE85E93Oog z);x(opznC&rsA3lMZXi=7P`9m<;-!nv(5kj0`E!wdDO6Mwvv{50{31A-ZBNld^vZw zfB_G-uBEr~m*$EjNXNr%NC~>jNT4SvGNl`q1vJ~p#QHpaQ*(aS%2nr->hXaA!ru;q zgEr!Rs$9}ch!ncXLMhfIKO$}Y)*RB;_ba#$Z?DMSK#D*Mcd~oPt$D;Bj`D}9Pz^8+ zru`t1uW|ncpE8*C<>u!IJ2&e^*$GN-4`>4?E-%-i^v^HDZ#tr)4Y<$(SonwA&-+I$N8O7g=nl7lA# zVTyJ;rV3SSXhntD8$bgV8^(eUa5I5`E=>;P;*ra-?g*$KtwCDQ*eNjtPNM2x02pvP zVl*~am1KZ#a1Pan=tMgK8#fvlxiU((g@sZ zlnKAN%VW0y@`Rt5G-N#^Q-Z{!op4}mam^jp@$2TghA;hPq92X!zD;BXKm@HH2t%6$ zRg_m8IjMw1FwcPn=mzsNVruZ+6DBs2RVAp*Q~W9_8oQb>apQMk<(tE|xM;!ddo5a< zn{Nn#8{}flTu={RBcis*nq0h{U+TTb&IJ#d{t@~^>?4!&J$RgKtVMc)jO(s09h8+Q zz@*Cqtpgw2fcV^=u?<)sHU#`Q1_!VQd%lUfgfE%}1x8C|B7zeuKCB7U%dl-V0L$KM z{%9^uZP;GX0{$_k=G4ssyGu+;92G20rOo?X4evo1S;i8uF%SXq?dqx z7#VT${=F}L3QFw8fRc= zqk{%o#=0M6pM|m<`Ksn1T+2)VZ&%7MOy+>*slCQbJW%xYh`B_-O z5f7N$bhyqBlWlK9bD6=3*Y2-#O{ioJDvXrdTE_hRnHV%w0DJYKm~eK$IsWY1zMj(I z3Ohp51RMZLs`$FvHNRk$G-9)?R)#389a0KRwrhD4K%<8!aESFb&=qN->ffbp;1V@fWx7r_ul zxA;U4``sY!EGhQM$6GkQo8SQ)HB!O|ma*S>RgR_Zs}awe zxEwNS8jNMz$Ep5PFz1d!Zt`NFMQ?Gi=0F+Ojg6eO#R%*|xZDX!D7|X4Kjh8JYN@m= z@5AO;D4PT=D=5CHfj@m(Q2ARuOLsWN(r%fHL*}Owr>+BobqMY zK`g>T;Z_1ZeSlEd00R#Qx43(9&X1JmVHt>2!P9I;Y2*8f+RkoI(o>-?);Y3?s{K5#GG^e9#Cn%`!T{(>{hHRf`9`z}lZSr^D`LBKP?PA?Afnjd7Zk z(!GHmTl_T441@;nrKj4_J*INbK~lHZ1QSb(h~NZ9qW%H&6S8ZA+len?THA`*2avxw9jU#CG5Ez$U=;>uC0Y)EGKkg5zNNUP5? z>g4W&RCm2Td0Tgtl|CRw6A!8FcSXn*#^iG!pU>zKwfz*RmkqZ~HMx4dky3s85{?uj zl=O4Ws=K+fOKz=HFU2xzDev6gKm=n#d|x%GeR zeTOyvH#kQIVdt}nApn9ncV}6KSDc^;@m_hMU;qmwOcZAl`hxwRS*$l|@jaIWn-tqv zLGi)1vSt#^WXbPHv6xc8s`HOEEg@k7(=m=~l#p!GTF_@CMn83&CX`dlWNOhPH_Z}RJ1oXPf`Op2M)i6s< zDw;WG{ZHK*W{Fq5wmal?TFODRIe#_smO99$Mk^+Hd7)koMatT#mYt(xaQZ!L|B{me zW;zfl9*KPyCwdfn34Uoc4cokQGynia=W^IOL^|t6IPR)dl)xya1y3>~&ffcuwhHUj zW3Z*H^2aP1%SLl~e+X8e4m%e=aL|z=rqdl*yIx9fH25&ls0Ctc)`v3eg*xa?&iHWev^w~q;$sc2*H zx$w;{14SQ5D85LoG^Xiz&$}5{qNdnThVAy~W#emD9* zCf`jZ!|z$;9o*}375lX^1EjXpy+@HQFm&$9By!HJr}$uCw^Cn8z&5vq=AdSn}0 zC-$zx>Ox6+mi2v7GXPWSg12~_1sG+m^uimZE$>2>vTwnOlq1Il0kcn1Wdm=u`XC2c z6*SN?w+(fqk?NN8us{PWSifzwPmG!UIneUm)!!TA3Rxu2s&g2jE@2ER#~rn+ha2@d zL%z_T*|M@S&bJOv&4dMqf8UaUyf*M~`|HT3G0qLQ{qngdW zxd5@8Q1&X*wTeKTHO3)W{!GxGfq%k@S@b5{b=&FSk{eVDvdeaKnd#FjanWHDOJHN^ zYgf_9@KeA7K;fA2&1V@#+tc+F<&8+{@?Md5d&Rf{UTq&<;+Jp2W*)=AtO@q12S-8^ z(~Q(If5nIG3V0G0YhJ|2RRANdGTcqD;LE@<+Uxh-;Q2=H>*S>cI$waNulKE_^JK-69-T*7C@wbpWEAx%^;pN>g5LuhL* zqpr+QM2w{Tgq)$;&^wD?>S(r3UD%=v#iL!%85nb7W?xk^ZmaVKZks0psV>P7Gv{TY zp;6xzsZtc8@Rx@ITx=2WHX~^!CI?oW0HQ!sXMV)KdE;2C44;|gx7ipCYGP|U6Jj*T z=xhgNgE3Arx#L_16-=Lw$X`B`l<^MjG!lPyfCkKOvdYq`wGbL8?8{1ojU z`&qOVA=e-r1f$-38h76)o$s)%puGzl+;tDPu#tkm4X^~DuBx6~8|M&b0ok7xUvcMA zwjX!0-aeXWBNkM)v(?sCQpb!_B7tQq)gbwLwpO?0l}=N=$4T$|k%w@ilN1Zg39~QX3h|x^3|1dA!!Dti+PL*)Pi17QKY7W)90z!@ z{|*e5?>?;Zb!bm=F6N`ltEMzBgED^uglB|l;30blwSv1YTRiS+vp4;Iu}^>z;ik=D zUU9fWuwnyB%fI^p8c)!kgCzIw(Fkb`xr+yJAt>WL6Gc7BW&bcwN~Y4r3mfM0`)}gc z%s{DO;xDIj?DJCxP)51RZK8VKR^A-)V`PO8RkRS<3Ycq>eCHHgcWNe1_ZNKgRYHAg zb}wZ(Y7{7bWWZMv#f%ZTX#7xDE6{E;3;-y>#5ck~LX)qBG0cnb0aZUo)jvo;xk!G# z4>cCU0>BRwujcQv3Hy+0I7_+g(#FP5SVpWxq?phkBK=)NRMDIQMDcLQ@lIn_l*YAQ zyaVr1gIw2MYU$0k)Qa~Vg*b0hktK3{RWVmY{IM6rUyPPm00pXU50Z4KBEjl@!_foq zl&Y)~gS7`t$1H!oQ={u^>3z+0bn{khz3()y{&@5qyhJ0w+^2D>SlF4JOk_UrDw$pX zhs=q&4cQ4aFk3{aLAnP7l{CBY5@kaF?~Ezuh>W++GkJtYdN~3LCPr@U)ph6u88AN( z5>&wDtfl}%r5Q>25bkV#anyJUF20SY*Ir4 zm4L{+Jr*Sry9sC~j)$#rTAdY-JuH*JYd>W~__Ds+!&BKcW7|7{Vr}z(qIAR!Tianl zbSW(gIt%rxJ2Phk_wL9Vnk_l@(cd{;*3p_x+exow+EsfBalkJ=@?sWB(_~@lmE`8} z*MWkvzdC>*sO0}jVRAz@JeaB-?dc`qCOWd5lZgJcVU7kq!dsQC%O=~A`OjzWr5G>W zif0&$<-%r0MmIGTGTlA3#qmUtap)FKMAl#jJ4)dE&P`@;uRL-K%3agc@^bL!ME=DG zVqfVZn3fd?^u~gO#)bDfCh^X4SGOLwPf!!+!%pITA%b zci}mT7B6z{??uEhH0t(}kqQKhy$x=+Yld_~3@3z`CzfIj1z~ZbBIMo2qj-DL6S9%X zGsWl&^Wx4%AkR`t?Yy;H8Du9~cuezKvwt>^$a)JcqMmvF#$$<-Gd zqf?a4i6xl^jCV8kvT4I(-?uk*-G}ED|VEg|Vx1P8INXacOc}{~mDM+*GJ|^hz<(y^`NKQHWFT_8Y^fZW6 zmAWcZRIoOaX)gp)Q z?vkMyy4FoY9`ReN^|Ar10w|xxK=VC?ZIo-gEI5v&JYcjzmx5|Qz%+72;}m|qwIkGq z#eVD9gt}d;5m0j)Ejce(O(r^#u8i?vm;*7<1t5!mZvV&bN~2GmvdK(+$!+`g23eL8 zF-L;LDlq3z_mV@DbwgZF60cZHV0Nn(dW&yr(OkyGm_k2i1n3>;ttVj&K&R%adE27(}c7&WE(;DL2QxDdiItI zW?Y;@qH-aZz%N8et!K0RYFWX}Nu_WwNa5+)78k*GXx4j+2*3aXRQX~qRA-iunE3*h zcBoQyP<48)wV=>rx|blI2Mn_GDLA~W{f9yQfSXSXLlC+nD46y z#RcBuJ4_}Z5BZ=xcolI;1{HcJZv{y*hTx7eX_6_KwlOl@8&eOq>)$=?A-0yjLg)Q^ z&Vw-vXmX`)s~e52sc*aEf7|rA*Ow)P5F?&s&uX#8OVKWvfDka`mlU48^-$_Jdo)|F z@Sj;DgK~iSYQ!>l#=A(A2|u%R9J36TqM+vwIC95HJ=Lac`06bXFXtLZk*%%xhEt(L zDo<**V~X&#%vTcD!q4|NoPwrk`ycRyL zlc(M2h@Mv2u^Y4B%2KA$f>8=zEesJw2r$IR^7C0Jlv#6!bvH>%f1EV4qezSYdsjdr zPZKVFJf@gwu#=D&5f0wh@ne}bnXK>B`bE(hqqo=6c8S}`#Qu7|EXCf6-u zJJw7>JU@%>hdj+WYM1tmlS&?JBi-@%ab+&>_A=WCcx7h5OdCib>6xanA6qa}Q5_;* z;{!4N@K@I7;D(9KwWUIvrScb1*ZBVf-N5ke0$imG9wu)te(23YnAYO9P-$EQ8}08J z(Z)Vo2m;P$40T(npqP1@mMd5}_x}Rf_zvHW3?}Z+f82^G4p4)DivFVF<0e03j6Uw#sP<14_>VD*(%ac|5YA z_zGki$C$K`U{W(O_GmXijnqfa?ziGAFwpX^k z<1kkunx@-Xm^PEW$dczq)qKV8sM=k(Nf0YQGwXEARFN#6Cbob+b@2dK z0XDR+C&Fslk#~;`D-6u=3?P!ZqK7Gve}oAmb6~Sgi(5KeD=;xo%yO+MHN>j}+D^*R zYWi8W`)G$N5Y**@@6py3{_!LX0279Xh(?Ww2+p^}wM21i8K3$rkTe0cCr|94dpY+2 z9xW{CfoZ736ES{i*M#)EhE?Yf02#nGKXJSuk+3Bud@E9=GGz^r(S~p`Ax08w*il!z zp@Cd>S-stFVNkxs-p7DzMEwnBxRc=89a+A>vxhKakI4O|b;l#}*BC~Ufk#9w>gJA) zQbyAEBeuY00pS9>&TAFhEOa8*3d+Ij47r_w<7H1G+0AVyJr(R;H8cnKUd=#Z=v(YDv!{!0%5R7%d)N&Xc zxyVWXRmcjS(sgrCxls3mgE?pm4dzV?4IxBHgQJMatu?}nb=R!Y*ds1wx6xH+-Z~g{ zjC@NIat47bW;FQ^Jgz>Qos4HTT4K!EW@IhlW&|Up#!#4MmNECb=qc|@kzKXR(M8^K z_9ogBqG#qRJ)iPdv9j&x6(XsC9ffDP%cTt=e<01@$;5s^+w`4P@7~ca@OEia78jj+ zwP!C5B2iJ*%t-wye8(whzVlq#0zmrQ@GvzkI;frLA(3f+xAS(lW=8*&X{DX<~$j$Akr zLx8;@b*%k?pjr^+sXp?EsdLU`(&p+V=o{Z5{WHC)?M6Up625??y6_?kg%jLy#1sG- zoW^Pc65SZ2+IX?ZNQcF6R=WiPzdu}|3O7e|j}r6KkSG69+}R20v|i;shH!+A?joUJZDP?1!8{aB!o7j7#8oy6E6jJDb@r znWgowV|)tU-|4MCIgr5hF5T}EF^#1iS%boW2F66W-EYA#Z~Rp4cBPHGUW&ZbK%;+x z*bKqrSgL;YkrMGwv>zV)ER@27g=WZ>ZVUM*jH8k!U#R&z-yWiR2HQWgf5ALlMjAqX zE!_@7Ma{WYUtxzD{JAy{@0&j?#fJY2)GQb6IFN_*^8&>QoxY=4E<~tW zh{4K4MpFm#XhiQZU6CpqnDj-Z5@<-E4BMw6oc;)SLTiE-kQrceiXWYjn0TIjEE`xz(iWdKc`ZV1l*NxE=IDo+fb-pv(v2V82{H6%3;8 zYuL2Egtwwd<4`W}GJDfp+$5PQR`-z+-v~kzeME=IOLqh)E@&64+?^T7MWTn)V`+t7<-^8hjm`p)ttIJ0brAmyvdiC@t={ZNNLED?wa1B z@tfQqDImPl8X}=G0@-!mOTQ3Q#!5@%7QJDXo5x(&xnct zRpL`V!i(IKoNbNjPzD;flC3QzGtFeUP`$_M|4_a@b}5};rQ(>B4P0hqBWwkm@NZ;w z(Ee2=2y>E&>V_|13C$@smVUwfRUMeYgtR6?9R&%$JH|vSE`NX2{RLNC5_6XZ$O;WU z1bMB$N9!?YFjg+CirUR9pweVXML$G69xvTpW}-^~_0od2ebvW2G5%V~)1veVE{!JE z*1Imq?QT|_zyJUeqyRz8T78s&09O3$+zx^_!5lCjeqOobS2Gn_iqBJlh*RAv^;jH$0vs|aGzkP7J_<1v^V#x2Q*tb73ezd-SPYuax#@R`L)4<_FEa zFE7YS#p}2YIdBNjAAYkD)ihEp77WNZeYkX5ri}rs7>63T!nx4ztR%-L^m1N7YZHML zf(iI^sBH~j*B^RHR=w!Xv337l0u7HuXG5Rbs~x2Dd~a&mfB+xwRN?>zMF0kLaE`s) zEgygS;yz=Q|>sHgAKfWa0JpNz*sWV$RzW*eW%SAh zW-Dj_UZ4OV=#zOw)n}q#g-a+deK1c$b z_FFg&sZ4kn$>~WrQe1ylR_uRQ6)OO|OwJw=lQU-_-+Qag!6~vH|4gk7Bmia$(tR5_ z%3*yv7p@4-H0b+gBXVqU?>r3sAgRt*EFU8S<-po13n~CFMnwY)rJKcck=~}Ah~(4Q zr20|hUa6*&IY4K$N{s1@-d(_<2o=rpI;IKcR(+KecR6dVcogUuZ+|I>oKwh>Yvb8@q) z+HIWaK_2@FDa8w?K9&efbJuw^jMPc2QWoI!tvTRfs21gqec9Hrl^!o#gDUBdkJn9zCZaVQ zHrjGLR4wC_8fxb3P4Db81tE(}+#0^|(|j0q1?W+>_Dm3@#+HjzO)6^?)fTK`-Gq86 ziD@WF$wJ6UVx29Sh(^kq^I{Vl2xo!lMlCCb`v3sAc`Qi*E@HTa3;wKnd_}?c=(`tD zPyht*oj}cDW@(vVfum29#nd!Z9f9XmiWfTJNL$O3`qiU}Xa*3)) zFYgR>#vJ&3IQm_Ya@-Y^;7;3P>!dj_O=q9Po}GaUsLaeFBeOH)qy&@@qC6-z8wz~HHl>86x}v) zs)8qBO4RPW|; zHwV-zm1{f;q%Puwcj1R1|IPJMMi3(|Ss3SQ8CY6qE$cFCJ&v{N(#uX^)b=Uz8&T}v| z6*RQ_zx||h3xZRn=dYqcF^qrn$<=b8kJ3JL0O)~9dZLlN9I6Fc(AcMg;3snz24?_# zlIkmo%-s#gyj&TOjd-GltP&wM?(AvLz~WEPha^|_!$DTW1OBplW~ty|_2j`)!m)@A ziz!ZnVMCty`V_(N7>Y*KV$s}mWPRKvkiG80m1;VpBq6CxH+5OFE6h`S;1BvDl8zAvaH)-~k3^HuX8RcIg$$?0SAr;)Xj+dR>Zcul|?Y#s7QcE~J6s_!>Am%Wz z$B2)Ctg`P_!Q!SzV@MDVX6)Xz#s=+wn{mAb12iW9(0IM?$biqJk*3vLQ>*d$#)zz5 zbxj<5r;1jP(~A!!?lUJ-UlZ~DW!ucFRvG%=Dub)`pmD&T&K%?kp48FNtvu}vrp-U( zQ=)g;;?b)r5Ys0>{rNIjwwTB<9XYcBY`2UAgtclzOzFG?fVolHn5fizf?I=|<=L{P z6zxKRFj>Ehf>=%j*I-ky)u8}8AT$odU5lvgpJeRsIK*$B;jx1To@{9^U%`M%UTfQK zQkUDpkuXw>=a!BipB&xdu-Mo6x{TdX!y?N5%B@_)7uPY6gdv{SJ~WA>_{3bt{C$M4 z6fv%|+4J(_e-6G?Z}ZN%{`(#T8kZPCkWiNxi3@YI2QYZwS*j5eQHsBBhRMQPCF0Sd z9ZXs6g91HBPE?P6-}VaLaVXHs3K01l?f`hxClt=}ccPA2aDkL` z!GD_L%DTEk$aClw`#cGmVF_H32?7$;Jn^%GivY7^^vDJJW-u$pSi`L_UVxa?D~nD_jLrRVuL*x<_7(}vgp(r`Kh>`hQY+SCV}4dtr&ohd)! zAg8XU#i>t$8)zBUaLo}g!`F%--pi@9-vbAAxIW^OaNujS?35eo7FLE~NrCz%KCs)V zIi4g7FRA|i%|t6Jb-595VeNy@Ga*OOD-mUltX)92H!AW{&15)YSENJol$}@btOwHJ z2B_c}{+<)3F7tQ}gz4MLN+fHfqFiO?v#j)K&sokxCcPU_8y}sPaQad%B+Yt{8%JiT zXgN$e=y%vBlmHDc8m!7XFG1u<&>P)DD~7=dxRjY?fAi4HsR>Xkf<;+8x8h;dWzz=& z_eAn6t8Kgz_Ar~i?mZ>-p8CmoMXk*zu~JN%3uAuUPW?W+pDYPw(V;e4}N?A`q}9L3cs`1qyT_Ojw?kP>XWRTvLGoju@mx zcz5Q^ejc;DVP>X7&&*m3bP;2yRYI^;f^UBY4mQK63&{u?=}b#q_NsFpd{>QWj!<+Y zujlkh_S%N%#0@Sf94XH96jy6gKtO=&eFuG`P;+?M1Mw>@tg#lPOBAe6htw9FKq13s z^t`WXuY?2aYc5_87HSYGsXC|bmZ%*!rl><<_ogZ!AVqTU`;F@@Y{*#4ZobNzFbb0r zz793f$L(9WX+S_)oRFXegLgE5ENh0LtcR;=9L`~~rQG(vCfU{^Qemo$+uP>bqaL3J zawzMH88&i8T3c$dCw-gAzdArvLqh7*dDwd$`l5$NRaDW(cZYK2S8PKYxUzR$d^blL zl2S}FJh5#k!A^Culg`EQcOZj1e(z^`t~SqptsuZcZ(7ErO;mbJNGn!$5<$jtOH-de zaEoAa2+{#y1-EuZ9}4G#A_vH=cjg3j20+)jU3cK*U)>h*Nl%}pt4s^Q;hcdEySC!d zX=O@`iTE9T+R$=?otQSwe2Z`!%vl67_q6z({$DMydWUn^@r^z z7wZ|;1R)VyM^UVW2@x0s{i6H;D>_)bFGgKWlMIfHG+!vq2=l^)+dAODuq)ZuSXH%u5L!_w8XKBVk=;L1il z6zaZ{PAm8)kJx`ehbCvvCeN=KW%Hcl{+kshQ0`W@2egTd--~v;*^9Vz!*v~H5}2D7 zUYRthh`7-|`L%842hPQ*b~GrwgK@W9%V#C^Cky-uKZSeNP}#v`tes|cn-MrU1cB1D zR(zJQk&11Q(y2}yHJF~xy~=Ys^IbYXM(RWfp1jewa|ldGrl$}Sq)R$Y4rMvyg2_kg z0|&^KqBDU+G_0F)W;L)chxf9PNB0s_TovgHE^$@m&38O(pj2r4pXG@%THBt7SD;+= zAVndtP>|oi+{Wohc|95o&_(W({pj*0mCu8Zr2|$JYpdiKXUL@>WhS81s;j1OCdr^Z zg3`bp8310iDI#gY`v#ZEP^d0y5yp)&5>|pkrRn>r4?}DC2fwfEGQy&z$1GU{@uhd! zq#9JY_9nCP1txP$bs^`Rkq&bKWIP%HmEL{K+g4m>KZyLdAJ~wxoCNDHT$lD>Z}X|} zux)45cg9sO0a*Yx0K_cO*n=#dc00eCe~8NlLiC$SYmRjJv0rdh1L>E#$BB+HF#reH z7pp6*UCaZ*Akcw3qTu;u#VhH_bMQnSc2SaEiB(7A9UuKfudQY!%B}ds5C8!!fVHlW z8_Y-=4_9wWxS-}K^Iots87Vustx{8@=i-n&zuWepm?W0I@AAQG z#>I6J2WoH^xMb?@u|WCZE6dy#M4MT1lJ=Ol8s?f-F`o-;*UkR)A>5U6J3TPHm!&GI z?Du**HSU9mY-jxN%00GZd#L>W3RPl8^h|CSKWEO9ji(QP8~BtH=T#9H+-{XOYvGN@ z9z!d#7^XtT&~hes=0YX4n%kg=%IbaE5T<0PoUrrv0WccwfQ#SL8pPL4j+A@Ao+++32FA)l20c|YPlnU|NaIyL~43}htP^8hg_-&Rmn+S!Um@p5va zhU>K(RD25k%($>!KYK|iO-IA2<#_c&(HJgv%AO7L&?BilkcMEOY@UlcKsID6OYFP> zH^u6-y4(|N@Yp^oX}Qlm&`G!W+S!Cj{_f!wEid?1a7JjqK_`AVihvm^64(PIkru$as( z71k+vij#Qg*%mEqc-4TGo)qGR*J<1||st!X#$7B<~XZ{4I7`;;-Enq<`=V zMk0%Vde8z)y}^R5`%`@M*-{;W66l)k3T9C5wkSueBMCYUoD8mgyXE=SpNW(gwXvF3 zujY%i+9Z~J6VrdK_lEQUoP=TjAJ{3rUu+_vN?m4DI z7gPn9pkR)%!uPrHi9!NA{jW*zDGoY1hbgAT868Nh$mxo5#X0!L~7C zL4{+dN|wG&=L)(VH7Zjq5OXbDL7h^L(S1*_yPzjz#G$yP`<;#~oIJZSDTJ;5h%BVh z*<=#aS%JIOzn1TYpHtTG!whE1Q3w@IzQQxn%hhs(Sa}!(>1ki%)oPs)21@@0=8OivuGH`fmfvpfwI^U)=YPlK-9;|xKyuDE6%#GlN^!$E#?i! zUZ4Td8feSp<&Uo@h4f$pQJR7}AoeJL1oy_4F|f-oZQ!^fN!%0zNqbop?Wy{){kB4B z@Z3vpxe1IF^UE;)@mcN*O3LaQ@7r|dP+%bZq?BtzF*V>kNnX5zYHyA*cw;SM9_Wsu zJUrHJhE^5;^}5wuw6{bSEc!gN)g3vrDoD=7UR$;^uB_J5k=u8<{!S5RDSofMX!?GS z3V%>GAqzX;wX*dG^%P-O$G>+bvy`38XtC3I3va@XGv%iGr?G;MuS_mh*vn~ftMq>h z8?qyjBk*34(jPB=F#D(hLSv-6XYL%4A%`IMSi(oDb-KP8{_+R?g(yA0P z1|bgY615(#g)`Xw`bA8xS;Re^!Sm0|@!VNzjs7|2;+GMVstNsoLrk?$VrTOAKjS2r zZr_^%WDYg#d?TX3U)a-PmF-IUj4(4R?FsR6nMwdT3h&T;-4)DW=SwSl-4Mh3VSxpoL@DG^BtJF#{eIzEG^-IAta7Fv|4woE#W zI!6B<(3zP_K=)!4E6jQUNGh#>+MqJ#{M&T1a*>Cf;V6u515g{m&ALm$zZyvKoYX;k zf9B<(V4kWiNo9MCu-%?uNHV>Fj*tgDI>=zgfpEp;nww<#@Dt>ecg|8+xai1X5SEE# z^vk$@{L;TgNew8fb$b>gqjW5(N9jK)3Q?Td!Cdtgq z#fQ{Z%PgO`lj{0LrILUFqF@}R{JHh}YxZ&=#(~9DX7qBOKQeV;;Tzd!p+yQ|(u0J701Q~B^Y4nRSQf6%j*-J^vu~C|2w4s6A#2t#Izq`eQ;ICo^>{Y_En<&$&Wr^Yo1 z%~dqA!6F?1{;nL;g@pG(vSC`5g7ngUhy4+FRuSRP|D#{I+iIo%J2SgTR4vxA)@IgI z4*+id-_caE9RK?37H*>RvOF7Ayfi5!6ylGobI`LIY-?508o&Uou725WJDTbOGyzE; zwwH=J|MOG-gT*~PdSpssR;TJ4A~g`&|L3f$Sr)6aAE`BZS+ujh4;n*!r)Uk{7Q25Z zj4uS?$&(ZkulRb#96y8OjKHfgWcw5**V#xIwk8ONa| zAQ!YF$gb+=ML^BMnFC2ZbpzmGf_fPi7qxkQk;rfh`seXLfO%>V6+tQCa;}0!GJrun z5&Uj#f7-zF9H z{yPAC(dIsswc}b(D!ulGO(8ncVMR~)^f2C>g}t9+h~k3*^zr2RoErR|46jmZ+fHR%& z@fZEj=Si!o8S!~Cl09Vg^f$puLEB!Zs=ef-DRVOOFQz}wCsd4|Ya zK}Q~OKJGm_2|@#d4CzzCSuB9>6`Hd$G&0bCTG`wwd1&Z6njXn5+;se&r3j@3G$8<& zJ<<4rD4r6-_)nMekB{1a~^~QkdJ{N$@?0vkAg#tG2(1z{L-o6GeHcFZFp+n`Fl;-#;vlCY@+D zS~=QD#Z3_&&R2czypp^ljyYfexL?P_z8Qweu~v^pe{|2_;$*fiT>h_$7PB1Z5aMhn ztY({z3okGoH`>+1p>$|0M@1tlnOFqOiLzFEEJH-xtXHv*0G;-LOu)-?vT^>;P18y` zV0wY<@i~j|Q5R$$kzTAu|AOu)@_(GF{9Y69c+`?XyB)`|MLFTxslg-~a@mwz>z$*dq#tNi%Q(1c>DrwD3*1fz4b;n^Ms- z=6`c{r&nyt2d4*-gJ~EG0&9qNoLPuQ=r>Rz zV9=ec=F>VPiH1&xB2}AIMM{0jIQmM_zmjI9i!z5hVv6bckfTnCg^cI2%{-N7S0tpHU;uB&v8kMZPC(vq;4=zIsy&_uWB@y%t+NX4)n&;+l-bVBR?YS!ggnIG4K2Y>QgMqarRm%dl*0D>(E&t=NZmCAyFR0Q^|>W^(Yzow*s+ zTcDQ>glWsRZxJ?yKLH5<6EFZ~t4NJbqXR$aBe@c)Ijeh5)Elq+gO>?pdv=UxbSD(EmPoj(M*#41b( zO&syU*ok;&4$kL~O4)jde24T&P8AAW4qYcV8Vf)GOy0**gFt<`e~O)0R6=2Dkn@$~U%J}!|da!ZisB2)KdbOoZ(1}TaZ7gOI00Xl` zAVLBUnhBCOSa+LYR}bJIQHZFdlbaYkxA~LI=?fnhcmNDzKCFQGjOp!((Ehpcz(lGX zSDALgDL>+!o1_HvDR%flnByipfcbz(d;$Q3HU#?lX~FVrS_E_h;gp53On0IxldJ=6 zfmT2O017|TM=~?RiVr2NMQ4>JVs~Uy(Mbk{H8_zpO|~vyE=O$zHMjJh@h(LzyGMW& zF98M&6yc`?KrS5*gR+7^|Aj;x#7E5e_JP@G1)yVB+W_kAZv7N200o@%Ti^h;YqTY$ z23%`;kAcv?kEWi!G>AfT>(Ykdl;~#I5G>*R$rkOwVgrHI1wz=%*Z=}-u>b(D69ya2 z)~s@C{Io)WLvqbc&mJPQH<5zyrxTaF91{n=fI-)y(X@qd33#QbrBQMpx;Zgw8@xL) zsNsY^NXy%ehPXyb!a)T3Nrjb&1}Tq-`%%t0P+p8?U#s^HjI|?wwM$-wghh*sZ6496 zzKnLP?r$}VvSV?4L z&YKg5tM^n|jXEF%_ruSbMvxQVx#hO~`pz8z3V&T*4{`{;fNaU-Z3dG}i4eq{fjg87 zfQ|+q!N?}B82^WBW@pEVhz-5a0k|6HXYS``ZT_h_&Qp@#j69l{3YoyTaC3XIzpXff zFeLzaQYEb4nX04Hi{`<200000R)-b2i4h{TN@A5%x5yIv@z}dzO(YK&0nCE%MEP}* zK0G$8azA|=U|adHFvkE~CmrLyL^ozBuS*jzsjy?Qax_WL*xg$`YfOFw!V#snuWAH# zV=cZBxHUIsGMQ_!eb_jw-x)^zyaUy#?|1sVM@2t62kc<6%C_;L#%QgY0w#6T{g7`e zQ81{X2mk;84rad@1BX~I#!5l0wH5b^E)7zB{Hcw{fd@)PCXMG^80r83BY6Y@AOO|0 z8i25{dJ<~FTJk0fBr{GLw_I}6a9>%x4SRl(h0BD!vqZ9hGD|+m>V_yhQ+tTBXJPC% zP=cjK3(UO56DnXvdOEUPZ`&O<4nKF@J9xOMH5u6c&~R3FYN6S^QB7#$XOCLnGd59< zg6wkJb;r|54j=tS8>vwI0k)#tI}x=Xj`zFI#i%~4HJzYU&8lhKS?P4zKIijlPr*C; zz)spafCYxox|BJOhfWZq3-RIm%0Cf4AB?q22W3OWSR)k{mOS>r2$4tt1&}FWk_K>e z(6Oy!{*wg%6O6L!xls#aZePc7zf~|*Oq93)01k9uTVF^U z$Z(3-f~9VAQZL$78C^;VifhPlZ8I2=g21n{;JEYo4%#igwkn*avhXgp zBV?fm5C8(KhSJqY0I}nvxb7~xfbrCTCQ8KTJKM_^_ZW|rAt?0Q-HUPHuRseoY{Y7U zj+DRv4q*V-)024?2O;W#Ed+WR9aA2swNsLqejeRZv|DS87jQ;2g@xE?{0;@{8qQ1^ z&C?_ESY<6(6ve2sHT8Gc*Igt3ar1000FDEmWo&dn%KAXG zn|MsT9D>#^0x1^auK->R)C^;)vsq_1)viE{?=@ThZa@G42whxa0OXq)%?$;W8^+k9 zB2;E$;+j;UMbrWhubmD6@ED?40Q9I-W;$K>_YWu^hfDE;;pw6jY|pNo6vOxb>^l*! z5zltUfB*nIa58`w2}+X+ri~PH8)eO!e+K>KZ^h77H^o;ws-f4-S$Xa&f&oJ+K{=M8 zPm2b!x=3Y5=v&Pjm4jZbew;BTg2<^R>sSB{LMT1IgO3r@r|j1d00rt*na*F&gj~py z6hT}SKZI}#-pWK;)nBBar^7FA!G?qV`#XmpZw5zRx0PMwBzTfzRDE$K8WP@N-be?# z1AqVk06gpV>kYTZ4{_uJ4fkBB<2c0b1(vE$R4o&J%8&x~Cx0iShmyyPz%rxzf;z1U;S zMyEKND`cF^K0yBQ^sU)`8C^T|nyMu!s9ZQ6YHrPV001vg0000B0JgwTs9tyzN-I@9=iVF8h@MIslKHfxxB z^`flLclO72Mo1hp@5uBLI4*?000>@0FIlm0lQY>i2wlb z=n5~d^X6fYsDMV)HJg2^U!Vd*RO^49yb1&HIlJ)SFX7FE4f*L|1>h6NM>wo$*qfE)k~ ziZO^e#HqrP>g^0R;?1Uv6JnuxeY&StLpxFks@=FbEZRtaos@Ant!}QqTBb*!lbfnX z$vys1shgg^-$2vOECelf{X|aLW}t3h9B2SMfWQC%LKAzvcsXK)JOCqe@0sF#7EsVl zM9?Pv1sL?U@0n95o(R^G^E37q|61XonS5TtvhE`mm~*7Tf&Yj^6Ftt3xk3N$*qfP9 zj3|X%4qMku_7v?}nvj^H0iL~tl*nsv=#0v=;ZrqeEVhsV%WoE5P$1<|CM6T-7rQ79 zm)s%0&?EryzyJtR5kS}6wlDw>4Nu!3)(&6CAsIyTR&6{cYnTAy@iGxP9D$BmrIv$h zghTjz$_t}O=!zL+(+$<0d#Lg&Q1)6GTbgn2TcUtUN}S>gD{g9sT%v?J+$W|oLEprA zEJ1+^%;Es=&vUW(<4FJjG>`xQDqI0&`Gpi)8Mqudx(HnL&l%*Zj$Pj@8&?^G*MV(# zewTL6uP%@~O}m5@>yW*@GXhYfyPrl>h($00P9402|qXDm>DH&(hGx=*k5$ zshFttCy5@2iL2DCbTU7V&nS;rb}$WBqpA31i~Owc(`PT5+=|jo8xIT5urbdTuJs~* zSP%J>pf>f5xUHxeq&UiHq{0sq_AU3>;h7NB{_Wk^h{C zD|xlVCpX@=r2TPUzg7IgeV`P1`<#YZAm>EA)mU9Id*DQ($r;QjIh-)G1HT^R~^*=RgAA zBAF(NU9D^CRzg%DM(~{<`S_qZ8j7QK;=iLDT~D>j&I(9rU%)^msx)Y-2@A?Ve?Arj zos15Z`_wqrM_s93r#y@Id#czo<>1*C%l+}RS93Kc$~Pjpi4Jw_Of5@SYS zToNni5$AeMS^kuNe6WCz^}m_*l?@>?tckJ=*9lZWXj!ME5yB4!ES;fpg_fEE>OdJZ z0CAuI0i2B#001swcZc@Jm;gCbQq7VPAg*3e(oay$4^OJS!L{!%(}_!b(x#Arf>~!< z-+73A5vrF9cr44HA*{l*2f%MW@4J0;yvJ|628N)%mQdVIg?ToQ*b!lFoghqe88Vki z(3yfI->tB%j9sQz-E5v3$N&Hd2QbW`lR$Ogm|y@pz$e~n>1JbKC-DkbBme*bgL{Yv zhmqrf+LUcbR0zOZlmP<}Qn|PGX7Z8j@+wu>c8k~}pQsAKAOeM6_5<5(E}Wse_X74O zrGccPL_FN9j^1Xf0SCA=000abSAdn7AOHXWF&4n=f-`C`_yJqiZ$Z~ zqX7c&aZX&oBYpq?2Y^_B01I@`B24p_?BwMP8~GN={OodZTEL$}Ph~NBNpX79EnD!K zYqSCkQECdNrsnzKAY!94x|L2fU&hKs9X%4gWvax+I9QD=44HHZP{$G=&dwQ4%V5q^c>zsf901`hJRp_7w$Y&xsR_ter z#&70i#7=!ik=95}FC2G7N~PLe@21MXW-qGAgqs{xVFt^(m7k#q>bsBVP0aa)6Yz4B z&rUe>oc&QFyC}8XygM(;guO!`0SYES0002@AOHXjfC18LfHA2` zhD;H@sqP1vWSa6*Eg9vpKT zF9v2UhvQU8B`=7A6M>@<5$9suyidG<|NBo?V6+L4%sRi6iuTW< zpF3|m-c@5c5I8Fq#wnBQNK1E!fP44^PUx_Nj^p&Z=o*eHYtR|52iVo$(gy;eqJP3Sa*OYZ*1A zr-wv5tlDl&>9Q*TQ}n+nL;X1gp^+DbQGnAC;_PP*gPggiSwS8gMbGL000000D>c^ zjrb0tc{-YYPW<%)hYG>pAFSEd3TIq=#<4a*!;I~>U#L4W=-n!g3_&(>At@d_PHUqv z;n(#2n#0~XeEsJaBAbw54Ag1OsDspjdmTf7cXJA5L4#92wW>S(dcc5Pu}ma%bshPj zYza~VoYUX{03@hWg3vsMA?FyXD%Gr*%S93wJd)T&S&E;Ww{ZPy23V`}$(iKsw3xMv z2c&Q`9EW!Ti3tG?HvCa?xIlyM1Au(458S7N>V59K+vvc-iH1Uv2y0R0lkSu0Y2i$n z3Ox1tgSE$`%d1|y1OO3$s<>3mo2aFE;#%;ssY{8;eZWAFLS2fCI9@Vl&kKA26Uq5L z00000034&2Hn)HiV>mUdl)0@I>nMFoK0tP zao7-Zrb=}B56Qq+6*!T`Y_{l1Hf`ldSAp7@qLp#%hIgZU+WMBfwUvzuW6s%@b=aik z3}bAhjX4X(Z-4**00v-#{r}=S&^y_xWBRn|KSzPZ9g?tq*wXdGT@+V(q1Q8%YUm6D ze4*b@6{*cmf5T93iQ;JX@)@}(v6*lLMzN$&S$Ngl4xj+@?t=ErVnzS0z9Y+W1dkx2 zVcMgPCcghlzonT$(&c>7$Nou#{@$YESDc;!O@p3YGR zKj5}LBN1`{5kt~h{k`W?5jUPWgqmMYozXL9IklG!Z^4;Ps9zssIt}H+W)DD8g=iEey@Hd|!hSB*SYaw^zCLB5zwr6-v@<}Zk z29AXt@Bjb+(Ex3)ip^waY5hI}AZtdhZ@uXwykeWg#Nq`ea@v6o=37m=m7T>!&9yB$ z4cbj^LfCf7wvN7q%B2~{Sq85p*I+GnyN}G!^c;$jPOrhffXwfW8NRJD^L@WI_^xY? zsnlB<&QO&rss;r#r=De0yyP0rYa$AxA^2(?y+p6GKVoAZFA9(j zdtdLsx8aSlay3dtRC%XR;j@-+&cTH$`Mh>Ux@XVKascaYH%8SjxQbjJ(W<`dPTZn~ z@N360O~-^+MAb>oWm@>Y1~>VPbyJ^$=6(WY=;*S;cGRd z%m_o{!YwRjU6wj5Wi~P{#*|j-bhxoCb!A54h>5YqMfkw?{WIM7?; z=<>h$CtJcYhjjOpQ+y&2Gb)?IZ$;p0lLDs0`V8%!*%v-lT!`EtHV3)UMTwIapbAsB zBE+qrKmY+B`Og9l5|`B{^AQ(a^4~=)KVh2*`Hu>drhKs}lP4P~3RkoYoLhahpr+V_ zWOPlSTlYU0|F5X+#qjM2Gr6UbTjH(}`ZPSZYxVgv<$%%t1sX`m+@Z>hcMbX@AlT4X zie77M7^wAGfW3u_J5Vz}-m$y*FHjr228&1l1aY^34G;|!fHhzcjx06v&&J=f59DL? zPJmJwszB3G62l{@v@DkAu7pq=crZR(J?FYg>gi#pTp1XS$2C$0spDfcOh4-g%r`Y# zZ|Ndt2}{pX7!w0I#k7XFvWoW6IRu};!1X`?05$Om3jx9`mg3{gY;}+86T~c~Z}a{{zvq?L zgfzN(l9ZqUE+#{^DOopAHg8jo#4}#N-L4LGowZl@h?4>4<3{s&u2vRNkVEg&OXq!N zRI>31f5dtREb51q^!sXz6&KrkWZKjsIsU&mN{L+G%}wF|P@SiJ663e2@+ygeR02vS zAbku4@VQAyHX2zV1J&VHD;^1OIA8!qel~zon~T2Sk4BE%KL4QHHD?tOyT-98f)t1` zb5z4MK78-$`MG;!0+sV+omFynj>xx{=WazoS_pZw(3SIg2NkxU8pgrFY!9pdoGAWfW8D*4T%I^!v@F& z8CD9)tyusAIRF#?0000709AqvVV_o&6XaZwiA#j3*|~YzK(*hNHuIyIPiFQ1N2?|v zlW`dr8qF(HV^xAV;fKTlr#L#RVhlRGpI~ABzO*$7cklSXP)?W| zAX_c}x~tqAIYnej4jXI+C)HVPB2Jiq8V!Q*>pa2hM1R;Aqn-434k&O(JxmQZ_ zlgaWLEhphBvKDcFaHn1R?^OyWn+|!^wV&KabO>mHs=xvrYZmkaRp|Ssueib5Q>!rE z(^iv;M?m*Ay78`k#-|k!Sa*bUCf%#qHvp6t|AZ2HR{$FhSav`H*Bv^ztmIQi_2E4(H4E@Ev;YF&ErB=25T-0H zagdQa`tYCnVKCMlgXT;0vJEs*v4%yU(Xq~ z;NVa#D0&t5Lzs(f5m;HgT{uO2xKR@-;42}j!mK}Pfb@-E-n`2H+Y;F%`pisbLgNn_ z%XRyp&$G}}WfPZ7&h8E#S%564t~v-h zBxhEF5(CA;r3begoxAoVp8i|XOy;f1{;Bhfv{ zJ)8Z}f_M_jh*m*J61({g`Qg49Kxxc_?!Bz8%x$LxxU$MPs%xn84%0pgUL?U`SJdpi zSx%^~U)>qO`#aYy1!@&)%GE|ZL^tb2Yn6PSWgKTsEQcxelx>lLW9d*x1|1U1H_G}i zKwV;guTo#K?Qx!Q5Cpfzx4lB>>PGsSQhX{sSM`6oRPTNxI(NI#&nz~i!^{Eiwxk;n z%z+SmX*;z2fConT>ya3M0bYE9x;sz-gOnsVODT8oxZ>YDO=94IhdZ;=Rd6E!i&g7J z+rY7Ke?Q_}%lIyhmd|93*9QPk!m)r0m`okaIcQj0gF4w{?A?nTR2cBUyIxTc3S0*g zz@1x0(lft5-K8Mnm%M66y}IRclX!1;7R3hY-cj-B6|6|GI|#8ldpF2W2D3-ayU8H? zA+!93GJ;T>*=nl8n$;%`3K(2>5Td$u;(Ie2jDQoA3eyxO$fo^Bsu?|%HL$Cby}SS& zg6TxD~*$ti_wXV{T9Pd(qohqYHDpUJA*G)8ZoOFn( z<%NC*U%*ke*fZmKxyW&Cbj%V2s#?Q&3@4t5ziR@?-2b9>t`Z}&9T7HZ6Ygqj&@x^Z zga+f9NDYI#;uDJdQB=G6XfvLC)7!9vq@I1hluf51?cu*nTi^Zpm#l~*L=I+W54C3Y zx!XFn!^2CCU96lgZ z*KU`9Y*orYHEuir1jun5D~~J%qp)(zxT;YP)VtCOXBjoG#`h&od>l?*zT+_X#&sI7 z@3fp~J;l8uchpZi)mqCzv(Vzm z_%+7|mEQN}W`weS`2IbZy>{K9F?ce(8IO6&ofNdm;~px}oYsfA*_=L@*17w*&W6y9 zYdYOPcKFsuCrxCD--WRWHoOfMZi*mUnB~%wD&v8$Me7RN{@DKdOlrV%U!CeHPkgMB zCZE)TCM3*yR8BVsO$ z0@r0|U$5O zY0hc+K<<*z&=kNuQ{^Ogx>mVuVjw0tfMBdO#({7(iw(^12UfJm0R^f=Q{zTaWXteBpLkLI3~)sGJjWIVm&< zL8_5Sbvf9*D!?Sz6$y0pnQnk+%CbIq2zJ4Ha9+ss&}kz@YSQ^z{&O{k0d1cpk!bt- z7wqXp#eqPwZof^l+59_IC*?oksRvD5=L0Ecvt+b<41xV#5D>nJ@D-ho4Boo81Vtgw z6WJl3B8hIN1%4I(-7lfKm|zLRU;Ct$?<<@NV2}&ZH^!X2=`3M45B(qXfFPZ_23sxn1#BD^RI>NhY5>`Id z8C1U{5!ywaGhCr-WETN9XbZj)Q~o1zedWsJ>=DGp$%7IxXYO49Am@N@CLm!*#Eit| zRgWD;Iur*-y5=RvnOpKX>DpO_U1aZ+j1jcGXh3_*l?rh(8{bPg!^W@i!1)8B+6$nu zPZ=L~qVG*rsLF<>L#h2-=@4<;06eo#Um4ammye$(T&lYrTcWSaOdmvt5ln{9g07|I z+tEZqSUdxSB^gni(TkfM01C+HMj!wJPvBo{o6)}pP$A}_8Cqu?^)1WrYxq|0U6kgP z7o7d&lw4)kTpf+#JIZ!DYcMauXd92l^j?L3=)jBGD#W zUq;_|esqV^7p3JBA)jIDdYDj+QV^Jumy0xuqO#H=Z|!H56<9#W9t=^vru^UJj{blD zP16P(Snu3O)*%OUIR1%NB6#x@ZUfh1bK7CfFt}WWxB_f-JQVrB1$4kFzyOR9-%vIW z`PL4`F0izOd#F+}oBcH3_Swl}&cs_)H1?!In9+Rxh^F#w;6v21uKY|k98GO3NP$SO z?<1QaB_55Fw}(I~4QQtm%O*9Z!1(}N<-4T_=%d&f6&Xn(6Z;v`ZSibw`9OzYftjL2 zh^Z(IXZJ8737?2=flI!NXR7>yw8~c)c#BX7DhK*2k2jFDJh8{-KQg2pkHFGyFu2b) z5?aoB)dr$;BwdQfMbb^&xs@a=;R1kj%`+(*~JCh@F47g~zwz%<6%y&wrZuBL9 zRlKvcZ};GgyEnf=ma7-l{p4=?qR%4WbyLs9Tn*eMkFhec#H~03I%3ZV_z-#lP0C*M z4PEmJKnX8L)#5B55mD-NP^Ta#G?Njp$lh!WBcc4X_Gj*POn;+@NPd5PUPJmX8i24jFjAK4YWvv`?2@8CIIAW_OCtJkO@UV;DYbZh;3 zwyNm>4zAv_B7y^Yfd(EfdO9P@M)g-E;9(T1+&qdzqALfJAESf>`)&I=xN|Y z0nqAO_`}=~|I+6$DwQ3K=@3k2)DelnvVrdcFBvCe7uu~oX`D>GXm)96)MKgfuAL@+ zN|7?itdk@5hP}E(x@JmT;==S2_O_Ze`e9QaEn{IgXcYg9XrfXlLWs5#5i-TYOHDX- zcZP@W&mkB{ekDK#BPpy=`25s`w%d}^+6sUQ($mur5Tv>OrFSFzDTQK&DK`b6uR4Ff#ZXI&a_Lw%9qbB z6i|!BpMNAS)qUC#ZA~J*q-VjXB-J6Uif^Xo0Y_%vioP3`ptPp>aR>s-l{4^PSK@c; zzUznqo1?A2kqARFnYqfvYUH|rHh$P3C zCVuwgLx-k@o048O|7Wl)H>rzMxNftp8uU0sUQ!IR$mi}Lx%5e5vZ7EhFa>qn>|Dx2 zfvh7z!6QQ=kK|&7L8pKbIkQjg*^r#I(a;|B>W!E0J|NeWpU~kQHbOK zC?|xdm1V>E_XY7lbq`+Dgl!T%1t(XqaZM+MO-fq+DJEHm59fD_Ynir;?s$dWrz=Rf z!?M(5dNMSoF)A%t4>74G++YmaFR-QGaWuf)*=;*|G`6Y&Ru+@{*zI}j%@6DpWK(Hw z26b=m4ecJwAi`69h%-ofDrcY!Wh$|_u-M}OQP;#w{9e>TB=^dAQU|R!0@?3$I%| z906e1+v$~Zi40#~H3VP)43HOhc3rFaeq;gGHz$ z4^t!YNkC2tt>8nwt++O>w2ZAHwIc>JWm~rU-oA&f<37C8I!}i$ z#~Mf(b8Mg@CZ%2k9tvhgYz5|W3kuRq9rvVCuI9Yk(xc$~ z;zmh*pTS;KvDM0Tvk+f!?$m6GSOi0{KPcfG2pV+>eFE{h1sZE>2!$n1%!kd#=hf}f zG^1&{p2<$!Qr^AaN&8;Nx6%ljd!c?@qy%;O3^9u+4wetNE+VVsfoL8!#2gW==4}i- z{@D&+Yca=&AslIdwDlUB6n69!?Q5J>L>^CX^4PkouaicqQh%90FId$rcS}|#32gc- zJJ|!I-hOyxRgdHn(^Nx2Oa=>q{hsA|Di4I}-M)erbh{+#P|sN^t~^Oah>atUb#cjlHK z)t0(CW4?K$B|dgS*O#hVBrkqG#AaLZgPTj|LSfbt=szTLQkCvNS=G+xU?mI3Ye5b} zSsd>op=#KYl2S;17m9=;w-RbO)o_zJa=Bs5J8&x-3NBRcT!XI=j;RMgA`{v!M1Zz(=D zy)-j%Vi7E;$D~pYt4#6_Y^2V`E~@F`>EJQE5OPKs)r97VQLt_1S>xS6s!HqaMxL3- z?ZfYlOC&}-CR9&);l+S*PNA4~MM3Rtsdi<3+B6bvCi5ab;Wrq%JA*@A*u7zdf`cB< zHkidbM zraX1oDXTwmT~i{#QB=1~z+p2>0=U2{qm$}(@X#Ro4+lTGgVL@Rfh>)sDu6*j1m!dR znx&6GpRkqf=LineyWl=ljEdPx%DuxO159R~_9*SUN|Rng7qTEGm$u7KzuNs`6`lEA zdPd7Q{B2^jvks*K(19Gon47(Hv#Z8Nk4<>Kc39(e4^*Sm7~LjdHs}907-Okz0hNls z*&nSeh{o&P_SivrFao#zilUb@rV+Lb!7RR-Tau?i-RT2Q)xXyt?FvB7JUiF1ZX535 z`QrA_Hl=?yNyh1K$s%8wmqw&X-|5 zNQP65OAKq%bLfyXo`ZN_XjFD@&h+xjdXc87kRXeOOvUU-HBFhOixqmQ(4M=xHyZp= zYp0<)F%BobYUXv{U^4u%%>W8*2dqtjN`hJBjk79%!N4cBhL9IM*N?ilTE;nXNTU3r z1VD!q4w3Tbz9L|?^kRcv_f*NoZHigL#IFixRpkj!5D5(pG}6HPKpTU26d=R5Q&{wb zx>)l@3}x9JE-JxXij2z@vDC8G1K+n{Kd1rL^1fMD5qK~ggg?hJPNHhu(CBi^WYuJ0 zbusB#HhSIzIKzd$+_iOB1_5i9YOG% zDAYuxQlymO=mT7TSHTB7S9M@xCci zCybN-sWwmn!VvfUkDB&oz++GDKijgqo7?zQ4HMddhc-!g8R~@z>*e3jEZ^5igLbuf zh|HM=im%WqZfH@lmL!KF+TW2Kcs!t`@b(naO!ryYrn7|@*(fUSyJmtBrj0&|0oqsQ zUubId&V8B>HR~l=+V>JtV67HCmFF?Iap3|`jz05n?03c-OE@D` zXm%~WQa7N@huIdSK5yo;9p-Yb?Gj)G0D5Ne(e9zKatN~dO^^35H;$(|rPY6AyaOMHl)P01zA=+= ziP-#T}mwdw0#)YiJMwl^uTs-4l4?me9s+YcBwzKnY z30OWRQVJfh@$-U7U~?0mZOJ(RIkGB6uPm`;9hh8#hncpXY*%yl}{8{dmD z%>J4LsPiQF;wY^PQ#c$cKrrjzhRU3l^3lj+(!EP0_hNUFhrcL59ENm6s2C|daqS(B z%(Vt>AgJscz+jn?7qIP1U|Q>!TfHP~aW+FGVW)lJo=YmA-s)wvTxJ>%qI&nwFug5@ z6`u9lH@*eCF7k_7v2zQ6rsq5wehf((aj>E81H_9z38Fj>g-{ICO6~$v#uQp^K3@mL z8`w&V^gs4H6j-lk5It<_(?m`{JmBpzp+(C=(#6Yx?uVZA)T5l@+rG}Z<1Ymbqh}%c z?*VR)ZG7_#`S4x271WoeGC(YVPBfzQCs>6@0W?s(g2!`wugJ@s6nWf_QI! z^y$A$a1NeOSUS`VEZkkxIKzkcwuE*0=SXA2wiA@BZCFKs!VZ_U7Um%<7?51JM%;0o zPabKHdWYGq!c8CN^Ruj0pCeXVR^sb|b(ejL=iCBudVN}p21FMk6dfmyYmF?P`q2}VtDTkK(Wkl5MSiX~I-GrD^Wrh(i7ZjkeJp#!p6 z_oES4Pqf?ThXa0qH%GuB-iiG`R@bnZDhc#{Xa0P!FJI?g?#^ z#EnFUuEC;-2%#jfC}wPn+r8Hk`C=*(Xe`4X5GPNyP&RAOqk;{7>19)Thn%n?{V024CcKfx7H%qL5W zjqZfSb+=TfkELqjaLVQ;l~ z{PN13+ol0HZ~2J|?qj71f2Rz$Ozyg^TCjFTc*x;vRRtHAX+|(mC*Udit}eSxPDKTx z!U`;)C5SjVNQ>3!`~XFUH(wpY_>87qGjs$qHaAZ%`M_TjlT%Q<)-Dd zHtq6XvFt5>EmfW37XhVYt4UM{@-=1_gHenn0~13_6SGc@U#q>!D_vE-&OJb+khosi zesZyOD3vB~f-D#BIiFrLsj!7;rBkH_%6nAQWsKEW>R+uuBOh!_W#;zu)ur`&Fa4f? z4r^a%>&lTR=`6)iM*$AulcJ>6`>>XtQ3B!T0&6t z4eoLp%>s=g_NON+0$C|5*YeGUIugFf;1U9-;zR?VY%nK_xoTW9$FOQZZp4|#?@(cO z4@EzSq;(CJKaogr{1@SI>B9d=6jQ7G0OlMn-mt7etq0>`*-pTrOi4dl@q?|j@e<$- z)4}A+mb_G6ewkGiX7#fUkQ%yLygY zQ9NkLs$K17P_&}W{JxaW)8p-11pl~Kr3%6Pl(I4}LKn#usEH8^1{;379WcO%i8a|f zZyjg15Uk}5#qnazu(WTdeLyrpI7wkQ8yO2|P z^25rbfN|c?NL{B)8A(^fpa?pB8|Wlq4K(w7X%THZfj!`cv*i)z_$!Gwd?~+$e~o8Y zM+$8AuxzFqowzu4*sNV&?=Rejw*#W>Rw)cQLS`_UPIe;S#M!phRNL|vwp-+9Z160$ z_WnEujM25y?%cj4K!-HwFqqNEue`^X^zcU^gQe2A#wAG|cBU!!*Qf??7rS({RhR`+ zhziQTtOyv&EUaBzCEsT!5aHZAyU%X2C@!>%@GsMJ2C5xsF zAUAV%C(x#j^%u){;>0`KE7#k{_S1fKYhK%pWrz!s^l=GO8HZeBBNR zFIp6|_@@Z#lmlP>nn=}xujgs>`5g>eZI_{_Vkr7x47c zfrNQlvgoTIe(64oQ2i`w07_cvYLIF}SCmGp)O_HUFK8RZGko;pd<+A|nNO<#1Lk12 zsAEabs)mfM^Jh0;Ok%OHc+7=#w83jHT1kvgF;rGDgL{0~>NQEhrvPE`WbmTogL;GT zj|r^tV93s}N38ktgzF2wSCHp6&C3@pNcoiFW+*@}83rG*0tmwd!07(1!2vapp(*qx zzJ*MC-$-}conzg#rkK|%4SFnvwv8(t{pnO1QfOe;b#EXjEcDT9N72d9&cE)vbv|g%PRL<=BZL(gS@I*OS z&p0GCi4-A~rbQ&05DM+T8ZO27TcLGZB&f$8NJKgl*w0*?A0V~x6|?6O%2V`QK%pLH zQ~8V6qxqsuGGlj7B`jozJFhR=hbKEX-oqN6401Iu;Ry;27jV&%^;D^o{(#v?$;`X+ zOq{N^g^Fj)d-_flwT)qkp9lBRSIYm;Y*g!Ci+^(KsO=nbVdXd|#!y|YHHI4G4!4QY zG1sHH%t!R`oUow@$H1&B7IzgJ5FBk8vay@$u%v`M2-cSb#A}0Gtt``kaC%H+#V!~KGon^yU_HY|oM8ZmX%-r=Dkw#Q z(zSdI{tjqN#e9uhI8Xak8g~qLm1@H8G|3K6xI6(?QAR{r7OT0c|QU__2CPYZ1@ z<&Vt#aqvqvA1Sa*UfY5e{mKlLe4re@Zkw6Dugn}w2mPtNF%3_+bximCSpkb+HpzI0 zZV31G^;>G4u6Op#irOqyrFTc^(cTjib_gM-YpAe_>`QPjTU){oW81h~4no0k-%EvC}?WLJFDR7DF5x{yAf!uDLP|;yL}{c1q@+YZLb?SM6{K52x}}@nh3^;M_j#Y+ z-Dh?_oH^&rnKNf*_7Cov=j(E01`otuYh0%e74?eTn&g1oq4^V zZ?8`~eS1-h=Rg%7^I?mBdCov&teKt8OAKX23nRs~n}wNt`in|W3J}aWU0~zhDpPxo{6vzWdPv>JA ziNg)spRf^}deLtS3p8Ip9#=>x(E&GG4EN_5E~Kf25E++tkG9AnOT+1`AdHeV1~@HRW{E z!f9gDwDA&*o|8$O8XQ0LPy-HEgL>#^6s^yvsnFdL*yq=UHyE}Slkji6BmFh`hToy$ zB?m>e5#Q$X&&+8mcW4#lsBa=E$VvPnUOE8i7VlDhiMVHl{&GAH*;}rYN)mA1N!hl+ z!hP26N7$`B`i# zr-CUXb)33z{Uj%PpYvd-s@v~qrZAR2$z#>5q<(39R$ua2?wj=+fjrIbD1=Tdb zXkRO#XU+Fjr1o-kWFPrfGy0rXmF_2!So5vp{Q73bQkuJ`ON!5GLtF6k$ax+Nd({s< z?AMWF{i4e9noeil+i@%*_NMj9j_|NxFp!vI)0gbS9`rylvvfl7aDK&2oA_5@H#YAx z60}Fj>!(@FX}{cs14kD3LJG?ah^@209RD9*J07I!5cK}sF%1mB8AAI!w$$sjze0}rm%rG#c>w?& z+cv8?6ft}Qc35x8`rr3BZd@Z@LbB$*O)ShwBehaNEAmK{)vG@>5=f3u()YN(N3&JP zY=WMo^{E{PqiplR^vMax|hq{%r59`hP8IcJk|v}1kPy3N(x8gp7QJbgrj8sWO*8J5PD zhK(k~uq!FFLr^zA~#i$kk|f`q6i3kHSh3hT^57)ek2@`a?Y=C8iUYT;46_Sh7!HogPFh2?A#7j9ETB-fwZ5KPbA=_ z*Z(#gRJ+2Y}<@b3oAsKIX! z%~ww?`aCBh-aLOqkr*L)t1>!-jn)hPK+{i2(?Pi>tRi*H*l!?ermTC%_?liQi-8{@ z!a#(5K_+dX47(qDC1M+ebeI#LE8W=^yJ6)t?lYe>Pm_+!cJzH7@{r-lv{7HK!8ODO ze6(X8RMtc3=kz#f6ph9i3?Pn0pMkKr{ZS`(jDwz``zkk$8-?+=j!k%8z{am$MW1Ov zRZj&4-)wuI@i$?CWh>M=gn`J?=G05$bhy*zO$6RLGL31sT&!MO z^)-%7#-?(~Qd6ztTjxSz%uR7CwoEozd66yWXkI3M@z{R(-GHvUg{&)FCpNg)BNLf} z+L{UREk^2wohAq0OH*S0Y?Xc+TDfM*5zYe_(m9#nr(bKBS|2enF(q@sI?(6z@G_nJ zEz#vhSEN6rxLC!kD@*?Ydg)dZQ?sk0a#5Y{?w^3}5#;YjD#aBt?m^eg+=kRsg@tuD zmdh!oy7P+QjVP1QYC8HBJS1%Rue@bi=!EipLctoheE&`gVhD2>{`pY#Q8 zG8^SLMd5J&SDLB$w^)XR@^repM8<9#_hCm2ec&xkqsI6^O;ku1Xtns;&G$@farooj z_EQ>}-kdLcLUc6Yto_6-MhVuhRF+7YbPjUr?1 zVJi1Jj~>{_@EN~*Z4dyMsL}AD`moxV_`FQ=qMU@Dkjais6tJ#x_Jh7$aW*SU9|LH+ zhmmONhMJh7f0?ryJ}!{sufcYnJ$FX02WnBX%5{PYMJcy3Ok5r?|JjJ8^ssi zH1_WhEKZ9^f13E^r zT*kjh#unKx{l#RJRVO3*S8KGVzU5>b$gspNj ztfD62i)c0BoDo~VJdOgIWnqq6_-T(GGfc~59#9I6E#)hpX*9BUPCNiZ`aAw8b&6Oa zKsG%Erhxy9-WOlUagNd)t@@{{jtD348=Aym?bWpJqa=u%C&Mi|;! z2oIY!+#~ZaxHicB5{_{b_@l&S2{OkAIFgEOCnY71*IGkKzBG)b)Ga9StVnpCv=OKI ze_nNIwgc~(<05z>--eIjM*n~=%yXcCjrD7pedgRK6b^QSp<=|-qB}-U7r(BPV>mu! zNiD%hr!9W==>R_ZLu!)R*S_;u1@sc>sAM=aE>81>slXDy&}@N+VBj#A*)ud*~zUl_Pv$qXQ`;9 z2AaF~ST>@#d6woGKZW81d_Ainpw(~7{xP44l$&Q85vi#U8p*1t&a$IsclYow&W9=K zq3pj$NEr~WtNL*-uN7Btf2wz{zP+pZozP?mox#==k1|Nfg2j$pjujEI50`BOBz5H) z>6uZ(FSu;fj;soP1xmb+TSC?Z1*zrj@I@be$jR^(Pu|C15m~1kWgjj>83DYExEleI*E*J@Wg0^jVxKvhH(@2J z3GsisWxZ~NA&eu#C<$frr$|3zf-PdUwwf``Q8mc9^;rF)`xb>2^4#NLlMq`GGfHS4>g;hanec z$IiR~CrNvRZt96O!p0V&st4~uz5U(Vn!aXZCwf|x)vf%JJ9S!LXC~|=+6u8}>l@JV zDA4aY-Cr`h5Ek2-Ce&wGhk$qE4)pSVQY5W-$tH|r3(?f1Is)td{Hcpdl6sY|Chph7 zlLW$EXF)T@Hd@zoCk10MhR0psh{)N#^L<$qE}>NC-|E%}i(0mpH=8MQO?#sUO$F;!gMKiL zVHEqL-9I_jesOxQwYNc)4NaKa4V^A0V3{4upnH<(b$h5FDM7J+u3-eDh2Xda)swP2 z{Q|Q+Iwa07=RC3)duP<6Z-1^km|F8AIO%31sQ*P}(IGy0W7c;cJrRv;;rnt0GZ+%^ zlbx=z4Jq^5mG!HylJRPPN9l5bz99Sb?4XkchzMoZ4ItBhpR69EychR?nh2%3D&N)q z#dCfT^AVj8nd{!6F1E_T_;20FuGYC@Lt8)m(*6+h;p0fknSrl&Di%{iTse4?hN}l3 zuN?rn3gYfU{xjv{+B8(;UyeZ~6pe|D8C^lha!Pi9*FnFY&ZD}aOlTz8M4Ql2u+#9ggkhY)|XJp=3K0_p)|9JO&NTgY|PB} zieta`kRcp|lMIs(!z1MG2eh(ryun1*Z_L?DjUA|UggDAZ-cS&dro}WEBC#kD9mtDi zMlLS-?&t%l#%Ha5{f;k!n+)7|67z3yRS}7$7H+9u(?8n(7@YT*hd?MhWf3Vy@YiQE zNb>z#(!+uzJ}Gg1r#`tQ*_qa--z2P>UyfQz+?OeF-wu|L@edJx!uDc^rzDK} zltpBWIZ&Td1R&nxEs!z#80uWhT@E>I1Ih8FwLom|Y4%6V`S47+AstJUA~pD8NO|xO z!CUWzRm$@%5B6M0%Gl>M)zVl)@!EbFG&9DQm8$JR&^N&#oPI(sx5D^U=s8zKPwM<`j%A?CpF=5N&bdi!XvEG_uCyAlefZ~maO>v2hs** zcipeKzNTT1Xz@G~D~?-i%9>3Q-=boY&}g7Z_9N_?z_^TCd|ts2i<7$1FccUi%7DH2r@jS1IY`DG2bQF93Q(d~}1PT!V^0!uaNd0XBX z>%g+X>#ugo_}bUD4M&uorIUEWuSsNmcG0^-mAy%!8lAQ zvM<%SnIB9Z9`mQ0ERXhVp0rcB{quzXdL{Hyu-Lj3+rfAj>~;PNdhlJy-Mr{8WKT(B z5$$MIW08ZW{vd(9hG34GUJ0#Z!LL)^LBu!Dr^KeAZp1+0L4WrHy3we-p(yiIyT+n} zR;4f!ouf*A?a%^ptJ%nXZNh5DBQ2Vk%2SuTn)V36j561O(Vm)TC3(GCPfDCzA9nRD z+!dORD%&3l-2xcY8U{-n?zL=xQkeInEIekDwPB{LGaX#7X4F0NQnF#eEPxF*HJuEu zB&e=pEq~tQ>fz!ZOr^EBNu_|KdiOC_;uZaP(u_i8+{u}b8d|oLA>$B{t#hmrPIl<% zfnbq$2764CdS}}=!t`ajAaLQ(>qiZZ>AkZ(vqC3%$_x&=#2=#s$>hymyxF9q;QKxXh(@@wDrw8NkvI6x z2Qqhk=4lBTSv1SQ9)h3)e~+(c%RQc5q860@kNswV#c&#QM3P9`n*Z?6K&}B}O4Q*?$_E?{?>z>CD`{O>Mest+nglZ5AOwlct$D!@iwf z9fN_{XG|#QBgZQ!fHgkN%y>#^F^5m_@Kx{1?(UnrsFHyy3=3cM9wU`*VsR%lcg||j z%F{2Y0~$(xs%X8pzPrXS`h-bIuEX|I#t=~g`tg9YuIhl#&2^ksCFbcILR<&jMw}jl z_oGooT2Xu~Jhy2GdUce&(Tnuv&N5}JXGKS5%~Yw%tm(CR>FA+6P>&3hV#mE4r^w1j zH?w(Yd$q9C3lv;3B#yJP42XX>uGQfs?z?$Y>PHwdI{9i4>{|Q8t1Amu)FJeXy%kk^ ze`#+k7`d9C$YS)O+DsSgYn2ygzqg_&2uH7*|MAqDHw#m=!Z$AY6ZJx~hdIgFF&r-l zz24T#6VIEMuS$n}|ABDttF@2unM&VT))Y=UzPV`N+$~VGmHuGfN%I!-*1r0pN(T!e zKaF&|#Rs+fhq}bsI4nlErtYX+Egg|IgID$=JXAZ!T?VxqiH&N*sXqGt$@al-3`|}J zxoH}`Jjl;@vN$1yw;%hZnLX6k#(T0iCDKB+mQO||g+Z6tF4=%H5g+$)+GzW6&!1oz z&tCFe(5>ehzdzCi7EYsLR5;?N92Qh#;clUCu$daZ76(UL~&INxzKWt!m1=}4T4N3 z6Z}ZJpj);xU6-QpMgvO|6>^DqF>~Bqt|OavUzw;0g2 zzxf6b8}S94CVkJvq|#GerDKb2EFB}Gb3%*#N#;_EeO8AlLY=9~{H3o!+F49|LGNAS zVdU985@nsK7Jb*LWYZ2SN}PEPtvJ1qM;L#&m*(C!tJxe7;wz9KOU?=s9@E!gY?jIJ z4f~F^{|={{x>F`uqt=loE2__RI`=V!j2NV_{)@3VN!=Ix+fcoF3LR@&^i{y^-khi9 zi#kX(x4jN5+=W=zhA`knY0E{cBGE(rCPj*HSlpOiIH$b?e$#qS)`7cSRk?gc`ptBT z*iyIRBn1Z{+f1``S;Lj~61-ocoBp^%i**vs zhdW<9M0sIc(Gf!-e+o{+9<_VUyml$G%8aE$RX07BKt~u(^9J(~!lI=V9tvk)mz*W7 zEIbsX+RXb)Ib2z%8-Ls1?Z&l?JFA0-(|o}m88q*V4@2Sj3AhT^Kq-m%9IrOjNc10u z%YQb?=qk>*_82lg=@e!tAL1ab-@CZiPRzwW8J5XBZt+Ow#B;*Y;AKxA&4q3VZW@_> zhEH7*!d4TWvE_VSzk&m;Xi$?Y;XzPs*7!YMGhRj&8zv+e$=hy=5wnVPd-%M0N!dO- zRZpQQ7Mp z?89NMpMSivyZ$IgK8`T z^N}px?#@%|+?h!VA{YF8OWY?1`#Xc}{pchK^~l2!wbuF6d!t!k3PV8mk; zoK8Z&#h}NcAUtTNm62b9tR0V-jn&()xf~ ztAsmht2`^QM&UUM+^`I&&k0S)R|U%*WT%4&_;}pW2?8d7hd#Q=z0T{=&aYqi1x{_Z z`T_Fyl@;8fbXsa^00;CYEGB>h<+OxB2puZXAe37es?XDHC4f*ub*KiR4**gEhzkq= z86eda&Ij54<$=Jfm*2@Iihr{}!`7d5{Kk1!8E00{62pv3w4#03QD`BCD6V&W+N|CVA1NV>ES z2Ho?0g`b2l{>Ro3)_?Ic0D!Vyp4$xP6A%=LM7y*b<{1gU!r_ts_yyvFWkeEO(9dyx zB;geH{Mem4)U*Vo;jDKx_JR6PmFUE&3_Lb~NH1P!;@)>M8 z+WXv2bch?a6diTZFI-4O1c;9Q4^9LB(Q^hRW=Vrx`WLS;4eb)+{K_Evw=ZbUGQo?n zgXd1pg8fTB$7uhB5&vRJhz?yMaqcT9a5l08FZzYz1`9t6b%D7cOqyl%AN>&T`E#!R zd_pmyg82XD@BgE5@(GCZ@j;oA{-*|jxo-f#HVXiv4gkQO0szm}06=&g(tZA%_eBB~ z1jaDpH)a~*@kLzGTWj2f+MuZCf;h1L<+}!1eLj!SpD<>~Y6t^X(D0a{5nl3u(1{3{Fs|HKmu#9sywU(s;^ zGKlM9Jn&(F;*w4e11K*HhWrkn0_ZO35GVZw{anvHz;GF72wZ^af(Nn(K@6~5>O@cj z*RN#J0M;vhW`Ofj4}uHezT`p10z8)(@*wXO)&cmgWVHanOFA@hs7nlaQ0NN70pUvw z&Hy5p81lIIf8iTf7)m95h2eno6$XIYR~QDUUD@yeP`{W*4`{r`fW`&pgzyM(=fC*x zUg7h20q9{QFihA9xCRb@ufSyB5nv3UKmsrpGQ1f`1c+cbuv2go{0%mNc;F(S1C#@N zU>DTN13Um6ffH~KTm`2_L&npAo~6KDYIz|SBI<_^{aaX={` z2D$+EAxS2H1|SD4fMW0imQ zP!WX|!gWYD1=LOtKxr)@4egK>e$bfsp(zr)Xs3gMkPHgwuV6h`2)2SX;0fRiC;|;o zpWKj^f7?OFWcLiZX=Q zpl~9ANr5_miKDHxvkMr+nVc`J35$J z;e$i~`q}l($pIO{8%Z6|iozryqhaOd6_q@XC1}Zl|I`;T_Ak7sZk?U2asjYj*0Zyh z#Q@;PesCxJAYIM7ZTdg!ttJ z6hx(^`NbeUC?B>aJ>Vq9$7c`7q69=CF+Oe?1z`bh6u$t98`2=cEhH)1n8m71-i=M{J{?gzzs5}>k>Xuc~O*t96vWoL{O9)B_kxjErXI%;O0lk ziV4d=yR@_nlt}8I2Rdr{f}y>(;L>?L=g!mO*Al=7GZ5H4kQcG;3h?klMSw|48TrHy zl4Fuu-=RO3hnjJ4na&y7K0^Xa4(9z3dp8fPd&$ ztd|pT$qsGK^3Psrk{XB&ebYh(IpUY}P!T%pR`4wFsS^(#C z9EbQ+m2;VM`_6y4K{eh#ba3GobfX373mV`4nexRq@-J}07QouL{IyU<={t6u%{TVkro};293Y_x;7*iUX8=3&)Jz&gW^snP){~B9c zIYaLY{eeCy+It&SW#AnTcs&J)fh<6dAUlv1$Pn}qLdbN=sE-61%56j|5`tWe~$StgFyW4 z5D29CpJQ*^L7>XlAP`F9KgV8hgFx7*AW(m!ouPx_4(Ob7GU{k64i{Y#^>54#|hZ?>|03Al55a+BD0@7==9E3y{rG z3Yy)%i?%TL&6@*sa-n{G;mwD84v1<APiF2*raW#OntIe?`~K|P9po-;6mq($pYhZD@ZlV5 z!5eZDbPX8`s??7hh19}q2tv+(U0#)3G1aNCVd1pL=v%XF?R!(U%^8l)JqUZ&bmi9G z`Q2IsOMbY9zZl1enm$3@&nF`*-yocq<>A%uXRb?fa`_)$)0h3I^=0QGyJZ;W=D~ZSdsJeAug#X!}NlQ`|Hq9#Z3%&jC z(uZ}sdDhV63_z66pe;wGlDm%s};m!}jKXFA5T?;+_Lz; zYQBmLAb8D!4=gcfZ*D^^O+X8P`+r$q;3f@Ie|G0Sm5iKj%Y>5FpD&TLUT&s^7ZF~P z9NEGN?wV!izOWC=S?ZJJ)RED*4psZGju%f)t$KywS;qP}pu1)Z!T4+6f6o2&FmEQH zA82^b{SSFq1D+XHgT3leOoE|{MA6OTEPxUo>Qcd$cKEV|Ett9HmNJwk9lM7nb6)8g zujT(IA&NBl&%yw6SmyXk+~imDMHdHVR7Ty{+N9`qC`*uHW?;Vr?$ONqWDZ6Pi^7XPpzPPA!M+pA7EHi&nc_Bz`{C>iX7BJ*nYSes4-f)?0-!4?mkU zZx3u+X_DaosqTp@|7cDv*W=RsXEiAh|51FIk>c_hu#al=>dzGNqEw98D~u+WxqdW# z67mL5d0^)DZq5xYk9zWdS3}wbfKGE{x?;*`uoXfVpNQK{|`z2Nyd{&2;GsUD(nJ; zR;!OAox&>`1%}*uAgOeW22^uO)t#JOlR~b1a#J3|+`7a^Lo!MA|6mTOF#j0M_IaXz ztR(_wE;(DSLz`DI8plO#Isbe%_yBX^w_F>x&e3}0?>M#!Kp2_mgGA3g2`g7>_^rVI z)y}Su0QVP_@BNQdm;ajCGO6MMbo4JvJ+&ApQc!~9d)fAi>Uy1K(n03juenN}vqD~# z*xK*WY%?6YeIf@oJV7MJv?w8+u0*O3T=AcwWzy%u>V%mtRl^<`5$=) z%>B@#3_tyIS-C&1M9NoI{~x;u;h)yg0nC>-W%GH3E1&FuymycT-)Aqm#4m4SDW4y9 z&|E(~5TlkWQow6;H6k&byj8{ut^+gxQ0PZ1DMJ2lU)50jsBP@JvegObDSx}G3bV&M zw9VV|iH-@dM}`=Ioh){*)Ga@*VX?EtQesn`z2!_%^Txut$dAS+I!+QFA`$@B3k%6* z=Fu}U!~b_jrTH&=1D%a+C7?r_#oxFgl7SuGmDOLpLJNvx19#e+R_8^WLCD>-_Tzc- ze!0kJP}2aMybk``d_C$HRL$-#9rFHGeN6VJv2!ZIHGpfIyq!}4RA*20Z)4=lfb$B{ zVQy<@JjMR$sb!9G>4Js=%M`3@Tr>FKsdS+UxgT_P9!X9icu;@wk7FEh1^jlp@t*}+ zD|}p=A?J7QyArxvjdrhsiqW^JGfCq{x zF@PVt@U((HLEeZt>fajxcxZ1_s6bz%4>)MPd{h)FQgm5%Nr|NS^zIr4eDlUog- zgbb?7mCs-)*@7VXTKnFy>==LQ2Vp>px0x{-cK}H;uz>1)D!FcH(qASSL4wH~kRz!5 z1jOTy63PlgF@sYR)G9ZxXoQ6%?w~G{I`=0!|XqI*8QA zS?b>yY$pb=K~(9rz=HOKm^lst#yC(~+(_87xv_^65VM4LOksY{SXKNj-u?Q#vcH?& z5gF8T;2iLoUB=SpGmBx-y6+1HCzr7;K;K#72}=iK&uaqTr~MJAwz=#yOJE8ASaktR zU~?WN7dWvQ3yLHUw_i7b9<8&9au5oyW~F1LiqqkzRC?XKG_8!^b9`0)D4LZ*dfIR7 zUT%E}aa>f-1|Fw^V{0EOTjzY=LlHidc3;u6*{k@e=voz8O{PUWBB$$v=2qZ9G2SC^ zwbJn8cl}YBE13u{zK{mm@LUaW^jY>a)L6Qhfpd*qMp*kmUOvj8*~Hk&AZLEl*Nxc? z>?5xg)Ny;U{jn|cR{YjfIy<~4hNBA~{sPB3s%U{cGnMcUpUMtZ-)8{^tZmNd0VOo# zr}|tvMJSVf4ZiJtQMsOj_D}#>Wp61AaW;COS4kWK&Rm%8ZuKKBI9*ggg?fKr zeE^3Bh}34&qeG8MlnwlsOCZuKW&%$EH`$;AFnG(GcsDj&z-8R@%a>BzM~eCrsd%sE zlmD27P|(dKn^aAAg0k)k;d;#i2l8>HRSsM>lHN{wcZFT;jPyekx?&8_`GG zi=mA%f57(}U<<)uMW{;{J*9r~qwkq=P*hW))r9k;D3!eYrShsqiv|Z^asXEVz(^;r zXKlisQwai%IrMsqd~8=pUdV_vzen9u z=^?Af6jhLsIc)69;XB6;xQ9?kZM3antQB2q<{NSJG>aQgp)#|d%Sxwc6@ZoWg}?Zk zhq(_Gj!q^EFvJ6(hE(M79(0P0G=N|MC;{sJ(WbMx+GD|ZL64hOzyrLYt>q%Ez?h7( zUFOY#(^?d)<_=FKaCh-_4U?EjYS;xdL&ofAI9iZWjlQxn5)c)XPN9J~44w2N7l(P4?yNB2 zpg2I57nu7ZIk?YG)cs1$C%=n7k4DDI;9KT1^Bb#M!Cz!z7wo_^W3Grv-_`W#wYbw& zQr+;=w8*xl=gq^Kjr761+7I?6;Fpx8NWf~37RK(;Ut>3iO2S{^C#yHS_$(zKKA{h5 zWf*U?4IsBHfHrFeDfIcN`leRl$cqjys8&{2|y7}hdyiP32B z`V4%*42mcYlf)2;vSZWl?6zi-%F6^KN9DCUL-yUnQ{Tgd08{jtTV|lTKJy-!#lc7N zUa)Ffg{mKQO`}qFTu-2xarN1Fr2M{*bt$Es!WFFmMR>nHqX4)`ylaM<;YBa19R_%^m)=(B?WZU(A5|hb% zOI-u+sW3RVUrxK9Pd>QXQ}dTQn2yBAmK}NpU>G(eS_y(fe+Zqh_#9U3^VU$?n6rzo|6IloIheopNhXwHJj*`4`Hu$(>Ai z38yyw*2UkOlzOMkeyP~dNZuXr-RMMTi-EXTS%nt*Mr7NHM|l&waXjcS9?&TNW_SbV zqVx*^QzNdE2_+q8j2@dSNk8-HBB0cp*Tds9f_32Gr$Sby$Iq|VvoMvH8k7m6rI7HI zWQc!%##E_+hFnp1+A~ahhKFjt2yvN6i3?wR02qG^qyHE>cX57gTfzjb5Mq-~4Wi;5 zGc+^jB8=Tyj4nKegeb9(CYdJW5kZ7w{f*|6XrC~L8%hwN@=*4Z#MQ*VqRFEnX0dg* zM|z=TQak3>xFuw7z<_KJfA+dWAlQ`~yL2f4JS_iv_oEt+nUEvy0(`j7&g_bbM4Z@L z;w@WXd!xN2t%FGX&~*0yY&PB7MIc}~>FycvBefT(Wdb0NZqg!vmM&N2-V(qnyuJJo zXlH>K9;7IG@-$U=O-9~C8ZN`3QQ3*5`vDv{$4PpsfWlM6+>x$~iyw0{_I!SzV!-Pm zD0U2*LAkXEBkbp6-;z(CUM~WW*MWco*XRSbY{xx z^48$D^gDNW&?>EekP6lpB-*Kn{`66gb{QV3a8V8h*;g_n76GUl(>DEIGv z=H~G58vPFMl>>a@ek&mHg+>LQMZrp|r!yJ_V8uQ^V{0A(%m)X$6&~Jb@5S|CTxg7| zIPo*41jt^sXXn;_8h)}eCd#CnH`17eoKzNmErdG&j+-onzNNutV({P6d+7 z|Lq*O{|(_?PCers`T^>JloIdT|3t@Zgn;qb_f98g)C1lqp-{NqC7h|I=m-i-0CWm$ zuydaCUr|rzF=aA+6E`~l$K(tJiWv^ag4ex(Sxb6MSLGY%Q??H~PrVuhOn!;a8`QUT zGE2QdOZ}1f)>QWPdkiA0BVu>r>&rRD5=InZ`nG#^D!ML7KIQxLOyB+7YY=Z~xvy5e zDYw%fCT1alK%nv%N!)xH$A}hfYL-S)(iElb^B}D9(=z>P9jz~Ub3{?lF~urrd3o=* zn*rcvR53mvbwND<_vTP?kh9f|Rrz^LP!IYCA7~!mtXY1Xf} z)^vTob&uNaIKIvAiTc)y#RcXf7M1vv&WauM0AHCvc6n^*QbDx030n!n;C%^A$N^~N zw+42HRh!pucw@L5!`~kQ!M_IHzSWEj%zdf>je@LnMm=lH615o^lvj#^K7R{UYZW{N znU7$?MEagaQY-JF$>gGPq@fjejT32QQw%SFoUUXO2+-0yEKUcN+@!!+4@#vp5-`eT zYxy5F36Da59cu!?A*MBDiAV(`gadxmgmUC953Kq_KEF2riFOYFAPk`7opii@quRUgL<*g?B*m17U(cZsM!c z+jMag1ouO{cHK2$&q?YBRMGC9@4SbuQ_#Ta&A7{RBzo9IR{Cb@gWG(clMEHzcOZB?LM_|*jX>3_8ubxrP7LK$$GvrCW$R{D~760_m8vUVY zQ*zICO|vx)2YeWg0mxBMja#stOz^ZwY60xI(sR9GV}+DU-Jikpp;YW4^^~;5x?r_m zlHj|b%m}4MdjL_HqdwUG<$iafLe%8ft3Vy9SuU6%PCg>1OSfHat4~Id)p_ z(J7Gn#o1n>0a0xvra{Uy5Vqg zoxZVt=2{#+v(}0t{+{L63X;XKA-;6ymzS3_f(n|BXbG=ZP6L%$IEUEli!dBzr$~LQ z8@|ec?PRQA*(5LonUBJqr~E~o*=>7`-_tCaU>ai(FHCB13T1Z1y__{j0Kz?7yH8EG zN$1f9E9@MJn_bChtSd%%#TS#WfvE2|B^aif%OSrbzw^RB`I*Tnt^1+6J6+K(+Nh}628Vfn z(n&Ckq?Ja97RF3d$KmyWuq<%eED`|uyVL%YO8*0>M+N*#S1L6T=<&mY-L=H z7=5=Q+|sYFFxhpO(3v^VgcFd)xpvGCP(y^_IJOQ@Wt}=Z5|4ks$*##7N5YzR!Gz~R z&t46o&C(pKASrKkTd+qg>`Aju6V_d-aQncxW-_kLl~t6i^k! zf2^Mt@5&P$-W}v}kswCq^t_@_f+)9PEI{luvbRc$qU@d)@GIRlFDEI#gbX1SZ6<0< zcO`}GnSKw*GY=K?R!4d&X-<)5`f{&hiv_hq((gG#ryqiWP!fjIT|Fe&hbo_Ix5Yih zHkR5nh|_B_njyb?hxe0Gc1&#|D}WM$g3m)x($#ZnF;;Z>KLz^V-c+zMcY>$T(QQ;d z6Ao6BR>KLv@MuTaS-@7u{9MXV=zFU=-2zKl79QPkC(Boifk0bTwA!xO$?U|C@bgZT zWX;>PDxUY-#4ZcToRK2WX}QGv8@ZYHL}L53W|3LywMu*h8weGYwxJbXk*~*#^-A%D z%y#R9={924f4a1p)#Q&CL_iu)jTBh<6ne+apBM z`RtX#v0O~YV?^d%+h{l);XptHXI-EyFGN#tBB@CQI)5pjC{sG+AN|Y1P_R9prsj)m zsFvZ25>Y(K(>uOQSswO_0EXT6<(sD?#cwcXL|xoq%URsg-6p2D`H5Go`SD!(?uom) z#D#TIqc7tx>4LEcN6SOPl6M76MPIU$uJ|&$2_vt9SvC^21<+}Rz?#>AZ=F5ZQa?E6dJQIYA zU-)T&m`8<7MSjaLn5X~f>VTa|+ zIM;djy*15{q9%z~8MzuIhx`&5!dkH}YiNnbMrx}!j;Xc^W(x(MZD%Wf0h~BefjkHI);(um9@6xe;2U@!@D>nT~1#%}q^mphn^9LSOZ4 z#{;j3eQhzPE$L@3a(iBgq{|29^FjwbuuXV?rVU!83!5_oJxSaLs`OUA3k3a01v{nZ zSykC-Aq>;5D_6CH*KorW!Nk<`vGt)~%)ynHvX|SGCdQEFfqt^)T?+mg1NmXg5sCuv z7^=;`=agOOteFfB|=2ES7vZbW4P0MfUTM9I;dvn`58DQ18U*)q? z)@5I|u@aq7D6eW}Bx*~kmpiX8J(b4YCjAzCkR{LJ~}XUn(27rzpFBDBJ* z&VT$g@|g1k?Y-Woze=E|x#GsaplwaWhnpjuA5_d#-h>IQ#nrYU-cYG_NH*u);2*iQ z_?gc2+As=@MCrFWEVA37S$&#FEO&WhL3!40^-%5iZXk%;y-J1ujUhL4ugo3s`k3|v zL>w69A%6MF z3qKa(e;;vq+`a1^eP_dX9x`52L}AGr85H??rcsQ|On{dE*9k=iH+rpIb2VK@wnrdc zgJ~)TOj2azjFT6bC!Y@daPX7tJCLWWB@c&XoM_u%6`U*T3mP<65%$0kDzBpTxp%ap z{S=^2jf7E8%f)$c)9Wj}(pi5q%dwYZl|=rNtaS#-tSxcI&$I2Ysx>LObTidt8Oz!t z45qxUlt%nA08!Ej@s=dpth@b;UOzwn!)|(20y2))D2Wjbn&LbG&EX5W^>8hQ*N2X; zOEV~?UIue@+J!P!C2kRcr3CEZR7*2<-dDt;xiN7^e6oFq`aZV_d;Qh6zdibpPd;et zlk%W=<_{qL@fRk$7r;ooVxq`!MG9-bfWM>yl4LoOF0pfJgI%JIZ7yXE0~LH)6L}g7 zPb@OedsJQ`TKgUB<2N#|A)BiSzg$f2B)o?7U((WY8Anlgz0D72k?+zUyqf zi{CX+jSa2>s2?9MLil;57L&Pmg#^&In1Lc;d7H4;(?2u{2p+>Zj z^TT}q=rhQC@)S6ArxB<|xX5ZvP*Q+hIyixNav=Pu;$4N_Z`bC~$AH?=Kn)!T)E5*FG$s^ELENEe8%^f4+pOTiS(i<$jf2RaH zem15lN7%W)sQ80UX|$+DDMC#PNtxa8r8$Y700e&8pKXL~J_A(wLnaxA)8oMHb4Rb>^qPV>+nboTzSJK!^83k0G-BoEwkhDG1BlplrIL9a?E ztTVmNJV(rG7Vqn8V+6Hl+)D3iZ&D4xJ|>Abj_a(0*kqP>T+jQg&syiM11S#(mSCr+ z_e)l1x=W8nIWfgjNtMC|Z)S+dxgVrU`eyHw3V$bTpGv4E(6tuF8iJl^e9BNQ7w)Ns z5#!jIjfnuNP8iD2^vYw%f2p%FtEGqiyaeytWpP?x{5!G=b1K2m22Q#I0>%Pd>5tS= z1y20??_F+Rkk&=_Jo!euAg2(xA%LgrZ8Vr1>x#% z+OCoqyA^UYK4v<++3Q8$#8|;c2fzn2bq%U6aw&KFQ{~Sk%!Tj^KGaQTZwG${T{Kp# zr0+iBatI{4&Hqu(99Xk=)6`Agk8U-j8ShmMJsOvV zi`o1Atbw!D@LjY=GHPWwrRMXam?LTd_|~w1v@rJtcH#;<;x%7Vv;@)cYiuDb|LQXF zTSK^jwzN-lrExn`6Nk)bG3C?;l$CH&+tSM)4}PuU$>WgUs>}e&yoh+Jnk6_hRqpBW z65PN(3V$KO|L`8B5%JfEhEC4=f0Jo|3RZL14GC{oa#rmCED2y-IvbNL!mLt%nh%dy$3EB%$WgitG1Lm zbDb+%P#hDtPZA0W@9hrz{3$$()vJXl**HD__YRezYl+$7!#)mjM|=jT6x?er5K&1h z@6njB=NGiO*mO6}_;`d6QCdii-g*8~ZXK33G%2c4zBTrTzI1u&xN9H%saZTo$4$zQ zE_S`IZpSE#Om_4~a*a&))%k; zDt5zrJ{cQP$Se9ae;cxij4jeDN$%D;H-pJSy8$bw+pLqR zo8<30C|!2!%1$Y+M0L=He;2{}Qu#Sr(mCdEZ(*OuD33s!1#Pw4Debqo$c)e3J9mz- zQHX?J3nhFq1J>w3$dhGNFbwAfUiiFA^0Won(jT_uZ7IE{Ys3uwo6%YzM>4JCZP$=v z=r3xRh}GQ7`gHH?qlKa)ug=f@7Covhq=mpRlMlq>1wY1S4-t#Q?WpZXB^_#UCW4F98hq!NCP!sM%}-r7%s>Na}ux z+qY4PJX|UqRYsc@{@3WjBf~A!unOz^ec|*jXv0J&v!gTR?dPEe)!rr-99fZDv~R+} z8HS;?&+W6gU-(|a!gJ|b8JB_m%Bpvto29^?U+O;xv9maF(yov49PTj{tYzgMFSla| zNTc?ot+|P8;%Kz}e9dbJpbT`2k0O>AGFl%`X^X_9`qc-Y+~IxBfHKtToeI#Qyo*I8 zXoY#E%V!cT02y7%X@`Lj$ZtPQCm_8nj_?i!i_31mGlJ8iwQ?_L*<$x97om18-_Z8l zvs&9-z6yfPC#RrPL&`f+er6v-FXavr@npVyxTp5K(dbLan}s`xtM@LE$t79F~!0JT5~SsA^D6Eb4cM3Ur~ zoBf!9q)M*?))QbE>HV%iAb_=QtZBDzvHE<-;@{;Jmb@uWc{n_ojRcf9h<052nE1QZ zET~^q6c3?meC>6Ax+@;*$7DaX=&1clsrs>*kM=Ir&I&4N3BI)flBA2YWz zeRp9^vLiiWWGMB!VR|yX^&Q!?55(A@N)XrJp13TZjO2}J$VoeVukpy}TnkgMzIxwK z_cyd!b+zOTmNP^*bL#ruwJ*sPVH~i$dr8P1m&-v#&I%pNdFiaaEE-0~1IKt>G*;R@ z$-=lU0UekUaI_pBSiy<=DPeWHmQGJzc3tT<9SaUoQ_i6&WOYd>2so(bLa5eksF)Xu zKdTHT5C+u?$l~$=M4x*tFQ=9v^O*6|w)>r2a*ja9BA_h8vC@V2!ywBTtgIG?@OozU zfkYuF^zih+?<>rkZy8-k}fK^pNLwQD^!seP_9y39P9sOjO_Eb6Yx>s|K^OOqCp3Vu$ znryh5+?LF&$?HR&=%yPHg+ptOlgT(q+trU;3kR5^pK;E=ng&%|d)_3~Ob_@<1$~Xo z4z%csXDCC1lv(&alws}eEW0fjn$T5j?(U6Bo4`j|+D*hReF)FcK+VP_e?H*jUjnze z4n7f@t?LtTTYDoMNA!T&jI9!!0OkDC$)GDf#K8jVXa{kP*PlHH_UH(@ z4d(?ze4Uu3d7fb>-)-4kb5`SM<@`ol@QjPDCLj&`>J0D z_f}(}hSI&1inW_+wxHk~q)_Q)7gnZ77P<+SdrT)>smF!Su=f0@8?mX}tNpAkLU733 z;g^_LS0T+AM{%VSjT_UoZZww5nj3MjQHZ%OCLcIa>dQ;X)lE*cF`CwLW%EY{oUXDyOB?0(Y^HZ29*I8 zPx7|1PhNM79|^90h&}}S&3vr7&AH+zXuY>nw2s_(`O@0;_+(lw+PaE-q&}I^>XpiY z11qKG_xjRA)YcK+htG~;Pn&WJJ6GNx@c4TV=;AZxldE@XY9&_&Q!XdTjo|~ZVXF#C zH{wKuc2zVrC`TKJz9<%d z0xOz?$yUTG9MsE?FE(PSNhbxQzP?9Z55}gzQ=?MM^Ab3c4s#8#lRIwwY;CQ5w?U3{ z{pN)}VV%d&3((+|Efvo5m8^6i4mRzspMd^U2{>0?<(f zjF1a(uyxHS+1?1ly&p_$;kZdLY11FJu+Z=S${?}2Vd^DRA-em7-Yxf(xdcOAavTMU+cGEg482>M($`T-8a1dzkpBC{AVU06XXr1}Gd+R_e# zTGu8DIGc{wb9Qr%Fv~4n`6od{SALp{YzH1rLbV5x#t1YoY7?Xo5HCOSZpp=mWO3fb zJfp4>ufS)rJPyceaxg^}knY*K;z}nQsK2W`So%kh4WwdUTr+X@3a zhIqPqCu~lsRJqRh*AKkTSq8B&wLQD9a$Vl}W}G$Th?;n@PE*xw#cVt_oH4SwRyvm- zxp!jO*}}f^@ETwmEA%Uu`CK^>b2H##fOMFTU<=5R^#|+v;AQq#;(2ZhZ?>my$gAMrj%^-;ST<|D(vabP)?e9n=OiN>sXy{;)-B(R zLwL(hlZ(2uSmcJ}{oA(cv%VGHK`pYQpE77n1eJ%5GuE7FQC~LX#@Lf)sc%%k>LeR4 z3JLV8jET4to>C5wZID@g=bpkzHRv(gb{ck2kRGP=nW?3mF1u?wgLkAv!dG$KFsm2? z%6d^VPsA_gp}8u@iAUO+9=Tsy3oi=en05~;-7}s?-Yt|ar`pp$D_kW(Y&4C?g}%TI zj_1Rx@r}gxPb~;-CJufX;bKbzcUQu-<1*mtcta?Cbi)-;zO{y#gQxvnd^@LC8vM5Lsl=-?$L9(+por#v;qG{VPcX2jz8|HNGC%q>w&$3f;;c)U#qB6TmW0uD z7%8dVp>0zd*<88kNXxKC7T}4sP`(*5$b2PrZ4KqmC`X?)CNStr-lKUtS``_0xb^oz z9NsOG$B2@u3`)syyS9ch_idYK$rM?B){&z4wEz5xQlS8%jsbH`J8{UhZzc?;`GafW zHh;f|3)YJdW(^uyiDwu-25#TY#HYMvf^L$XM}9crp>BPa8jHGDR*qr%#vmV(Q0uDI zm+|ehn+!Vz&?x11jDi!B1oLv&@{{$GD0`8gkfkSYyH?c+Ex?TY{Rh49KJ2<=V$Wfm zY{r7iRmbr=Yd^m-jcO^1jTnvbfA)dg53YS-&sBHq!V5m9%Ns`@s3sH|cbuV{t+3bI z?b^0BHIynhV3!FRxJf|ShXQh~Sf-cDvGpm7*`M3t!@8q!GHdMx-l*a2k~){8SmOZN2wh*s80MoUY42)i=}J704#ZAEwkUGL$53k4{-Dj1Xw@ ziH$2?XY~O!hC3Jb8tnk?o}BK;;!E~j z=J*9$`L%OVO-;G9X~Y#m+SiB7sY_j#VcP@mn_PaM_HGWn=t|w$Mo5)hLU5jN$@D(t zri=AzATYu5oC(XIKt~!JX|uT|5dSG>;#fw@9d~zc$oS>MJL)?gCqYZCU)l6uHmt)l z_DA~FFiBZQ5bP-=N}I{ZjwPa0xKY@084Z#!F_C&lb3y*!l~b@QxbAW__v3h#VYi=9 z!34p!@}hhcMlX3ak9c{+wd^(4lj&}+YC9nJyz{w%>wP`HWr@$&TF-AW*Lp>g?AxlO2se}x2}Z(D_PH_b52F(@HqWaps~MD>J*FR#F2Xhh$amX1SQ5%%A3W$uoV@P1#jjuPGGg~dnVHaV0h{Y720d3KFnjjETY zmvb!7ZTa{KTCli<@`{fR{=4|K=DzS}+?%4UqH&Cth2(>0#>!F}SnNN7; zv(%GLg82-|Ut_^esrr3pEaK)3<%2KUSc7P)I(r0K5N})3e52vHXx?5KHszc!UzDjt z0JR;5EckZ`_&C^C)7N}LnG{IiJQAgW=Mw8Io8%k>sE;M`e&(+7x?(GZI~{9*i&mOy zne6&H%G4@%MBbi#WE%t2t;aou5vATTP{Fcs?;@h)BDqR#+-pQ1j8JrbOgf=kaGe-dMHA)jcks;FOLzE(uNY zTYnbQg(Bo30*w;LbgS$i$sZzIw`Yo1S^a{y~gw?9^`m_-fjX{5VV zXT)~CMR^J^Ca4PeQ9PiWS*mCH^+4qaix2Ev%=8P_Ep=-1ntoQ}xv_t!b5>dIY^ixssE?p|zzptM}3KDe+ z2AMWN`~wJrOhh%&-?A`&d6&N3>hhLD=n{5PD%rc7a%f}wbku^j_=O71)J&2Ticr1( z_g?Yx4DavZksj~B2km$Q7tD!OghdN7=gPss1eLg0al6x?fE8h_T*dDTk>wk>FXjmz z+eYRI`D0PK1|0}HbOefhE*d;mUFal>@@Fo{I1H$kU%%}9SQNmtJI6Mc3V*4Nt3O!P zS@DN!n2sIXg2lt4EX<@!o>`~8Su@N|mek+V@>aZ?iu-JvWniHA!WU>8yD=QBq|e-r z^iD&;NQO^2AMI_~rlxHfqBDB4q6^=Ngl@|s0XHm6=7=6R<|G(exdWe5|Gis7TM0{4 z&s*&+h6Wp_Y3ySNc+&|DX_t$jgjtoB@BrR9Ut#JZ@ zwGDV58Kz#YF=U_=(kn0A!h(jgp>Rsm6-jLqHZ51A`D;}5MKYT%N6)CC(E%#E`y$`l zn&=D_tK6r!(;F?XG^NtTpba1A{T#2qrKe@-RH|?jO zlsL~4(;Fsf)Qcu8m})c6@7q8cOmj>S=-;VRiOJ|O&9y@Rn{1zO*HlBH?_Yx4+ZsnE z0tr-6UHen90cx*`%XlvB$&rtpfN-*;7kwYXN@$)OGZn3~t573-4yK2`vM;mz{KcRdK z#_M+evR>B3wJG!FNW~OmctK~Z{wK*}`_}Vel`A!7ZRrM#s5xD^hRZVpk_Bj6AYmL2 zJ8^^Ulz)7kfaU4Wz-eAD>LNmD&9*}7t_H4rdBit$F-%#jWiVO&<^sGe{P~@ZA9~yy zB{nK-KDuY$Q&2xN@^t&lsC1QC(%27+^Z(X^QE5RGu>pF%Ulb|DM$Tx5Ab)M!>A+lc z6M|4q-II2}e!(H3XcRhJx+NJ)*Ck@!<}Ew8=E+^Q?Qkf)e==hXG_9eh07Nx^&S6Oz z?r+-@$9mc}?`24%f$ch@&3qE`hWuzWO2rkkbBWF*wPHJ_J<<4)kDR?G0~CE^hPD^w zrY9@8V>7q0v+0AYq}o#Ep6#%CWzohv=1`lE(f3?sE`TnOpim#ejw;xEiE zNnpQ95**s!CmF-nJJIn6KlXVI2v&577tTElC0?dN@TL6$TFQCO(kCZMXHkrte9REq zY}2XEqk&wA$pi# zyrpG3Ri+`e6yhmEzUABx-q*)L0!bYzHL?cNif1i4{LLq`F<)EGr(Vq^v5DoQrH6V!E!x!->Y+Lew?Cxi^(omnKrxk21`^=x^5-T{1y+*a5Q<|#SU#D zJ5Va?$(kIyxvqR0aQjS6w%f{dXc9yYkGwQ4nu0U7lfsA&dvahQ*O$KnkFnZ`U1LURLr2*8#QC zNvhEmyb(ksIMI!Czt^<(@rZ8l1+K$>yA~)tcLYh>GR06h4)A0m%jo82qPt03>ql@L zH~2PcLL6UGkM4c?$~BU+sg4>See!y$VsO_!rYvfu$iwZ#5#FaPNayaEb?$^Q)-`6A zCCOe{vu+1Ty@Gr5MhCVG@(1P@&6%Sp1)nYLs>H7vu=HLfLf{M`hy*jAn0q18k{0x= z^0laY${2^6h#W@N=A_l#gxr!+#c zzMM}f==vrk;5XHXY!-g?5P8ik6r5>)`N*L#V?u z<=fxBf?Pi(QFAdI`gp8^w)W_H$&{Mxu2&0Vkx+i_7k=tLojj$C}^2I)p`{sJOJp_S178V?tYY?~Y@9 zvN)if88*xq4YBPB`Gb)N_7W%JM4Hx$qiHBmLkD!$*q7K@Vxl**HE^$Z#$oS zza#WT4nt5c*72rSQ%!Z(8_+hV{NCvM%3hB@h*h$W|00BFGOL&v37vr==hpf{K}H;! z-GH`rB~5{{^f${al-JgIm5U{@`YMIg`E0BEOKrt6B_??2V@@i5NqSzp^<^=hbfW-#ZupxW=CM*US6N)F3!eB zxiBVRz{b6=z=2E_BD*oNbl2oM)>1P5UfHtS*U~Xr3?tm^hARSxZqT4lQtccwRK|s| zROlHij<-FV`Wv9c*=!x0Ttn&OI6WcEP5CaSZ;GS0)ADg4Gqc107fkF{fTWm z6WeKHH@4Z>Y}{~S+cp~8wrwE$z0aokED$>Z8z!^-P%sWm(Of!`oa(C?QY ze$U$Ox=TzWTZH~HW874X{khvH(Hmm&F;9Y00r%V_JSHDa*|CA>w8MB280BV}v8m%-v?_b}fXIe_YX&A@YyS=bR z*_2G0N1QdB$91}R`P@?c{ezfr9&^zJ(>^2RqND?kMR2vWc}ffGNb<<}p9tu895wR0 z#(4eTMh!gsZ2qA8+{PKEENr4+Li)TkzwL?4?j0OS2cSmlRDb9nUm+zVnW@zgc{NZg z_En)#`n|JYtu1U#v#s%l7z_vddrfAXP>EM_>FdFd;gnqiQmwtvU4B#Vz#>kqa(|WF zwVgoqL0LU{0d|drb61jgh!r7&{I$1IvG?6$^BAI)iDJu-rQUzJV&nO%sNAs-uQ#d{ zphTScm6>~nGLf$}iYn7XvB%HkGTXcu8SLH{@-ULo8SyTK%KmXwSuX-=!4#W9EF<39 z9`nKoM8? ztHHoEeC`8`I8d=|btyx#Bk37>7O1Lh2rN4Q!a939f#Z7hU&Y_mi82;J3jTES(VJ!R zG=z*Ognjc-OqO<%0}GEMA`hf{2shxPmkQ3mCVNWu^hqu z3Htz>jc;mxPx?{sSdbPBl}m8D50fgwXZgb#YHtwse7hX=> z@MqcH3p)}N_4b3wH2olt+gxeW-G7M(F!mr$f&SkI>`3cACFBNP_SLRVEl@Um39Re> zmsa$9CHybk24C_&9){J+;`$(Po*T+*=W4$Bx~MD#9x9l*n?Z0D&4Hli$fnqK2BH2M zjI-d-x%u7kTCL;eykh%A$^QvQZkJyms}f~N0o*iZ(f)jfDFC}iSV#RcLmw58xH|RN zE*9tt(Tti6tKI}*z92op+JV;s1&u2IpHLN=e;b{j!l4=s%Ss45<3QP*iYCVhX-B-< zGelGJJk#x^ruT(83(~%2pWHxRD;sH_Oy`d9J7H7)&Wk_`U!pMI8sYL%A^sZ9AvY-g zy3!L>oocNjWqVW>F{XP1Z#vVavpRh|8eRU!bu7jVi#4T}1XZn<_<|?$k!8CBEC{C^ zZir-&Ep|!M-mDn&M;6|f3@J(y9%l!^WM3RoF0FZ&zGa*oc;=_ zwF=Lq$^JL|&qKA1gg@Iw79X0rfZ1Z{Lp7z=+|18XaPaJ)DqeY#*=u}d>#T-jFGrF* zbnAZuh=FAKLX~qXaGA#QMJe#L8gT9lGsm*4e+fnu{|{Dl3!!Z9Z!!AuU>|^=NjInC zAzZur;gBD!vR5vDAfMd9YVXUKb=;6MM9@DAD$qj(&xUntys!BWPTj0^>x@pUO&<|x zY%@uZj^_fA@>6P0W?+8iWdG9swo%+)_-$≈WlmfMrOc0?u;O0*BneeJ3Ll?OUI~ zr(Sz;I%Rs>pT31CezmVoy@(mhHI_|Da{bC2$C%&(JRBL8P&dO<*#6-CG+MJou|InC7) zdk?hpCkol1i`-=Yi@<}$rfJxBK#K~{{WH5(_vXkUq3m)LQJs#n4ZfRI&#og zubw5Wc)(E6A5@tey!i2t-Prx^gd2(3^}3`hHW6}<3!yVeBt_fB=A1BY;D)AI7=1ea zl#Qt2IXHRSkA77bPEGO^h(U!qc_G ze_X5yu3_W}Lc2_r|JpZZ@1IrY$X=j&uRYkNf{AGA&$3p^g_a41B<6#uJCLO3G*E@d6)>SO90aP@7gm*S%lV zp1GzuXlUl5+MR0PYgZC}<}32OyIzGa&#%Gf5`w+qr_01aSwY9h^8bZtsg%+g0wuts z@%7J9DL;9(j+EmT8zELqA^9F~yZJi%L3oXlrB>tQ<@tOnj%|dP8aujADb^c*L#O1#mmu>`k-BsJwBt#OXHdY+f{h3JdelFFmu ziJ|QfXyxpL8ME@f5=NC`IOWf8Ij&T?RP8E86l%IFSvFfk0poh3V>^|~-=;o!nxJUu9fJ_I#zU&0b&1i{ z|C=6OiWKslv&pH!(~_%Qx&Oo#?1gTRLuzSY|CL26C75FL-+{Kd8S{S(hv49)-I8C0 zOUr_BDXN{63jIW5(A`T&`6*&Q9N;PTZ8~({l@b4u?Q_uFjq`E4!V4s={xDPg;_^0M z!{47ZQG10fLdBxFzYFou5Q*8VHRl=jIe|sOt)&4|JPGi%yIi>RuSLhf9fWH_Z}BXR z1Dm>j6~wfzE$AmSyD-$^Jk}Pz=bQ*!z+0ZPWdpY3Q!v>B-uJ_yjnJacJ#%3Dpib4L z^3aPQfy@QX)+Gxf1b4Z28xLB=}2v-9=A&4E9c zdr#EI-x5}k%e~frwVnX(%^2F_U;X=2qtL5U9sAS;S~}4!$50bYa!s{$j%_$7<7&uP7`=6x}qzA9z((e`&9v@rX8ucx~C^9Dd;F z-40C9Fx0^&B+{TB3-mDMVePyCgEz&9aqyt}kD0>V8nWgo{<*1`z9YvTGe`$__;b}X z0{f{kLbr;hg2zpJ5IoCHztX$!qY+p{gq(n#R|SbjjKOcA**_(u(QPPJDP=F)UNxSl z+0gk0)A_V1Q{WrSmL+6jzk^_*JIN&k9{ju4Ze#LIOjjbchtG5BERPLvP!rV2ak=b1 z7c~>jvY+>JE&O35GY)1VPCMbmn_l~vH{_&}l6&VId+d^lGmYtu_^V&do%zar!&YRm@366y8vR~}l=bO-trV|41>d>?1eiF%0WaIM9qp_b=NV%6H0iSFPyS0Xl?K?;6@5+FmoWFuB2XLB{gqXursBW1a=f=9H@>KThYr>yU#pen9}R_Nspc%i_)L{G~c= z=-LH*#lM_Fy~yZ>&o8T_eef(EtCzR@fsoP$$ z799TP;iWK1Xot$=A&^0gguhR!2Lzf5(CJphcWlhF!ROpAhhh3xzW2xb+LqMK(d}1l zoT?{nUbF7rJ~0Y48*Z^OweHqn1Q>8z!L^y5IsSe9Nb7AgCD1Rve!XZQ&w zG07Nmd#Rn)InrhDD|iS{dY;eC3TP?UweCf%oy#d5NgLv=gdz}PD*<( z!$dg36)s<4{4XFyw%;?gw+F$P`voJHgw>}kE6IvWdMVe3PN3*P6!InGzC8bDX{ES# z&dRigHdry#h-+@1E7|@(S{ydA&=&yQmV2fYB%>#_Y z*N~rt=?fIOj?5vH-kbzZEL*9nwMprKW$?7=p~E6xEs*6n9$}xxMAyzLvF}3Or61Oz zKD?ct5_N`)LiuA*+H}!V``=A66R4sp;T=l(smK<+!?oyoE25Ny0t%V|(d+#zRJeHI z#Z-(~Y6KTz|rO725MeHTHa)>(j^f1W(V`-x6x2-czW z`{?fhxAv!Bpxuz+y>Ni{+G_l2i=;6eFyKiI_KQCMx9Wr`l&?n@_>eA#=l&{tO{JK( zQ?R62tC`K>&hL+J!w2_|!D;+_0f;+1CSV}Rw-zB1bIK^6*FNNI6F|4OP?uUiIJoj>|%6FgML6tnWe6XRKd^i-%3U^yZ)+t zzT5M;-cW&SG-}4!s%Lb*AtHH%e}uje2pKBl-$qSwJL+MQe8y*Hp`Crrb*vaq zLdBqvVN9AP+y){O{e)G1^gBTg3L@MHO{*@H@vYMkEEE#ySwcGhSk2K0kiQG(`Kgo~e6X;->R_EAe_5xi~I%2({EshPQZ? zqg7q`KJJ-`Ew_@pgjdxw%^FDuBc1*xZ?CL?02Fh|@+t)ioO8`(jju_#kJ1ili>vt?0_iJ^r z%^tatpq!4GeQ6KkmjxQj zE4raQm~>p!E6_%w{+P1OcKi&l=U9I#3>E;`{h^g2j?mW_mNaowhoR)%=^Kad=CD$# zG(K&9C4$BI-kZ4=;gVe(7=R-acOKH;rshN^yFj*kb~~X~ZNSoj6}D4va!Z>(Ri{>8 zf>ama0j0T!TDzl_tv%@Hb7ex5`}5D0fsWr&`#9!El`q8kvv`gch z@**}%vfAu8S$~N@IQN~wOJqER20dIwSV@xlbL}JUI5??+VKXF8JxkqS-iN(Dt~wF3 zG8xQr`rvdZzjC>j$TZzmal4#%+U&1u=pbS8h{~%zO6ikagfsC#Y!2k0MoLUv0RpH~ zX!&A#g8o*;vvMNCrCdU?%Q!cwK z0Q`+%I|G&?JMA)kX3LH|v=5++iT9Iz&Pq}V!=|ThP0b@JgU*ZC0S;-46c&HyP?11n zLfTsxuD0jQ-dz+^t=r0jP(hOq(?T)(-XIKEkja?UFWS+PR3e0|lVA5`@Vv*34z-QH#Gazf^boxl{8joqc z{GizVhX!8v!rDLq;D#;RP2`?{pKq+a)ycu8vbnC!z@+2|h{xom0cml5i;c4ZNDVjO z)dwFH>$ysXWX&30`LR!*(6J1RQ3_^ibv-NMe&3%SCB{sALK(28Xks~MU`_-8%^xga zdi|%Y4_>=3rUsV=qLn9c3r8UIalfYEF!77d*UI_v1q}t#_cLwtx&-%LHYuY5-t%fDx?qD?7bH6G{|Ju`14u9)Mh)TG;unYaO7jG}jD zg*MI3uYwzE=PdUFJbHP9pUfe*C5mSCd8f8iIL1QrK}l`BjpgzIpX|vF*$l0JpHr5! zYGB-*yb{XjLJU)8FE+bJ z4OsQK0T8I-@Fs@_ri0apX8S6#8&HZSIgb;m9^bSCO=Dg}*(+}^^wt;H`v=%7^9BKC z>?#Vv64qH-RbX6oC`2gz+%1iq%;H}X=-WH#5K+cH(uR0tCFGuQ8rXMx1idS3X#7~_ zaJT;U(?yHg*c|Z;s4V^>VyJ5mdR>{lN5f~9fw7&aP|m<~ecbQxz{W9AJT>}$egpig z20h^2ZP@T%IsV>%A=Q?TM?|Qnnc7i7H9orYtY?C8A1-Qh-W!keb>|m!)@((0JzCUAPol+TjgTnFjP2ad}eQ&oW7BU02JYKQ@_T-mjzvL-4c&E zurS$Nj94mrRJZectBpAy_DNRC#A$^G*WILBGog(}fl|>MFh!Rb@Ii+xc|5BeC}861 zr-r*dtMThIraiWdBz1MZ%-pOr-w zUcyonBX=ix&jq@1b=jRh1$LI6dX#93n98T$rY zn+B2K%3|MB;n;h@j3Vs@9m4dPfDowuosz*%CoHXy+cZ+OqEJ&))^9^*FA+6S_gE@4 zKV%rR`S;4Uo_EjIMe^gD!%H36smQI&axVMR5P$>c- zi->R!3rX{$OZvr|4nS)41jC$_qxhgZ?jyu}ZMdu@mcQ6|WP!^*OBmJtSkrvvUcCLK zksjL(9+5%L9DL}S3TxTW^HT{S%H(E@-SQeVXzVV3xyR;pYIG)X`LO#YXY}j|)3%B0 ztDCIxP`B!ExTfDXH%AR`v^s}hq!}~Sl0>|G^s17Aa=-D-^L=iEZN=B3b1{}Wx;EhK zzFhftNAhr~feG*Z1$vf1KF!Qc(%7v846H_7(0i)QCQSdHeuU4-s?z&II#{+wwqW z1n}Z8Jx!Ux-Jd}ZD`+gC-}R#Zd~`RGY%8h=Li7Ye02S55nC}>#UwtD3c??*3DR>~8;3E{X{ix|eyha_Cro1e+}ee}Buo>UcGg>iafihPP_p(fN=J*~^qr!WhF^9)&28v!$g8D0w zrSQ|Np9})`D9p-Si$vDZe||@oI?m9Wb0jJl+ET+>AQ8W3K=@Y$jEt!O7AR5`8&=Ed zT#Wq9TC^ts*x=P4=~l7Xc_puR1okF*d4$lY9O$ zTfqOhve&v6E{jjJ9zWiUAcz#5zd^8#^#=z7`BE_PyJrq*8(C}HJH3_}uywxQ5UFppubx($B)cBxtI zHOhVKnvzcs!NB#lvNw|=L%I)U`oH0qKXVn^J({e0zu;; zJ%kgvdk(N!k>3IDh z!7u4@lSmhhzAyueVn+igOi3D6Cl_qb4d#Yc)RELv^1ekOy=y`panF|mp0($!gs}@4 z#TT6!pGc6nPr6~kRY^<2CyYRI z+*QRs*1nF4n0uQ7d?ziu4d?^>i|KHzu^Li8GgM`>1@LyaKRkmqJ1#fXH?3Kceu54) zHz{oUQ3s(^eR1hEoBkK__Lpp*B^?S{CNrp}LWoi!roYC*vv!WGD!QmU@`)toRCje# zP{x6%89=4MA5>&2?g8Z(5Ta_5bJ|xLIngqKJ^ze_h7;1pOJzgAGT%1wnxMpnrOPb=+*@Up+9!by$*f3^FFqYZxl3E94#F=88_5RP^RDs?XiF!}%B z)n|L8R&QskKy~sCO0T}{S?(>b*D7c0Ge{*&l0!U}rqNC%KK=b1xV#y7n2(xVtm_KC z&&)eBpW!%e0ioWg-}+A}6Sprjm$0nsn9&!^;nEi}2}hUdXTVaYcyGdTrhsxRR2xP7 ztv49j8O(mLphmwB({5r?q%WU}S~_AQK4M@-SN1P+fX(Jbno~JE8}~_`JPL$=7Od3j zp-UC~Y(U|skH^=M=P1O|uG}-mC~=Y4Kt0~zzIU`e@~kV!*say<%oFZRpFB!s`Cluo>q#z0p$wlIEc7Vhjz_A3KzeI`9<{o19jn-V`YS-%1!HDsn!K*G~~; z^ebo-e(3wiIfVwCSniO!%^b_ac8%X|e`O09*w++WJBpCtjNDgxTJ(@kJ5MC3$%4S=BFJ- zXf60o6`0A>VDv0!+0y)A%UTir3HZs`FgB7w<1kNcFQeNPqmJ<(v$P1MraE^t4;eon zjCi0Mg|$T5lB`aEMnxaAmRsR~Ua(=E?608B;(jmqeOS3j7Wj+T-d+KLQ+&1yP-G;4 zcFT_;7BUv~2SsAg_7hUCmPd1BK+aXcErLk#V!XO>-ZPG2ax6U*QhH(EA3S>RKZ*bn z9lDf_ZPRg}t4-57y&5tIW-XfJb`^kU;@YI|L_SyYZ-M^AXt)7T!}e#Tti>pUkoBu`D0PYAN%9)oj!nd%s*y8$tAkV! zK;r!(he%Imy|fb~LsUfBY~7Y;(x7Tv;ThD~m|dv)h@|IDix?`lq66P0vl81l<1CND z%eyjU+C4>T#MXswJe>8OIG7UYJk-xz`jZE{l6{;_uW9#!tRhN}wAq<~SiTKA(|taP zf$XCNOKa$!Vj!jPp4I!kudIW)G8lmne}TX+ zomdul???Q$lX9g$%>j!c#BS%>$4DBw#U9a4)A(LYH0X78uYbGD>!lt#>L{sPjX_OV ze#`@p%r~erKw~}*yFBLoWzYd=&xFepR8+J^H{sNarKP^~+!qOBo*L2AbBqe1z(wHnk@dJXy+~sv=`)wDMXI(hs9bN95L~M2GTh~ zlOxok$}QnUQy##REsdVyaPR_{uGxs6;j4rXcfGcT`w8xLYg(ICWXSVb54>SXdPD|YPD%ge>*#`gGRa=R2ZnGKlb}{Gb z?>1)N%SQE~){Z&+&HTc?*3GxlHo%VwG%T$ziqw%-^L=QO=L+cgEDW#mW1S4|%0l6Fg03b9bEEw5HI%R@sk&HAO9C3qATq)c*)I}$E8 z1XU4Tv<5pPH1s&@f5{zgtRb3%1sxF3x-rL4VHs#rxX}OkX{;{#vsNKvh_>t3Q(9%R z2beV>P;wEvmaU1ziwe(x`fLA)B%Ae7#VHU@AVOsjkV-F8w1xz8g5(L}vXu99Zq8nL zqunLx$%Dm}6hUVcd*mGBTlM*L6B>lZm^_-mS@f&azn=am2P2qFV?^Cg@fRZE-1>5q zSt86Z>23_81^fOr8tF!(A`C@9b$;`ylkwke8LK(ZcbG9Qa-)u&&p~U_2&iKP@BXng zwzrf6EM71BGV>%s3{f&^l;k3?xDHU^f*U6(NvP^C`xcRyNVO6%1dseCTq+Q+>Deu? z5qIfq#UaP1vh)4=5PxKfOT9?x%$S6T=^?l#9i|!2w&4(AGqiIIID5dVdwT7+{ zA&6+lg7SCECM|#3Ii=$5m-5J(Zl#wMMWsf)|I+xM z#NT49=g;Yi5_Qyxc9d*hzeN+cC7&O(dinz3IbHyr_V5(z72(2dIY(Yc$Cfa5wj@hw5dZ&R(yN8|yD7(~NdN<8a2s;*+ zel&CcIH3hgCbtq58`xy1ekAcWk%(Ovl}F{DQlF8WsZAaZwiN_m*t#>9QH2>lhd;xG z%c$o=nuxk-L(cQj3Ux@oGFKfE5p(A+^JQG2Iyp1!UhogfPWnq?ONphM;Sq#`s^-l4 zM_99@*c^%Nr2CSoMCP2Bz8KoT)~%TaH3UFR8kbU0kfK9Eo+f^aJ}x4qw;2X+7fYoE zr}>$>PU-+74E?O5;z)2Uw2w$M%IifJQg@jWmm zNGTQG5{UnO?b--djRSI?xT+$meN?m2?jAhDxgeP_TGIj#{`%!5@a~7Iq#w zUNZ|Ql1Lw!fdeFpo|a@>|1*){??UY(LdW77X=0CBh5=OZ^y4DQT|({Tz#bBYlYur{ z|GiRsU&k_CV{l1M;`78uuyn_({|Z@ypiway?fFHj^Gc2ES8mZXb`3!di6~6OZb|); zhLxK;LW_o^m7MmPMiNeuzQlLQbGbDfrRm2;jOfbEK#AbjVNx(NUU^2fGB5<-S9*aT zz77Y4(DbkS_Q%_}L_^~($86VH^RO;H?_8L6M;*K}#|-ie{U^bAm>c5c**|vL2+ge#QuR;tNOzwWTV2OaYZoSCWJZIgLl#TXC}`rgBkjFkj`#47 z@C8zyGUZ~U@BmgS@oq)V77N**huFjzzXMv)%{EiX#R`u*VjNr_Tr7P1AKaRR%Zo-#IV0%X|5d?06zjbhF4NxvQr`Nxy?zN<`T7 zC{$#~*k^c3#q=ACQi+S@Ad|?KX#^OWmeuvQ-%PFq3;D-t%8k21oG1X1?5CgN@P?GW zvv;ueb8~y^j*sCfhc~5>AQa5){s2I12kLfjC6qhW@c?!ozR3nlMo@v79T2^ihDa=8 zt8|B$yo1-(E%|1x5gJ>ac2Q~@bGeOunOSppV12)Va6286A)zKA4SE^0z&V7YMghY*we#? z-!8jWj9i4)gv+F`B4|R|Gx1H1ba&X{>2|`YuS)ri4M)$v`1kb=vWhge8muf z&+p!cAaD8Mcjb`F-d+_hZKscyF3(p%M?&l zh0lwCC>H5tho- zjK>~@fx$&7A4|(a93%?@8#gfNy^p0OlD5PP$U!hRq*iLPLR`BQ(abU6StT}Eebj|; zY3NOb8;q-5ctuROsbGybx4)p&YVWCgsb4*_c0nQbyd^>~<_i)_J4t-R{+jd%nhSur5*S)D|S8?s+25Wn&7xNZ+-%M)P9Q+YC& zq$KUq(CWm;6$qeTp}81|d@=q8_%j>dz`hF*=aXc4q=)s&ta^4)Os@#Tl`kg6=#XER zAtwlgJ4Jr}StkIPUr%sQgR3A{vPj7=;h`j`v`vj6AA}$Z)j7uK6|D1pL43hL z@^_>-IBaCdKiG&E8W8kCc-hG^C`kwm)K0_0@x6>1HTq(1Uiokx$SeXPQ~}Tm_Wd&A zKQAY>Ju2|$);SVHEJVLN`EHgmF`)BES)khR#3SE2x>MTNlqi^fV`h>DCpExwpeKk# zrE-}hkDajA$$p{(^J+aSFeJ==g?E}K6G1L<`|zJ(op>HpBNqnrPFlN>M<@ow0#UNF zWD9>2;yEV6Z7@-hm@_z!5oZC=PC+>3K$ijYS6I3u7*}5n{gdPZJ|I@Gc61;J;PWNvgQg? z^!>n>vq8LI9C30sHObW!%0LS$zHCpJzN<1%3$6Z2d5Yw3W<5XFqveoSgP0re%mzEO zq#;XUWA2#dz6^0vYD_`Z^kDkvWvk1N+zTz7dlPXrGTi_M;17f}3($pls(Z)CT74m> zT4_g+b`4ET>EmhqSRsV@L*@M%;{i}>DZ!JCN-!XRm6LD<2k^lM_mNv_0^S<|;Z(x3 zy12y?7h=p@6?Z5We+GgL{00cTXsA00MmAPM5tv8Pc--G~5hbeXKsB;a^bkZoK4UYq z8dLnagbmvRFVIirZYIik_u~TVKqYlCmWDu@$9&(Z=neWSqkhYQ&R;bsBx}-*(gRpE zj=+oZuLlOjVWSm(d0kRW3Py)zE~{IU$5#v{kszBS-QmNIGvULO?ne`dxoE-#C93YAtP{)>|^IzWT) z+5M=BN%dzVzA^9CoGpa~o zf#4vth2H_t!Dp26hooVu5+h2N5GszCWx$FyB2l&Q!40iPQLLUn7^}v)2p}FYYYXI9 zX3eqCS+84pvf5+$GJuUpiK zmN4{4_gGpr8IvcIF)jQZbq{`ssFPCwcuc9`28cd-(J_Aj0w|a=<58@xHU@fx zKJXW#Spd|L>BiMr-~JD8{}!b-xl*?K9Gmnpa?nB_Au)*{WxfEjEQN^ph|GMj6Pl}c z@QM^&LpZvs4PwWjdXOFnT|)GYC|+|z+!nQ5(P15SEgF9S^?Qc$hE={NdPc!NgKROA znTy;%A)K2c!}^_Q!}>f}aL4$h9iIdpURtsPOUlldCX%>mlzr{<@*at!;rDebp>j;D zC^|Q(Nk|2HQaF#NP1me~`A$j6SA;_JN^_RRNrF1mnGmSEM)7%l(W`CgoXA96<49zT zNGaVsT8#61F!9Ai#RI@C3M!B{Hr<3+=9(TQE2mFgWLFuoyWSBhrVYkC7PW<=m)m63a*Y9B*t_;DTS)_WYdcoQfj#jcIbmX&2YgcBIMBzaNKz;7;6)1-> z{#$lyHTGYSQw{I?4@8HTbfNh6wdfpJtZH5t2)CDYvwK{lX!?nR5N-6QVsJitVM;LK zdcM1TPjt|`1$_WMW)6XPY+N`dj(sMpE=a<21zxpcPUtSgO@pr}#>1T#ag2%e!7;7` zFv=HAx5Sy3(Bfm?f`g^v@Hw`o2#2AXdzU}NR zR%|BC8vmVmRsN`f>N5>+2Z;bk-rq`vzumzr4+6Z`FbYK*G#b8d7lsbyxCNx^BYU31 zE#5Pr$VjiqbXOV98;!|->$ZBF>}NwL*y^tjGsnH0AC9M>HSiGa!=mpF^}0bw>rCwy z5|j^t#OkFQKQq##jI`%Kz)|Eh1@(rLJz0R8Ra|Kc7Ni z&vR}&s9xU}5a*14e=nfrI56Ois=Ij_sa&iCSsh_dA8wlAiUzS1TF4pv1E%B;j>gHu zy`1_x4Td`6bo4~sgq#FxAI7cGxHOkVi(nc_WlDj_i`$ELKkn^2;&qQ4)m9&w(9Ofy zCQBp)q0v6hm{h-;>oe%Diusp=FXFY#c4|p*sNWG%Qm})JLE+4qJU@fFc<*z;ojto%@tgy$4~|90;nvDz9`fp~h9@r=L_u;YUrMaq))n&CX67qR2P#D$D{3+!fwCrZx1P8n-(ZdML2!%R+H*PbRhe(c?A_P8`*{E>(y&oH z3^Ll|32gMx{V?0^fswySO&M(Udb#Y3h(Y*|@zwNiNJZksGV`GsaP}SPfZqh5l2l_` zD%RQ4aIxjC;r=MxjX^eKyffq*#-FB_>c+%FvM6D!o=B{&IBfO1l|`uryK@=4=tA-H zZCDbSzLYs2aU>KHsz7lu%&&-$M{7d^HccIlWdZj{M{;ncK zvk`%Sp8Idti+Ak5;gDs!koW@3cIl;)u})TuLitevXWV8$g#f0b?7hGm9H9YNScaBu z;&1j?e=s6oxpog=9DX?*kHb7|dW!reMW#Z|=lWZ2IB-ouB`#BmZq7r!iM0ir?*V|Gv(8Yk_ zo0Y4m_(Z<)}fwKUz*HyDzR&*3GsKMi%yKitEwH*&x{A8vgN`B`iddiB;TZ0`d9-> z5@7yZAP0TcvyI|9LQRPhIuu7Dbjgc>=?m&HG}?XjM}nfE7b3{&Gv*;S01h=cA#6B6 z5geL!?UL}sc}(DX<fB);vhjX0|nPieol1XMJw|jGu$J$d9 z67?@S)%-)4H=QF8l(i;2ctvjvVxlFthhXDRD*t+g%EDK`xdf+8-rYC3^>GJw{#JbS zV5(36>BBlj321sC&kv_*c)?Co*Rp-)MD#Vnq&Mj; zbJz?mfWPLruNyesJ?>Yhz^gDfF+wrbvpo#wKp^U4Rmg_kC!_&dPLRXPyuFB*3 zU~FEDjqS^y33mGK_pPrcrnXmxg#{>OL8lS;r^F$rLyltZ{7kL?pIBrqaA|-OO)z#1VRieMdm#kYYLPVp0lKsCkB@Q@%xnku4>)X zv}2R#Pu6IhIEqQpK?_eb8eaEasy|atMM0U5vo~l$jyM0pdt=A%lR`10IBUlN42>1b z_yd@$oJb*pe3c2TkmFem2uA7V7;M@}a4<-M=D08t2*gT@AN>tZzz!Uh%}ez@ZC+7* zF;sYlvUk<)#|4TwFXci&yn!qax~=(5^_~K`0^wCtxY`B8Xw2g^Z8YzT?2P(t$mr4f zB-QZbI*%Q0omOHwAy6FGVL@GU`W!W5u9Gq|TL)Jh|8s0F0l^zltQ`)_Zpm8Rl zyp>%XUG7`c<|uk9pNQ@vD-`#aWem?SmnsI*2OqAR)kUtqNVYxCVkV{O2oV95U&`U} z1I{H~#J)-KAwwMI@rp^EH&3JTan;9}m>x6~!gv1j`sGhp`K2oAMRz;x;eFD74LPEl zqmD){>^yG$jE;eU|NBm>TFc_dfeCVF4-L5I-mstiO|fnqxW>uMUx?y)$4@U@o6K?; zN-8A{6MT6vv9@A39M%)=166(iU<$<&4y84k9JDJH3BDTbY%Kat^);ePEXTtcRcH%NaZi&6(c+4L=}SZbHus3TM$v{l;OwmW>G-60My@D;h-NkAVDZm z6yjJ8K`4Q9Es~vUmLJK-p}0MWCQ&#dNG7=C?OOi7d7+mw<2dtqE4oE+pnm;|byWTY zo-gKygXVAzF@TT>?dAU$rKTHL6wud&=A%+c%e3Q5VG=jR z{psqOo1X02-sI}*qUE!{?MYet%}24iB4l52GvnUtG{QUr#+=qr;+sRt;|%A|v(sbg zI;nZNyxZ3Z(eK6ItaU_ommBf6P+kpjLP>#O`mSevi5I^$Fg>B0tC^(P2HUlB@%kX%jMH%(RmtS6k`l=P*^B&&O1O(S@ht2 z%e)v&kD?4SmQ^s!YPm`+e|@h*V82HVm{YpGid+tnW@!Rd+D z@ZVjoc`y8AtKO`0GFvN#F$LM!j8c6_EZ&WGJ0EQ*mOs zE|15$y0G#6EFCSfewSwF8+1X1r=8`P!RRx&!!5lm6`a+G+8Gj&5?@nmP-L5sl<~L>WfXs%dbwI!H z4W$7W#J@6~FwO1dWQ_imsLG}c@CWUxZW~0{6hmIDC9UL4AZ_7%Ay@Cx0?AGMcrsw0 zTAv-+%wd>3+#c1)(ew{W@D-^hZ3sl3d*s&yHyj4g;pML3BLBME|Q*S=O<~4UXvXmh~L|3z?U=fej4vAD?`;J;f zI>@uaTmZ&$MmT^;Mp1eO-UCjk!DtA!4ZYRqB7XX(a>x5&GNf?*C~>xlR3L-~qG+Q@ z07t(GMmzPphI-F+sph?){}=*J%;C6ehy~U5%Xt{eG(1Tf!b_I# zIWyXHHZ}rtiw!}P*FQ|L7ZbW5{4x`q?`zMA6t}Xl!||TpY~(B(6aGDd__XK-VKChi z_$J;i&{E}V0vQ1t;D=Q7YE3#=J9$L7jJE2nOlW956g(yHw|!i#rm$xGV`Q)fBm;(4 z&#$j8)t&6Wyg$t}r(ymph9dn`E-Yi^HA83-TyWeuGcY-SsHmd8$%{n;cBkjH$O6=H zE9fe4hhXe6^>bMpOiMgJI76|-rvS5dwdN*>aZ6!-3gW^dn{$(Vr|&dQhZ;QK_$!^DGuYpoLDVciqO;;7=fX z|BD2Z*wMuWW12-l+Ocv`QJ*4WcXiP}serLh6&?hGFTa&kcSSoK(oiA3krXNqfuiuO zXZs{j?VTJVJQxpf`v+8na-N79VNB4s|#K|RVji`qSxbW_&++|Oa-&0QZ-Qx z+nGYxB9tB7Isc{A3Pl96$19(}OV3WpdYMEHQ;zd-9UFqm6wTgv11-S3f)d- zJR~I(J%+qUz3&Nxjkv`qroCV8ogDCHxDJ*PC1%7gq+AGLdvyIR?B2cRz^jsA2=h4m zP}-_-dBOhV1ec*+~@7H`0v2f%;QQpbp5IfBqw6Z8$^0iqFD;-RZR^ ztbM*mzKA4UovDgyMONc>9M@-IzrC0ro|gs1rE>gzSBwEc-JwLG{$=<4U1@&-B~FeQ zu}a4QGn)$6(^uER$;YX*V#AcqGu5SB97B*1n4r=?os-*vhsS381t!bR}k3*_m6~rd;>%up*efH>8Y-LGKZdqjs?~x#^(Q0;2RLTOq$(5^$ z4r!X{*Jx}%#;L_1N>22lp@Rs|RYmQTLQULD>OhJb(4H3h0l_VyF}I7OTYvS4Mh!@C z1YAYzabAs}&RXw$Xo^%msVWlIj}x7wIxI^c(K(#&Nndxg|Q4=ftFn z!$o#S3HtLX<7ftPV9^DVfP{l*vM1M4v>K|`ghVh48Z1!MC|}yG+f`wYQi%MlzY*$X z>F03@hiIlogF|Xj&aj$w50O1`h${)1ivv6J8xvnngWXNfPFo1$!Fv^QtS`nVV5>w6 zN$_x5zI`Y3J^OOQ4?eeoCsf~WxGU)VeTF#yPLN|EeOY!U2W<^u$r?m?VVbiP6S>;! z6TkKTpofx~4I5uy+0s+3V1H@NpQ9WZzow758Zq|yw^1o5IS@su>P@9tRH1$Fb&S;? zN5c4i++`F4`GbrN`L$>F*r`BwpM?%)+cR)cvN)%}yUJ^34VtP04CEqX+(f(&mw?ji zL#C+$b&ODHYfC!zx@hIH?isQqS0 zQ+dq@T4|IJ$n@Se(fzdox)xjE?q8Nxm%3Otl|}L?S!{8+jV;Q9d)mp}m>>)%{1!h` zJH@RWYvy-dnnk6e@2{ZY#*YqM+$1ifs0}=EL6t2V9f^lNq4q8vqug2Ev7q|_BC}_W z(Pw@0iL1UI@)R}3igq*PXtq3(f6lSHEH8do7UfUfME|teOHnS;N6FeDBa0vj1{S+_ zI-C0rHgg*q)9+xxc+E3hV@W>o4h2~ZNKK7`qrbKH^7ZF(iw`H)vZ(rjsDZ&gkGn?8 zE7QNq;mR~L4(US87eU8T%R4hc@c!fkjjEaWD0hr7Oy$x?;$*^u5s8syN!qF7Piw#) zN;U;ij?}oHZkQmNNIknX3P?`5X@$D)G_iodAA1-*rAJga)|S21ZqryL=D{sF{1=|- zhl^`wMP6hV9NQv)9dDtjJIv$c7v-WQ>af&4duk~Mc8)JWjmSZ2=!#l9Dd7by*W#GC zA_N4lDwvlQ%<^Zfi#(-YZ3r$>cML2&=q&IxiPp0dIUr=kO4-HNn<5afVxHE;Ob8}Y z!#ICX=x$AHUB1aqtV%mH!G_zJu${qYnW0aVvfUG_!aN6O!X=3aJV38qK&58l?oN?B ze(65u2Z5DnK>ob^>5KINKS7>_4~twYy}C2GV%5XzM2(LjUqBSt#kIn*fzH%I+W+gm z;A?MVZtrH`s$~zueDxu6|GEqXBK#nT#)e+;yrU-@sRjm}tGbX~qUsm%=#3){MV&0E z!od9(&mCwj>LoZ>=Au1y#%98MGWM}BryD@+hocHrxN@A0nYGb$!3f?FX$*XaWvUqZ zPw)Z(h3mf_XgdxZ+uiQl9Q#o6bnnJ-;Mz&qv}rOsLSjF*KX0hdLmM({!PmDoyi)tv#v7HX1e$k(tihALWq$;&?9( zY(6NvR{YU8TDko0J3u2$@+X4HWxLlG{5zvM#Blvi{MGq6UU`26Hf7jo_<1sxX4l80_KEXOd1JUAJ9 zY=^la!JS)i-`q?X{bTaeMB09D-o#6m-fSp^*_ER+cmN0U7-)mXD09}RxetPs_m&+G zz+YT@3p*07?6Nr7h{T!iN3HLP@RPToT{NdOQ2>t%cQu3s*KwAblaj<(?%UoMvE&g) zT&{sMhNn6S{ls>5E32X>Wi~$I(xS9v*K|e0Wg%!NwLav>f_YmoH}f-bXPiN0_h;&F zESrpm^}C?bpcnmh)&AX?)=S@V%)*5Di@S70(m1WL(X$Mk&ov=7Ja`+MZOJeHuOADaa~o2h=E>N@pUsu?hs} zT%@LGXlkNTHz$Ac_iJZSQzI}A9z#Q?iSDFf;Z$YRF@&SdQcL~UA6zqjN>2m^vLft^ zJ;(W)IEXmTDu16@mf{tHYxSo3ld8KALVlQIJE#jx7#YQGPNsrx{$MXc= zqA)RCbP6sVRJ5b{Qj1!iVN`n3C_$`yU}-v2WxOT?R9!?vU$HTnjkF zt}))(r%gZ-X2~$BfE$U;nhHP?2Gj6-D`|48OIG@igvCGb6actLzLtWRVQNa|!dT;Y z`g6!uPVe}=?W+@b^+j8LuyODAWGHs2A|taT#QjGE00e%}#$-TpZhk$_?b$E5hIMbb zZ0jGRNk-LR4#Dv?nwfnsn6$pUO2It=Pym4V*$t@I0F=Ky3jko~0Eh<#t|{}}o@A2QhkjsNm=kJ%=pPc!AvDs;B2W%=Zk1z*v8?0gsTRmAlPVML;Ms={0ei4y%;N_6hpP8|Ke-+k&g7|C~{rL~+HXM%c2`P?~ zhw|Y8xd-rgzUL6L*rOb1^MIW;B>z5!I&2Q-HURSj0RPE81G_HN*jJ_A3W+t@f-n^n z*c$sFrk?WaO;9Mep;ItTY52tcas`QYkc9SAS>R_`fB~Q(z~carIl2S(FIc82jJq6B zP_w5(1mR~GKD4)}T-B2r+e+LN$JJY$*KqB5ggt~`l|rWn!Rz3Bhh<_il#=x`+}^A-ln}lQ{R7bLKp>HQ_G^S6 zZ+-xirw|cJwh6k$HccGOs5u?G7o~CN?4poo`=nBPE?7Wmd2$N{aCWdl>m~{XfZPjE zV*zn)G0#^B+5Nwb4)IEMPK5+z)uBUo)x5^POsdE(X4|!d^MWOeUnx!B8rHKaNCu0T zxA`dgz*|3=27Hllz7Tq^G#&KhKuk1PY8%|#&4>nXmXB{UIcAwvq7v3i;?pDu`_`VN zI>teljWhNDh?@TqekKTK#DayM*Qwjmbw`!(gE#AS*sGuPy;DWf&A)a++~YvM!0>(o z%<_H!9>IV4adOQHG$wF^S4<|VX)0ktw#WXF=oss^2feS$BQ<8TYsTpQ_{p;HcM(L1S8P?p zbQ$dj(J%un4uF)~noIm&m3(>kLB_MZBDI)})+M}`mw#EtIn`1etDIXOZ%vmskYi^R z>)y-?p96E{KI7I6mnxWvPaZZ;h^#{`FT{ z28Z~FC!6|2=DFHJt(&+<-0T7G^h2G7O(rj?3-SA}W_pP{v+S>03Z?lP>jW$1RhT{; z9iT}+$(S|N21SGj=E{M1l?XEq0Ki5CgU0FaDMXri5=Earhm3`I1aERuO?NJZWiFQG zNKN`yIq|DOT9kC!I5r0AF&XZ~v{5&v@qO5}?uS?p0O8h*#`Kr09(djcL&`AYrAH5KTarM&ZJoj9n!FQ(no7A{!~O4UL{?Xe_=qSy$7yZ%pD ziQ_hIElCN<4yEV=r`Qx2W`@)Lg^HW>&sgh4rO^{o704X8nq^_SxJXavOsre&T7v1U zu<9Vd0HhR+K<+lkqzAw)Fu|B z+1FA{8r}TftBb{gibD#W8V8eCaf3$!aE|QCIl2H{0Ix9Ee=7w5oJtLc8G4T0LwLk2 z=N?dP+y=plKU#2@WAZ+((Poz@^64?yMD`;pJplCV3|3(u1({bxeC`%Lgul( z3|F*Cyq35LzC?+7FjH9{-!n?#-qt!E86zItrB{)`eiF)hugz0$C{pH-;9p*xKkI8} z?HTh@4&-|r?YBijcj&2Z>2E=CNecRkt)`-R`e(p1$w19F(m`6zp*&Dj0t6@uTo|8A zUDRjOfIblBMRF;n8eFwrcO;+L)0~+oNR(j5@-KQc125w#_K?p?R2qW+~2RKnKzPTc^Ki>cCE6rKIog5f5IFwAVz|61qdm8mT=OP??oqRC$ zfJs8mZjuPYJ4BBl+TpGLsfEY%T4n-e1-Jnpel-$6p#1m2uiw%o zU(FP$ugGeUo=Vu5OhREhTN1^z@^)Hh#4OfVql~^cte1!3@x`_O#L0X2W2FKo31w2y%qbLvrD7aF0???;-9L*)p+0{g>pW&KFdR5*@H?gs{AT_s$7=k$ttwS zQ)`kPJuw%WQ{)MTqeH@@w0;?&hTb#)fIEE(F12v(r>L2R=a;Wb`>v5C&V?+`efnPZ zMA`y5xQT6hidRR!tnAm?u!Q*3s-O|Xm(U-R2%WPeYXlirI_@UBK~>={Y@B~YeRkx1 zvTYaQoA8$;F~kXEymEyD2p-0{k~s~lxLQ!T!8}gPK1po7t8dCQ6=E|%$mCCEX|%l^v$+O zP6S67Ka)Jj(~8vCXLOHz!Ml|TPzK$GxOi>Cr?5Th1a8)IkJTvk)#pY}Q`~y@ZIvhN z1#uBYBU$(0hrv+d+rJK!-PGlpo*q)GYC4qOG=fuN`qr5KZj;B{;{FXl34?4tSpv7z z0e~_;0QNH4Bd8x0x7l_>>B;_Qov}gu*w<*3T6~u3Wa`(PrZLw$da=rBY8`Hu4XExs z+p*8y= zR&E1T-W|yyAVbnY1fV*Ah)cpB0g$|`q!+-*hS^V>K)HeaYRYg~0^21uQPQOj1)Xuc z<9Ai3mqSs%r(~ZYr;~)|HBvpSvG=sDgGocdSl)`aZ$q0u!`BM6%qm*5*DYpQf!5c@ZY=9y6LidyB`=1>d22Vi|+f&5Mk20(i6ce1K`g1L~ISs;>nsSSEbr7?0I z2-&*_$?5J9usXVo`a81LGvax@GkQM>4EdAJ55(l(ZN`8@EvaK0Ol?wu?N!2LShQs| zQGl?UUgh!_R-k8^IxW*Dq@7k`-e)EW$a5WQ0G@mj8DU@_N+yyHfG0?F>o1~p?SeK; zXB(>XDjd{;fSR5cH}-JRjuV*L^1_9`ctHE2y2brE3RfXby^*dFy{XZxdt2Wr22Pzf zfbpjYkM|MF>IMn>Di2JYfM%74Ul&F;W~OGOcIap_uWzq_w}hn$7=h`{c5YA~1kws>NNUu<7M zr27mhT!tSJtDb&9-k+5$w9?8)ruT&=#O%PyQ_K*3U2ABMbiNpk1Rhxz0P9heFJRb( zAqLj}TH(Qds>%>^(KlA1ynFRVxXhz(eyl~21RlGG_8o)NBy;@+txUBI1ey<~cKMy8 z*1vA~G<%!82W&POb8svIubpvNem3u z2ZXqx-jvznTZ}F)D(BA16cDssu4AbDx} zfV?;)VJ-=j(KoCJB2RZ>S3iclS(g?$GMS*tnhf=a=^FV|hhVgKNrV9~;;jfQ*vF87 zy>2p_jTZ|YN>_bdnX@lRhFR+%TIBt|-MNT#Ni}A9$-1jn8#R_~g%r@}it0}$f6^5) zHl=~!Oxt3bJ8_dfavx@8x$@=UH|j7_L^Bbe$ZFlopfd;zemUpqx|@otl+wWj7#Vc) zd>9!aP~hh0p#mbjb?9@0BGPXP%v^`<8R9;29vchi6%(Zg3trelOTWmgDCpChh{1dg6Yt{U4>+wbbG0%zvcdnu4Vs$%#e zFSP{MYk$!)9QH!42Xoo9YO|kK3y?Fe@s08yQy%#IFeAZ4W!KR|9)HBG{ZwKBko7|o zCl8c%c;U{UG#JU(#mFDOg>QaUO37|ge3gYTDL(+M;D0l?ll;2#4)sk`biTyKb^X-a zS&$MjYfNW&;p|X9o19AaE#t0-C(13oQTM5cn5I2AQr$~npFStSpGM*S_ZrIIOr*+& zJfBf7;^!^eLKXc`^zF}80061E<>2_iOD;4OORF7SxLEvY&5rI_W0sm>6B;Y5BtmtM zyjF8=wx!>Np0DqP1%RG^4Ml7k`&AY#3?g@?({}NW5 z|5<_8>T^oH!|c z0^`V+akizw=ef*_OZAdR5TYvsMi(Y&4Y?05I5>zsnPT>GDsj_J^h@ROE&KqNVPq%B z2%YbHC7Zv~$PGNse2ve4cyVM#(SFqLAF8&k=;Ojeo&`f zND-`LC`TAoc~}tg5v4J^OzCvLPI{n1;`4)w))lUdFbc23n9pa|aBh`zt%}vc2~YL9V*hd=+Qf;a|viSVT?C6tbv@CAXp_ zG&nV*ar+3*5pp(Rj(9lF=7-UsI}<$hk;Jc_hq+^mW;f4uI_%23%DTUInl4v3JL!4B z>xVNZ9)DZW6zuNbe2i-wxKVmsp(&>NJ58A|O}Q$`YoLu)tOWj{TJ;qVTSaZd`kmtz zO0#Sb7}VV_toP$EAIA#G5KwjikaoyPoG2ITcd0>Tsk2uw*T%ZKkkUoo_u*pHo5M@b zEFVt)1mGZ$=68t;@=UV$A83?!G+N!H$7YZ5MzYqv>Q7@6rrf?}N8h;cjvL#6FV&*J zjPcU7#6PK+G8X=33{%~aJUd?;N0iR$KZ}xrgCHXnC*U&67}qdMK}=j{(FDJ#x>V4V$z>tp$lVmbeKpEauQNGWv|4w>q4?26$IuYM7lmW6y0XyS6L;O@=%kI@LZMRz&vVRm_ z5H!+-)*RnPaxc>K!H#5P_GH;7j>6GKcW)!hU zf4;N)SmP-2eO=}ILGT{?EdYD%TT|nWE(00t=l{WleA2ZbfOr|STkwSoX8cb6ikHp8 z%l@6yssCg^H#JJ3KE}riaH$Wq=Sl%!oynf5H9YQk9P35h9I-1510{ccq%rT`lSBsWKdC zIJKc!BSWl48o+G^ET3Ss$Z)Uj*dw89WAU{f{_{ZssSPf>?{lKn4e}<;Kh|)Sz&YVW zuhKz0ov6hN9QDzDO)fjzOl#Xl_G3ntAsy2i6Y(Cyp;eZqzB)fGs%S=+9n4HMnX?IC zOp1wH*5LFv9Y23~jcEyCups!lQs*F{T%jUK>ZHKy-(B-)d(O8}0L54JV0K*GuX4FL zx+3YZocdtD_f1@@+fYVKhr_KWCrwImu}Kumz``VFgi$tD>e+dPe18PcqFo6gffpvr z4g)_DY;q9<%cBz;>S=0CPFA^N(7JOCX)(7HB+M+!RvZp#)SX05e+ZxCy^MATS;F?+ zxHEZ0PqY|e_--zP>YqC>e(l4S4m>15!Vkdh9HrnYgPc!lCL zd`P1%|3WWTUJ3o_nRE25zofs}Rk>-}p|jkfCU}}K!fKGwuQ2pr9`?pGLDQ^vE~Nj5 zGak<{;w%}&LjDB!^za!CrlROoMd;AW@9&M@|5g}hX)|Hu5{#Heb)HZA zGXlRsCkg6YnTj{n+_kbO<8=3`uj3zK+rjSOg}@&Z``eTbRu$gEPItY+Ynfj*I z`EO?0K7{Wsa^4SQQSbvyXvDHUy!ovb#g)m~)Df`Vu=f=|hjXqK97yom9x#`*I$Uym z9(=Jk)S+sd8sPgozzm0yI*YV_xk%M9J>YrNGI}X0X*gGzNZ7-Jo9UfP=T5IJOr$KQ z*Kt21j=?Xu6t-pKbt#hcnMLhQ@9>nt)~rj)BaQo4lU8xJ|A}{BT+wXz{dc}t!6NIn zWfkGGhH1ry501dtm_N^@XWgBO>fcUq znFw?te>_vhGh?jyin#^RW^~t7{b&(8-&_;bsG4-PV+Wj(H>Z+i9D{3Abh%TOyh6xq zyn8bjv^t&1aR))9(*2jU3l=pSJRMfiDPDCk;H9JWxztImvmG;-Z2qe9SdACaxOXcf zTF-{DwR2AqsLa z+q)4h>P@!E+PC+6Xd!28&P!?}&L1Ef2TG(*T?COhbV_B8EM)wIY1DSK znI1P!7%7Rvkx_}mn&(XUMWID$dd9=!-YymdLoT)=70yK5>U^G|VOPlegRx>~5TRS` z!K7Z>eqRb4j|@-YbUw#zfwj>!zR5Jh_aLSqhJi_+1o4JZ+gAhm^Y$sHgbugE%sXow@hnDFNo%UGiNmg7Azf~}3Wae*XlxELqQ zBQb8s;UCvqLhE_y>kwuzO|m%m{s1riR}va|0(FYh-`mWtHJMyb-&AQtz6>90jknCV?a3}+e#B{S>vvK_h0)X%q30jfAY1MCCKL)|>`&jjFN(F7-+qx4wNPv2;mN_Z+pq_8sRW!V; zRa6&1cs_qE-MR)r!_8vX%~jG|BvF*2ZJ5{aj@|vbXg@Z@6#W}U0f)KzPXQTUwe+aO zZ+L=0hM%P}5tt0|`7Y_DX37$vs3zus%W<&UX%?;sk@iS0F^ZinmXd^mm2BKcmyK9fDc$7(x0rqaOcI?fzri`jDO(2COv-Jegpu4$p599P9gtGCLYRK=5iVTn|S) z5dPRgQpR$W41kSXfa5%b3=1^VDqpn?+=o5ec1^=+_;#I2zPdGpS@p7KySu{ zV}4=bQoFoWa6RVAk)CzLkbU^w%GAbA$+++BAdOIaqA%Lzj(cJ1ag@^)fZ|Ik4dRg_ z?Ye@7(ZsXH>9=+#om)PvwV@4tI(x(d*KL~BQ+G-?l2v?vS{7p@EvV_8;icbVK zNmP){s^-87)t_(pM|U(JGV6YR0uttOhv7_@8ofJ~D|J45n;H|F&P(>BBl0=hYlk~( zV}tMn$?8i|wvybUmxQkUePI8(ogG+JX^>5i9i>L_)I^)%;sD`V>D^9SWb-e_S*istFSwzrKr=a zm1RUBT&iQ(Jt&Z0@1bm!B&$wmNWLE9A7`B5q0a_QkyrMN3pSb!9m31sRf_pcj&CI< z!C;K^uRW2ZT-EiS{&aX_=TDTQUrm_a^u2T(7=}TdEuq7lsiH?Md#;ic>Z%k=tKg6O zRn+LzdO|HDTtx2Rn&ook6+VV`OZ;a_q6%~-IRuI2W}~fLhLE9s@rfxe5>)@N9HV)N zv{5IQvQ8mneCIURzm(`)HLTN4n;Bsvt%AR|NKejq)f@h%xrq{)>E>UxKvRB(=55cM z?>+oFd)-MZ^n0yhFfydoF~z*zHcT5f24j57H`A zx5dgm#h2br)`_z#U*vAA?%rzv+)C6HXI4-njo*qE-dXlbTFgJa^7l=puY35!fzwes z^A=KUUlcEGjIeU^pcHUxo3~6z7i8O~utWWZ3uh6$#8m$8MG?`nH3d7XEz)soJE7 z+(d$|&(y&C=0}m~To59qF#D4{1ollMhi#7H9dnG<)!pyu@J+C}djc{@4H5|Np}&9H zVGI@LLaM~}yA*iM#Ph-n_sJkMK3JYn4c9RLjqhVzgR{v{g9pB0qI8j{Fqa7~IOf*6 z-^JK%@{CvKh-%05U|e`@Xl{CjfB>l#+1FKeQikrm?NG^g0^=i%ZX4shr0RsOpJ&~y z`a(1%H2L4^3vz$g^2O!Tn8oGwIwszuCbIT1vMf5H@W*$&G(6CX>g%;wGh1&}?fK8T z9LY!gEtkFtc=X0E^R`BBylyi+d?NRl>;m9B_dTMlG2wngMDZ$jcolFQz9Y~0gbI#R zhLzqbZx`e8da~l78*da67oVc{B{LQ z(YB7Qin>u9v4KnM#7m-umHOY6)|PfUicWn%;yFNGqw?c93UPnWDKQD}H&bdZOd~Y{ zUg%6Lh;1qshY7>3eWonIAZW7KLQNe(8x#@aj@OI1N4~h@LKx-Sn|wJGLc5Df9q30ixtA~n_ zI*#eYwo8vjC6yq|3BWe|-W@@3pmoK`7zHVNKP~@^DXFKedps?*nW^2pX)n6JPH%g8 zjYcXu$n8M2 z|AB&QRywm{&V6}$MssfTnC zC?MxMn&xzp&pN@QL-1@?oww9#`q8VqBU|D#yqv~>U1VvQk;w1ybNaE*9uc?s`hhIX zx*$C;h3%l7+g7{M{bc?35^AuxFVcsfFG7`01*A)h_q8BJR;uzfpd<>*T(jMo!e`he zC=ooP&Xm(VkG#`#^skR+`+FN6L*a-04iz-dtUHvfi0Xgc?$HFj7|AslV0Y zpNHMZn%?I1$uO}OO_2|g6$MI)iG$|U)x`=_gt{!VygjZ0t%241Pw$cu3AvQ48zr{a z(qv_WSr0#ORF3GklDhbxhcz5s*pU9`imHFw1F17y#luyZyHEo3uWkY@U~D)kFJim^oeOZ{TSy2ZJa(!^(CH?a$?f$WE^e!jVFZkgX@6 zg*hZXEvW#gfny22e17hXce7tcl+|#KWm>s-OYiSevvxZbD^C38K~0{!u$81Qm~F%) z1!YEN74-=j8a-|X_lKIMqLz8k5B(5CgZc1Q5-~Q)C^sHMb<&)$$O|y2gt`cf`!Y`& z4OWM*YLN0Wts#;Te61$Y(FKSznIVXGAHyI<*s>8#_p4-c>IlXLaoOT#vg=JDJ;pOR zxCm`3aW$$?VFf_xPqkqU*lucXVi@^8g;Vah4l%BuD_NMQjfFU1O(E z&!2!7FC;#KRjcHnL**nO<)`8 zUk+J?s5XsgJ}*}%{y)WqS{^f z%|tH=NNCprh7=X&_AT`Tp{h)!0qC!WNT$d2(aLHgmEJ)m_B()`nY{ns5`@sb7}L{{FJ4XHoos6-s_69< z^*J0-+6+6n9!EkZR!dFaO~2oN&LvGSZPFlYnDNPr6dJRq=M`(hq70SK(4(obTzolI z%t|ey*HgY`+LmL&=~C-Ve@y);S=&N%{2Nc>#PW?ZpIEz)UtE#Rq2)EOL^A#(P>Gip=C4Tbqsa^R zwoFGU!T`F+=ja9{nIBWBS{%hX9EJ~m${x1ZZ#E#FBjm{qm*rp3g=ZEbs+ivG8|2xA z(9ItfKz-tecI)cS2k-uc8+0C{6dzkHFD9W{3-_`QFd8J{OzOvefHic}e*JCna6jGT z9Jc+1EkYtgq};#%!kdFQq_~WyK95annJUb4r<0VjeQ&s9V~%ANPo^d;dh}(}>ITxI zuQZ?cDr34fl!!>W`@_5`osec}eGRvNs@gq?0&R-qrE`_x^juaVv(S-rpm(68>r#gE z*72(itLK$2cSI@K8@QOrzTP+bpDBD5 zmvAGipFK?o?ZWCm@Cy+_+N5qOL43-B=}q~56@2(%Px57VwXq9;NS5C+2l(hoIZ%JU z11QWSPHTi0eiC|o1#KVeskUD?+Qg!OXffrsL_=K zK=5A}mC^Nvx-T~U^=Gi4DpR2@)==f|*N;WO@Bq?n6qGJQn2aSPj3KD!)%pJec|eB0 zJ;f1yy`8v^@S_oUv`>xE>6I^71Z=CRlFxiu6sGq__$bdly1B)GgbPTLK@rjmfC!V1 z74iI}{}hjWh^dGWDHeEp!M+IpCfr%nBDPBML_P4aEo$a=^z!w~dGIowj$i=ZgO}^V z=r1||{@;rOatLVPfCkI>4?tK!|Mi7xVb77S?twTyh38zE=f5PGFPqC~lw2)r>_sGw z#-BeD%yRI7CE%E&oXsUjL3jxll*1TM=AU@%`C|kgbLBLg532r=qbP1?@0(WIp-m)y zJTZ;=oM{W~K!Q+9i1>8HVX zJr8#~=Ux64QV`zO{F+s-8l{}~P&h<-=cK2fNRXft&_=m=EFsfI9ENqF=NYybuE*vODk5Vst53`EiyY#zGLPUX)m7;^^Imt1*Kg+SLe2W{zpG-+&jxBCE; zfEJ{&atZU~YETlPGY)!tG!t)+H1Mb6^OZ}1Z#A#7#j;z;y@wxx0T{Wtetxd%u`B-@4*Em!A*Y3^uLZ?c7a6>(C6aX zDe4io4~gamdfJmQt|ctA>HVLkqOM}za*_BNXaGa(woKn6_Jjjv7?8eET~tJtbm~0< z{XjlXP<3#mYvHCg%GSb!4xpdnU$)c1?6lmLr`~`Bkom0)-VOlJ-R-;p0H#6UScC;i z7yuWopbnOo@B$E8rE%~TQ}U1^fB&q;T^7vq#)+`DvaR9Y;X&aws7x8Si~h_$kjG{S z>XV>Bwy8|vOQk4U8yXnD;FA6CNTY>)I_w{13U_vq=;L2_*iZT5*()D^Fxj6T&ntGL z(ho<?>Vm^LFiTb0`p4&KoIrshh5ackK$;GX8A;p!ZjV0z9 zo-Tz%_KWc$Kbq}uM0Y|_h>s;3w2~t4HMfRM?4Fj6majd&>$F7u?0p%J~6p8>aaWqKXh zlqO!)wq*xcC&2V+2mlRrkOY^Bcm>%cst;go6Tl$`YJzS8gqn$vC--OS zC>Aw$%Y^`ZB_IVX290I;p(y(~{^0q&TkO0p4ZU{Ig8_`6kLm^vsP}^Xr;R;{2tkRg z07}3q*e#EPFopwG8!e~%ozv(KPxhhO6SEaFu)-3SucbYKL!P^z@$Ei% zUtZK^y|nA-AYMm-BA?b@`%S8VvF4T$yk!h4@xAL1UB5_)2);~4_y25~eHZ|perOB} z-IvWpk%o2&WGJm(mw*E@SFh2ZkHM)4GASU8Ls8|NRR0T7)IGdh*@stKB>yt-0`@$8 zVrK<)e;}{;8vKFOE!ZCVXFKj+sH15!w5Jc}qC4v_9?Oj>R<6Wx6x?wK6KZFl21kI{-P??r@2XIXS7 z??doseTN%2`(58~Sz(btwlJeLJmyS{o?t$&Eu9xHU>+9F&(~TsZ2x2<6)?|F$lFvN z^$<#|iOM|&2PaUO~qpFo4W}6h<{?}Y}n>=V&6w6txar_vd$3A z7xa1@fegH^;uje(m^L03TYbC$yQvHp+LHlQkzt|jQM^Nfu8SlWZ8g$0OB){NHGx}9TgG&l}vpQM6Ezu z%;kOGtyOq(R!947jR0>=LvKE-i81|`RUVzD

    +You will need to move the follower arm to these positions sequentially: -Then run this script to launch auto-calibration: +| 1. Zero position | 2. Rotated position | 3. Rest position | +|---|---|---| +| SO-100 follower arm zero position | SO-100 follower arm rotated position | SO-100 follower arm rest position | + +Make sure both arms are connected and run this script to launch manual calibration: ```bash python lerobot/scripts/control_robot.py calibrate \ - --robot-path lerobot/configs/robot/so100.yaml \ + --robot-path lerobot/configs/robot/moss.yaml \ --robot-overrides '~cameras' --arms main_follower ``` -Note: You can't run auto-calibration for the leader arm, since we removed the gears. Thus, you will need to manually calibrate the leader arm. It's less precise than auto-calibration, but precision is not as critical for the leader arm. - **Manual calibration of leader arm** Follow step 6 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the manual calibration. You will need to move the leader arm to these positions sequentially: diff --git a/examples/11_use_moss.md b/examples/11_use_moss.md index 4286fb8bc..4ccbb93db 100644 --- a/examples/11_use_moss.md +++ b/examples/11_use_moss.md @@ -123,22 +123,22 @@ Follow step 4 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMi Next, you'll need to calibrate your Moss v1 robot to ensure that the leader and follower arms have the same position values when they are in the same physical position. This calibration is essential because it allows a neural network trained on one Moss v1 robot to work on another. -**Auto-calibration of follower arm** -Follow step 5 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the auto-calibration of the follower arm. You first need to manually move your follower arm to this initial position: +**Manual calibration of follower arm** +/!\ Contrarily to step 6 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the auto calibration, we will actually do manual calibration of follower for now. -
    - Moss v1 follower arm initial position -
    +You will need to move the follower arm to these positions sequentially: -Then run this script to launch auto-calibration: +| 1. Zero position | 2. Rotated position | 3. Rest position | +|---|---|---| +| Moss v1 follower arm zero position | Moss v1 follower arm rotated position | Moss v1 follower arm rest position | + +Make sure both arms are connected and run this script to launch manual calibration: ```bash python lerobot/scripts/control_robot.py calibrate \ --robot-path lerobot/configs/robot/moss.yaml \ --robot-overrides '~cameras' --arms main_follower ``` -Note: You can't run auto-calibration for the leader arm, since we removed the gears. Thus, you will need to manually calibrate the leader arm. It's less precise than auto-calibration, but precision is not as critical for the leader arm. - **Manual calibration of leader arm** Follow step 6 of the [assembly video](https://www.youtube.com/watch?v=DA91NJOtMic) which illustrates the manual calibration. You will need to move the leader arm to these positions sequentially: diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robot_devices/robots/manipulator.py index 2c358cb92..a20d5aed8 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robot_devices/robots/manipulator.py @@ -338,17 +338,10 @@ def load_or_run_calibration_(name, arm, arm_type): elif self.robot_type in ["so100", "moss"]: from lerobot.common.robot_devices.robots.feetech_calibration import ( - run_arm_auto_calibration, run_arm_manual_calibration, ) - # TODO(rcadene): better way to handle mocking + test run_arm_auto_calibration - if arm_type == "leader" or arm.mock: - calibration = run_arm_manual_calibration(arm, self.robot_type, name, arm_type) - elif arm_type == "follower": - calibration = run_arm_auto_calibration(arm, self.robot_type, name, arm_type) - else: - raise ValueError(arm_type) + calibration = run_arm_manual_calibration(arm, self.robot_type, name, arm_type) print(f"Calibration is done! Saving calibration file '{arm_calib_path}'") arm_calib_path.parent.mkdir(parents=True, exist_ok=True) diff --git a/media/moss/follower_rest.webp b/media/moss/follower_rest.webp new file mode 100644 index 0000000000000000000000000000000000000000..f0dba18bd72f9f0e6664f4e31d206b77bb0fd31c GIT binary patch literal 156426 zcmZ^Kb9^Piv+s#*I~&`!?d-<3ZQI^xW7{@2wr$(i%l_`Y@4kQDoKH`Gr!{@5YpScO ztCb|h#DEQf0ji=x3MvX5YR~`xfZ{t$!2r4u0FuJO3Yfs(j{smyeLFiV&~IdI}ie@IUc?<^0e6aq+*(&e8sB>--}>h9g+K-@2hw z-eVP${(nmSe`07OV@Jd9y!Y?GU})#y1ONchd}9SyC%b>x>l>pwe0S;_$Nj^m|Ah+7rif77J80f1U|006r6 zf72*9001Ny0ARS)PTxWQKh1%B-+@g`0D#+K002%M06>}kuA}K_!p!uad>~jM003+6mT0D$-n0DQ!KeZA#@Jg*s{Ol{uftawIZ-uUxA?mh`-@pVU)O?m#pefym$F8-+fQpucP+v>aV9c+w1Q4JCv`d zJpQn+vA2V|H{TD#%J_-5FKv6^Q#r`k<;8j(R)vihIWYekO2e?j!A zox2}Cca1T2Ki2q0m8OITEf!EJmLqyC_;{U2N+3uKJ8;$MvTMxC>)3YGr(^vB2K@&T zj>UTf4Fz^boQSsxYjf;_E=+ZOVkgufZ zEbufbLZWEpJdJCyF+`b^a)i8=INl!Iluo`Qk?wwemF($tA~V;BYO|aeKI&Jg$e=L0 z>KL}T;qLF^*OZ2!6l!fhbwTEKu2mz*Yke4Wv#JB24IBTOeu%yDS*vIB)jEpozp@?7 z9}`}vcr{yIREbagcQ5{zI=v+>;=Czqu;A)QlZ%V$=C0j~qdrhyH$_eiW= z!CDf0%NJTP7_J8l)2*QRL(}ZzH(5My*QT<3v*9pXkE0Uz;Cj?vU1o-S!_fa7r&2|? zwO~`Blnh*TSEIngg%$KyOK?Y{V?0MMDKfGEJdB)%DY4OROBvOfcZ+*p;j3>>Ny%&F zUd(&zXs_mkpreQfr}Mc{QCbPmbpV^iU;j)^_ptDsXy>*DYByGzm>(&kMOp2G+I8k2 z=p&?lVZ8}@!x=@6zFdmKAQN@YEm~5gop-jpoi#0)%>xgZ^i*B%lQpQi!hh zcI@`I^S22{3+eQ-O4}*8?mX3~q|Iz_7}w8f{Px{OR?lGRt}Biuj^Xj*r)Ni;{EF8& zbBdMd#EQ33kEC4)=SqZzqqDtLh|UtW zw#|j_VHGs|=C@E?0BVMD&P;d!+aPNS-Ey*-9a!U{E!Bqs7hEg-YU20>1M;85@OrB$}XchL#L!BfXO! zdy1LwSm-~4yhl;G)7;kBu1#ecyH(9dE}O=`IQ}v7_v`;jfx?@AQfcvP;y*G9SqZen zwHeZU?pamCKOvinvW?C+`}uE|;Bi%Ia!0TwHk>9!oC~r2@b=x_Iv(F&$=%j)l3I*Q zIKj3=VlnEfI*`i8f>R-lOKEWIR+FpO43V3ynKWyZ>N|^g6FX6Gs&DbnpdEuYi9|sw zod)egMv`$%5eCXYhn5NX49Smx2nM6WtZHQ4SD*W%0u!3REo=%Xrq-^qE`{6^2r3br z-Fu5%*}I7{=7RGtzPS;Kgg1e>OV=v%!Y$jrDTdJLT5EhpBz{ad8`+~S%_Lc6^41G6 zgmXN3P4TJNA)Ox8Yu)e$?cD^+HTRn%{Qy%qPb!E*N|T9aV2r@DySt1B*_OG##Is*dMuXA}J&4CO-w(b9L6$P;iWx5^9=` zZ4e2>d(z^+#p5(boi-FjjBvFiMLoaNkM6I!>h`SBpbR}Ade5F8AgtO;Sa#M}_Hn1M ze)Ly0?UYJV?V?k6H1UDkttPvs4+{>0s#^e6vcAGf_)`sVtc^j|4XOE>l?ha~RD2+a1rrD@&Q;SprQ+ekKf+?(pf)mBG z%o5H-Q59&Z-&C0>-#oZ-HslV|HtmY}M?i&Qh;K|iAK0eq9IUKu#3@o!C^%GpK`GcbvJ;R;;5jD(C~cWBg|JY^$Bg@MP~0<+3tc z9l<}vRs4bubgL)$26zSkM{ll|+R!ZUtvPfSf#Lk~f~v4hr)W?Z(cA&<<1YE-N!i|! zyd1$@6l0Ia2Gr`?HPBhyV_uKQs8{)(7%CXevqaVs#?#-ub$d4R;{si_HRBb7Hb5?6 z1QssVD_*)+*2)C4isJRRY`b_EQpa$Ml+y?FtZh3jtAt(jss+u!q8JA`bh$v(z)>jWdGNv8hxT@b4p13}h3@(Ey%P*~$9+8HT2U*+pcnEHIA{E(a=W!7Jkj*4 zz{wJr&~=sumDX)!=H_&WDGU&1FBqa_=GOhp9bpn4El}v(#iV#cZ0cm1J5DH)OdD2I zYLcc88DYZedgx3ka$rOry!?DLNxO@E6-P-a7_NQ z=~@twgrz zk%1?h;{EW`W{V3{+6LPQ zN}}Z=oe@RR{Q3PooFU>r*Q=ywp;`mtYkbx}ffJ>x?x`iDimO60<_W_nCk*2B%+0Db zMiZGMkH_3OJ$xMeDhN~G!8hA?P8Wx(3V=jPvLwgEydH4gn;n)P9CDjj>4UvTQh_*( z9a#{@{0#si{YLOu>W!KFCO_4`q+lXR|INyCkAu)n{IB5DDg!B>>L~1r@omRAUe}Lw zMI8OLe5qkPJ(_%0Zk;^?bk}V;+o=`tN-rduv2)*)kMFnpRy6GP-D_diW7f^{>iB?> zMTe0Sh!b3%e&~*llzSjs$nM&eL5A;?3cef4^95J8`ogZqN8IcSw@1T7>O|U|+iQXh zXbSI~XYn(uW-CRB)=v~cr1c^z-l@T?00YMC2-Uw8GV9L%xe;Z&h0UstNdrQ?boqK( z!(|$*67wgC&tGz_@_A@C>02$ExDx&{DG*F6!ps)uF|j-2w>$t+aHE`{T3%ANY7VI5 z0=B@?N+&tL<}Av60@J7b+fc`&M&5oUy;qCDtAvN1%x)v+11$}V%d=$ zHa71&UZoyx7kzA-vVm7yRGf&xwK4Sh5vvt(@Q_l>6$`^pHG3Ugd4Y$kiD0xoKW*Mo}(0H}@5C z2BhikyQ79=nhxxr%^V|i^%vrT^UB=xSCIndn^ULD@Tml_%1l!-oxXIO%~^dp68{Ll zv2pxK^GpbIU;fde5+Ge^S^d|Qwd8r0@}oomNDE8eLxP+2!eFpELucV+faUhhS^wJV z$li1)8WAo%4=X3jX$Eg=F62DI9Tq_7Rm4*1p@FcRiz8p9b1vVHoaZbLnvtKuEZ&F8 zjZM8VH~8$ym2Os{;&6~q)IXr?f~Y?o6!*$Q%csGb6e+=3nRp@ZsbdnsY*isPUMP*X zeS?XmAIV|rul3nek`kL~TQyOBJEEXx;KPoNa>B#tPc{h#6d9y8&3nb%l}k!0II^Yz z+0kP5Ts`o-lXVTW{8`O(v5cCa4b}gM*5wW%?~WKSyvy=S8hTRxvltqp1Y8Do@qD@$ zOXuzc=IBlZQzCS-Up11g-PSV&zZLlSIxUg2;Nba{$;hGyjc{w5!t0KAJcweEvnn%) z>tdSEYe!yz?JsRgri3ePnqSO!9CYiQ?_ugp?F0kbfS-6(A)Uz!^ZQ8fYJDk` z@%;+O3gf~jc5r~uU>ggB$%D7PrsnK}|D}ciJ8555k6$B(KW{y94ca1gzy7T0xANFT z!l@(9;Ls=9A2laU*3dqQ>(o4;RX2;8~$2QTl4&U+3<)@V} znsR7vt1QZOBEL5}^%JR)p2`hPz`#UY&+*z>GobZg&EUEHlaRtBnEk2T3}AB>pX$Ri zi%(j?Rx+M;U9Zu_17kXE7RY&yW)R{pgdkLDFBds2#!(TB0uc?8pBoUXgh~|DATXHu zdhlCA8+MOqB;fpe6;>`9%_+JLV!`bGe(-nzKI*B1+r>`ihqHY(^_*g&j%T)RL8)F| z$3dvaTXxNoC_G$XXounW#rNZYRD7w^FxB7RN!>`w;={C({GbUKKCB4`sIs(EbV$nD z+2Q!8 zNQxO%1keg`11=TFXv!h$Ar-lnRGKm#4gp$t3w*7nW|4k#4w^j?oI0}lw%1yarzEx= zRvANt(K4N3xP~XFftg|3E`u45wVBz+PV*o?%Srewq+iK)40qmrFX<(MePdT;Owxf3 z1GM+?_D7lI7L`tBAXzKEVN5FAidBVlaL?vta;+s)5%>>=n>w_L+cIuxE`eVFD-&HG zUMpG&sdxg%C+@Xca)sE{ZeQ0GbLAI{HZM)l8k#!yKx~t+6ThV|fi@k8mUgJx6N{hd zCK)1-ko-1ZKT#e3$2G*(O7tPSJSb`ba8UGw@WJzhx-==cAA2u3*l6qOiHMhfYm0pQ z0A*ULCv6C(3e=QRVDrqchVU!iX)gMA15~d_6WQI$=8VDw#aH=q%0`>NgjFEF!P|c5YfRyRJJhP* z)3k^KTYo#)M0c%v_`Seyye+r@zSdh`?2o`MHlN&^&dWIKCJEPke zZn{HZa3_N3lMImSCw}+Zei7|*G!-r7JgdD`sa;a@yKXHM$uQ)h+Uo#jUplkB#gX4g zQdg~Gruuv|y^jvFh=Un3h6Zt7)!Fef)5DY(lr#1-Bn2pm@>IRwxAb#qK`W1&Kp`nB zNqOfDKccg5+#5|u|IB86r6AJG0m(52_B zRm~kuyZ8LrFn3GIj2)^S9b1Afl=qda!^}6zLMW}Bvt%4PT7@wanubrDBb5||4?L7+ zk4`2g@T?K{7@mI-Zp3xaX1T0>Jf}dX%9F^`hj3L>m$apI+q3Hg<`dvO^1JeP$8E^G z8F;QLc+HIiCF`Vrpd)q!5j4>Hg$_V-P}GD1F0y#pIJ3WwTTY!WsI5Zs5bH1Gu0R2e zpi!HELfpx?iv`C_y`W}?Z8APPG3L<(f(~dT>I0i&Bon?0B|rBhXX8!7B;Hg%O9Pbd zyUVgXIQ1S1P@BdM#c`xw5}KVg>A3%9tS~v#5&o(5!MzT4cPDiE7i{8fga)W-HSEN@I~{bywFxU*yB&8~QnT z_GV;|R!rXP5I*mekkZ2vfCO=4nJTP(FPA7t*>VGVrd;8dq8Gc+G4f`)?e-q{@IKF? zK9H)q=pZF^JQ7Tt@4YJh)I5^G&j%f#kCOH+G>%TdxYUGiiQ(@+F_&S{(iQy ztXm64iQ-=~q?(Lez_dyU08^6inWnCq7$y_drAkhTnfDV$lmHm;Hhx}I=&=*Ly(~F= z)0NybSb|^=?AP7Zc9P5Z>G+6WtkMHQuT}nt?*NeovjJG*n(oy$hoI$IbADyZWTRX}pzsiF- zwr;MA%v@i33b$$ti@aj>`mhLL)#-*HjUE?8Lsj?nYOBZh?kU~xQSFpJiM)aG)t5oh zkHIRU2Ef?_r%3ps)I_|2!N}L&Ev-E0z$YVJQQNCwZ_-auhWL8%* zm5_v|fFc-*?{}>-{#MPwB^iv0Pda?Cfv9*yoM)$cA9JZ9&k`gXV}wAX!nJ$&>$NE0 zJXX$Ph~NMRStN`_4@bXK)JiYre#R8 zwN52yjGTj~=bDzbdRHDTGD?30+C{V3UT$1)1QhcTzxiikUy5tQXGg1fGM=YqG7Nj@ zyf67(Hv&Q$MQ$Sb^svjV=B05tA??N;g)_cJzT6TWt`lPE;jdx)n7yCYLG^pu5u1P6 zyv^P7V1T)d;UWDi(lw%X^O+!3#wReXf~-Nd;FH(o)y$7&wuIam9SQEV_?=a`CO3bp z1#H9KM_GbpU~8oIet@VjYlZHcqYl5UKv>zSi^|)=y3a4``FWBY?NJ#H+p#yBFGJDI zrzRN3acr2q4VzV~&55D&x6lxqNsHfw)wXbHUJt3oJ7!@Dkw5P!k1#7;GL_72giX>M^^~k4rd&ZH0z&8`gP5xNLwxWrS?k9qNj5M&sP~!it$+%lUkQt=)HuF*T0hs^p*G_(@>D zpp62`9J!^!8G(Plwk`I3)>|}V+s$O7>DvFF~dmi0YfFyx+VH_hrSDS-m9@YAZpPIDd;8X>7*e-NI!wH*PfL+r9s)9IH`erI%FdNA~j4>ec9{#dx z5p*tT?L?=pJ)KiXx?ft67s&LHABD>1&Hd|Fn)&D+TGTm;JcaCL(2gM_0({f=_2m#^3@SM*(PDV$eUNqZ`7aaj6flz4zY{U*qR+3jxgC{nydh=F&kH0yf ziLL2rEma|u3=+vmpc1$!qOD}ACIt`l+k=%)mN(_!)@v?4v6w3GIT1*DS~4o{5w%20 z_^w39@5MG0$V(a$Ps|W!c^dZTywFd$YnYFj3_SA-mlSEYl=pXFV3CH{#^nhuz1o8a zeWH~ujNj@#zk2^PT)&Ucd!1H$(M;$>AlL8XfQ~dT^_w$Amu-Vu>xr;Kt#ye2uXhxM z_a_0#dI0?z8u~gzcax1ymRRy0oqPzFBop((*RBKBtVYxMyO}5| zI0D#P?fC%MqljwGBbNh(HXRg>rM+3}ded_-p`rP>k-8PC3ynG+Z!j-!m$B`9NL1jf zZ{X+j>BAI%{lFvIwL9i(tL@!;L|Is}nfs%OL?%2#hyjW~>=*v%3F#D@hV8@6u$|fU z`hzp+mgk5zw1)U-Z_=x$1fKR$vus3)bYGCrsia7A+|m&GSCLHykAas8M~G3JV*8oY z-`ot{>9{LSKf52scU1V&&e04?)%JlZa*75+S~rT zpTg>e4(%LO9a~h?8CvGxIK$2ihbeQ&timI37x1vZ*RIgI7T}aU4C#N)r`D0f1&~&5 z_o8{Fb0l%2n%Xt?%`TY-H&MTWWiz`i7q~?$Jf!de1uP!Bc*#XBVe)^y_dG;!S#+uUm@+akVtVz z?`T6No@xs#P{YLeE!?}+wp5(xMc6xOL+$S_E+lh(uoF-UYTi6bf=dzgX4ayoQfUtU zD{a}q3L`TIVc5`-PFo7IZ6-oWXl`pG->Q*FIDM2Ilz$aUjjJ--U&fM z7fR`3-~7=oyH2bj7Hci!PwU@-xnY;H%m$OHk*iN{61sC7soK!|8+C;?>Nc|+*DAk$ zQ6Yb>6*{WAV+0(JUD^SIp1DG~>%jpdU?i%y>%x%{GCjz|OV*dzpLgUxATHVh9n3yU zs(kb+o`kXZ->GK0l}R8+!+(DY4IfWc346aFlbn~51OmQ3^@ zC9HM}5=P%l<~p(BCm`0@^T*j$q$MeW(7XPbzxPP}L>(kvFbTX^{_aTp;(B`MvLlAI z9w|(p?20X;h+PIoCKhDpEGNY$Z2en_RM8U5y^AYt)ZS;VL!6C%wmIRy{{eGxT0HN_ z9274r@Dk|6FIQ+u{{cLMtLruAmu|W8s{@?>K?tD|q_mvThbW|$^V5q+(8LD*_wcPy zM4}W6OYbWYS${U^3q4I-G9KuL-=b%n%&5tZh$)2a!yeR#ggs8sugVWyzaUPYnVvE4T$lJS z+s~hz$Ep5nSAx{?dPgkN2&QofIWz~1u|^>hLbbuHu=#CkdnB1g>m_-8LF&Y{PsRiY zK9KiAC=WAu?!ezOMOc*S{N=JT(%B|X?2_VndJwv%(Lq^WsYhwJ?sO{d%ENMLc@eG|h(=<1eAW*!55pHeWhcb;ScR z9{!q6*<}#)C_3gpa_$h#(QX!ncXs9vaF?dvUfymQqN=4KU+pvSeX6M=_drC+@_}(` z9_H42q*3CD5hW4{l=xf6DmJ~1{6)~lyehwa1Q1zVlS#tO;B>_}{!W!D|6NYzO)oV0 zvuM*&IQ;Wt!zYMjiHBb^2BAYo9>c}kRwil}M*PPEqVXh_NITU<<0g~#E@;CqJJ)e9 zro1iRO!;%+9}NxNoi6*~$Bk4tnRDU0wz#)HI%#6F-SEW-9H2WTf~alTkyn97JOXcS z92t6gEX^W*|Lij6hi_EPJyl@peAWMV3}03CaA647gj8M?~`0#bIl z=!d{?o9IJ(i*yyo^dYjJ+49FhZ<}t?Ht0t~ZnJMgGK8WkJo(V^{(YnxCM-NqwN6Cz z&VImBrRRm$7sFeYi#^}0TJ=>;l(MFaAc_$SWdvDcHm_ntFZ8RVe1qC;6LD5H;|U3r zwRriS+D=@uT(PzBJ17SDnBBUCdZMIc9Rcn{Oo<9?v|=(5iE(+z&$M35jj{&4nHhTF zDqEC8_8WJyPscn-BBhqs1T-o3xiT2YJ8Ib=XT<$s)A1$#9YJ58!l`?GK4GShmlhj@yhb45%=!vTX}2utVI? zDwu)jh3upq){jS%c)qra;a7J|`&tNQ8xM3kiny@GM|%0Emh;X+$`ij+SY50+Oj6V% z`Se4f`P%EMwXJl4?Az!(kqk7qq5IkGUyK!Hq_zR(5Y5*k{O@!KgLDJ^L?$3!2SHj^`5^ME6Jk zNr1Rs+G6b^v-Z~B-6_hO%2&7M=Nb$>UIqOTs+Xbbb8T-_QEf8JM-G#HEdupJSSesN z@+=pS;l%eCUy8fLtsH=T3Qz40p!!MT+Gn!xlygb%2@VWn$YX|cOWNq!lowoENB9@$ zQ5eWwV{DatlJA;Gz60bpab)cf`x4vCqBO7qRRAFp*`%R?nz*X*eaunGknyc(B!kqO zbARPu1|Z2=7KUR-_1%4<3gSr=9$Qlt4MO-ic}3i6yRO(HS^Rw%)3hH3CJ*LkaE{2v za?$)ZhIQN^e;*#70_`fU2-%qUb-}KtzoOEzv)(jZEUy66tZwQRXcy>g#|ZhJ;{eph z392hm?!L>?XIQXh^6I}Dy0?Z*Y}Ze((GJj63!?%KCg*>HEQM1buK~D#3oZ% z&cs%D6T(Obx>a!M?t~GuAe`0Wwo0ad`t;MN47bk+Uu+F{+iJpQl0ypo;uD=jkdH;;K=v28(!_y zPN)8O!~Nk>2V{DIa2bNB`7v$nkDw z>-4`8QvX~D7={<4(JSg!x|Ph5hOD+>!7s_rf_~gyc*MR>hrui*Tri|Bc;zWSuqQCL zvJ!hssfPv$lII|3UXMM&!XiQ95UG=dtbH;+p6vwewV2^A$sxi@#kV%^CF@?p1IE zA;1Ebt+$Np&k#gPz=~&M#bZsKzfd<=Q&%d+vGXJf)Pt%ZsJn*rpHP*6;cRg3#6;zI zqcz=?z3aY@4bNBnkG24d59d&y|yGd_x9FqvVqzZ!5531!8ngY1 zPTSp{(C57&#>a^UMKa zu6}O`P2=lIPtnWqhZsY+Nd(WA2-5#xN-L2e*Ujr-*x9p_i(= zTCLSgPYc%*P2I6I{JBEEGf_*J$J9v^1}+K|pQB#(u7|XHju@8Q$DLlCCXJZW-el1s za8wbHjc_}3JUIUmBsgAX`K%D9g0%%CB5bMBmh zi?H2#_tQvr4B8Lj0%Sr&D9pW5G94UY81sNg~f#|-I;FumGzJ;7UM)aH;W`V`a>?@tp zHAX8k6~a*y8eID6_AU%HuFT0u*vF3$J&kIr8sb^8FjK#cvyy9LV*NT;JKm$J7ig0T z30J$T_`q$&k!-Kp`jD2Jk8iVBgVc5N*L1siorFc#dMspUrHe7q1&(s)D+sx4OSDm> zYc|HuW6d7dpvAKr2O$I`Wyu%o;8F8_6<9+-EiL&O>JVchhv|}}&DieOJ&dT_qK6D+ z72pa2oW<3>#Kd1lgZv+L;LxK-RJ4AU z^PSZ(CGeZ^;E16{5#+&Kwzs*BjG;!XfiG(zm|f3DhcP9>DTC?y}Gb9K(cK%X)P)jD^@YOsUypvsb&>ZlD|?#8PfoB|$jBbdX{-GJ`0@bY2V5vHo)5i_A<~wBA zw)|4}6>?vF3A>|@G|};p%j=v$Emr1DLx^+eC{K?$kd5DK-CeRtc#7;FSG_7CE=A1FB}2N-|MV@+kwa6C}}p=Az)as zFNBhA#P}sqfyUPMn+_AWvy^BT2u^v<*!I|z^?WK!hB#ugJ=K}p0?JFD>(S&i@LZ@1 za2At+pn9`UW{sthym^C%%fmK3Yta{Nn|C>-4M)33`#&{E(9|r!lay4HI~n`VB4eLKM7nz{y?NY+3V-lfE5sne}ftMw*QWRK)aK4Cphg8~XlyUhz8B=JvXrk%+B` z!FlhS^BqUw0$8_yCZ9RmuLq^)IK;t2!5b&w?iP#9H8|kc@u9F zINKc1G!}yd-u(Uqj46u zKF8|~0#>JL>WfHAhrS$kwXXJ@2^KtIC(D^r!S$b@w>QHd{5}(FFB$^2`Zdk?8esKF zQT09HwP;@iV9hcY&zc-snR6>mNWs#B%m<9;2WRRz+c>}dXZJ-!gh4!Q??koTdYqjJ z@hdSL>51Jf!Ic>h)uv_(6#(QiOhQd1%EGPUqgM|7hZ9VMSyP&Dd^kH=dENR2o$v{J zlTew>UunNkq9vRnh5u#RIe&vu`|iy& zSD;-RO<^r?tAaZgOmo5aLNP`hYhy=!>O-J6br1+hE_rxI^W52fbU2Y{QgasYDY%2^ z0G&2h6e%7g-Z9{2=TFAzrJAH|UjEKf5fvA8Ut&}s4k7(n5Eugq?td&Ss~v3^TYil1 zy>eAQMuvtbkfL8TSlzBQwfkO1CZ4i1ai)v_g@YA`(x5aql?;j!}9)(K@$%NVi>->kH74CQx10o7Bpe1sf|1j9tUQm%7yS=>VY)~EkD z0^a3kZ4jj54z!A{|4mqHQ8BDYtv&{slq6UJ_t2{|j_bzqcsbG@?xAcaGGNR5@1O<8EfE|MjTw!C(TzoSzI#nl72ecrh2$nBt!@mO}!kVyE z@xUi{8NeNx_lc3RwvSDwZpw|ButY=sQorvTvA5u=$mGloqqgB=Vl6!#Z=2MY<=5%9 z>2z}6IAv>fI_>nNs3c^vs61Bu2H4?3F?HM;Sweg;2ICFMDPaI};H-?PjsY;tDdlFr zIS9X~>CWR5X%F}s;AzEgD!SC^{QZ46MAGxT-LZ(eC`}yLDB31dCKu=pehd*`&fhZ6 zk5PocCR!1H#&A9ULFQP3D*HlQ52qY!|1%Oe>F3&B@t>0u`Pbn$>EXBO3{j#0^ZsBn z3U=tppa6b^$Uq_C6zVJb(~g<+MLJvlkdq961Bu{d4?;FLa(REALkl%>I4>j_=vG%9@3VAZ5WMnOz3U9tR1>8m!pk5psx2=K(CZFZMS!^N?K@C+0dc>4_A7 zhWYBv<7W31B&BqqzGznfIO+`2;M0-4;`Y8UJY6(1<0wI%!|MzK8BhU zwrCLNd|mP}0Zhy2(i|{zBjT8hgQ%m|&{5dlvmZAvJ2E%(`ZW%YQ`WWv!;90ggRC zhPkX(+qeksu3w3;M0uk!fL#49Uf#lK>qh`;K?}-gMW3mXz>S-ov)w89$E-AqT=y{L zI_s)3iofIeIR2;Nru2?Y2cxqvy5K4vp`QF+Z}Lv){&u$auKVxiz$EN9y+{2@jx?A_ z9sI&R_h~#FqI6`joLltDMj?&Nhd2-MWCV^x0yFde12lGeA=Iyrz5QVo zh9NBHl^d8ITMH}Sn{X#ULRwMxpxphh{IV`$>lI9?Y01e6Bfnn}5%-0!Y@JBrd1YJR z_p1TW%5ON-i*b7XLtq&G58W+Ki|F)(QCE5tgzAtNZcDos@C*g5)gm=k2>rD7N=ppw z-L5Vj1ch0g^Lc+J;RS+tQAJ3Ho&uxDe_dZLu4EqfNK1+ia><%CnDq~%7XHj(Y(PxV z+dxAT5@xBU>itm|8i4Ak&H}71x{ zqTWzxRaYtD3Q`E<2eu-3M-&oLl=%M5V(%$Ydoo5mlofCcvDL#_3;S1kt~I*89--Xr zS4GG?EB4LD&s9{mD_B6dXPmaOyD9dYW7Tl+`(eBbcx=oH{06H)L{q;3*)TU5&_w1!WBniyS#vg#6SG~!flF`*i}xS zITB}Qb85)UB#k00YPaSJFK}Qh*AvtXcK%zq>6xCbhrK&x|0k4CZ?H)x7h5?cH?`1) z%BqLn->46M6a7$RyS^eRekc^zT7RR=Q}Hw93ox&zOrJ{6qmzU z6EY=tceSZz8e^AU24w^Z?aMbI0N2Km) zzt+YB8&1-cKjH`RZmNCNvH`l2dB`7mLt=tJ<=vpiattZMm%&K z8Bn-s45FHbKrN;1toDH-Rh_5bip5@uzMLz%~8bl89*GNid6r`M2pZL*8x_Lv> zJ0KM59x7e!OW8cVOv0H6memct%CLLV78NW#2knfMNMC%C>8i+JG(xV-|oQWAfp8f~q_R5tX zLb{2m&|!s1TgDR##!jUO)_2a6Zbj>U0)Kv zpx^GnGwM~AS(D`}LNY#`5ZO)LwfRlL%F>$UXM}6!Qj?T7jE4kZ82E*ehXWsw^YH567dFXvouJE!w8izZGt=h;Z6}-y1D$CyDw02fPqFg zwwX7KBF{p$h4>shA9z-HCCkp%8{;@q^uoz+=yl}3IaQw z$*@2|A=}jiekps-;hdXtO-`+3=ns6*g;5jvL#^c8lb<_xT}}k4$+j-qU&ppFl*S7a z@6Vd;5KwjmX1b&&bm4#;F6w@ZrNd{lB+A0oAd@)1$LZffnjct)S1)sO7+*Ou!%?04 z6hh}c;ikr_at^^uyGLWU-48u(+sESbI74~XgAj7~3eZ9i;o1rmK1Ao*_m5Dzo?=(8 zzq)%tog|`3hr)Y)Eo;2tO;slmi7xD@<@(JoBal9@*Gq9ihM< zz789SgKn#oies|4S=tuD_;0Mqo~Ao5Un~Fep0Y1q)*+|$JCVp7{X=Rey|)-FzloDL zYe^97(oAGz)wNn3lpJqzC=-f73HN&2zCMbKvkSuK>UYf(Z0umz-*7vvTR*OuN9%Fl z5XnPByT<%;Kzq98Ru81&noAnMGPh4V>7?rQ)EJA|tO@H=3l;TK2x8Jh>KO8hymCi) z#O`ly?ZBidJLz9TkT$hohY^PWdG*U8hri2q*2RW3Jv{ChTn-u9SR2@wi8H{KYGLZ% z--ry2xEQ0$`s_O}pM&gcIr4C}owqtCwZI>1p-AJOYj2di0zXQo=KK`nhllE(#*c3i>t%G!^G_nj%21!FTNr$^Yzl z1*E3dy*+1T;pm1%(U*=@i;UJ7LIQ~zZKGi5AFWA>>mZrIC=-*zh9M%YkKq`hKbUNEgP!Tnf$hidVh%3#m5 zoU;K1dt(9=y0DswYSPrexkW^x{W9~%r$Ze(IXxx+NMttwdlvhQqhQ{Kt-xh4{e*s> znQooMN=44zk;-klw&a&Vzk8fy#l?FSpG-J`rC$GQF1~JoQHm`^y!#Gk=x|tZEOf7s zy#eG3;n%Kyj;~J|hjqg!&Z3^*nV%&FqbYAK`AIQ7w8!;DYHYA|Y&UaX({AMWN;UhB z>MUU+U}7KF#ZiONazGddXMh)Uq_UP^57#Myly}f{9fwF%zZ?KQxonG8?Us?GtAZ06M<*gSLF>;#5J}I=Q{1}w} zQ)4Rl&U~#q@GH_>=`E)hy28=}842U4{0{62PohcsX@#R_I{-F!b|LUKl z;i0Gq^Dl;RIGUs0e_i%LpZfmkRKA3y5^o%&An@i>Q9gd0V^-PYykY-z=ReB>FI63(jdWDWZvQNXlOdbFRJ#= zB2l1Y%Hrm^2(+9TKzUdnI55{QGNJS1aEpk?eSov@sa&2qulW{w-&n&}mfE>9#AT2#jwd5C>;|aU;jg)vbii6fej!#ssY0XQ?iV)qy6AQ}cO^O2V zI@IA(~agH{uL$?=trt4*Q_*4-MeY4pWJgJ;SxS(s(S>Y-Q5p z`HPFh8$$9pq*p*ulUKp$05+9LC^yq=8l@0bTlaIV#JlE4!kMpi=w|7Y%G`G@jK{ zGAn%?8+(Bpc8;JcjmD-hjOKGSbKE9UNRY#8rOMQ#F*d1}*6SW9IOCn@UCi!te z;gP`0K)Xs2^ONO$xhy2ufo+oeZvg44Sw$>us&)4F0YVO`D(npGg{v;fm%2<0p;t}a zteKr>O}6xHziL65x-nZ2Q;}Z0)h{I^KA{;8!}eU15VWDo7dR$evcNW z@7IccjjH(P;oHYUi}lnAksMv-+_iBw=|hfAItxUI!KV8EhuUz?9ikabqW9?LAx0xk zH<9F#lhNIOs?lYy?2o20RbGyI)U$){#>jhK{@!P3YV0-}Nnu5Ngq{4HRFM((7*^M= z5d(B-L%yqgoe|y?yX}u-?MVTGU;}~X+0WvH!U0V*Djj!YTI(}>=-l;(|116pWOnGl zH;Y~=pN06+`gn~NRx&!5F(1^BNFXK4ig4+l&shGXterG+_-A!)j@atrThm1p2t-F{ z?6{%q4#(n%b&KK3I9#8a+8QeuMmR5|1m;gkT;6X6m+f2-H0n);^1Ks>CZIqiYyD8< z^9symj_x1}=$K*0OgxoGU9j$`=-fDr7^X~Ge%>#CZ@#erdw?ln*@v$l*qBdb)@qow zKRZ7kq9GM%Mg|&SAVvkgpDI56mA-JKCSl+Gd1h8?sNacDBrd308;F*+7-vNZz(;xvOxUK& z=3rMs%l}E!TPu@qTXa@*_TQ&~9^PN%s50j|LNT5k9_7fnKTKpauJ+1R6LBJ>i&f22 zh0hmj@jGg68@nstHDmt)3Qz!if!@?=BBF!(t5jg5Q-^gH0A37xmEU~Un}IyreOVp;MMbfVxcCw$#Co^XifhFWfNpO ztOgIt?=4fNLD0C%Ykx6aso7;XQ*6f8G+7t0#b9--LXO+CNG3N^B+VE570u17R+9zx zGG_>aAxYWrf++7}`8azOWF;JDl%(_Vg+okHkODi{ezmzHeyk&5Jx;a`vHD@{!|a$+ zhsUOvFxM4`1a@RfdxLPP{);S12uq?%%TpyEf!2Ebjo6MJ((|E2fb+=oZAYytGi&PW zyZFw8tKV_-$m2Ae;ijU1DK&zLhDBOor7iovzH92Rquwz9w*1f5%vUXo=aqvsJTCk`LSD1{Dt`sB$Pj0lzlo zes9Q>I9pM;j~zL6MSwyGv^%$st9w?|+xmz_AY3ggAXp~IBXE;Wq#YkJs&iznx z57^8>v|v7jqdyf0KOH0;H~c)2bj{K5Z>^=*gV9^_KUUXI8A}Doov(zW;$Kctnn0%c zHXGWU?bEBox+j*vr#by!k-edEb`Fp2ysA zQ@5Xdti zt4=P-{cQn=p!bpiBwESxR=sQH(Q8%seaa&Nt*!`~77>|A=g7EF^>+6r6yk>{r0~2P zcqv^RQzcQ^%r!go>^OcA1X?UrfZlQ&kK?>WtVp=3*xAc1vs4k@%k!p zP5RO(w|lp#+=yFJfSDRkVTY_V1l9Xc>=23WCzz(~7WY{xf!_5=wh#uAxX6z|J_;sZ zURhF3us-Yxrr0!Su^ImpiE6r6`po$6fdnbU;1T2a36-Z3f8&m&cW}mcy{%D&%a}a&Eb0Ux?^Vl-%wpB00&KAwlBC;K zf+s%xYMG{Zmn1l~%F~~fsTd9gc(Xw9?{$9;Dds%hC*gHrXq?V$8WDPnp)@O$&;iFS zVuNhRK#Dm^!4V0$v^pA2vz7`@3rl<7daL=&)u-bzQT_P-W>Qp`Kt%XqxP7sFw%o1& z%9B_-(>>3Cx%l$p)72U==S!I=^8H)#-Kt(P>!emu&Lec+Y;jtG#dVY z7!9qF1joZe3H+gHcx;g-?c!rixj(CyxBDypH^M@t95+OWKG|reCKSw*9oCK<$gT*w zecSI%PFH^=;3ElOn5DbKWE8jioB0!=(CSteAuy5{W`u6?wsI%xlOGBz46%g7z`R2Y z-FxY{2O9GjPweQFtsGz39{QNpG!5p^PUbQzyW%UPR!3dG0O6wa|F|Jq$|`n6z66h& zkAR+}k!yHiB`J?^jpaB#f|b6DpC7rB6oaBo_s^l9TzEN}tUeXj2-VEFjOuG?O%~6oU;4eC(6t z+P-4`tF4o9VmQc2Lp4!t;OwC1QKoK^9~r&Epbsr*ka8@rI2_2R1b}O2l&iN0HT-4@ zfz%z?dRv0g(#@$;Glsv@b_5VU;ia43c=vSqBVQ|%l=RrDrd}(Jtdy$P4~r{2)d9*t z)KjozN-`3YhM0+Br(kaWHl6x12=mVtoY~}p>c4y@IO3XenG~6595-o_;F9k>QT3ON z@ixvNwLJTq+h++iuUM8I4&d{}Hae)3L&^Hk?DX?FTBtj#J}1;X-U zb^r_!IwA_3*EjduJcOKWU&nZc?9uv3-lFGnI53Vd|Fp~5Y*tn8`0yRH)3yt>VR^mL z{2=LfWg`KF7VRcf4d9S7ts&`AvbL0QEHnELTU&glKlJtR{P{A=LF(1=2!-DR{U}Bd zxLO7kO@F0f7&_QxLUc;uWm430l8@;}|FO&IrFM?eXzC*Lrl3F}*BUuyB@nzL*tqj+ z`-+NyRekethb5A9F93T_m81()(;nIKtv|^Ya8B^Vm@1c^;dIQNWa_fG6~xQ~+}(Kg z%{sPcJsw%udn&qjb~^|t%gzZlw~7P&bk$2c=+@iY5i>wnB!ndAK@Js)&Wi&#XoG*w z6DaUq(MJHJiYR=HX)Ra~ah0)`&tV&|d;XGSveG48_dy^M{L{{fb7&9 zh#ESWdC`gNk+hlhm#y^Qw*D7ch1DMr>#J_;c#ToUbDbC5xMG+hz)}cC`n9zZb94#g z5TGy4U8amsmn$;r*C(AH-zIsm>BG(urRg-+S@p&Fc@^o3=VMH$28~BY)7Q92W(5;(`mGRDUEAz|a~O2Uov^ z*eOowX8_jBpO@lK&qy|;!XpmT&yOK$uHaPN({c%AS)L!P1c8$QL!E*)&#AUMc!Air z6Tjj}SWS-=sO>>^FTm2>2lp^{*7U*RsvgI#WLE40w*-GH$&a}obuJT?vUjjw4+WHx zz7BC(jo}@yg%g!QURk4D&@||1Y25BOPX0h+*SnJ9$yM|(V#4n~)=`|N^(J3qewvWu znjJ}&=DU?CM4j2r+w!#fp}qY~mB2Y!zCL*$V{;nTge{T2Cm?hcG1g$s!eKbTO&)<_ zy9GgVvM&csityE6QyVk>CNTs;rt{zQs`-dDS*t!-r)r1NEv29lk{8}2s@>MBmAdpm zMV8yf*p%V^3meIrSbZ{sQYWv5yP$a@YaP#O<6H`8O!mh*d3Ar=nJ=RTBXp`_gXiff z4QgWuIitXqs-pxw3V3RYeWdvCqsr$W3xlj`q9z-IO`cb%)O!n3s7>KSE#?pmkWuj= zWaDoFZ{AdpU{EE-ADMkJo+`}Ou`iJ`Gtq$wikTF$O_}T>ivRmQelu#n7^f!Cgfj`N zbj$s`ZvK;%Sab)GIb(l?vyNp2Wy>sE*Lh+U1VH*^T;Im+hZIHFm{W#$v>!}e7F$x- zYc76W?Vj0ko7D6BZg4-BnW^S6x@#^q>Zo8HphEg1c)>xI?u7{u92DWos&&^|CPo#ByUt}n`&356^H>{(HLBN|;Sy*TbA zO}5BW_k_`xGm5&H=|dN{}kr5VvkuMeVaQoO9&=Xlf*{{}JSwvNm~5wCnR>>N7X7xX-noE(0BIo}ZzSE)YcmH0btN< zJ(F;=K5(KzxhVyBu^6mUfdFnfLhG3~EeKF^JmLqe1y04fj%~g9e|Sbai{C(eLRIUCX~=X2ubvLA5(Qn9&Bl%&7hem`cAVR|udkBwemMK6_;b+wzY9(r;C$ zx2<-*O%P26Aw-D#RI~=}1J=cZ7TbL^>H3b5INA@5Q{PcI$~&Jln5W9Zv`~gfa%Rcx zMEVlzw=)J1UnW$sA);u9(yk>SgS%UgBLvCwxbe?k_%EoC9A`JL;*V(D&x1rjL>YPxHo*o#|jk2dCUr9VD&W&rf_NfS=;iH=hRK>^UXiOz{bkQia5 z9qH>IsWo(8Z}o%rb=-pg18N!%FaD;ozUfd~wB*t8_ouC}@6s@@)Pr%5Fdb6{VHSG( zjjgzJ^KCYs6>;0&r7Y`0Et?MYgKE3uK2qacIBVffqiQI9^~FQ7QQC4(r)f0Qb|_-+ z(sync;3&O@z_La3nPySU=#ybg0Fv zZvvfAzr{C$5Me~nPiy?3*5kSKd!asWuj}3Zy=oU*8;}663ihZfErlebhpi%lfiM9` zcsW(n9;A?-I`A*i<}VPU93kFvF;-q?fRQi(W#~5QfJ7=EvtzOHR&O&Dr1zYDy|89j+$If|79an z69c8Oo7#@i%!oXSoDLhF#rpZeN30GyFB5w!DGb+L6!5E5g)@(1kAb4-cPqZYiHj#D zMnoOROZPuw>3>d}U$E+2Di!QE9h{ZLrR2@cN2OndjIbYaxdhq09s=7wJTddzh8wQ$ z(MC+eR6<`@2=WB&H*MBz07uw3{7wx~R{tt2=jSc;E7m059Tv1(I9 zG~@*aS&(Uu(7-eU@gaNE!>D&$@M$-olQEKv1YP&es-szjo}w!S~G7XoVC$;BHrf-kB+g< z#3BSZ!N+tDQR@fxBYP(2Z3k&n>rA&=xhhtq_Ox={Q4icei29Z}E!btu(QpasVqEhZE>4Gk=UV+J|OLYml+D#S;Btw$GY9S|=1`|*;o=zPcj5_m&R+J4<@ zQUmSsJ)cnU>(L?%SeTmBKN8h0<{6%%#z9_X4GFWx3%F0lv_D@X#5P6}pxbO1Szl0l zWy1lnby8N64H9}XeVpb}<%caUOAIt%4G4EF(>VuOF1`cNE^Hn_9=>vc!}e`uT3U_H z=bW3!#ZKzu$FU%2#Ad=ki}i@0y0!sSthbHVX$sI~BcYf$#EQ1drAW#-$MZXvc$Kn=;!PK zQ&!JUDbi!rCk`_B`cl{@qD<()GCJ98(0b~)$^^2iYkeUH)-TG?7>(DvW@>}&M|6lp zpBQ*5N|6vL@i~Y5&EN#c8s*cI?y=m|vw>NKi@QHFCvs2p{{}g?H}}31A7bP(q)4q$ zR%bkj{DjHW(Bc6VW=7l_z&auGbw7R}03sa@_t=u+M^4oMX{1v*AR`gLBk_luJ=B0S zcdzHifNTH)wbMksgswWS;2I6x40UfXEyLWGP~ThI47EIWZR351Zk$>X!v2ozM0T?O zKW0}DUS`fKHYuGApJisDCjl-KgEy%gPNBy^FX3L&>4l!Z7%)*3^oD9NN*15`$+>!> zycFzYp8bG?DN&-t#BFgRRw*1Vx9ik1sfqgV z#E8Q#+#V1}k9u*)&M{X)nh>?~&*t)CF(cvjp!_sbvfJOt%d&qVUV^S1h6?|~V|z%p zf+G(6$K_oC+CtodOvFkz_?0Q5^ul6Xd_Bp%z7N!y#IL2%g*?RZFW-4!Sl(?uRHH0ky8+-8?nfYJlli`fZ?K=xl!GkU*~uuQ5qjqoF88 zS@1O5H#@-ubqQEjIU^5tRyg+pgP4S3VHabw6 z;@gB&0BT?7fAQa=>)8Mip1&{d90*qh92D#WtR5eq1Hf2?p+{J;|P@MQ-93h5O49Jsjx7xcVP; z_`k`}c_i}Ju%uMP-KPKYxs{vLDyVoW+O}6idYc{=Tlsqny&N{N(1|xg)76;i;!v;pm%U2}C^h?=eTcn*Mu2E5UuosdRS%CfnNyG^rO z@I0>75&NoOGEqgnrj#s6v+ZJ49}vs_nrV5k#qi7_<-Tf(__iHe4;k5_mNv%&13bd8 zrN-T?=A&EmeNP9>IIGbaab>ruvtC_1N_0BDC`yPSqmT+LjU+(;t0(FhnUMV0` zP$t2)Ft)W{$eTgsAmq=TP=8zm@w=1`I5GH>;;jw=*iXGydQN$7jZ^gEI?b~;_)V7l z_Yvea>23eySZ9uq%uGX+YzeUh{fT$nXb5?whsWMboM;GeVAS;r8eOin`K#k%8~hJR zClEWKIW*~9{5U1uTPra~H(Y=B0@5$J_P|;nRbSVH$8=$bA z4bGB{IxfJ~sN|6{4wz4(&B?cU$;uiZpr&h>3jl_~i$x^kgg*I~JJh@b2=vuI5$HuC z0sE&w-oN+BG~qriCqV%@X@KtS$nHq({O&GwUg zLi=l!SlydlDn~d|vQAhBd|c~5oJqML0yt%73!he)e-9htXr`99K3=!N zl)L;(3O&zh!*9;lU*-Y0+X=IHnWCfvF9lN6ZSfYP%uL^)I;}#m_0oviF!KuwpYD|# z3Es}9!;SdImibW;lJ(!n_wlqQwayM(l5B|VJb~ZAOYTD6ALp|{yx*tiVfM-`&;{5K z$4G4_79y4mnHyW%FU-Ok_oIwvf?z5?i?M*3`gMcUYDw!H-)kB(%c4~4`yZyNRcQRb z@^vcp{AS0XcwU3tL5!o5y$Kzw>HM!yH-}fWj94%>gMrwzZ_POdx?kEly7o@jF%?+( z1^A4w>r!G|^^h27X6fjh2vlyg(5i1L>j!uL424zc2205WGDC79=6j8>7`LKZ*s~OH zT&!#!)cXZvy@S#&8x=ewpN$oNO>!o;pqZH^Fy-O6SB#Qu8D}-aFvvCk5x87n{`P(g zM~U3J=metN;{Ea(YJ&~DdwQkLD+3xu9WL3B1n0WPTow{$0?|S3Uuz2xNIB zT%TDk_@)o9hd8XYXNsE*+F4lyX@!8$_e*T_1qbW2={^r-+}J9!BLDGb<@F6iGMB!$ z{0DGRYrgb71vX`ri%Tu2!+HSbNE;20Z9~A~-OFzr3uhaXM#`k8E=|*Vfe;DBU019D z+3FqpK&jdZaBi6N)gJ@37Xi90PlNb6U`@{pk1hx~JLB~canzRxN4=lQu~|#-)O5Cd zOkLK5J^wk!FnMwsfKU2~Nc>3s+j4)56}zzAX4FS-9rb(TWa+5wqi~5zkC#VT((w6& zi=_OQ9v9n0$m+5Iow^;tctD7GbwP1hw>A8R=@m%p$xir`@$)AE~DIJA)NC(lE#<#$iT- z`$JriNK)u3|J96_U{42*frE_-)6+e4A55-`BzHOBvqKm}noBbDsCvN4*aSL-cMtK3 z@JAAh7Sd-?&99QSruUaDy*6ra%x4YYP=ofL3Q9vvzxBEatKPm^x%NppfZtC+a`oV9nR*?w+u%;ponZ$D^g!C#7c>KF}Y>zE@J zRock{piyO$+}~(`c({bwbeHWV*1glT`t^kLSI$|8x_RW2;u2M3VTLL3!7!Y|SgHkF zvaEj)e;*H$vrm?0+URlBXOI8&UXyU?C@!W;#2}KAP`eF zxG0Qfoxj=wqPc;YQ0P3QGZ32mSZ#1>luHShyC=9LnM<5@O1JUsw}Jy`!5agDChSdh zb0O!DY|Ysf9w%ls3IvVuECO7dO~Nz*9z)sqtpl>5p!YytjN)PSZ{{Z&SzCm4W*3ze zv$=~QG`_}=oVt|Ts`&U@&AmAsIf2`)ld2D8!0n5%%{mv=#-}TmbV&nb3LPAbGGxM) zJ)(Q0DFlr3)sIn`(mAL=D$}#WX(xyqE{g9{d%}iQ7-isB%EzDSN7o)0_k^*1G+VgL z?eAHQaq5Syw9$PEm>DZuRG-LZ@T*z?im=0R9TJTr+OfIjgY;xQTTFqx(!KsSP8}>s z@HDOoS^a4nqz<|CKo>=D-?64QfO@6#m)DyuaY}y{l8;2};})gUJ5h^tMt|5rBq8fF z2LHJ_Hp?&M?PYwb^7tXHgWfrLE%eS&(I;I(E_?lJbzayQ515J?l(nY4H z9hY_fTWUnyW%!oghxWb`VArc-g?)qtsbkO)ySV8iG{zoo^K{6(XMrG#PRxLA%YopL zFGEFdgRW5|-w^uM9;B1mO~qMUBI0*!VVWINjulk$BLiIsBH5WgP)CrNFaP~^U3wG! zfF{CcNb13t+ZOV7kNf-~)LIU3)9ZGcwXIa61)S^0CE})FlgL*AV7V}6wfbK}8A;%? zlkQpS_I6@D=|lB&&c2)orA1l)yuc!CWd|?Y3vSqPM{ie1F(NP0zw1qQHO}!!-@cn| zkVmVg?rft=^r><;SR3r+%JmWuGwr?1joKp16JXwy+MSAWK^E{mS0Co#dZ2#Z*C1#@ z!3;7QT2e~;`+z(+YiPqrKR>elwX02HY0X_FGhNCMo-B3Nn5X~MG<+3$_ttN9KWe0j zIdWzyxYGYj5chZ%5G*Oa(``@Mu|ZWmr3!6Sb@O$x22Xk7!)O}ET=n;DzU8I z6ckoI@-?@U8k&{yhL%j(jAcTwnfG@bcYny!4YiU<)EG1joQT<@YumdkC8SMinu3Ys ztgqXtHir1BD$9H!Cf}kJkgyOqtD6#?^rAdTzpRqAKVUYg?g+j{M>B>ztVQ;M?x425 z%YTQt*3W~g-<4WO1}HS9QKeuQy}hS9=Xu&#Hfu$#dB-SpYHz7tS|;UhDNjGdM6lBj zVJ!qGVviz#qjsx#_+Yza3?&Yh5COSb0#$6 zrheQjbtZDRW3sFb=VPh#Bf_q$(a4Fil}v5~U$_nU?c*R0(YRv8@6HD6u;E482y`+}|I-=e^wyy$kJA`mj`n;NN!9{7z!W?`ORtPj&Ew*T z`z$lpIUa}Qhb95T%#HYkLY24XyUpZ>lCU*ayCpq(n1u(6{D<1jHW5rbMP3siy*g@Z zaD`z0K0mS2Pl*%T*1RYpHo5#(4!jrQBaM+mR$u~KI&!Uz7!3tkEebs970HLjpbRyV zCym!Ny-yOBCgd!vw0Kr?2Zx$t`>2j%60N>O?}fwb0pkF(Is3obBj#M0E*b2{i%~nU z!AH7J1o^?PE>nEx30PMGE~2tI5_Q$Ik}C@3 zCX`5J;<*wL+?iYR*iS8HyVUwBrnm`bOwRDQ>oE)w7?z#y;o$~dzWdEjnh~y%c_eJT zHt-v*_G91n0K;A-L&oEucUuTx+PjqJ&6{X+2F=$tluw1IpUHfaSH5vU!6@-VBscr; zWS6^g#QqPgyQ_6I#CH?W*Xmn8s(}f7-0s}#;*OcLmNP6z77+69&e@d*G|>AD z5|&#VWHH-`-Kj2H1Z9*kC!r9uDuJ^Q7*3fdEcR>FEbg!cG|IP&fR4}*K>qn;fQ^}u z-fRX?y4Q7;fIn}}P^a8iYLU)a&V-G}TVq0!?|g&%x$BNT(Q#rNFv_J>8v`FoKD?vq+GhP{NnS zSVE&*yF1^$j+yBXx4q;VLbeu|N$tMaQz;Q4-9KdCGV-|gjeG8oNs&L#4ih7QZWWnX zMFTE*Miev?UxuY}#o4?_ji#VlhBqJdR!j9UhOrjf`J5Klx}9v9Ia0d>PLVY4s$5A= zd0pCLGJFv|^L*hyG)h4n13X_I+A7YUpO_P60;~u3bXk?odLFTc>iknxP2(X*W7Cg_ z=U6Ukp=&2)7yC@wG-xTR%M_eZfGh3IGCvu4L5EdO#%&}PT0l@cMpGNoEw81xex`mY zfBl%}Sg&y6VX4D#uV(sl2>oetaM(m62-6rN3}@KIdG)Ymc>q*HNNSEu5^@TObgB-Z z?1E5zh7*p^AxWt^qZ`Pbb(VJIA-6&AiQ#xVx<_a?*%NXf#$Z<#O~4 zGOQuPU3aDlVMh$baA=xgAL?pZVQj;#HN=?+S_U0`L-})jD1~WI@-|!Wo(Tv1Mk@_c zh%rxWfLs1>120y>^Pd;eyPe5AEunCjv1x45q6i|TZqV(KlcALtu-gBUOXd{>Z6g$a zySjc7VzTu$aWVa@(a@`tA~WIVocY+sPsTAy6Rwp%jh0zOPRD5*$==r)qG z>IK;qkMlf@TuZvCh|5N7B;8M7U&saM1c1z9R44b@c)bYP!8fB{0d2>1W*6b5+MDl0 zqAj%9C}kX9q4wZL^zhdqujcg)N)hjadPiAsOjL<#v)&Vxho#8SUd!LoK}EAT#3Cfz zGE?yL8<3SX1wvza*RWXP0yGIg6PFa8vpIUH|-%Cwm0F2}rmfE8%@*8^;JhQ9YrQ)GhkvuZZP!1tUs1?f%xq>`AHh@i>lPXDTL2$8v(ZSXGrU zZx;hTw?H7qwc9UCiZ2^rndK2u-qakyRJyHj>BnlFCZgjgQvWfm8Uk&OFm{h9zVb9e zr&h7V7AW8qgd&<)rq=tvU~QphYvcq}tTXQ)e?J&~VCm*pXWB4Adt%yEk#>6EK8%}B z*~IgoHUb?d_8WWm--keuYf01F=eYfMAcG|r#F=G?r=!Us?$GEOsf+y*A7EO<68$Zqkror z|H1urnCaasjQlQII3KZN)aWWdT;xm+z-2(YY_Z{CH>$d9nwixMCw$>d8# z)1)4X*tx`kqM_33#GG2`>W=+R)*UGt^EHBwoL=C>+NUd&8|h0bntXtkK=< z)I$#x6JkrF`Pf^bxhd5+pJrRRYq;66wE-%yo~?HgejGLZi!%8$Be_r`I~L4l&M0L3 zaD^LNRzX;B&ke^9wPZnmwEG$a8EJywAKhLS+*=lcNeh0Sj84+_w1l&Vkz?w5&M#9_ zMNY;nQ$2lgA)`&VxFL$K%uppEd_D6F#o>{K{DO>6$&;-is>$~eufZ-BnXJ@3{cKI& z(ES}NcOD$eR_PLYC=!X}eylmydCQTE1qAbxNHc{9pFcWRHHxWA2#vWuOUA`o{=_(|k4n2qX|Gyc$j4cbHJO%jMN z1`dC+9uezFIEU+$)~%1;FXC^D{x`Hf0>JSD{5+^6>Ex$9gN9glR-47wo>`+B7EAB%OhE>F==fqGa&9~?9K-LDKsr~D5WfUK1*(E8k@>8>h$F%f zTBU&GMDixXux>trwnn+D=@T?V*|)~*UznX1vF7)yX6b1xaHCBl=F`)qbLC-}dpo1= zlvN?cJ5@^HPE;VFvxtsFsQ*W2Ftv9AJ@Fpa*)GKeh3&OKIAsZLvyTW!) zRqy%R^5nEI1UxRCJ#D6A9M$iK{qhM=L}E@Fcx8DLM`HOXE~MC4DRId{D=TZmA!bA!$p1CG&^@XIE=$BWfEyA zpi1%Y$uH^25gc`=`K0T3+!^zhTfxA+ zj!jn(uX)G+lW;%*#%lI<>(s$yS5lqNic*Xp0T{}H6JAwv~;EqcQf3w)x zUX*DtAUuCM^o&CKrwErvFv4)_9E_xzj<%wtdIb($<{po$Dc@q9oC!|)8XRx`eP{t? zk40T5J-vlB&VDX$4Jw9BLiHqD!m|z0Y0DPpq0jDCt_T#EDzzBm)SNKxY_Eu-9c-=7 z&Qo_x6n(bA#ADJ0 zZ)-anMl;WLBCQJV$-HG&08 z>d|;^VS1*T5c}^eu>7Zn^n(ZJjm}?d%hWNUx8Pd2JK10Kn^<@Qwz!zQ;pgM4G&pz| zR?sxf8K~(#@HKt)hhbEQeXH7Uly)iLnc!K<&bp+vY_kB#j)c~9&{q=rJ}&qy{{_Z@ zfRXbb91Fj)V8Dosf#4B;t}mj5zNnc0D46VKGiC=u#oV8S8fEOBP)KYsTPSHT+~=OG ze|JGfs(a?yHY;2R9(>*2BKtUq^-B;f?(?}GLf%Zrgqe{YVDGf>dZDmK zmWX}Lnu-smo~5*DpVSKt%e5Q0;j`FW!UGSDyAm zCU;=GA(BkrnPY@hb1V}=(-@V>+dCD0|H{EMH|${3V_)aR#CJpCBE6Vvg$buI?S1e} zoH&2~o{Ponbd7)`_g?nU@zZR8Awsko$OF{#c?dlLbpG$(8`{ZnvG6<=@1m;UsxFS z%awvSn{mibqxiv7qEdi}a2EBZe{jZ~wMqE|C)i4{O59*9bc4d{;44*TBBjcW-SR6K zW?Z=87jKFh6%wF4g5F=o+J2-sM8nqcaLnTnXs@PAi1+&zoh&I1aL4nYylEYRlf>J~ zYG_{}2P37Q@w?=QR*UCKB2=41qiZfq31LhhFMp126Mz;LRwI#V0Vad$}` zk=Brx3rp6KsPw!d;eQa3GxZVxq_n%gT}EQ70S;}Q*Uj=+e4U~(8LdLgW=23T((Qz% zc!)`qTx7xqY_n~;-#EY{S~hWfH=-0*hmh)H8`Z(BA0;YiI?}omn+1`;d9I$f!a55< zjPmIlv7mgzgeV6}=BJa@$U`zPOan5HTc(*%W=H@VFqNn~6baM*q zNJ+8)59nmHff%l4K+1PRYY8S9Rs39?($4_f)VivIF0%r7OH$9!K(GrT7D6sbxkCXy&|RuzQ#4iJf}-{d-d995k7h7Y)Lnw0;vUF04UF#+r{{PC+Gvs7zW%v zpl)V_79h>Q!EL}bRc#(SgkM^eUziT_KBB7&5|C)gkKmoyvQl&wq5r@6u^nLf3&I(R zWu)f>&@Z~6Lq|_b>lmuJ;xNnSC9PVieh`-5o?$ZP5vpZGO(z^n^`NehH#bS(8hM8K zBv=8rZJ&cahcD;W!PrdUFPxtlp$=|~o!ixP#v)fTLYF<+vDcy1%}rP) zj7WSl_@`DSRHLW+Q2(>^*9YyGy0jST<0Q^TmOdH#M<8Ff zO8IDHUARs1lnyqg9Q4S1iwW)C_#Rn>6pcuH#Rq5t#88Y(!0`gbbIrk}7A(05S0-8j zlhP~#IU`V};yTXN6m&*&p$XQA_xp{8pgDX0D#X+GekrHEe&JD_Ngn|)EWb|;*1c4$ zB-HcwRQ4FeY@+#PTMFBN39`=~d5pY`47&0>@ww~5yQ*?(yKt)jk+*@bHl>V3Hp!Q> znAP2C(hxA$muMXM0L~lm9AgO&OK@u2DY#3TXHONPmCm&RMFX{#RSfVs@G_c^g0GYS zUc&Ouu4pysi{xolsM|P=X=yj!Z^X-50`clXKdSa|u9NIj2YP3vU*!|PJs1g`BZ!8j zb(8-3j$aN46X#m=N(b;#7{qdC1ue}k82V+^z~ih;FD838(%=k3&}q+ z0xnL#%xzu))567=fSF$@4?DVug2ook zo2`DMeDdDF0#<4-vGc&#?-m>AsDM^<#M?qQ zmV*_l0CeXl?;4p9<;nR&zaf$F0NH0A(lOV`$aSDfD*t!cQ^eokA zF+350$xI^r3+zz)06ypir)S-d4@g~^=66`jYBxOrBL5!%bwG;0!mDg~dfLpLSL}!x z`sbFH7_a0yysQ{qORFdvaxY2>t*Y#}mr;_n(>SdHNW{A@se<81EhW8*)bt7`%;90! znQ7N3WK9n!r5zGbL(;L8Xe?nrD04$fy4W4?&Yf+J&ckWG01oVFr-0I0iQ3Vwm z@xiok`NJ4xzw-ywK3G&SzB;_ocP8(HB?heZP+Tn*y>BSHY6X452zoM5#t2H0OP_-K zw<_owdCRFu!gG|&ZsVW*T@|H9_gRS4T=;=M^qU~Q`|pzDoJiRuQ5&e8cWqZe5~eb{ z^O9&fFB@lA$+7K4a?Hl>BMwhXM~6&BhTWmybE62F_GFgDrTzz)B~Xq)&uIx`6Tj47 zFj;qd%DOOt?P+Lsjxa^stvkc3b=ggo2+prrx*gfKV2q^o2s9DU5M%GPp*J?zPK@j)1QE00i$UFI5Kel`^X_M> zyU-RK7MDr@^3Z}0ZUs%Fx@7*xD3h7vl$tiZ4zdke>dm{D~84a-eMi(rs9a~XC^6jq@>~QDFhXuRj<=`x!RaMICv|=_YlrMI1J)ntn_>h?H@tV z@6%r)fU46_%g2=AAcI|x5Ou8dI^#H{ABJut5w@M#Ryi$vd$N~Uj3~doEdtiM%9eUQ z0urDDi(*Iyl&aVOBS%P#P^sM3k?ZQ1+rg`On34jg#UM&d+qzV`8F9Yau++=I_6T;9Yk>Sb zFUP>I?+!AZ;6on@>O{44G<*(!D-_pu1;dI9db8Gr%5EW|P7EPj3dwST_TVl?Zd5)_ zy1pG_hjTBi9|PprDvF;OAqwkzRn^E$1)y1^os=LPLPsPGGz4}~M?WqTb=Tk*;|0-D z7=4%F1Wa@j+yo4Kh1xe4iE=z19%jy4z9|PGs0ntCE+X;_&3Ws1tZ{M zp6oQ2asA!IAoqTE)j`f58hE>RqQ>xbl!pjn*ja?&S z8dbvvAbSS+!Da`el&>;wZl_gAUNipHe3~Ig^(bbJx82p6@Zob0Ii@2Lv4w+SZ+Svc zR*CT6l=Poyb=5YausT}G*&bkPL#-SLq|2pxG@$#5MBcT>zs9yp&wnTVK(ETPQkt>h+e&rn#Ts3Tcb<5!EkOG12qW+CU-57&d^E0WCQK z!gMr^o5Awx4C^v`W`-=Uzl(s26up%qSz-p5Si?T3xucL?Cq$E6M8SdO;JDK~{}F~Vv<~pL#X-4Mw~b)c#+X^5vImS9b}Y*SWcQu1 zD?s%MJ^)j$eb;7RwQ{Z?083GfL}D|>@C&AwW5mQqrZ>MEk&8W~TlPH2UyiTh zP9AgU+9WGrmLO4B_jr)_!W^c;km-}!*KV4yb;}yH5s*p|wl^oLrOgK1V zlt_le6ML@Gc18H39f!%IZ5zNw-a`YOtkgi(i!}!{%;~LD(2*C??kR71Zi4Kc*!Uca z%T<{fmn{-Ops6+vZpOd^oB(e@&^fnl0)+!kL?&kgufbzu{pczUvdliobR*u_psEdX z`ceHGdzz5?N~=?QQ_c2A}zj4HB)RT@5^qgh_d6=0mQOE@z@Q7e*`f zxJSAt?jTkY;4VQEn-NU(PjvhV$Mq3=U%kX9ya!7Ys6#dfy}6gadzVP z4XEiKF_juOs8%nCzS_H<)OR4EF*-&s_Kdx2!mnV8*mQqXLF3mvFKwdZvf~B))vhi> zhbZG1dkceG!do|0AuD=$ZtDqfhmxtDKV7YfL5%qAt0+t9XLl>ls@VvI8K-*n647@M zdNLOe)6jJfj1cD0*{x#!Y9D8_3K&p)%UKl z>^L2$1nMkj7mZlF^}cO1`s0T{@kur)rfkg6yM(YI2g7ZFR#yBZ3~K0@@^vmR4Vzc# zf#W9wJd`R*LYppU1dB`kph`n~($)zUeq%u5${V~Z&gR&WBPj{n9;re*TTmZx>8)IS zd%^6BfN)>STf}xWs6VT*PD?_O82faRCE(mEIuRk#VwP7T@y2Jm5;rb;r>)R48L$%Aub!=0<>2=L>hrfhqz=zK3&XG2l zRn3XkoJ^zCtv60H#MdluFT-CsIkp}RrRqK!-Ka=1l~*+0Fxo{vusH~hCa_nJk%*fJ z>}{=30{LFe7u*|YrFV_g5~eZs3>as#y)^s#+AQB!ZKWt9Va_uBDi(J{K_FDp&GeBn zk$XZoe*a369V9iWnvw;xfxYX_w^eBO=}`Tb4~-WkOuC<8NJ2|0YBGWo>fErU*ZX^T zYUb@MFz&`@W8p`71N=}=KeR4KXrcwy2nO3uD-xo}@gl+1VS&^1mgC(NKqxS7c(Dz& zv<@toTy!;5{^m&q6fh}?^dk8L#L|=H4KK_VW-55_Q`=-~ezE~QMYuthz&oQZrzhlp zO7KZy{sqI|2V?}EaQe1O7m^W8|LjAnAj}vxXt}JdBSl+;ceZ6z{8W$BtYoJzMz2Yx0}hS@HYam8NWaa4@glCWPt%nhU2P11hJF>J0u5tuwrXb`>- z=}aC59y#1LK2yr!|kKFKAXM4u|!EYMNvA3WTAbYcO@HTB&7$Vm?b!wN2@e6py&b&e-b2)S<&3;DpT)hoRq;Mzxm+o2k8 zoq&KXyrNN*+Zm>nanGK~Z@2YR)Fln=HFkBqn+!%wQd&dahv#1rD);bDPF|k!O`Jz9 z#FDye;uu|oAYAkAc82-E=z7!gj?>xyW*HFHWxt_Wc6JH3+#GS#BYi@a8#xS9gU z`4qO)z?nZ+1??CznJ7_&51Y#1onWhM&nOqaIC^bj0{UJnydPNR2C)LA#JiteU!x`J z`{h}`kE%u`8nV*yAfO;??5@m#5Ng!VoD+|tFxil4@bIV_)w2AWhQgt**JXnap+u)` zKn%}6L;vQV!Z+j4XV46jUKN|1%REeUsW)s56chz>JdwhppG$TGT2(AxmUAqT7ho>Q z7No>S^`;q8*SY?+|JcAYjUM3`i8u>MLlE|*qGm>&ZLJW(ltD0=Chg#`CXA0oM8%D7 z;%mENBM~9#IX-P(trm$qxo-H|Hfui;JJ0b%zVJ+4xBLc&go%o9@Vmt`!=mjP4BHZj z+JaZc;EHHTzA+iiz$g6PAeaipmSC*WBQ&~Z#|=EV&+dh;I9GX+-5R^?W7Cz*#dE9v zx~L9DT09nZv3TA5Y{wYMy&e=_)fHJQk|vR8SRmzi+B+o1K+?)$ z4H!lh_y_CbViA{sN^iGxZ{dx!HoMjEZ$1)yeQ#^~3HRC7)zq3-sf~y!ZR20{$+MT9 ze?0H<X_NaS7_7phEk+ZuFEid;}H$$KyPu+D-ek4(oNEHj5n0eRJ`j}wDan;t zTY}*$mkWwtl~;Dtx1#Rs>Nvb1nAkF?NRDCtq3htRB=O_+KF-!@@dW0e?voE`6y!{V zJk|;qu9StZXg_j{_z&+5*nSW)H$< z)!7}c{NrvFo|3xTS3)KcRe-ag!BC;(aLX$ykg>8O_s9!ZBi zo*rBnC0DKVn9VTX0XZhFs{cp~&SCPrtuG{^r?_bdMQR>z_u$!5W2MYJdMncflITau zYlisNUn@;)i=eU!SKx)f(4#i9lf>r08s}P&k@t6XzyK`IoTz)}3C}wW@1cWBhz!Yw&kOQ>6d~~AwyVu~# z?%@4Kuz*SwPzHZ?H}_@wtBiHdavRGgf2DX{2FpPm4(=8EUV+BfxTiO$^@JNxM46r*kH)}vI5N{4MTR*+fIw8cK6Wq9iOEw1C#>q)C z_KZ8cMyDJGV%3F~j4fcjtr380rnAOEcV~?(q?Y*-`iToTJ1fj4*;E^7(r1K(|6j{R z$|M}-tr9Wk7Bd1BTYyMc3e-=|dwy0Wf3+_5&G$>Y471zwK9Cj*Qle7G3UhSN&TUTE zCGzL)`t`?F{@6AOi6hH_Wo<6Q{*V;r_0)KU`AdYD=>*AgX-$f=b#rum1ztCM1MsTY zSKBQp+g}i~Q)lagsTMAQADOfU(ph%yd|P^FcduGDeM?WD0C7G>h#Jl=ERLqbW-7A5 z8L#Uo9s+z0!W79=7TC*f7B0*7v8mkjoJ!oO_T$O}71i;7?$zLxPIZ&3Dw6l$n?VQl0 zYYQStC$g|ZAyPmWIm!2$0_v&9(TVow)+W2i-*VOJ(PK%7`{u65+hmS{F@{h$(%OhL zM_lEYe&Z-V`y>T)4j`%YG~nE63XIyfjs9mLl&H?>zrvjirtbWL;rg^#$F0XgK7CON zU+~Dxd>*ekQz1N+vR?Qxw*}9^UIzFWdsf}I)k#BK|C1`$n3m_9pH$ibP}OV>r)^^J zrjduqqP)JB$f0HF@At#6TLYMbEt|7&7#oMuGs?2cIO|oGkdJk$s}RN%`z*I$ zGJ}jex;=q`fr!klen^BQ@yO^r`xaV%>yqzzlN6H`8&b1DWmc*^zGG&E%w0((b)s7I z(I4=dcVGo=O7#;lO z%5Z8JgTilWke0&$d~03c;@F=dJ{(Zwhp@nXt5{iFL!W4$BX99=Wh?aD%EY=FyO#Qr zy(~c?nX<4^gP^TSE50yzTFb4y+%uduxJ5QkJr*P<2XeC!fmN>8maOo zef~~613s!rn^56{2hx_fni2htY-;`PwW)78vJo4LfyqJlK}Cs19#D+qVVm+7>5h8W z7>wIA2I^L9r=P0sAmr|))Dr!*$rWVidh)yfnDXB zM}_3Uv#5`&_va2~96n?r?@`raQS5#wfXVwONbfE#$!a2*b*uCnhxS@}JfF@2gnR@R zM-Lc*x3*W&_5JFrto1)nNShsPs{AnFx1uTilH=i^CSKl$yVd3_x=>zFq2mqsQ*=CC z?!sB`CXMNV{|uuOpVs-9R`}+FN>Z@J;*MLYZ*jTWh}3^pSy42l7W{;hy0kjNlw!;+ z1Aw>E<^rN)+P?R91gH93WH-G#=716SDJTo9FFG+6%@D`B4f4r)GUsKT-G4j3;^A4) zmm{`v;F@TUmn`_!D0r&vFd6^r?q9BWG-yTreCZr$JSLUA-y!p}t6^al?0*iXz-5F` z$F-(Xeqjyi4}G`k^gwtQKD`?P5c}WA2V?~?U<-pT535#Ga=qNeAP@%>@U}P$Bs?1C zwzB~nIWVOY2Rk=d&qxLld4JZN-_*OKG}h>D>Lp?m#J{$5pvPizkpJnM>C*m z6o7^ZL{ekH@fKiD#D_EiW0$%`fvJYi}vf>rU8gPyfdzJQ`jAVFr1_HH%V;tO7YJQveRE*tm*ygL3gO@Tg zhn7t{?I%E|(!(T&s+2%PvjVBeE09r^QOtgsorBZzRNi|corfu#L+{ohQC13=m5P9k zhr(y90nx&wkmUWy^IjQ&t&&S$UX!_k>5cx$v z_Hp6VA;na2bfeThAqAQ*2Trz8>_wH z0KTcVUP}@eesPSk^OvUU?2?7zZM8r12dqW~`0mN{` zVQqPk_>h})G&Oe`;H3;})J{l5(*CZ_2~`AL^5}3xzemkS&~1oBE+H&MTQ;E@AAns_ zA1QXAkb=f(+da)0m5d` z_#wDK_)IMc{oFBL638M|7+2d+5z7A&^BHZzrb^qS9RdOIz$y!!P7gevRF+<%9*1+| zt*3H4LQud^@%nmjxbdXsmY79g{!yCGtR2nz1CqgI@eKt!R=Mi4%ul78Q}kB{SIH~K z+>@jwWmpf*R?KIdexxFcYZ5ioR>ti4qT3i$)Bp0A`F*@1vSLKillDSWKcv48KB$AZ zFoMLNHjUWOTuBA|Q*v{zS2R4m8%g&daf}|)(MlmKv%#oIyore=?kNgQG**Ftcu52$AyJ}C5@%4-L6l*+NAZ}o^78s*U=&-2>AvqE&8I$c;TiH zB3+srjC3$EknL659i#83PC+_6DwD-WA{u?EYE43Zgpq+|AoqE(7V{aG}ut&Bs8nm_2NG zBm5Shy+4SVTtu#)9)G*C(8+oeh48LG(7H|je`S~T>VQog*EdPO z@X1XCj$u2i7L;t;s|$?>gqdq67}!=?ve&l8*j93Pbf#<6Y8IGCH?Sbe5`Y|@mS5r?D0(D2&<6r8uCDFQQ8 zCflFuJXZ^cxOITc)Rku{!1`g&!9=WHz|?(XinG4s=o2-=QO^L9Oh z20!kedlBnZV(&4B0RO!|*phSHWbt6f&4D)>=iuyt&c}l)6uL?}U=|1@;u1bQrpj;j zLy*=bDqi8?aQV_J)uUvD3<+r4XCDD3nNqyt6L^xLk&qITL2 z-WX^?J?`-fRSNxG)`8we!y}i#Q9aVzZM7IpIb#Rlxhw*KxPEL`m&JfK(&J!_t$Cq9 zSatc|R;*%W5mG^JuWlmVsb36@2+oSv{NeBhWJ$h)$S}oX_}l5(1}8YRA}YpcDMb&Q z8pm03FW0Xx-=YO^iw*YsW3NSz;GAdkEO){=#-4&I+q;-5M=c@*G%D%XNK;4TFABCg zUSbU^!H%Nf&h$^tt!`J{zUKiPH6Zh9$(R65qL9S+68%2T$bC!}on=5cHEus}Urfe|72(Z;w(mibmvNL}F;kX5- z#Y_a_V^dEiWEb^3fMhxj_tFe+;^Q0!Ar?-`UW(*D^%NvuNP^08SyC1HAL}h(xkLAM z0@5DMz29dD$)fMS~ zE|s6RK$DQWL;*avXz+h>uQ;|#^5gG-RgEM7pb!;vk6bAWolk?jXSW)^;DU{JqQ3A= zNjFL%JFf7wF2bw|^r5bwiQTAL16N1Dv1aJr=K@TK zKv^$L7N@Db0b|f+242S;?O#@$cY@h9ztu{W-hYqK+HZFI1W;)RO(}7%)CrblbIiQg z&|C;?79E1O3=L?JXp!P5iEPR^bLf`or&DYQ0cSFcNhxb#Tnga>4haZc)y+~L6!*1u z)>JAfzGv;{2GEfn%EQ2F7FkQSy!TiUQZ0!Fh;eC=Kl*)6XI!BEwuX^lQe3*E?v!d+ zfLI?O_2lK6%223|oUKQ{0JG@Jyl*)UStv%2FAQ)Dji)kDMAmz=`{_!3Uz_$RgY37qk{P9I0J|+4sNyM zSNXZEaQek^&8_Nk=Bx z5OrM5+4;4UK^$sPD9LOQgBT}BiHOZSvb^whx85OU7=wU>k&=#D^@LNBQjq?}Og}+N zeeyD;my0UfOL~nX2YK*C1(V66gt2$gKP81j*YU;}(bkrA>qes#e1V|9U8E7u=x;7!~JuQy`K$Eec_p2ZoWgqfmn^rM;i&aHf^WmZ9Zw9CxhV z_LOK}{23>nQDPt9f^U|rufPPEif$P-8V;33RI-pMtOBBvtN0L2|Ksf(J~|2DpTIhe zmTgA{>g7a?o6(|L>wBhB6ky0Ro@1>drdN0{N6XKV|7nJc5}w|4YUp==TEagV6i!Gl zlZfhdpM+2!xOCRzKqS?~;~&_u-N+2y2TOCgh3Bu0$(Q7J)K^Ix% z(Sgx+&B|gP+qEqLfFgXtDb*q!U-&3P;qrVE>_)9qi6VL>f3-40gWO$=j?gmVWkY}) zB?wp_v;MZrH{zr)OQECXH$$s2;uK}ma=V3Y;(5m#wr7=Ueyl{Hx;4rA4^MBBAftO= z_`Ipv(xp&|l9!cnxK0fbQj9swSLuY!hU1K^M=I9xSMN_U012@#KT}-Itc%|TQkFfS zZ0?tE^eUoKx5vHN|=uS^|9y3Xkf`x;F zu+LQ9!(Z!9b86vq9$5L#23-t_G0%DpmSCK;NZ7IGz>E;MHE(zfaWNYnir;Dv@^BjV z5ofg1H8(d+d;c?y*!Z?x5;+@1XW;UTR8Kb^WiJLyK{h%R7FXKN^wi5xG*`-K*NcM1 z{xqiyda);me_yb{Nw?3|X8k%<0{3}c?;iqrwy}n9@oec5+xh)wV$tW4n#+JGi7-Sh zx-EMhf_?GQcS7a1g8XFw*%lL@2KyW%7xw7g2jU_Q4ExASoryJ3`NR!v2cwy3jFH?? zn;*mRfamI)EdUP$+_%~CBfUOh!*H%>Bl)eQpjV6u+tX9b6f;9v>SkA^e{sRrqY3QT zs4blFl%I_ks@g8tyCkA~c>ez(P6mUdzg(YKc|#l=CV0G!#I{QFxOWnoa}AERAhA>~ zMB&0ITSFP)TY1{R-(wk{X457Q;P3}j63z58;M>%_?~#+#1-S0ZK@O{9_@_7#l5{3x5ln&zHew*a!S4uat*9g zGTVK@GOM%vnj-B%ichbV%8Di22l>!YTDnc1S1n<&^m|Q&%;0!ev+@OAtWUNq^MuUTmWGkWo zp(!iSaXc(4j&bO@K~5L3KPp=w0BJ_wTrcgvGMy{dD?0nyXihu7cYnRq=rIH=RUNx{ zmU>gx2Qb6KJ5QC7bX$>)wHscX$C_drCQLG4mbzJ7$iKe)zNomT1iS!ItW%l`h+h=x z+se9z;at&dg~ue*nOskDe22^#a%dbBLnl{y4*^H;mYstWCBX~TyUMy-ywN3u9lv|@ z%zRG`_t1$N=OnrrG+SVeg5ssA<;Yut=`zOVG{H}LxL=UNkM?Nlc{!jxAFs@|?UmCC z($`bEoObP&91|%B048o-x5y2bJU)6VHEL) z&%Sgy~QfK!y`J4{gq)J+dher97&JakX5ig1!lwD}|~6#11~d zW4#}pnq+kzVn&YmQ3jvI;e7~m81tzI*fjlme(50gWoxC3Ms$e?*F!o$LEOw_4w<1b zNDoC8U|rjlwyuyAs2~{3os4CNJG?HBAp^tfw49H?D0)}*12iZyC){R{N!dQcNWD+m z@k_cPrDG&BLMX_XCb|qCt`?oLkX=|Du_Q=I}iNQ6eROIJtg&D=25&P=4xH-~c zr^%`b+_`$);VvIEDxJyjM3fBGb21LiPUdbZnd}fUt-~@n@pdZgCp`_|ahA=R>$`Q+ zeh1>5G|5`vq~4%;%T+-xW8y2X#cV{11493&*9pBRa42zu9LdqGt6b75RMaT5;YmeG zn4(Y)t(^DlYMzkT|35}ksRYEFG}M0#Xoj{)60JC;J z18=pvDaiGPm>WDV^f8gF+B|#nQK|pk+n5g8UR>gJq!q{5V8aB{nMb^<=Aqfu_(!ZK zbpf4oaA}f zkjI!&u@uTKqMjO1&l-w*F-XDP*1p>6pr!3a?0%dw8XMDREPJ~l6`@%TEP z5u|txU?dI-fdG7&Dm03>noNAF+`Y7}BG?mk`E{h->Gi0W#&JzJK=d=R z!&ZP!hVz$m5@4oid;n26~5~{l1JGd0!7LKOf2t>sf*mMh21(;{v};IzkT^aeC;=;eT4APk*vqL7?=$o zT}z^q=E>+=wHlv;6FyQUcr_!H3wP(d4Y6GT6p|}e!yQHnNsT*|+0cGJC_pe>+C9}= z#!(lAz|iv9+?k7jl);cLa+8u8{vEFK5S~@310lgXmKWqQdkQZuhD4>O#ZTPDtU%DN zV2#J{G#2=Q1gNga_h@qXF)y-VKZLE{T?}B!+mRE`-x;ZmFw=m)LBL=WAwwSEso%AhWrgMW)cA= zf};Zy&`CflA(5#A3M_2-wkpGD5CUy8RdD&?TRp{biy{hl~N`*^Bu8o0A8jEaQxN*_0sNj5W zwmkgm%CYw)+Jdr?)jOwoHonq|4NV7VK8HWC(=@p1K3k4LlDyD{+G%Sg#;%$O^qf3= zOTyA)^r^Fa*jq$IIS*w3{M`)EbMNT7D9KM!Nu@HSc_hFD0KY*KeM1LEW z$6rNHQT+Hu4dC46fNrn_h5}X+Iy8>pE*39WQ>p1)(bb?lmo$RQ9G-6|3S(jj^=E^2 z8@xv!Hvjwm8Gr=|IX}>)yuDM#!$p0zGcn0&-_ejoP_3%FwNC?btqXUQl_pc{mFbj# zcw%D$v`)IhUcGcrlE*{BbfZlJa1AF^5LSdi{#cHo{m4StNXrNh#~xp+OffxKj#lWM z_`B-d3#Nwt>3F1N#y2!3*?rb2Eu-M}0hoSDSinKfl=6O(pazQ?=Fml5M^%ImGbm48 z#H>ahexBF_U@bI}Ta@$X4JmFInL(OGc#Wq5_lY)#8(BK$8gQ9L?e1D2?^mDNlk+tH-NSaKi@cRTFIMo=Rv6YJ$UCDGQ823>6fZ8|x zo!z?ahQag62}z}+qbM>N-oUA4ot(DamQW3Qv_lh6AWu7mKUqNvYzZE#ak5Bb?XPk; zW1PXv&#Jz&AuY~UTg%|1&^~lLYAty=_dbDC8L<@a;HjyWgCwZ6h!J-q*knYlz0rT9 zQIPFR3M{g75@jfL?Vo3FH19}znz?5a9XV1Oj-_Bfak?0msNGe$-Q=??=M^izD@=F$ z@Z6<~?xSEq!p*YbW(;EcMhPlYXu+5Y*d>+_&Eh(W9vnvFdrf=n1opr*7YiFGaAR!Q zN{%$J!uMFguY}PcPfT<5<}aix=++MjO`73Z)FG_z4ru0q6FPDVR3XZ#7dc9UUz0Rw ztYs!gBg*>~A|kG+R-2&NNH_P%CMyXj)1Efq&^W0n#ZO${0xwe<0s3c6Pds3dS@h=R z#8S=%^;PoF(Og4#gd$n%OC+{*9ZZxMe#RkdRuX$;--oaQu#Ak-LhHZ3{nHBde~6*mb}KZItYt z%G9C^``hb8>ao`W(q4x#tdhsI6VAmVsKZ9TeOM85wR4g^qkrD|yGBencl*|_KDG)f z!EN=JX{rHU$GE2_Y{Us5uzqebB_sJHenkIFCTq0LJtEKQ1B%L<*X!1UaBRSk@`h#( zRL*77Ib-O@NdyCt0a~;*l=U3|+r498`525tWca$U#acJ-m_B;0hYp!W(D<=ecj~V2 z(e1Xwq|A(*9htPQgnrazR>Pg1ju>3Qoc3iXdh?xnAsS;zI8(z1Bu2t?YzjyCc58e% z!!#0Fl;nw4jRWuz_Ji4nqnQ#);*3yNpZ@6bg-HQ?m;Y~B;PNPKSz?doZ}SF9b%}N^9g0APbkEW^>e~-71MugdlXlRO2j>8s5b&871cjp^hH5)t-7ofHv9u}@HdKI?5SGP z20+roSkx@n;LK#pdXSpaw)kZ^6iqA20euIJg9f)GUcXv25fn@hdAFUtd_%E0bSZ5A zdG=|oC`5MI5_w#HArBzPsyKlWM_99+HUm6RntPH zzXcV8NC2Ga3*}_IExE=9nsIk;5ftuhCXLguDo( zY=}sxjsk3VZkA_*I~_a2sfa7B>g)VxgiOp4Uv$|(+<+dEQ3~v5UzBE0p27C@0F9U` zc}hVwc)`i|c_u&ZLG76JN;~gI494>6gaC5FY9DVf4nA2?DCUPVK|~lsb}#jM8<3ec zHQh|EN*JHb2`eCp@|0-=?FMvXXLjzKfQ8#n@COZ&f-vo1ZB))h?N+j|xvjg@DFY8D zWU?QkXvT3EZBkL2rNW8bUI??t^-!4{v10~jVBDd=;)y~J&>~cRXLeyd6eU!&$AoC2 z?2;+}sFK|f^gtrf>7cahjK7H4F!M3ouQY_m>vbbvrJhSE(w$qk@lh(6X)X5xu}GQ7 zbmH#ea84^(epRUTr=ytr*PfUb2ZK{+QU$0lN0SUY1zgEV^ zS6qg)gMQV1-?}qPd41!HCM9(^IC$%tP(DiYncki*RyST-+?MC{9H|6v1PZ6PgT@ zE%UI#-8Ja&~GQk>yrTcJDWlw0EWLJk& zB+LXikWzke7Qn8G{p$OvE=hhID}dS=L^bZO^^!m`AQ9WFXxAte3%jzh18%!4m7^3% z?;rxV?tz0&Xe-3iTNDUlmQR&B?Ol=MbYWWWq5QqGA0?T5>65M zx0dW0icK&kK=QW_TYwgjiVl(Vp^}0dccu?v&K<#giM+7rwHy*Z51br9M%p4+8?RVA zRIY@9St}cbHzn#;id4WMHnQ@Dx~f@@CL0@ou>sjJ3$$-tpKIL*gUBB~2b(dI@Z`1p zv(t34($(JR^D2jq<-atmAizz&rxH0?Yxcop+yzWFz&S=j0GNuNNt$##NW~Fmsru&j ztM3+7D#F5C#kKed!WZ$XL8P;hVz5!H|3t{C5S>A<69DVz!uSUQ8*i)Oob1&@)v9Gb zx|=976oH}V%>3h^P**vW8np1%2hK4Geb<^O|ek_bB92cGRIVg9PP5n$N^C3rOT!$4ZO}gX9_NY8Uf1cO}Pt zu6UGpl?wo%tp?`o0Xfg>II*^q_bEd4l23JW z%ThwY!L(5F*ngra>Ug5nT#(_TY5nGQ4QC(u84_Upxj-YmyTyw?IG0h2q1khizI;JA z+`x!A%^aGe6+OOZjfB}Weq1(65l-b>^T(4aW|JmeR#N7qL&k=0&~MH%9~k>SH|gGl z53d;VWdLVDn7^s%L~#_MbKt?qxfM_&Z%@!{6B;urikm4ZTN5+0LYkwK4J{lMHv!|< zND4vaONim}xTi*62hk2kRZa&s_}PGW*;Z|VW;hLh5qGu9s=0F(MZVUL$KNer!AD^L zgQ}r!Use+f0-y<;Y=pKFHeFcVmcv-sJ-WXi`nKEN5ytsS2~ZVI`ZHIi8qBSsLPmHm zci-2*(MvK04Gr>*J7s|Q455JOx2EM0Q5|ZQkUIM?dI(Jl1|hq#Xf>Cpi1tJ|)FyQ6 zP~}8Y8?%ke=kV$!!GH9CnPG>9vkeDj3K%<6WpRCgZYk$bE}Hfpy(z`?!Nn@h!pdP0 zA#tJw1)^a5`?f&%*NUwm>p?GA!2#b@OgPzzLY13P8`Xfg5Q{GCjks3fI|5rGrXkt} zg0O{pz-C2xJJ+sb^WUhogPa2)ZCyiCS)raw2-qMFDOaElyY%_98rxv#8PA+p3yV_5 z2~A>@V9zK0cN2sWCKz+B1Z zO;`HnaLm96aqoz;PEeCBu9*&1Orj`~uWS;{EzEJrnTcS2HaxoY-QX*JJm{sODAiZ= zvKdT=JoJyZWk{I36-@B}zd5=CilxY-7sG$i1T8i;%3TQf2g9|(5clIt4c<^2tGB({ zO}!2u%``%N(10n{>M#R~D~NUSIYeNbHmTs10_tHH5p1DCDw%_mail!8+1N8!pWcv? zv}DAX;l5UZ0t$@HaJnpdda=Zpn+naSZ-t6(T8U$KWFUG@czMHx(Wz*)B5@SUArzVv zfp(O7cSzu77r#lT44C8qdnMUS4r?nIoTJ+oe&zZU+xSmkOkYuG;|U{ z^sH{+zcfrBSJ(~{#0@Bc9dA45a!^+ZBaX1C@0gK;}I zG`r*-l@mKKg$#%Sgn4MVga{?na(v-9t9#Laf?+dQ&oTYKpPWBOW?d&i{7L{j{G&9? z&3f#~+Hn^S#s=@(6MUo3t$P1fCRJ&q3d~+g7l1au`iYZWRKm zwRHrT9f@>TvBxf2%EH0bGHA#}qnM`9T+i67Ss9;v6olfQ9xw+V5eO17V!?NMB4cJb zS~=#6H2|D5(EWutF&o$QQpcCkc5y7Fq>d?&W76Zc?daYOh+-4D?a^)IrmRBNTP+iE(U;0qIoxyfM}! zngi4q;NJ6X)8@MC6W^20YrmFL?h<0mqk*C%Ojrj#_8|hKwH6Wo zgU%&Yzv*E#Z5ZGQVS5t-m}-K4`cFp07blJm?!~pK`du1sdf=mDIOmF0SM4+GDP_w2 zXQn@{>#o-HtRlG%kSS!EqjIZRlA{0crb+B%$X1(U2nu#f1~=SEdNUikYP<0pagZ<% zhZ_s-*8DI9zB>iSc2$F5ROu#&E;Q&t9)MBk6ab%ze`XoZZSn2wSS!@t0K-6f!{&r%{(_`mu87Fe|Ho~K2wm&41|v*fP4Ri%TOJNq{tdsONjp}I8QOK0ZBU=WFSHefoK>j>(|9k>)#Y`aRK za>s)NxYcyTm4j#{wc4kqibZ~nGvDD@N&=)O;f>FxU=Zgj4}qrUE1XfZzqb$r$5e63 zP(93Z2HwH*0a+YLy_uD~pk6G&`K)CCg2sZhqimd_(v^eGtpKgw7LB-F6t9x^t$4{> zC&mhh9%C_p+h}?zWWsqYT#;1XN1^%$gQ3u?pDS<5NfSa6@68p1i|dZ=~gg4 z-$z9-W;x&?MZeJFpn!+U35aC24qm{Ai?3ds7&+M5s9|em*xh9{NHIxB;X@ZXJONlK z`65K);PQ?KZY{6u$xfiv1T32x#Zq zW!swkpTl@)NdcpAJ!H`23XoHL8h}<&usSq51bMV$Y-V-6x`+2nSD@f|D-QusY$0K{ zekHD;KoTd(`e$I>=#AL;_slCjl%ZEqkQ4LUV_&GMF|lN?81RL{8-6>7|Jf56F%`fm^_qKrMEpvKdnbQqqP z11u}wqDnBskRX#95~+9)Pbd)J_k|Q3R+|3mEeHQmjaRz4ttzN#-#j~U#Cm|tb{8?M z7Igi&>;!sFPRhD#ukaEGL3%@Hq;huI#x`pG$3^I9Gz~J8;9kS=h^_THA|SR)`9_3* zHPp#|4nmpKosO2>aEeakoFWhBQ29S)AUcP;9|E&Fqv85!p&%Z*gx4!{`nRyG`|x{M zXV6iNRR?vebVMN@AInKDi4VC1XJi7rPW7?UJ#1$9(^P2FLbCLV>y?Qhi~3`@JEr&` zIT;>WW^L!)ebO{)qW&hBA> zJW6nV2kXS=@Q;#Y<6En}UHNG$+@*~oeQ6kVScle2ic@iKlsj?Y?AYw+K*~DV+jT~n z7f&ohL$L?kNEWX;IO?+uA-0%<5@d&bkZvWyMW zHmdg4FwfQb!HcUd21^ssL>MChKkR2o6qq%^7NGnU)pp@@S_qko4ErN;sX#+(NL>Bx z0hPA%0ttfRgV{ge zG>?*f^JtQixiF>#s>4gR#A?nIF6=um9ZW~9M>$vO+hR2fJ23u6acPnBVaXK zBdv^Q(5)IuuPxLtginHIDp11jV841-fGG^Dy>S_X3k-9(eORVEL*Ao>qh}|#W6>rm z4ZtrU)G9><4In|V%qjDlh|oohVviRtR4Aa5Xd=tYCGi4BL7QWhih85m6^enO$GU~1 zs_g3BrT&X92N<)-6yyV`W&93s#>mXW0izD*@ZYk7%k%i?w-r5DEB7hpUVfT37> z;>2nhDPn(l40t&0<;)ww(DU0SIyqzKsP#EUXw5UY4Ozq=iXW}6L!Mj3x;c!Sgy%sO zqI0$>lR?a)Ag?xpH;=4kI2 zzb^9j5bEdZKR-&hqC+df25F%g$SF8*yg-OtG!kvS|U>gxCHFdY}q;x+j_v!dQt5{nP5 zClP&7rz(86Xp5)`7QUsB1S$B?&qN&M{XkH3FJyf2iAavcGkhKfjw0{f3{$Z^A*;xs zAf$nNmn--K#kn_;$n0-GMgptSf{F_o2Np_*fc8JF{avk!aH~2lK#=7kgbIWa>FB&P z-GDvJ3vK;>E3W|HH3$f^5o(Z|Tgxk;#2~T|XASw1W?5@1Lf_DF@q^a}@ny|!!X$n( zbF^vC&G0SSksxT-6va@Taz%dW;^Yo@8&5(L*J=9eDPN6qK(JI{{tfvKfVb;u6hJhh zeh!Bwtavo$Fa@HtkElNhCV+seP@R6EaK}eI(dYvs4M*e}s{s0cbx??Es)d%nHEMl^ z`$WvZr&3db38rna$X`+_SVSUCpwS(C=>}8WzO*35GIU4`1y4|n zs5U4&sw|@;IL2U*MhQn6hAF!KqC;d{Oh_qo{m{%A=CllbaZOL8YI+X_uXUTlw_Uyr19K^08oB?%h0S(|y zToGm$DER7L>p% zz08|TH0E9dY~P?tUkH?xmD6wV%so!2?3uN=eSV*9NnW>STp!tC&8`S zb?};1UPJj5Mo#B4K_N!<~jNjrZE81+KRl4PS3N@4|x5d)X4 zoIFii#eHqJHW)6ym_=P|7;jjOfk^gRHyC~_ZC5FY*QwzCMgqW2zxrpsX@3C(zmFjaJIwF$$$0TYq_ z>-iryULk9QH*(5lglfIY_$qR6VBH~#UPD+;2hKHiKG@vS)%ol^ivBwuu*d>QM!1*#*IxJF zO-huMsbro^&k}Pj`?nzhkTJ9F<>cwgc^|a4lc+9vumG* zW+YFCsvrfeZ<|+WpCY)=q;)68f0yG;%`+~{-3S;t24mCXj@e-k24W+z3ryL_?Q3F^ zEmxs}A3)uV#W&v;cfZgYT7sT{9FNTvR;e`ep5db@TAp4x<8BCm6u>`pkF6$ma25ap zm2i6({iL0fpFp#R-*ZmV{HO)4&0-S)d595-)jDzEHDxQ>>z(Y(h3|smHlX7dv z;@RZF9RMFOa2~*i&0H5u21PA2H~jv18cV7UKo(BJ75`iaXJB_7OhNUA3(T{?a;8X$ z+Sfxl#NUkcWrPW@;D9I*e+foWi4y=Qun7$S`Qi?(Ew;^3+$>$Hwn~U}37d2dD$3ki zmx|)PYpYyBfj=L97K1cU2(j|JxcFp19i4o977JdU28R`4qN3=(FAUNSPPeX0di^@J za?`9viIkKc4Vie~V_fOxwpZqr@&b$xV*+IL6>m1^(}m#m(CD3lsL$J#45@!EJr^@7; z0?x)CUqXJHCb7xf<>^33k!@OTC`F?K>xd6EPu@eH!K_>fh99gjXLP(32{OxRf!Q+oEGdK)Qq6hh#^Tz4dcRm9vo)+gLvF% zb#_MI*`JW;1k`)i8q<|o+?0@Cfr^H!Wl5}zgK8AY?mn`lx#`6R`&8WV9A&RV`L=L+Ij{H z+voz`_--o&Sf^s6sVj3dE{E7A+`xdP!FUFz!cyy0dG-Ye&W?bJaiSHCZGASKCFA}e zVH>!eT{k<&lpZIbCEqMYlP%W-^PT02IdhYgct zeC}zdZ^KyOjCyclQt${d`G%4H1mVN9@s539xLM{TiSru>-WmlM0YK&i)O{?)0R4Nl z)6TCx1ENngo0RBd+if^zg4JNF(+X}lHd@F5(X?~pr}YGE;e3U zA_75;dm;@PMVL@yP@Oe)M;X#T0><-+kQ6(?e2;*YN;?rC*DNT(0m2*%JGAhz{hh8~CK zvoSEJLi^X5D)3cWZXg?e`VFMMsQ*A}H6mD}R7N23T?qIHCMH&ZvQ!23FNLfcMYLeR zLDnY1mY?1o2%0f=E{sFJn0}v#W=d<3JUIAEwt9nqXuqmj3gP$?fXU`W@&=x;skuXF z`x8n9-(ce%K2-D~5`FQ&Hy|s&wV!Su=^1&iHlYvlCqX@#Y|gq7Ap;P@s-akFgXtDz zkZejRc&Bo=$S|CgIz6III8xLb%DW$8z=A%<3LnaRKA!OP@G!U1Z#@f&M| zBf)#Eah;1R9DBWQXS^U5xM{J@Cp}?yI2eei94-9qfINJ@0pijy{xB8ThU=zUNnqa{ z9cc01$S^rAPvg`iYKRMC@uhg1e%K(V5ZYztdp>lXMD!${&#4kd6TD4DtM_$wwR=&@WgXP{(_y%j> z$3sgTnL=Fyfdm%|m52r?oH1_*{ltd)XKmPfkeo|LFH2nD^A_ldsCm7dn-RnhozL9> z=>PdRH(gl_ECT>fxop_i4!lDxT{Fn)@ryywsm4LIRYSTR(n`Rui5n@T4l)9k3)pf|TfdF>Zl+FU;hjMp9iHI^!a_>eOg{RTXhbMFv7SF41s2rA0DR70A_h#IFL zWRsK18UO(P)y1b?JpRxaLpQiyzK~*9Ja+_->kZ(SIv zFl}Zms7*00sU*)lqXSvMn=VEu9$wVDAh)|E;aR8`7-(9JCX*}J7#8CB=Jptrl>oQr zYGaqji|)JyX;ptxqEgJgrSJ+;e9;@4qLP)*43i~85s97*m^|k?GV$$1LOjoSf@1x^cK@QcmKF^TA#LN&;?|89gtpO^R`1E}EjxXS!I{nEZ6SU^Cak zCv7r5a8^;b22H9v{Uot>QGp`}KyThan#9=nh&Kn%D>nXU(NEwkax;W&YASeFenPFM zjN^TMI8B+tDQ;V{8=17(8E*gss+UdpN-XjmDGq#Ho{s7+KEhaQQ+^gR5kinn}1yA+^L-|J@S za9PC+Se0XC6MeOrJc(7owSJ+bk)?IO53T##fRE-xDevP`3v~ke!&N);wJTx(0{Wd1 zp|eb&ya?cdgm%;|Fa?5Klov$zq8p!sEEao#lKFRw~idSUfA7qgX> zhFm*SKQn7sZeRgiz!c1lRYj!PqgdXBL*z2O+9l`xt7qY9ZPi&#zfAXVhTDIPtp3>) z_`^0e>)3)KL*Su||IjKD@3$m+LGEq%^EsJNn$ENhWw$%DU&bU;=4X(Ov!H>WGoRAK zdg`+fmrc;HlWFNV5EakZT9bhE=#Rr^DPMpy1K1^5uuO0WlO0mGUmXT3G!( zEeNW#25CsQWyZ?*?D3;!7^?sPo20AaQVr=wFQpU{^b4*7riC%&-Nht+XR`FB zgk5OiYwcDLG{xDPIO0IOCtO7svo-TO#J}jp;^IWduU?(A4CjW z?Bmbwldza~?C!VUHnyqpMYuWXPm^*i92S&}ObGs_FVc<8kJ;$(1LOb&mMotTVdL|^ zzEr8W2De;}k<5{2*b$2F43h5`1Ps9riz6ql48n@_wCG#_09QcRno4k-?4-(ry>G&^ zw>Imf<|e3M{J(NThJoTGVJQ&=_lxW|L;+7Gf4tE2z57=3q7V@lS0r~gx}FlOtUhRz?9GLegubrt}yP#{>KqP z$=tG9R8L(S3d)Xt;7K)JTn)p|mbdGYNOnX+bEWn*_CZn%0`lT9N+Vzyp*0Qw6|Rs3 z6yTm`kj*PPlref^oG$jJ0=?Ps17IzR`&=uZT#UEFO#PRzu`~byTO5;aE}8(6r(ywT z88Zz0!Avf$Mn5^?wVQj0R_oSBZFllioT=ov3f7G?e-_FT#9d1?r;3ac^ndyYg9r$% zKSDLm-eibV=I4Jnl7e5=BRG(us@Lw@)00Jx+83yHSB7r~{YuD!P)U^5e@u!CTUJR4 z3?lus4t?`57{2{40OZwH&hdLZj;(QkHo9FQtuXrO;_sBW19b7@j2N95)`P5ks)KH* zLu1q4U@h@rdJ(F15y?pyMEsHb%#~ ztff>Dl>LBla41-j3c7ppQYHf0vo-A_w_$gU~B|Y-n9NdlG*FUc*HI-{w4QNCv*T5hm0b^j}|e zikW2_h1)=eqn=X`n;wCb5CAUA9$L~2$Le{m36TQQCdx+9E`Gw*00!uXBMt(UXlB*^0asA_(vWL` zZG&(|4@w}{Pa7{zJZowPNM$xdbYZf**Wa^V@RUmHy{&!v(s;Qz*I%np1S{)q*Ysm} zjRfop&3QhOYXgb5SPa*Bf_2YoXT|MO?YGNJKjFcTTlwSPoPolWF~oB&a0~Wx`E{BQFk0XwBt6(v_Dyqv(eoutw@Quli&=EcTt4>V4S;Q4vO4?_ zN>CuBV95iip00|ku?AQ`9=tTT*L$ol?7g05l65+~sa1|`?=#*j<*idbb~U^11{Mex zElr-5p0#wsxlb}Lf=G5p{0W>KuPD2lWa!mIhg|ytrvT)f_+J+lwctkZNZz2C7R)?L zyn8hcVrL0xd-z~hskBnB&F`CzxEzSrA5LLm#nHWNjJ+q$4_HKUk%6QOyT~OSg?A?M zB1!_9cLVFc3AohR7Zy6>z`*+d-Y>?~drceGE4WLQFK1#p3TKVv5`h=Zy!d@%&57~= z$|w-6nI4!WhygQ-r_XLQLjY&}s4rb;s@(R>QgMr4VDcymz@+Qdc!7NatR*4mP$NZd z5@eK>-K1uA!Rz1#5(K>CqNWE5715J2hI+W#OP)fruIdA4X2tL4+!}Ta?pLi?bU5M` zfhq86(=0$S>dshJ7P}xQ+GASq^ATsrI1ts2)}=gvq74b!Lw(eS%+_oZZ(Ael8CKzf zPg^Ru)bNWt#AQuAZi+2|45$Bfd1gYI0V9OTeZNNZ>=!0$HfRYpZ((ri+0QdJl{idL z6|Bp>S;LJBRBw6D(X&8dQ@oEn10Zu|`o^^f(5`3`D}XjKUj6&mSD&j3gx1eD zBV-riS+^P{CQIf4F-ilZ9S^w|K6>Wca&kvqHcL=Ns)>$xP2eNQxMxD~Y*rRvAT0<0 zB0{2B=W_}&mT;9DVS&5B_-+JpCIVmF`&_3a`?u@O7xoSQObzTWBiKoCpI}FPN=MNq z)H6ue+8nseM(5mlttr7XK;*^#a`N|ezkN8O;&+k{?!z$R?X2zzt4|tqYB|53h}7-) z1n)$6On45&dJ^@zth)st*L6H>GU;&L-?P{*WAmH1YP&BL0bbFM1KN2qySZvFX*joD zN09>faWFA=MK8U>PWdGxqT#3%=M}t^W3(uCvmAjU+7D8j@e!TTs-u#W>B>s7AXQAT zq)GCw8NezgtX_#HF`~k3-G-ZEE_J$_;?0K~Hl84R0)hH`>1N;sXM`ae^1PDemqaQC z9=UPLn=X*MMIbn;OoN-XH{Ad_57yQ33n{>)ayC!*qj*U}&BL@&uwZVEYQ7eG3EmQ- zBnDVdXEo#)_uvgH7yNuaKNdcGB(^sSCm*cJ69x*cx=<9U<{h1U0Se`y~$bbBN-!nlkBP zm-ZV58m}na)aVrMU?T=u<>SJSF!Rn0pmE~iTRm)K4sfT@xw-&N*V%#b%nKW&dbNPy zhNNn35PD|V8EtlRVkHEy&Zmn^e=SfRrx}?+&QF74M#^61X`C7F&!Lsaa=@ijOiRwD zs)@XB*-E7yt>dFN@kyrh546HvX7n7|@hFV0`zHM3HM(s%dpxQpWpra+l%dw{EYC~` zGwm%@!Y02gme`g-9FXRZzm^dpj#_pDy0VJCZYh0?kmk3o4JmP{(EmLW8l zJ_Q|eQC`G_PAZVyPI6~RZe2O{4MWn|1+`08+1^?J`kOLPIDs}G_-Jcu@w}mlyv)4` z(6&mWtun2C*UNe3XcUiNfF3HM95oDk2`Nby+q^S$pox2A7&ZT zVlDagMIZvdM(G&rePH`)WlIZL^ih%On+ouc9nzhS$4IfM6e1E96`$6wiEAv~2P1S3 zhe%)7t^R4_VhBd2g!)B;oivfY>`e)(r?hV%e@#%L5B19Hi;b}H!~q4aCnqVVvVN^} zQv>WIs6aqz$00NAh@i~Os;G1233Dt5u#3H7k$1ERQUOA!>-Y)kK)suv!zGDmI0sj{ z0h92(7GUjm{I;-jSYfm&vrLTbE#@~Vig2E$ddPqJfb2^sVCW{a@ITk0-!YG4O6;50 zLl`Ph3yS&xAL_2fX?uFRgtjsT9ds8!w1u#mKgS^k+h1>`wN#I5KK=;&k0SpCo8a)L zgkDw32zKz(MlnKtHnI`&RKnV>|Aj%ZBA=d~7hxMX9^i&Rd+vOC2$v6jwXh+J8g%(H z!3Q=t=sbmdshbo{l~oQT4`6{B+4GOW4T(5`gFvg2V+%(;u8ugB0Z^0jeSG8mgU{U@ zkv){=G?7?dNtgPh+^CW(#;g%NQnuxTWt497);jJ+A26P;$X%8hfJyaro^NmiG9R>t zIgFGYXiMd8Qsw0RPYYHwgk*;}1Jl{U09O8oidS|_`kVQcydNtw*ZUen1> zq!jraWx{@})l4Mhu*@WVQgGZ%5JA}?+M`7|LLS|(^^_ZI*YtT5T2=gMKp|5gLZhDU z#Uam<_;j`AT2-B^r;$@F&;R9j54L9T!EYW>3PMI+JfCuUOr?+4RPramrE-h_%5&oA zw>7g=k2s0|Lu|Leo0(}}X7q|?KGBhebW{qPex0xsB1HEvPK@W^)-v)q#in<#?-oC8 zvvyX##d_XSf$P_dspB>jkptS}^`dfL&UmLJ#rkGzc{HXYlcZXUU3Rx3%?Lf4Y zH)$qWEh8yqbCY&|N)X}gQL0&c0Ob3kyiCJrR}O3c7_P+@sF)S#< zNTh|JpMP}9y8P-PEDpE;vcEKrqUBIH8C|{BvIM*Fmt*BoazCN;EzPAT+Zqg>+lkDg z%y%hI7w$8~-F3OrR-GUnH~B9ZVZOXIF$fD#$B%$@`Q)U`NG2X?fw-D~=*cFC0U(pg zL#Radz@!Dp3X%8J1TxJP{+ZGi!GGd?z1_X`{bYnU?sd1{D5Q@%1l(m%u9jJv{vJi5 zPXAGKas>b}9V~?+jKvD_OIR+5D_qP@U0-IjaC*uyDjc|Yf44DNjXVp`$xt=O2cYSZuiP0LzW110dK z;>=CFA*E*1*K0tkZ71^C*76>k`|F;9`DRPtLn0CjZzxK*S9qjsc(8vc`+-A%1zj0$ z!aqhxqQ4O5qk)K6+J<w@->cD5}|H>{OD`m7;j!>RP% zn;9BBmDW9h9R-9Q=y~_%n{wzZhR1+aDX;=sZAFqr*GM^8c|V}7?I!@)hN$m*poBsH z-~Cf9E~G!n)ESAqBG~{Gz@m((>*^gxm3LcRm-5ah>C0TioFyif32oMOTv-HbF>uHf zF$6l{nDYrev;wUVGCT=36|E1MtX|2W{7^)~CDPrMjv~DgW1Df<4p_w`l`4qJWU?!b za@ZZ7w!xR>~pXl&ezZbV*EUs4z&qX@YRzoy#BmD0`;EqrO4!t_X-;; zG~2SO8&13rTF$WE{xIhJeNbb&UnbaX%qM4FR9xFuZmV~J3DI}YCpMOjutj&?ciX%m z1fBN~3?&y+I*h+~Ac9+)k-ZZX$r;-4(vspSKPaj7L5sggrQBLu&Qh2^$;yKiosvet zPDnfMDm~pEY*>d-fG&H5CWxWxHyT2s3MOjS3$?G1Otw zuaWN+w^+HZ1_tKF*JXS~(dMj_x|qv+Isk4Lo!hwob>N(?)?tY3PJKQZsmh`fJK%EYx1_oUW`&;(F( zN4;G9Nc17molPI^NyRW^^;Njc@n(4Hj1U=sTpmxD1<8vFb-8>r9Oi97Ej0ETNfkaO z-59>Me}#Ce?5o$+mRfRsg^Ymmr&N?d*uQ94StkW==3r{K4ug`iXQl!jLG! z$eU~Jq@j3Wnikq?ap4mvI*=R?};y2M-aj1R+L z{R>sWsE?We{$Ea?Gi_-+dI6{1fYAVJ;Ocwg69b`XR1&Y%!i$71CPrZ=7A#YN2c&Xb z&8gVZJb>9itx{}FfD6g!>_(QM7$DIpo-Li4iu^_b7z_d550{r@;G#l(XcoY6;>#qa zd|k0*!phallQBPu(m`{D9%v~YPXm?(sO@)6zSs2mkTvPyr3mJpTvff}<)%GK4qeuS z@*ZFkH#j0abvoz?tX|Us6hxKj)E75;1B-xOo~R=OGZWVSxj8Yp_8pBEWXIS8*j+83 zBS@R60-FJjr}PM0(wjaH%c` zXm+XTbNu)^#O9NT){UsqS|p8PL%y5}YrFnJ@D9FeA&DurUUROu6c^BFR)uw{t#zc7T2x$3dfyFAf&NrB@u3b>j*q46TgXS z4smj%O>$yhA4lS!^>SAmH};*tSD4hOS)coOTWaZWO*Tu44#Nd#gOH1pWe3M|m$DAC zex9i&^~~@1;TM7ZQ{alfu(lc>?%^}N`taY<`84566h9I-P_mO{>Vpb(G~i9xzFB2g zx11prNjE1umUh6YR!|31zczZI(o*KkEjK`}+oQmr5*l$^pP}Y_OoG9kJ_D7*y!HcECTD`tC|I(fwDQuI{p)5fBAD^B=0D{fyoEUa@t+*0j2@5n_6tKYC3)y0y>jlg9Xv3UjYlP=vgb7lGT(o}^9uWpwl3$#WLuZp5n2nf(n!L(^T zVt1SH(>N#FIg{(GrlcoIobjt24rBoY9*{JoQH=XRX!0NV-F~1J5X~AMh24UINKEHLUqWb;6gv%EP2t}!UF!8NA^pH4%1&Ldgljq zpVuuqK|-kz^lmrmiE82BNIj%-{v4Ig=X&Yw7-m9x0k-J^hPcc}5ZGkHvtVceevHv} zTCoC@#JpkQjsG6}B75H4z(NHE10~1?L~NII+w&M4T@jMn|Q8&YOz&nN%!Hq^F zvSFu-3Z;BRDck&@H+CnmA>tOF)3~r8==8mE(0PLh;GNY9JTnc?vozmv!R33&@~#qU z#Et#Plf!DgF2bs!$hzB2kBomfxF%bYt7r3pTKbGr$9}LL`v+Qx)ACg@(45!}nrNyH zP4TaS*+hNJ%7X5g$gY69z!%B6|bz%Eq_a;X80H0N!XjufKOBw0hf-ISHOjK%`W77N&v#DBu zNAziE<+Yd&qjt=Db&X*uQ{w67F==>KxG|yaWV$bb6XrkqaPHF!0fGUqqVu4?CPw#0 zyDzp=1X$jkq7C*`p2S_*zcLI{`o0!r^8jAGbvDMSfzm95jgB#+O?+53MNK>O%Q9?| zNSA0q_I!f?Msh7RMd`0}bJWN&GV|rv3k0_h#NKx%T}g_In9YQPwsHsmUEEUXU-^}n zFjJDqfj0jDGJI`lH<$ryFQk`cyRpq{3a#a+5NfQ;@VYy}57rM)UgJ7|bH(X)KK*9> z+ws%qW`l_$lk9RpYF53Pq=3n1F!8&IG#Gng?b`*hzYa^)b4uw@zY`>a=eNWmT84~m z3iy{9qsk48(SR%UGlwb-z|wzxi^P4F7aorqES6H?O{k^dQOhCsGJjQR0tlsZBF%Ha!MG;95LR>p+l?4$icGM0vB+~a_w*g%i-5N z-z2&J`yOPJ=%fsf1CQ@#&vkFhKw#bY7ZAp6bJKmmr-T;d3_Wip+^k4qxb2Vw8cU5H zCR=B0dwQs4=}UHD^^<_(NS8;gcj>ntLMpkybcsDeS6MH~O&V<;$9mKikRqwy=`__o zhvjx^PvR%0TM`vEI5kZgbGD@jnj3ilFXB?G)V>I0snf5tzx$BK%BV853=yDskX%I) zK#HUbOuP@9s}|PTvSMFxK<<=DFKFjT>Ir?`avIS7ic0;p0_OV|rurNRXCw#$j`vjm zf#>Clt1Zk z%fV37;Y(l z_+VoPqG8`dUqA7vU<9xpQjvTD`yclZ5WwGRdcQQt22bZNiek4LVx?&=6oOFqOSJ1i zwG_)HwdFN1p!IurDywd3P9yn+!a_1WIuLIIesSFA&q-%j@u}#)uE-1Ndymantw}*^ zyyEQ-JYO+SO<;9@7{)ptVEAfE!m8Q+3SC;_^T*-x^g~HQ`O;fg(Y#5Lmnj6~+#)`h zNq+GP!X5`ILa$Rm@Mgg7s`5G-5s>Q_T)uG3Goh+mHzb|Yj^XPAv@=ljCDe17v7s}C z40Pc~OOi0yz+TT52Z?Q;4?67`RmJ_|D6Hx^{+*&TLA)TydZ zd^16U_3_<4v4?Q#EnzM`76F1yh+;ergr841zP~?JJ%ljhx3-Wt2q*_wE&7Hab9?C% zR6+dV!XipLjoL94=m_*#Z)GI=&?Xc8nnife;g0s-mesUX=IWV$+bxsWaJ)6D&pAOY zqWi1frAx2Vx0h+AupP$y@eI?R)jisF)aP$}Cb6`C_KfTH5u5Anb%>58pWJi#hN@1rAKX7%%#4U#}M%r|LA4;YJ!$uZ`$)wZ5{SdYQ(o zN83HcpE&i&k4(dM(4yV@tFPXJZgqGfFUg#2n@x(qGZCr&0s_mvXcF{3!~g(g4EY*@ zoLFY5jGQyfRH_SsdOGvNR=v@p_;;k@#D0V)%L{V*PTXYL3bW)_MQWLn=nUVsoO<_< zS!T}8Y@r76TtayAXj|d1S!h$s^MTvXACI3@B^0dya+2g_5&t!zaKIY1AqdqNOLuv_ z)r&>sF&dw!ekfAs7MG6Xy-G$%{IkcSlVI2Qwh6=x^hF>Yxk34Hyu0TAD@J^;8BSrI zN(Y4?46(BrgTnr*=PcI{#^3gLIrVgxh=!LGHQ(5uBN1Sz1%Bi@*93EC_&*wf8W-mF z&CvD)UIqE_@7yexlSa^Xr`5V%AkpY7$xSXTy-GWFpr^Nm%*IRFLIflFzMR=wemtSp z2Ce|oN@uPWkC*@eCE(v~jDkZrrmx7u{Kt3=GHOp?NtZVSH_3Ii-!d3E6jKq(^ehvS zh`=;lZ%7TnW&jX;<3<76UGvYj0p?n(^L7iuszXHT4tg=oD-z0{A9mQpc7MP*Cl>i0 z!V31)Bsc(e%-GvWD4Aw!Z%IhzzO=yg`X=9PH7QSo>>sFSBwZWnwn1Wl*|-9Z96>99 ziYL?Sld~4a%_iTL%ffX*>;H!%88O`GERIGGd93F2jZBR404)-glbn1SNO&|}f!Xkd zR2J20$_dAXZtnY?kyhhEh8QT4tLuAiEgA;34GOBDA7c!BAEzoGqNbaN-3=b+E}B*$ z=6hcfk|?2jppJPut|2%>{2YL;4iaBNPBL;EI4N*ilyrMn4P}p2)NpHe^^Kmus}0)c z-<9b#*rzpEjfwKuj0eop{%odmb zS~CrbGD5>^3{*A;c5liF8u+TdscOUF_KMqKIB*G1O*Tpk5`be1Z|84h2`LxZjKI<| z*_l=?2HNM)!-rKI5cyBHk?a@g!a%Z}k()yL+FPeSxS*il3BT5gBNKF_y}n?jnvia5 zr@{!O0VvexncOGcAmmbM|DU?Da6tf|QSU;_)4<2449D2YxK|hTUMyo;q158V9f9oEsqE`bMSSrNS3FP&msWyWNEd(r{bJ%xGt=mp-r;&_m!z+)-@G}&Yx zd^ue8GYyN~yP~Pa<{z682eoCs#r**`$*9A;KJn`mTaZ&h%yqSX>GF}gGU#YLM8qIc zy(=4v#ctQqOt-P!U)iHn9I-RS%rZCodKs!5;z^Jm zUcSr(ePS{e*?Ya4H}oPbZB9;OC7HD0IWxk9z%5*Ij7)#zr}3uy3WS(0+oTL z2*cPZ!2mm2aCGsIW4+8%d-!Tzr_aOwQI#uw&A&6KPS3fyhByTDFDTY)l%C9L0S0D~ zhyXnN0XQ;0Uby1J;FlwfeWxmmDduiCSw#NA(Gcw^6ld^KG6YF{lx@Q9z~Xly!{esB z!i9bLKN~@LIeaXw>=u4!8P`yFCYPYETV#q%?|SZs#z6@%^YXPx{f?+?r8wAlT+>AE zMT4qYd4`z{sye1S`uC)a`vT$9*x?NM>FiJ`QQaatk6H$sUq{r6FC#Q$a%6v{d-!77 z6&kVs3GS!MQs2LxEWErm*B@gTkUS=&=7VF)>hreDyZaUb*KEEg2@6?7hyQwwCoyJR zPyxAyZxN9OARy=@&yBnD-NN+n&RSZpyBU-lP(nHeL*UhJhKh5bSpC;YEd-t}VWVi` zh_i!kfsrPLcVt#9mw`BjLY3eohsN zjLdyOEb3^G;Zw{=&6?p!fvrJhfCvx`pmfNhlQ=UErr!<^kpXBKF%aRrrE<_^opb^b z3RA2ii4b<6NRUw6)B-nST6R{N;!#q?Y!}~jwcmp24l$@*cM}p@Z|di!AqNNE=chhk z)qvzg)b`r|ywP~eksZ)i6)lAEZWWJKlF>zcvo3|S1IlseX+Yv*AeR_bx5aTrgyzH% z`(l{x{UK|>X=4_JqJBXghJgM*hrSoz2g|@$P?5Bs*aENo$5wm=lQG_HUm1sDIDr?W z>=?4_&wKORhOnax@Dr9ZC6~@Gw7l-ZTS4WqMyuAfF3WR)&4dF5_gq^TRTE9$)$Z<{ z0WMj&b7(M>`(kPwNBt3Pdabz#nMP1jaSs3oR8W$drda}x#dw;_z$WQ}ckg54+j-90 z`jwGYNRDpJ-^el2a4rXII|t}cgT2Ie8?dJ0W^n1pPuw0mxrahS>Yemcv&SY7f~z9= zj5XvyD{w3(3M{UG4R7%BlClTb(dtdvS7KlCMC1sIwu-F8Hbvj-q}R>lRi64YNSX!! z43L(lSF@8a=qq6Ia9kp>+G0D&2nR0QhZ7h3M|}|Mo%{g_!U9)fu~1(ohEVxp`m)V5 z#&n$)mdei;kv?LZm9=VCY=hxpEFE18^77gBv+hJ)uPcW!wFFvDJENM|INWr{3}@o~ zpf&mu^Bw@?;2LRnCGqQ3)gahUA1-9DIbr8e1p+L1u!6GtwcLMuS%ixH^x6b-O9-rP zDj~B8-Ch)7lx?kXeh9?JB+#$~=K54%^bvkd2@g!=VLV__0;ec0^=>cF!zMD#`4rp6 zr*!vrpQ~D4#!oGj(h9tesD*k$(Cbu@%}p4;?Rf7X84en5&NM2EfmbX{kyH{e7+5uZ zXjZ&c62sL@67X(s@`R6OC`seWFCt9>GN1=txCBEpaX3v$g;`FwVN2 zlyrs^18`L{_nbM`UMh>xG!8N{hCv%QE0*KJ_O^ESwJ>ydreB0t zn)4M}=z`B!_t%5?E)#88YHryx3MCNG2NGTVXWXmixOJxTKJfiY(OP~2{TesUkXMJZ zcufM7&+iunRjGJ&)D(~f<1???1qW!)XP&&VA12Sddy5qJe4-x&tr%(<-}hf|t@Gh| z8}UN|g2J#Ke7-ioaF+}?BOy3fY%ldVQ(tTB0EhN`tRj^*PUWHMet?|voZLcy+&Hw= zOBHWlcR_^!W8hF#nYrL;ThYzCH(&3-rVT$a>)bBbBzmn)tjAr>uxQ}wW6`-Dw@P0N z7I#^kzxZK}W66mxF>?axz01EknzZVM5b-ZZDq5l}H{5{A5{1gRLs278?>wZGvI>uL z_>82bfr!o0x&`1>l4Wsnq>K?6TFQN~bDlmILGlt=YvD(FWlYeI)RLK^f3b6$GYx$C zRqnYk!{q5eV(uz9L?F|_!bGUoykX_{gu?}wh{YsUGx8L9&_BG@EjvgNT)*CIEzWl! zQk|RdT>!Ko#!a#3D@LpvC4kKA+a#$&SQaLyg&ppu6i6L8n8BPs2@Npqi#Ws(4tIKU zu>m$InY)6c*Yv?xOK=zulRwcr`s2B}B`rQ6oHgUYmA<;qP3iarehFCzZT#LXdjGY8 zuyftZ$LS_p%qmhz3p6l65U}wMIV-a|cRe5P>>g-wtgJNXt1$GR<}ws6PFWq1HFS%H zHp365nHpb914GCMTbzKJq_I~h2N}ed!1Ez%Om=4SA}N6S)>XEQ6Yy$DZp9>{X@caE`8$1YFj6u@MN zI^CBLjO=K7fH*kgB7pM1R{vd|_L&JAl21rrvqHu5YAa=qSV;^Zxb58R|Ehj5*B_LH z3P^Z)R^&r(_!~8l00$ts(6#6TywghQCDfq+2Si}zc@J=^QHi0;Ow)$IL_$aQf>GWB zInN&0m4T*;uX7-99EhD6C|p-$@QaiIEPbC?+!0q}}LAt-6_GkbA zS%{B1f4&Vz;SJv)?UGI|`H*wC)wyLVRW7y#34oY}BV^(YE9OU3DEgHa)q|)c>jmQr zQLT;_UXq!`0l4*fI5DBqF7-XJK#z&E-Q!_(D*{6(GA;r#UmzPNks(I}EA3)1@{1%N z&8vi)KLr?nNFgu3_7l4f*Qu*-5hx>rh4f?wwWFsP9ui?fjT!#I-L-@WLhS%9vI|d( zgkQVOwuo;nH{x5I4&;8y1?$aI{bzApX7Sy!j~Q_%uWc~#uorTJ&CW2>s&;!=yeqE$ zTv1kcLaDvG@b(wFYJbDuRCL4QN&(XRHun|W^_m=6FE9wFV}3~U>gy|5KT6%G}6 zOnRRvo(3`(m{8(|`hG()`K9;H;qZuw9|NF;t{8Y+nd3CT57kRu%Hs5`rS(0zQQegXTr!k=*vp0W|skO7V+^dDnNg{-A-(1}?9M zNP$W8i`Zjt)qV95EYrzR1qyhg5Q*IPkV$4`Ho}n^E4Zi0gnW z;5FBo5u#T(NWXAhAOPTEBx?evHYc=dFMUoxa=S7r7y;WR()QzUxs%~b>}obsJ1R+{o9D}PXC6r=<2 zS{eGJK8sw?Ud#4n1k|x1;hZ+e*xI@f0>|JuE}!4V2$O+4ZUZYgHDDN2>4*5#FwwJ} zw_l-_p5Hg?>oW+I($O+Yr{*i&)FTu7IR%Eu>2Z7;Y7ORNEH+`}pNmv8c;Nw?Jwza9 zHnh?OvYKT?ZwaS#LLBzfVK=wu>SR~4fP6?+8E`*w<=Zx6+QH~m?Iv+v>FNEQ8U{4N z^^*IB?bfgDt&}Y1a|XcB8OHtXE^{f91oST)RcFCRDosHJ|CsEw+gEd}@LcIke(By$ zlYon6RZOqyi8y^we62We6lB=|ng*X2C)~yDsv)X?xiK{AxM<-adamZBx)CspAQnR% z14PM9OfS2gU2!(T$&KBd%FN-8a8^G^q`<7RkqCOBtjK8oSm=y$iEKk9Q9P~!i^+6t zu6v!b7(dgt2M7MAp;R?$jyp*>L~!XEG=RSN(h@e&l7$Be)(X%0tEsWUfxM->71>(Z@VRPc&D}cp!FN< zGV}V6!Lo(oR@%=4vFDB2$82~zI?5|a^Ka}3+h;F2!2-aWHJ zY>O@^D<<`Ftf2948!6rqt$+V<)#?~kj-%pBV@s8wv@Y*Ca`-(qc#||DIHvMDY#GbI z4Pd5>LsFpV1us#0^gjk5Hh#ZybZF6c0#9ss%r|5t25YTP?|n@*ldAR7LRbzg`>_i){ESh=%Qvb*;|C88)Uoc5BJZeGWC-{j>+4BEUHZ&qU6smlgVj(XNamz`7PpRJb-^4FmGXLb4eh`mnp%+1p(jz zyAlgX{kI*z^kM2!99P-r@XW(P;Z5Y0tWE{6R9|->r z`}$JH@6|9bcZ#4~sei7L;#I(2CS_{!6G(v)A4EiQ`QaLDw}9svW=J~1GB|6%02H?_ zQ3qAlkYS5z;X(VO9yfv#+dlqvTZT0QpXJHv&QbA`$GTpuD&tbIg$wH*4it7_L#K#r z7nxXBB;K(cwz5ps9Mng(51XAGyW;O8gwQ8bk(I^3$gp~`YdzQY$)a4nUaPy(QOh_& z`57WM-V1Cc;MI$)hb_`}n~ExF2kVep6Mu}ES1?DC=UA$J){PaJa^FmsSPu{YR-&d3 zK2V2Y)-{L-Anz|wX!8?a^IvFWBnCh_70a-fwmd98NRK-mn2Ept+6GLTf=|E~o#Ch$ z1Uhor__fltFtr2Ov6oQL%HWT{AX=-f@KEM$U@^pl7^2Loh?sa1IoKPpC^(arxR@PA zj(p3754SC`X46VJ@ZgQg@1G!0u0Xs8CQ%D`2rvq_GuUg_^v=2f^8Sl?wpJbWA=OP= zxHt*>c%iZGk_6}r$E4s0^XB8?-C|u-v*>CLLbivyA2*AasHV0Y?5wD&?~tKduZB9C z_)#A#E38nTuYDqo4>g@a|?eMb$PNtxj4{74@8ZwwkZi_fbis)8HfS@p-kkcwvbv-MqdxsdJ= z(Ak==`V|E-G^qb`eqMX$4a!Jm4A)_tObXlgSd&-)jNdxy6xtsXhy%YH$SnB`@;20j zO`EngvVDHWoZ~#}u-;0x^_O1RGiYz%00@lp{{*a51lj}-{}%n(dKzSM4hvwUi7kb7 z`+TEggfn%owJ#NJ96gD}SJnnXktI)n4dS>Fe&?MsM}&9&rE6?J0fpEY!?0sbx|jc7 z6Y-X+X&04eozxG4oyW2Ta_Cf&OZ2-oYut5{tM;vyTMdF-w}Sf>`&t+`(wUZ;!XLA8 zXp2%1tAlhZH0B`Pe9~8dL{dh73os5dw>SJU)sar$d`L<_H?*JszVTUew@ZEz__%FZ z(Vrn66l`a`(wk*NJp46F!Z6I&FPws}syVo1O7G_3KA(Lv79!R0a*X^22;n><%7krN z*b0|;JKM~W#FnEkl>`^ARV`k)NF9ilr{}1Zr=_i$7p414B*wpis0(s}Fi#HNRB-ea5{* z^o1Fvborj}hkz|EY-mW&$pff*Aq7rGUDi2=aU?2hsh9DlL;8% zkO0a3-&-r=<#G62jiC4E-~bL}tTWXp(QlkOQ&m>Rb)WSf`B*7L$jxkOB`}~q_1)Xy z>X`|wc9kIw#~D#K6ar!+HUMs)w~4ImSNf;$bWc({2M5LNzN$LYhh^eXWzF!N>R9qK z#+Yy)KhUyO<~ka>o{Vt)kVv6fZNnLfPGf8bc6D{d!+I&X?`h4kAMPL#SxSy9--DxM zkJ=s?Vad@!Tf!*BpinURBxwNoPBBbi04-fyOU+^MWVIe3pUF9Cw5l7=$M3WOP__h? zlmW((S)o{qwcM}!>oJ>tiX@**fr;M+JLRQKQ}-BPFmlwa-C&MS(&az^mY3WBVp*~& zcMM@EIv<rXbJ0uJ78qZ8SSADY*vjW@1O|w* zPSt-4-D-zhJOF)rfbmUD3Z+Y$3)2JnIly2#AiE+RN7<`I=Tyvv9DrY9g<$3?nk2{s zY3!);q1pMcZXKlNrqvh}21#6pwOKpm!JO1~nYd@sA%76AW9+&taJcJ zBHu6q)7k)1I}hm(fyfQ^Y3lHE??pQQuGWZT1b;#XB1QYqnUvtSJ=~Z(;b(d1y;I85 zK`3BzMCUTMAG^RjmXjryQJvRNw_(awP8ljju$=e2oS(yrh1_KAi+K$jcs7X`d-_viKhba7qhp8 z_ke!M%EA%{T_>qipD|!T1y=1i9Q#?WB#5!6EN#ExK#WdO@3j8 ze>`ZxnbAJRD%2NaI0vszBM@*-S z&P5Ma^SN9cenm(Y$m1jw#q@rd;7ffCer~uV$|4AnU>q`A5lRUFAOZ9IFS@cM5%f_& zM#JGAny0$OT}%@6i-l$OQr=h}5>Mo~YI?9mYX_PcM%&;rSNVbW(?n@1*po?7=8@;- z(oc7Bg4rfDSiQTe_EmiklozRL5|n4B#3$+y9!&H5a(T_|qjBYBsLg=0yDNGzAAlXc zn|x3vJd-Gjb8h;Ma-CXGr{+RqzX%gb-rBR&f^MMH(*@@FewQ@Rk+4!?cG!Ihiz%Nd z!22hpW1bB3m%gHSDq^!YyNYWjsqR8Ys*iF6v1c&gBaFL)zU4BY^$Axi2+^Du;)E>8v^x&;fTx5yy_BH*=bZgSUda~9T zXBCbpXsRQDnmTpcSY)d%C}?kiLyw_$O~~g+hxD8w55xu75XmL7#E${N`QGp6Iu^A7 zZT=cLE91x{@BpJUG_7QbjUCh&l8ka@YNp!MCDC-5>T-bSD`D?i9xKI!&6AxuJxMmD zF)8y-cZXz*mgzu8)o599N@8e5|aPucW_xzIPB3$1^N6fKk zVbf@`y@U*pP_`O|StOWc#xfZ35>w?2nspsqv^as{aAlV`{(Edm6O$PeiZNgTY@Sad zXUR6$J@XzrpLuJY--oqN`$Hg|roKS8W}mNd{{SVjq+x6}63PUNu(s_!!qaI!q^_~< z_oX7Vu#Bky`% zVpZl(^tK`@qIDvF_{^|Tg8yqnMIIr5OSb7n^_ydVTVH>w(dN>~ zgmw0T^NS;#F)1JWP9<%`DIphktMpK1nZV+fPrC{YZct5osO0o?YcR*9jFmR~HyeY(Q=BAGwU4EgufwKEjtK@~OR$_d`Rtw_l z6+kHh==7}eJ5m%)8IAyvAYSr-OZw*1$`*-uGE2XmBhs4R9Y4y&nb=8FBeg9l3i$h2 zq!nwXe?T=n1WiI7(IXe5U8jAhrClZX%l1Q{E%DdWt_r1PpdV2&7JN)|`5M?DVJ7U0y#4MvPQ>3*qk$OU1}eWGj#Gz%*<=R%HRq+$ zj+DkWudRZ5TH|U%!~9<}m%7$X{@^AVZc6|TcX!j+7uCwUeC?%kLHVMFTjSNCer_qLGIiqJqVp0YI0P!xeK`5nQjNqt@A( zQmNC1MfHkG0QSp=WLp3YU}@(d2FvDY}3#y3mXiKo*XFiib7qRb@=F8gbO-zZl`>g6w%0RI!bl znAa=8{@x0wLxwtEH7H?^?AI-=CyVhWEJeKoGS-@qp&lKknY)L2Ktpo6b4R&mk?7x~ zfVCB4%1qH#6K>b>e~9c0nV)Bf=iZh$?{EmlRAd@DKH|f0bct@@C6M)+_oJ(L$YBEc zWa0ESriXQk41}n?;(W z;BxOx(bw7WZsP)D|2EIb0DTlAw$MY0_7)IT+$#@0Br`#L}uvTX8-~j7)T(iv>i?1~xF;MgRq9cl6lV60P( zy2;zH^ja%@DCX$y9~7FCnku^s<#Mn(n-?tauU&l?Y$N9l{)7@TGJ_BsQm`RN(m+cE z^C5N@5~6F=a~ht_?tOf7DG5P(=Binw-g{XOp@uHWv_-CB=Uh|ANSyWcz_@lru)~*2 zziT#VRnVz(t!qA@r^h0@^&vN*<#YG7@aAjw-0R9v6ATV0a=hycO-xo$^D(Sc&$!t; z7!1-d;{zUd>(IlLpm_o`Hy{0ZB!RB6SE6*?003-(ICj+JmEv)R_>?`(rj-#1Q}g_4 zq!a4Y>%QtHW^rvw-ya&AsXa?~;j9<6}A?DF2LuSqed?sj^-ZUJa& zI=43#Rq6%S=ukA?%~u*AZd>QNw0`h8-&!dshTs$z4jVPV!S%2&YD%+k*$sIrHr5lmVl@BY)>*Kgp&%*9Obo{=s0rxH|mM z1p9cl21PNYZ@C;9I{`3weuPdzXi~Gw?`qN3+B%GjBMW&@%s)Er`{3aS@Op6u8-*9wnOw7>w2Ue};jB-Xjxwx|(N7cOG7+M+p2{_V*sK z!B{60b=FN*u5OdbQ@#(?$$kv?6k{1ARs6doIa>J&bY)~p_B>{GZKQW=9Qc7hSXp(i zT7I~T2tccz!C*V;bx3~^+$sagV0eEV59)+ik&zMp1)K$6dCTFUB*it?vQl$$cc_6w zF^5JEQ0n59*!j%Ua-m-UN8js@`EU5Q*Mzg^}oKTPR9 z#&k7YA2usX{D0#C0Swfus%2;Ar8L@Oty$h$;ZOAsLOB+!VTS|P-q zegNCM0J)OGq$&GnR6%{4mciMSG!5f^p3FD5IQ|dQK9@5r;=OgLAal!n z3(6Sk*!aOG-1;;GVUZ4us5+#GR z2mof{=7j(Xfp)4SUHSW*@QCoiodL&dpYUZHQx0I44CL&BCehLkHkCWw4b2h4${}LQ z2!z#+pbGlf2-D=unP1YnkOWT5tk+LYuYX*}v< zY1-+2S0yAg;-%yFjPxvUBzOUTN*oE7c z3~N%N`DV7vVbq*J-r1U}p}=Rs78nA;o7$eKznYKgs9t)F_`#Pk^mlbQ)*+=$@-l0K7aOekRC`&$D z)*pCAYJ20DN-`tAPx@I?HML{W{Fz7+592?0tzPt^b&cvE*Un%$9sttYun(#DZl~Xf^#U9=)>8=Ci~r9jJ4e1>2evwmM*}TPs~;w8Q8UkX-WQ+)Hd?^7l4!4 z8>Q4IBl@dwuneGwcySka(~w689TmsVSEL9+b+?LihEkan>hEv&E~EfZU@L|q7;%Bu za*1t;08ZGw$PEMvFm&c@V-8&XUN_-Qi$T#Gym{Eb>RPc7B2lD+l7wx z-K%>Wu>Ni%XWV+0)Oy!{P!m26ZqpD>YP7~oyb#-H5?y&_Jq^P^u7GT}#dJC4$FoHf zDt*U|lMZe)c*9312V`h02IqQSn!v_8z$&-QD8SZs%<~)x8$Ua7eO?A5SosWPGL2rL z8)7<{ZEN9y0g5ab?aCXG6IKW3)-c7netA^!0pPrlDLJs;X7{1)n)Qy?1#`DhcbdlSx^}t zinO)nn770f18}s)%DN!Jq6*Dm#wu=Yp!D}euxfO1<~98euyEEt$YTBY=4Vt?&TW3L zWfY-ClpzUIxqA&D*QiI>L9j%h5J<+WoVUWxxQ4~43m_^33t^lDiDq~Uz81(4r79yf zPV9JlceSIS2JYH}aqGbTi^6HL2F6i*XiaamZkp|?4-L`Qd`B}MoMQvunp7w)O1Tm(hH6AyKF ze_wdjflweE+VJc^_;*F(U7@V~!5tUxDT8!=4jL*zDWi?y10k=ciZdSTNKoam%kM_6 zc<}sZE7oS86pu7>Y_zR%rcv9l(QpdFiwk8L7? z%4&}vZf>%z5)t=dioGrE=a&RVeQ!Ja9*A0e0Z=9;kiV#9M{Jt@_`=tu0U_4NlbeCW z`do*wwR+uqMJ*Y5Srl0kPmWpE&P-vWa;9NOM(h+8+=33 zWwsnJq*wRDhYkjEd6dpWK2n53ndWPPg9lj&Sg-~0q1EXD;s(aNL4_h#+67-N!CGy^cr(6n$lw8T+7nCI zx+R_AXf3NTnfJK@3n5@|eR-Z0dM|(t-BCd;w@sz?=(Rt$*bac#_ydr_EdVfx797Q# zkDr#xQ9AIqZbLq76XKu(So%&YJ}DMI{!hLlk(Jt4{IYETP3*J>bWI%jB}bwQWm~u@ zqEn)=fz;I2Aqf>vO}=zW``1ctt^S>MBl7Xva;q|vI9wzPop|-}o%Dh_jA5pSeeM7# z0xM|%v9ZAGN$EK32d);t>41L4(T%O1tU)8v`Dvx;o823*Yqjy}#i*fL=5R|)_}xK^ zp}JJgldHt@|L}3RACeb!wMfxv-L|mG(X$sF4y9q|BI~I%%-bi1X*ug7 zA-rdm&}>(xuNCAURLSr8ZN!DHpmO|)4oyKZeyb?hKys)VS7$!B2r{E=fE1VjADBoz zfC5JIqN&x2o~+ZS`-3F%+onjcB@|LBzxaVM^1QNbh`dkr{o@j^3!(cHcd3atGV4gt z07{it2fL*E{2)d@%yhqE2OS6>5eL__&R@;S8IN9`F4d(Dy2}Z&1l?PTk zfE~DZ5XMGB0egW^Dl5XD&^><3rw1G2s=XDQ02O*w*|m024kF1m)Gifk;&_`7F*4lO zQF}@nt)EOV!9rL_$F7BrMYwu@uXZ!zr$#E)@n)T(|GSn5V5+=I1e7e$?+UdW<@Hi# zz&ZMe_me4Ci(uN_?}30MF`R3tw|S;?4yPVYdrRd@R9NIE<>qTLZJn3m){o&a^vbkH zlosU1bjS>ZiQp#O0W2%ts-9KZh5GhD002gW03_jVr?$S>eesAAvoF^s9$*ciE>!Ud z^T2z28KvI+EX1j|KddU69ag(tekK1r>+YV~nN1%;b@G<9z`1+2~vR@Xq(>OZ|es z`g-L&$5nQyv)&(+`rrTA{}O5=i<<=}ElB4MHo%P-AL_CvR9eFj>BJn;&5}@rFX9?m#op z!AK#r_&sYi;acGYm)=iBX?-@f%@BY*M43Muw?GY7lzbXJ*Mx{DD==qcV=yz;zZa4C zP29i70a28!1Jr$%miP>wu0%)SGqUi*(I#zH1&j@L0z4+q216yO4M;BSM1-De8EF6j zXr81;p6*2}Y|om;8VQIzfXNRV>7LF3F8nniqcDZoRL_@u?Ip6jGVL2@GFeS@;Wbug zg4p;ul>9AIXKi^T%=cr2LC7rit(2U{GRnleBl=PzS&ItcGm@TD;ZxvJ>!EGXdVxgq zVz$9@AdPuxPXc;?6WAQc6L4WjT?8mvmnK}$yWK7yhb={lgeq@CAOTk+)JdlANkKvL z1lL%&SlNEYM9W-F6@uC2`nnfS9YIhBk*RhcxTsQ-dVOBXOK3ROLJHmKhZyWP2`HSX z7Zc6A(>3LsH*M3#++|l6*h0#cmhhYbZC_4=8F07OVLKVjbkm!r0VfTZUc4N*r#Fj+ zxLUlY+Ss{4vU|#HM!bdcSAYNox-bMr*a!vF0J|Na0g#!VOSRA5RlI#(i6@m-tm#LC z$*x3pHmbGabMfG?P%9${OlxsCRl6DV(mej!naqYCBBcac2yZqtf_}V(-0oZnGs;X8 z2d7MkF?Uq}0tzmzh)LVXSko^K56%(1QBb;^0g?r6OzNz>E3f5AL(XeEvMeyzLGL6C zxUz3E>kid;w7ed*w4Q68y^Oxj&#foJk@zlFFT49^ZLAXRliv(AWX4-b6i}UQt`{!X z*OYC}g#xTOD@uH+&eXa;rw`(^XHOs((Zk^2>9_$)WyQ~@S&(R7xbko>kz6le&L?zX-oCAj5q7Wc^Bn|fbG4|oDVAxiY*7mqwb ztv^ZISVA!s?)5q8kRH#~E`zq`ipqOro&dODP^18Ie1Vjj;uIpjD;tUOGG~V~^&b~DX8D2<7hx7V7U};H^uSgM+8Q-4`rJHF7CFAka>C z093l{Pyxv))D^7G62lkz z4?qID+)Vd}s?0|YStiZ>p3biUjGUTKZ6V`o1T0G1sMFVvP6k z_CSmrtSv?++-UdPeL>JgQ^uY`4C+&>=f*xoSdHShl(z^<#Lht{QQ~qM=}sK7)_p(y zm2=NAxT`(gjJ0CcwI}e{kLYZWjPo3rg-7Ng^FUk5&88I~BiI86Nma-Nk#sHqjap8| zI6F;MVEQj;L)M#XsYQsS-6+%&=f|7$&y^{6$=33nE?&qT1nIHyd_ zZOKWJumj+tHshbcS$OFCT@#dXq~{hor@t>v5&v<}dxAU2viHj_ig4b;U3-&o*4d8W zJTaI28qoo8T2kC4a>J6lMs51$5bNHkPkda>r+HPkVN+G)-C9fw&%&i#Q=YsaSd>(~ zoY2!11)V6-4y7SgPR?<04Kd%o3+SXqDsZE#Wb2AK6^B7;BzR^bK(+FyKw% zQIsa9VVxb7-zE1~q8N5EMG?tylB9S^!}GS!91xmid#ucXz%{LJf2wqrp_XhQ;?J3C zK=(|Vn14zQc|YylYE)EB5gcAg{qfwv3AG_Wq5W`Ao(C|MbGR$BxZ8mPz6dgkf2BlV zaSLzB_w16|rY~NIX}=rxBb_YR#F^h;dCFITyT*Y%a)QrxJjKJ#83^aBB)J(LZ8T;h zcdN#lO4I=&)k?f73=og>hTE+@$?O9E!7^yD_v;!U-S!O6;qtiJcD;3RxFHNu^B_4z zt(#rRYg!utH6ZXrn0@r4(O+q1$S>7X3?EP!&;^@3%+^9>V7KQ+LNh1V)XNhJK`Q2p z^1x>xD|bR@ys`*thb)jU-n_%e;3Xf&7^h)xGIvgWjcf}Zeh zh4qc!?Ht#a#4blS)L=unmfi^yChwkbP{f&ugf2HxZ;ndMsoDJasJL`e;}pgJCmq3& zbl)@%1te5Bcm%+obQKy>F&mnFqn=l;PwP9M`!R|aKutdayltOPHQGV8nIfo=7IE1S zS>WfI4399f&p9v{WxIstTFw#b&^x0BjANL++JS=^SOtZJyfDBe*T4V{H2cI>X!bZO zU`sn(>ikw|cyR`u$Hwn7=+ob9gLf|6wB4FzDEj2A1M&KWTk4kg%ZfmLWvMCIcDCpOb(6ik=I7-8EO+{ zQgROENM1<`Gx%}y7w=#d`aH`f!5JWb`#h4g6^+hJFT^q9yitz>%zw}P zoMl)E?|qm6Dy@<6(;a4+K=# zTx>$ufSSVu) z4{Z{J7u1+ub^YfaC!oD+t+ou6{V5FEGVlVroug9}Cq~kBEchKG_ms?`k`>Y)*Z@^z zrpF;nola$V(ApPvd9u4F60K$#QX0KbY|&5s3fk^Z=YRzTvb_$SMqLupR-DC($uh}h zto6Dg6+0?$?u7B+$58&x7i1C0v$jfo4NBDr4=*^(8YGp=LbW~Mfp*+QRXVw(l^@hb z-8NY^zFhl$BBOBXzAH72DdG5Gu*WW7M1&3S-oM0R;pxFW_iB7RML4d!Abw8;lP8vP zGr;tC#Ab{us^-A!d(y9=@*A-J(WBQ*Y5Gim)6g}4rF_ud_I2)Jfd{z-MOBJGSRCyf#sAx7c<^#` zbpozX#?s5l)J_+%7Tf0{meC0tO_=6Vt=cj7bgAd8f{?=001X)T@+bek(_#wq#cFK z2ly)ufwL`{#sa+pGu+rgPGzOA5r|(@qWIT{$Skfo2(%_pbDPui)EJjk#&u(Bb^;r-B4#V`%sqbF% zaNAXw>nN2jsP}-_bD(>El;T~&XUNML2C)}?faa~RS1=q>EOZ(rP``^VYT9;57<{)* zdw=u<@nf9k{7y*3m6RiI_9$HWz6JcM!1}iM_JzWRU{eL_hIaaVU>B`aXTa8-dbM8m zYD$b**XAWOWz|_8Nj5%QH7naX@A2x-Xz-@y>Tmr+;)Q>gmvVkTSN5x2=u@>j5@QL_ zi7%yjtNInhZbv+Q;EHY*0w-~=(dIB(9-EP*k&htq{I;P=7>Rk^ zbu%zDbG7zJzsC*Gn$7-LXeuzOpqP%u?k{4ag)KCW|DfDh<{s0tf|{sv!f@qHAo;L# zAa(@Mejml72{FR$FnC&JC{wbewuZY}VY&PtS4YQ7t+#1m19Aw#6zD=(>Q8)G zC#4o5ta)ZQGW_p(YNH|GXaE?ig-kkukk*hri|&1|^;UGc2A&FiYhVBeE=qLKRNycy zK!f(0C(rNWLU*g7fd%A?A8`u0-LiqiWLYgv5Z{5DS_gj&&jIAixIlgS@&}uEa6{8* z9RwiS$e#$`6uCcw@;#BtBA)iX(8d(!EhqIuD`Ln+m6v9xt-;(p}Vn0yg?m4Mg@>*I_cgz z?OEiRZ8n}nxFD~D)@qfUG-3?Hk^AKICOgbda#?BA;kx!{n$n|_B^|VA0u@8OKT+?x z#NNmK^*&+h%D=Fw&y~+G3z#DcD+0p3ep4f%55$JZPM!gTD_&R}mE?_;FG&ev8VNjo z^EJEKF?e|-}4+Q z>(Q9*G;P>RM*eXWL{gJ>FhH7(G2O-!7Zk~b3)Ho&B0bg6SFV3?5(Vh(*Ebh6h#TpA z=n=~iOc{)bir+{-Oern8M*JuE(u?VRN;-wK8`RGfXr|jOX7j74T%DmFgZV@dSu?`a zC%JTl16>#NJnm9`SUppK5bH4zYT=cWu365nR@!{>I*KHc33J5s9dG|60lkGHcrX-R z$jmf?Y|y3yTm%&1$C0nvRWpeIm?4VgHfLvcJe7{4vffo!!B=Uu=mL%k)$U{QJJ zSEy={03a&0eYx_1GzY~NKrcs)Qd||jIOe(t~4%`UpbsL#*rMm zJbguSN(05yHQLE$%O(!EoG6g8O}=)bNisl#@O?JkahMqvY6)~K(U1<{i#KM>M8%@X zy;{X{d_OJW-qZwBYS$YGUtFern?6_-v@$7{Q5+NgX_wOrc3xPt9!L&Vt88ouiBg+! zmpRw5vzPRI@(4zRN^0)N8LJ+x5Os3fxBw#nM;IdEJM8cuW^xZY3q@=t;ZKgq$0n=Q zAnpWF8!27>-_{XaCg<$vLNZP((#Y<~jI46Nj)RE348ILPP`(8keK3~Tw)6xkK(*=4Z|u}`k-Yu^h&Xh zA+BU(`Kx@C;WY5Hybm!^<;`Yl~?1G(35 zco!PUc#K$aurr3UP}GApv0m-fn4uW6lj5KpTS5a+5z{Hm>-c9H^6-)32sI0e{LKVL zdYLdpiv;=Xv$PCd?5_;evCb+(IqJF)NGnlY*UYbGU|>^?@S~38(@#3^4BbrYcMXr0`6q&c;yq zL39H`an@Ax$v1$r1SS@qaJQ_H*fG=)2*EA)z^Ng0X`ut7y{uQoMmYN_2uJ`t}d5BRlxcMtJbVk;jj9*Fi zLj9d8p5jhRLnh_=t$qSY-=7ciUi(?=F0oCf5551Mj2BOejPRa;guP)P~ zU;tAbCfLu2_Au6;&CJ_Bdl(pbSx3*KmIriZn}U;*rUSI{IOuO-oTxz)*$ z6(wYWvXF?{8VXQ;HO->@h%}lqcYaP&9?T!UZsHwe?_KH zFGS)w!i#9nNA8aaC;dVpU^+9$3tH|GhvTC|prkT_%d<_dOxo~FnN?=~i8K*ANlFFq zm8dGogUyip_a+6m#g`cx;%zoA6f}yikX)0kUTzwpI|62cxj+3#vwJ&q-Rc1yY3GYF zyMa*GP>7opZ-aT7nm10(cI%F}b)f4Pns==ETR`Jg4?ol+s)Z~MnsT z(*@=5SP7;OBE)djRapZ540#lz(h0$}W#jXfFs?AAokysXKtFpx#&oE-IijL~GD_%L zehG*P4n4jI2j%+OY64+}-j9;Q1L?M$hKTm1QPz7oxbzN1gyDX_xwC=bJ)dgW3#Rw` zOL)hzk>pR3g;7HeH`uhu(Y5n3&(DsGk}Lfgkcay?{7clx#<&JV^rgmNzs4g%i1oPdZZz>`%hFl0E4oZ`k624^%ggj|)B5a0@vFiT1>o6nUwUIM~q zo9uZ!d!RCuZjKV|dtN|-)6b`-dK$Mc=)FX4Zq1k)+Ou-$9#N1zcl$BS3*rMZr;x;v z>N$*K+nOTQ?6Von3TVp=;nFPu^{`|36+hOc8Av-&?5ypnD7g+9-ERFkDR6Kz|7?rL1w#>+rF+>r@gnll2KHmEWxQo+}42TOI@0~#>2 zkGG@*qil8{37U_Tt2e=TU46C!h_?5YtP1Ve79jQcU|mhI%~9fDu9*hQXh;zQI`vEZ z7gy0R0;b9>kiI?jfxDwB*Yuz@H{xjqwC-uSziFTibj-kI%v`5u4(Q?SE<;HKBYE%= zMAS2#I$)756V&J^T$XnG=V#16_ubA?coA5PJr@o=X$HiY;|!U-2bd@gT`rak;AKvW z4VhHFAj#?GG#5{a(x_T#p-$RMQVLhT)23Cu*J`=>y%@To6O97N2fDABe4s|V8hd4X zf|ick-N783;>)C$Agnc<+;>!i+SxGxdKQ`4+f`<;G_X5|<#1JN%#a6Ut%Ch-W~k7@ zTH?nSv|J4;)7T$qb^e(6dOd?1SI0GpB*iya>pd#Z(h&>9teq-ME>FHMkJtHm*KZn| zwGl+hKf_cq^`!!|5+>%y?7FLVlv7q6FYQD8Hyrgs#{DJ9c4Qmtfw?*e{ zFjj5HS#W05!>W9+Co@0Z&dS*kr3 zo|)9tc64_$j1TY%By)P?3sVRvTd~(>e8*{!)r1B5PLng*+fni6v7&^w?*u}^*$SFf zrFlV*e_4BMND5yhKXBU%mG{wW-YBO9;A?Y&7v*rtL*tR`uhA%w&2lJ4f=ZDV2;6j? z4u=cw9=?@>gBU31SBrs;chKbaqM zrvbu;G*QlL{N@o;YW{|%mV<}zp|-47+)ZRU$>5}Im)o@3R;#!2pIeAg0=piqY{8l~ zEET3PQNfusg`R#IU+SMmV(|n@D`{<7U{69R?MQxjaN!jM@M<9UaqXTs5@q)!v&#a* z4Z&9bMhASj3;~Psor+bF5Ez@E2dtX94Nxl@5-sizlQOK+PSSZo4S2fqY1bp9?r(G* zDeF&ar5#f<;aGsR@}q$8_R-0nw`jPFwr8AwdZf(_Xii>KGyTVO;x0d!4=rS!hcanD zrPr~ty$%r zgS-{Un9yJV1LQY`yG4k6!bx$BVTP`E5~mRYzM4=ChuY@3J~QdJr+OTdOvNP>jgVd8 z{g5wL^OA(>%{x(5s_tDWjorCQCVhI7d>Tkhv&Ey4;zIo-WB_aW1LyM#-k=7aK{|#~ zn;{j&q}Tr|v(q6(D_W;ak>8Z6V zbUo1eEFlxJ4G^o93#8$@Pr(`@s@gP9<q0HJd`69(vLhFhcL+qFLnPXVC z-sAIQh?|Q}5etcUDB~mC18f^;T1ymA(qWDJd;kCiVgawitkzgXSeHV=3f-tJAvGz> z*M#3rG~n81c^*3IB>M*1RYk+z{k^5Dn{*|XC{qX1sN&YHTvxp+XeKKG;K_+3ibndJ zb=~|#E@Jb@7@mkr?A{dJ!7vW#=_FIj=X0<;3Za3;%6GzPCai+G0aJ?c0CGFtvIRjJE@-EQ4Q9LMQ|gOAg?s*WE|e+x7zBiuWZ7BF#A#^97lEB#&9Y$wv^o!n7oWG2e zTF*KKk0FCaT|4f|2c^=#qD9<1Aq3$MQ@Zm+XcjCFxkd6e0QA_}9MtFB9zE{7uVeZ2BMHC+C`%r(&&`Bge zUr0@r(VC~@ViUbAdqo?-NL>q_;S*b@`*~jZd1DH^ibp8Tw^#c3Fp#=(fH=2g)~Ui( z*W`Dv69C;Y4oZlDd*yq8ny63@i2&f#YhZPs$EAwDR-Z8dcDcmoBALbhG44AWN&f)GTnFItlOgigaBJCtsA4gsN`MBPt)YWE^8yn@$?JBcp zz#aDy5b#_@ym$YVZMoVj9ruLapj-Pvv=kb<%5ZA_s5+&h4){NF3X({1{0D{1@2RYx zPvxWfmr*ryO#tw|kOj>ptrM;L0Y+O}Kjl}40&FwLEymHHmi#9ye6PwG+%0dxB|V z)?TQta$$W9FPap+$D}2|8yk?Y6by+*nM?v%^h4*)#d>ctid{My_$lgO=z>E)l5$b@ z$|?MA5J*fOt4VNfaV?34wi)h2GvFzBf)s$-S{B{JNN`Q4JXNP=_mXk^=x$5pmQlD` znF_yx695SHh+jaRSu{I{W;`5p`}6`C#zc(Gx={QzA|el`KmtAt#Dxbr8?Af>KfX>r zp5FihW=U>yyoI#k#9j66Pj8>={w^C5E}K5 z8(E(39I!OxBuPRFHV$z9_AN~9GTxJ~H@?1Qd@h~T$ z#YC&rA)0%zS&4#-CNRItWK0{5M||~jnhxpm_2JSa`g-um5Pzz^dt>-+Vy`LwHlDj1 z65EO6)oW?^evd?-p%*nvVV8>))Xu>xo(Qp{Bqd(pK6*a{EwG{KrIEx`Y?wzb@^Ryuu?Z`5TEc_;09vy{`}s1Z&X~lccA0a!XBaYy z)fC1t_%w6|mTY2@mg9pLtXNmOg^r%8S3lKdSeEa~s`WhP4G4|u8BR#tX zN!-Z8E+|0D;vXCr00n-MjZqxVuyjp+9RFsN zs|Ez?EmdCY$9{oJl?$vP!Q(%cIP;XTjHB;l1B{x6J4(vRp`v-`C>*SbP=L0GML6D3 z3@tCa^un=rA8UYe)yj2N>!uDaKig!MqRCV%sdf-uvxFkvAbIhg1f3P42lfNJLdIl7 zlSYpq2y_Te{8I(7i(nkmP6f+~TgrAc;$QUFup@#4I>m|q9T1{mO7fX)+xPMo8gag=6w+;#siNIOEq zLA@(du-NgQAg3&B@3G2opYxM|SE@7Hi;jmZxDXy3+dh7*(RRgSvlYMmLAO)!tC+Kp z#4TO5o=QlHN0h3^j(<RsF(*<&fa24*qK2uvqAmqbxV;c4M~rNR3vlXm!JX zcDQ5Z1J}o$Wo^@*{3$iKXO=tKS;_@6(;DQ*_{vz>k4+cz00BLi>8Rm) zbyfX(^nqsZydH&Ei}Coe10wW!vU@ud&H}T(9TRYi37#J_UM1$vDU+B{Vp0Zgm<9eb zm9h^gZ$)Sz_c-AJ^fHrq+Vm=_k)chMLPR$o%Fi(32fzk%E8X_tM>6X%V*+3(rUK7P zXC4bD3SBeO7bS}MDqNkXh8XtKv}*K@%1IgwwS}MVj0LvGc$iKd+y$&&hddAG{K4zU z;8iEt4n4=+co!J`fWJDJl_lFmb(>)!8Rr=*-JdXJwplI_o^%2bz6DxssnwmNEyOt5 zV~S}SKKZ;Z$bRrjtPi0Bv z9Hl_+TTePiXCzPeAwRtTnEsbJXcHZP_!9!+Q=5@XqM!V=_g0Z}b^WTDlEdwP>bM3wi|4=dzc=#qajCB#YyVb0R8qI{a6 z)&K+4AOIG!_QLT<0viQ@^vC~qCGFi!1qB+&A=E+B6xnlj3VWC)t$d??vtkQUL<4c% zt_)fz67OCj-T(f`?C=bqn;boANEc*%D4Dhn$8ZY3cgS?_iGkDW2g`CuXK8rz&N(C# zGQwd{6Uc-5-&B1HTlQO7jD~Wxdv7A)&GohALkfX^ zDPv{NQQ2N3s%MAJDjyAv4>0q>po5_^JicVGq?g~ z+)5%mErlX#-=oK&KjC--tM_95E43c#(Ua#$_0V|TyS`lh$0S^29kjROF^N+=3>B;} z;Rv#bR<$T>DGIy~c~FRjrTd#%c&3BvBo##Ug*ccL;^j`XZdUUf((Lr5@%*#%PWy>a zbV7E&N|Dt4F}}AB#AXPaKxN@O8r2#ga=(Cbdgn*|9{}<(UD30+rV)tIi_$(ORCrJT zqyPX8aP~LLI>lDp8=l2z-qV8qKi%G(=nu-Q$hp*gq7Ss_3p4J$1@v3R2`_vOigQ}6 zfQIWx8{w#0G5{sd78%^irPHj#=_3D(@QrZvOV4(TM`WwBYoPLSg&tY}*cjSCe-t_Z zYC{fcOLK^|$*123KrlW_7%qqjxhCbf>(L=PS23;8JJ7>oDxN`(6p!e9ee@9n?VFbx zd+1Xyhpy=dRK=;G#EZ4|cDErLJ;x$s61-Bib7@3u9*D_n-|X4ah7Q|YZUzf=;fiIE zJ%!4*xVv!?EBt}?$f%Ot!2`A89At~#Hp&b#?3Xr5Wq1n8@SBqIr`em|*WAiumcb-L z^DK6F1!@ehSGPd5_HYC6ch$);4U0})!X}YJ@p(SPKWnxv=1psl8-ps+4E_fOydU{1 zIo{=8>X@72zZje)?0-)F;wIhiQkZ(2hmKuk{?-g?eVq>Xfy~W8+0ZEgp{V};e%oa- z@^Q)5g$3O^qkuBvSpQ`HZ3~c%kt<=?VpdOB!8QP7z^584Iy>OB&A1&~**?y~8oN<*3CmYW42m zEBvwOx4Q4zZ-Lt$2Qpr>LTX0{H=lnZW#wfoswXxXpN{4%P`6n84~m+EU?WXC(|}0p!`-!MaDde1=7Rb2-GE}V8f{LU zC?kcQq!7R05<~ogqVKM#wudeiP7%H6SDyj#n*3{uFsF@3uZ0Y3SawiaPbFW%MbgSX zPP-O=V~^t>K-A~KFVw#tDMN&*o0NIP#wlivV*)w}`T@-lg+$Yr z3>#B2^B*`<@ojYS5V;qzmF1dy;_e#y3Ewx)L zR24Xe1#Sjl)<6TGICQZykam1peqyd=O>{*}8LFQ@z8OJ71iW|*X);u7IiRo>0`duVRwynPsmuZ+ zl%Lpn6UFd{HOyCjg&xBu)@~3YYm>K>}&^L_u2?yF&SLO2*6`GtJso_6hrE z)geqmXaENXobGDXJ1@B%1PH7j7FbQFX@K+pHo|$xmx6C3jE;Uf7bi*Hm$>S2tqIF< zFd*7VbMLmTAFqSoxz~#PcZ;`^C7<=LqY#xxPQDdL0_c!|>636W7tezS^vB~#vff~T z00bz@qCqq+LXMHTFZTe?ztW#Qj-tYE%hjeZhB|yRLU%0Bs5%Cm>ri<**?Cbv^e1*Y z6K`k_uruhQ!>J`JmsmqW+^S`-(`%qh^P4n{FGePlu8QHxgXYab z84~sBqveK1r6@hmkYIf5-bQ#3H%@@FHApaU1jDsO+(Hi$1)9&$Q=2hS`tw4piHfAf zF*UKUzBpc1$SE`cbr)7t7pEFWZ%lGVs_$m+b!1RKVU2#^4HqDOJedz}(L2rLSGM3R zEg<1fH6eU_aQx>F+X)r@nLGbWB%SN8^%nUUX1Y7g*8;_>&ar9M>+Xv8sPeC|=xh`U zQ@rSPj}7;O-YF-|`>`sRQ)qeL_i+FQ^nd~s7}huwzPJD_b7Y^(l_Xblt8*EtQS(ES zKmu#Y-ug-=A>zlg2RTYZ>!)iV!-q<*yt45^EtlX8G1vgK2k51#lSm015dA_)pax>& zrFDA;ltlTcPld*M>%+{@0is#Tx^KjJ$*%r~eO=SDRklvdb^uxQr{5*Aqp_Man>)Y$ zTTx%7e}F%tg81FQrJ_cNLte|#2A)=(4k+YP1Lk3?F_n?p@326j}`E z%WjV(XNgJDuSDu8>$fg7epB7OQ=EK}e-B0#hH4wzTL~7{zF!rAUEBNcN@+zQEYB~0 z0A=7XFNNS@csl=}R70=YwF|?PhN6AYtgwUR9x?UH@Wnt8ml!2Z>$O53^!14ZZJ2H2 zz%BxXqYIaNO7}LQY%of9)m*jD45Y!8h07@D$^i7iTK?e#nh}r#Vx8@Z1eLk`o(Vb7 z5^ZrEWOx|N&+62f49>=(_)_2fo4V&@@zy=_@@f|jmVW?CrAkZK02z}_)-p)hJYZQj zfjh&s$G=cl=Sp{0vA7LT1R8*51ID)QxA(3EU!Xl-sQUiS*e}q)KT)fn)#37eyHsUh{CvGDq2zZV^AY!lWpY%9+(*F*v z+KNXfS8}%lB1#H=?g<@0hgNs*C2uv87%;v75KzL4q+S<~mL&O&u;uvK+C%_^TG=*D zIN9jjZyU`W|41J>epR|2N8tj0n3Z9LGw>O4HhCF+Z!zg6)si&q;l=8I4saSG)wrMi zlR_(9<_Z$+we6&!Nr2-YG9j}enBFP(m8w~<>CBeyoPwQ4o^7^5y9)LTm}7J;&aCPn zgjE#aiw}!ewgb)s*#9bYz8Vux^bwwC`|PTQKod{}k17F&`ul&^PY17LMVS+&1*_Ec z8?8q5kwQXm4!^;N(|&aU8?qXvB|00J9N2;r2&}ndFjksp`$GmsJb6l${xO_+_HZ7M zq{=glhQH1h$s62}PX>k=++N`fPa>DW-Dq)-B}b%1ooSmmDdQt0F3eTC8)bR(x$xr+ zlnVV#@&CO<*sR~qgs-w#Xd9Bcr!UWj5QoT%2`%S>-M}JstQO~loXN*!kHG^QJ?H=N zms6s2ByHr7CcA0am%R7HdA;lpxqg~7sOE5%f#Ui-yV{t)dA z!AlwU5T-C;e(arq%?QXu}_r zKN{ixff3o+1R*#kK_m784*cWMV4IadjS>ecnALwmjcXOjYHiIN@AkJFj`Osj+2#0> z7hXw(;JWY)udE9qjJQu5^Y#bXPr=!WP?aO&+85g;NqIVy)eEa-vXS&)THZk>(jx~e zR~Y+ZXmmUAa{`8YUGQKGTOK0;JfJ$J66}lU&~^((+~4@!f_1K>^z{JdD@g@q%?Pv& zGyAvJ-^vPkmcBK`%XB5%McCe5lrTROEuk9^fB_nZO{^S+TAirB-~l|abvY^Ae1XBc zM0W=JCYOjFc_-0Gf!VTO#yRlf$seL$)qLj zNzIFf(b`9SDa-0w=!RLy0)RJxT@y&ezn>_l!;yTFRdqq#iel~@Wi|pWB(`^V+5qnp zsj@=-cv5|r8$45j?bKQ@0PdL26nJC={AcA?>@MepC&d;)ma-UzqiP#+kpy*Ab^aH7 zyJE4Mpguy)U9|3Y$6eV&7U1GT0#E>`Cexe41BFm?v|^L;-#nZb^da*>;2aT5$^UEQ z97D7ppJ-P^Uc{ofb)XBOZJz=dOaY25-qMES@^9Dr88~$ONu>3RI$F|Bf1cS{+y9oF zJrh)4$^NC|y!p~0e|=NpuWwPteewk@WDlcOJZ(=t`Ezpk!j9IWeftdax{yjy-)xLG zA6|&X&HjtUb#$HFpVujQH8u%X;9ixhS=^2`+cNr(b=s=acU*EgEAMK$oumCHAS$*a zLFsYA5+Mi>UHgf{>w8QCWQaf&_&sZ_3&-PyuUEFm@#~ZC>y#YykU*$PUR`grYDNv( z+r1~Jj1H+ojqkR~)8h__q{n-b&vtgJI32M&QbB;Uw}nGZFUS^;`ArjeN6s;8+p({E z>z6-SP&jRjR;pzd zfDonRvQh)bnlO}{8r+0iHU9Jev#VkbUf(*)Sc;UFZS#HW_>4SD2UriQD{G%uxt+C4 z+KWPme-gc<|NJ;w7L1Ygu@j9Tz=y0L*KIs3jrNn}&un~n#9TCSh#MFHvB&i}X355Z zh9y~rHDJjEEIi5K&&B9G6o+w41+Yo|j+(fWOPESAx(j?wT*ijdl0PefH1E5#&O#N7 z7S|Tdw6}rIfcHGWHRi{?x$gBe@HyO@BT7w+3lsYk7O%H~o8Ev{Vp0qhWDNsZ#%6pm zwW)p;_Bw7hBg5;;X~nsE;JJk2Rm0v%xuRy$EiPXT~mHlP$LS zqZMO5ZBTP^S0cUmOP`iHr8ClHC#9099*-qolc?UWdRSqf8A065a({1;Rg5L%kRR4^ zu2n|CQl}c?Vq4Y`-y8j9`hbX?$>IsWrjkxrV*06rtGLsd0Phdl zNok~Vdzmso<@-9&y!HDAx#T>E4B~xmC4D1)?8ZA23&;*pJtg574W;W!n6YLMt_-OU zmS`h}5`2h#biO4iz?iT9&{vxW@pM)<1Q}Cl;@l)96zl+Tp)MPPRl@I<%gIr6NK=l%1F86wne|^N@6Tz)z0?7w%WVUkoRBv+Fo7M4Q z^0Sq6ayi}T(yWD4W`gu5u^2O=9ePs9E7>*gDU<6J!ZCQsH?R9-#wFT?_*qA$vPBLq zqw^Jf1xMgf>^y}f-w>Ht2Y1vhzQ96s4BL6D8LHWTWVAtz?IFg zB#>Cd2LJ@otA}`z3_pVJG4a~32aP%=2BjfO-xyigBSNpGw~P=bj3H-vc-!55h3h|9{=Z-R8ZNrK_bH|EgmeP6IE3`=wv|fNHzKk{ULH@1O zyn*-rAc6q$GbMO~xQN-HYn66PH`+Wk!Cv~lppwfOOvTvnUTF6iNdQr?&)|^}>U!?Z zYl``Ivj$jO+wXYQt^WB>?p}E-!YZ@A*vZ4njFKp7-&Y3yBHBj>|nZj(b#aBH4nfpmE<&=>r&LFXosA9B1J zmAdRBh0eUg+Gjwf+Sv*ZNpI$MCT{K8gv;Vj`v~Xn<*zhKeF~syfV5D|Z8Cr_bRBrA zQ;zy4qQ6i2z}y#-_39tK!&?AVAN=+;+gX~_k&!N|y%;xdhX>5LC^ofkB8EIcueC|6 zT+Ir5BpwV=mNRfzxoo^2_>^8k5F~=C4WgUeXGWYd z=6DvBN!)|RXgZ!a<93(FKacAAmkWPu;!XdsvPAm=ZtwrgaA;;-u~CYOEBY4Y%r=^f zp`k6)l1d@nRd7+0kxySztO2qAW8SsAOF#WY1cGhzv)WbiFjb|@cI*X1N4KO#=`DA@ z5a>@y&@6JUq`VYvB(>3pqUP16Tsaz z{viOXb$Bp~g;}RM*`FeL@GGdC3_pdbaj&K}(7jKTsG6~x!^rU~g$006P_(c|*#z_8XQ#{l zy+ilq12xUQDjRRF%(?jK7yd`oM5G|tcvTxVS(jTzXM0elXpf#Sjtj%EW+6XzW?0(j zP=m31$t3I>rL&&IfuEDq1o+x&V?`fuM#6P^<1Amp%|Pac+P6M4DU`>rj%w1gBhkbC zblFNA%_;=`#+sK{D^Lk6liX57&szn1hvnMn!Og=F$?C!Nl2Zu+&59upa`$tSBQ3R2 zo%QhZ0*djhMZuGw!}EQuJXjG)xP2&qLX8j=^FWw$#FU9+Q2FR^}_l0 z6?G5ywVVMsJNfWf%0B6$xH0?iVp;hqeJ>SK@Z50Sfm?(dX_EQXsA_axTab+8)$~C@ z>|`s~nCfkBoj179sF$96V50~EAXP&{$j?&nfGE(yr};8jJ>lINjH#?!B*}HJ(*+Cy#1Wrb~krQ~l>q;?t4iqJ2cn(kHwc+Vzg9ZQ^Mue!(yzS=d z#~lonB zU-UU8!fjs*N21F@GIMZc*2nu~8In@BA&ouh6fN+#uRy-eaJdiN^wGh;ql4!-Wa`SV z?KjN%2z~LxVw5-C z@8N>IuNDD20ylR618bwzQhF-qfY4Kk__|_>{(7r?)A8FEiF@C&sI_MBN~a={CsS|* zz)bF?g(Hm>T)z}lr3G14`u{(bzuo!w|0Zuml1313xI59A0^6@MXOjZo3!6WTv;zxE6 zX+;}GU}I66PVZF*8j*y6a>@^o>IpKkm^oF8@^f_yF6>w*W*y zyT4RPN-;iLDnyicpaW#zexqWVHP9llK3n%cZzlT-uQudJ%-Kks`;RHqh;2S;%T1`Z-l#N_JY7a>xRF>`RrqV9e3 zh8_|;QDx00Vwd7KEcJ#;J9Sal%9Rhi?dM=>TRwx%{e`T&5)evOq0Gjhc#cS~BQJ>! zv1j5RFPP4;<+i@3BElg#8L!zZc%a7~EbyG00>X$e$SrsWe5;K{o=}si_+?GD3x}>7 zPyi9{i3O=w$Ee{x3&e*Plz(T?S{b_+y()>{B9h0{gKLJW2}(f}hw)^T9*KcXTc_5> z)XhbPl3!t|ZH5*G71*n&zalF~;R`aGMn8Ld1(~2{-txL+aOYvLv1n8fN?I0>Kh_y_ z(4AaGS-9)OWFL1_v3{B`N{X*;d42N}s zR&S*sK5@xjzy9ORp|#xsZVhc&FwLGc<8ZnnK|G}%SSBJuM0RD%cV}=+!t%|V6OK&k zW}EXlP~9|IH%_&*pPcCn#BLzcfJN;rzGd^7LO$SOm3JL5{YfyiqgH|WKD*oOg!U<~ zw|-}3Vbpmg%fEY#2nj?G3)=Nkt2Y;M9EyUu6QrbH5bNCrYtJ87zJwg(-{uW0@6I<3jRQDGe)sxi5^%3tJI z=mH-Km6+OfgA9k|{o`ap*Zzi zx;`ga{SvIpSnei3^7~C7dont$yeA6L1zWFe^MAhN^XJzjL0kO)0p^FoHCy_AV9b5q z_oUUWY!Kbv-04?CA2O3d4C9P?%R#Aph5SpSteI8auTOvoY!& z3Tu3l7PRzfqkFaRdr!7U>!>>qRj!&Ont%fKF=NV`^^C#Mv_DOhzE61s>BYz<{vcI( zWCknKCAr7(?_b*?n7a>gY`9Wri(0W)o&&2 z^9kCOcF86UQP6Am?2Ui)X$2PdbN7RrbPg#?oKnwRXQI(_X)dakF2&I+j9aYpg;a|& z2kl}DO>rF>Q1vzSO3Pc?b`0M-?rRiR0?kf<_0T7TbJ1XwvHpOOLFtG-_et& zO!%1QD14z=`9b*QHw1cB)+$*f>IZycqd1Fzg+jiKKA3AOfK(%Cc-zCV9Szl_!8LJ@ zj4)Ldmk~=TZixKjn#Y}#o)nlUtp}jEV}5G?SZ`UF%cj_;S`cB$nlbRbp;rz=tHM+X z*C6-lKxlXy2k@9fILeS*9U74B&ZY6p`ks;+xM<*hY%H)0Ht?Y}raue#4 z3ub)z;DL=6{BW%-#9zGuxKs(ZxvU=Jt?npChV5Q~*(E&93;zGW(S4CIQkIccKu%(_Zn;-wWyX@ST z0Drm$>w}z}tYrklbVoisQvj7AGyNzandbiB^x38|ZR3%ct5Ep1yu<=Mq|e^bTU!wn zO8auRnUfpGBn=Y2_$A6(mNDFN6tl=p=OhG~^Ds-eNE9NhyM7fL<-E&1s|04wigu-) zx+}iYk1`sfWHmJ2!-d#HudFh|cNcNk-|sj|TDkWlx$2@%;$tq{tIh8#kn_a&!Y6fV zlLKJ89;I`0$eduIRjPX-8&%VskpZZO=Q2q=bJ?xI?iW`{1>=|<4*Ak^wE?8D3|T)W zBczIA;zhUdRp+O=3Z{YP%HUavja@)Q9CMQxzIRMA)aE$&r; zu?Gf=7LCZA@nrp*OjVkklcbO&_1pvT$lmg`^9|_*{nd zTXKU}ILD@{g+k^0+Snu%L12}x;UOJW$-2?&~ z2!{$7Yi2Ga5~a$>95XvUcusz|@#nCB6~?D)*iH#=hG%{P^IZ&)#B=4g)Hf?7yXV{$ zL1mHjf-?~{#0tu==7clN{i)i)1)6eNg;{uV4peN^I4RHzWMWC>+GEWlXkPYb1eWbh zM?nv!VzN}v=^@eo#?0On`2ya&jYoV;a#%jbcDdYPUnV6*IzgS8h`C6N6a34j-ga{h3jC+u=!a~){ftsnYmWw=eo5772Mjf@I z!L#G#Isvql0>wM6>NdXm$62&E{(2>*QNgW`A*qb@ z!O&Em>p*)$0yHxVov@MrC_Z9vOT-MT**%+yAH+H~@vEi{W3`0H5??+f5B{34m!F@+ zV-B&!S}sS4xsDvw-pX43WI|bns_BpM5IQ&mld>;tY_zmq?u6_O0GuI~_vFZsi=q-9 zJ4hvsBq8rB_m!Y;l;ZPqpPkU*1R1&P#!zEwXkM@20BnRe!nJy7@G-Y$<0FJ#95IB{ zEuyMNZxhpjKb1@LH_)g0c$U{YzDGVB z64@vRfyXlBJ9l>zddsg|A0at~Woh+<&w+IkItGiS{KF%Kd2v7IrE#*G2=P_7wAY-P;VP`{*YK$*OqK$#Zb%z?{F76+yRO+(-TnZ856mM*t(E(H^S$$k&!1g! zCsf@Q$UYCi);}j` zxjC+#OrGaJ?_5&Q%#2=WH{x`qZW7yEHrlCp%!zusHnCsK*~u46Etn)cxWAx@VLmHu z3#|4VepnRCgw9i6hUbTbo67~;cS&ZL<>xbo-<4}M@oh{K6W}%j$(*$nBEFnuM@I4U z5L6rTn_umv-jQiMz!jWyLH%3c;WS1sl#<}MpiAiKWteZKwV?wA}j695f z%Vv8B-DlP`h`vpPQRqw(r8(@$81@#0RJF5S2F}f*4;RCz2DZS+L?i1eS%$!T%2QDE zkR!YtxkcY-MBYfXp}39U{p*CPFm)m~Q~uk``t$TgWk(@m9LCBvlK8gOyTc48&nm3C z*^@PFolZzyLS`ji)qec9=EMg`|Ke2`80)9)6bDBdJo~Rscg^!T0EOOao)8I*%WJ5F zL<%YOdevb6+uql)XX9L-3A`lO3G%zbHkFf{I&C-*<5q@J1=bU-o?QKIr|B;6{@B4I z9Le15T0no8){&}o%5uKOzu*M9#ahE2QQHPH5Lo9Jwb%3Dj@G(yh`A=RHtHHK6&(_I3=j${DCi-n3Y+-=f!ZT(2l z?C_(U=(DM7{VL-Oi=u?rSfP7H?{Z%o_O9QCLUl884;axzIj_Ct4COxHzs9?ar%(F` z%x;MI!%L1#lLSl}C`+$&@H$4*3MsSW328Na#R z0?$io&#YXCrpQsXdrXjXW{wqEk3V~%r}=q*2c<}BU9Vxc+hv*uPEWLuwB_A2kJ42X zu{2RE05N(&hX?l!MN0QtwprKXYbbL!>=N( z7LR;=?VS2;XbE}m3IwgY4v%Iw*6|VL+%#&8}N}A|| z4HT(vlPDD$rJ*(9V$8oN>5Cv0&a3~-Pm2TY8$tAZ^uYp}0rzu#n;hSNKpPsIwX-HmJ{K4Rs&ccP zX;a##>ehq4mK?;r5CN(pF+jm56Hvzvu_7)|gQGSd%Czed-3+Oi3W_raUQ0FLb)>PP z%z+W+cDiIA$%}bs&u#=@V9+zql#vwzyT3S8F>`r+ZK-7U%oK^y+?a@M3r0t%h>&H+ zU$0i;Mpq941zN#FpH=SmCdxB13+6|k1!X@$cze1@{l(LH4{gzdF7@#B1wRsSGAq0M zTAV|cL~IHZZ8M1E$v~#d-^mgHq{qaQiuNCO5+w)HvlV{=y!T7O@mowKX)@NH@gsr6 zYLaz)ohU%3#tWVGk<{#aA)><_V-1LMTRmvqiCUj1t4pqio{9Jkbst6#{4i5DWN~hm zW$PX|rAzDu33S2`r$GvB9}fs+T*!Q_8aIlKGnk#X*^zzfc_e>OZY?OA@ zlo*3}nkB$OH_QZ7V)0pct;sN&FU5Wm9r26t6DOU1P8%2VNY@%dt$OUnYRHWPGDxSI ze}jZdq=S{-hJ>JJsS7=P5|1~&6UNc8Ap*~(IgEJJ$v?{s#C3MWS$yMZ$87m4AP1g3 z`zI|xM6-FuM9Jx)IlMCwuIW*+b^?Eg7;%zhM_;Q!ZS|~IwzXalgUqsmaZ>3<2Hfn! z%3=n*W4)ulC;!TGS2<5m$I=UBJzt;@Lsq}(FZ+%L-ngnkfM}yyJ=u3%)bQ=E8kUJW z`4Ns&G8TxsvhX@7;}Y30UUnFMrJj6KpyY$_T-ll|3a{I$qoHtHFTdiacfQdci=~19 z1A=d*#1TiYXrh)Y?CwOslGyH}#EWBSen#@6qMhe>nU@pK>qO=%0E&dMzyh4hatdy| zQAoFongPKtlcvo{X-7U0kocGHpL8WMW7Lj@hQahjdC?hmMYvcvYGx7MR=WiF`;2^EXibjg&P?f1reuY#tZz zNEW!8248I#+jhDd`B&1uTBfuzXEzpuKtiYf9))*%P}7qIm5z*Kvl7&>A8J0Jy9NoRupcCC!nyUcPCH?Kz+ya1CpHGE<1W*Rjfrt9o%rLZXq8DBA0|&dX zz*eL@#bY-W&YOnSXeP8S-^#?QGnEO3x#soRpG++0T|c@^lDpXx{QrBFM_Llr)rmna zNq+xp|1)VyKyNW8Gfyn(yZ&HcRSBJ?zNWi)$YJ+!g7MZ;MTOn};mh?tqBee0v;@`= z5}G=sazgs{4NvF#rhW~1_qF=)G=>2JK*MwDKZ$BX=-$8RexgD8lBWyHBE|PHM>6TQ z6~yPweEY_D2ar76+>gVq@U9W4^tmAA5=y~xNMjm7AJ&?r9-4;M-f>Z$lRFcu1h9Ep zE*V#pvU&5Z3cQqo!XoYNI<-R>2JrFkMRZ>Lr)zQB*{xC3xCrihq7-l7Kei5ipeQ0_ zOqj^*hwtAnNS%#Pbbwm?_~oMyhq?h&BP=3@vOalsZ;xKbwWutzZAKQb3WxQ8A@x6HlDZ?JA z@^>6ca5RXYX#M7hhB$&1JE%N&m6ew#$l}Zcp7VAR-s4Db!o^hW5CInKSOI!rL3=@- z0L3@#FUUZ>o|SZNCX))Vd}vhD-PaK`l z6pLueudZ!%!}V(HnPX2A9tDQr)q_92aMX_^C1WqcUy+~30!!HUhGgvcB~*ocqkTIH z`0gomPhkeDipM}qfiy#xh-8=s`|Ai`fo>V_X0eUgqw#uVVsv=Ki-dyUol}B-;W{z7 z0tJLUhyW0U#4JQuJYgo@fgu>~#QprSHf;gOi|}n-O)DHa964&2Ie(d5|encVphiI+~?ooF0yv#Ap1^ zFlVHC$9Wetb%fw-Huz_9Ki5VVkMU1qb^vU$w|qEW3rl6h^Mw!|Q+#YY20L*^$ozBM zin9h@`0PB0SlLjS5cZS@+q~ScqxVrz0a205Y9mzktD~TxFu=Y7HuXnXr!l$fvmA~O zfG0yFVpfZeA!V(l7)>ky@Y)vOdv=mO2C}QzTc%8!lwSFC|5LS}oVq6vh5?=Y8j2Aov5mOQrXhQYg=zA(P3jh_Ot% zOb~-I^4A`(I230rlW9ah(sp+(LwerDVb?_2m1ft^5Ny5m?)6*5!BX=HvrnNhRwM!g zsbWmJAXxFa&>R>LDc7VyeV*{@BXXM{bIPJ#p_;YlA|Tk&9@B5kcQ^;8?SBd)&PZTa zD;6eVvdjCs;YaZ7BkadUb5&4|dF@L63Hc{iRd+}XW&m8$!sA3G3`a{#e_U+l9`+Yx zdRS--{Rkgu;e+| z!KU6caMkd-Z916QJwSTUC94PA6tkQ0j7H3^Vc;Ge5i$f~G=(A>DPrz*01_ko@FJs4 zBRx)NG5{8)ZNZhR8;W_P<`|S361(*)>3?IF#!H&-1YpWl!^za7`VB?HWUIAM?>xpD#m6krXxn*Z2lP&OFt`}R=S1%umm0QsTq+g#4R19ALU42ijZP|pL_Jg zQ^AZ&^W}&jNc5NwQO6*jy7Ot+>6@Wl%AvJ_XN5Gilx^VnlK-O)d2I007+Rj)qt_V`Th8H_FD;q3+EY zxS602u~j2so|p@#`Xcx%PFx&NS|}8BX;qA(TBo=&XZG!KEK*U)thc4lwUbhnuDgL* zM4{W@Dr*t{A*DYR=+L0EoXbX6cMX2QpkcLBnj<2j?P#%wtETxiQA`&8?S&nSgj8dR zNvV@SLV~R}1gIC5wmE@(ARV9lC8cu}hCYPq+a34?aaC@QiT{Cn9upG+la@d+5|~Sf z`4U|W6afB!eEBXO-sIJm{-h_wis6X^1Y=P1ELXb?AgLj++~l?6;2~V6fW&rm6z}Z( z*uMdx04K(`;rx-6t%*bwdM#~?RStrO;4wZ@hB8`1Hkz{+9#D9!!%rc=YGfJoG_WTs z4@qZDG?T2!AIPJnt4Z1Z-WH18#= zt}<`|RJ645XVCu){-Q}o#QnECFfimtTw)eGL$qm3wD{`5t~EdV`;=rw{^>REgpdrK z6)YPJ%DD^jD)xgqlD0~pdQqjQfuJ%XeTp3Bjst7}00NuoH7{HE9vn$^EH*WEH%p;p z=DT7!DG4&MHUB#z62fa@h@S%6TZf0@msLp6-Ab>;T6h%FLjft!V+?V zOtEm*fe^6@%Cj8YkPB~PCX+a3rpFf)o$BA*-pNAyAZ+$))w!>eim&arU%VVN=u)=E z92l=jFc0!? z0q9icf3x6&7JcHc2XkbH&r*`ta&By7m$sQ8`>7z@wv(|cptFv%bN9Y1^ke}H3ZVR- z!SoNH6^smQpoUv?LsY!Zpgm!RE%LXr;kuVMFWIAoxn{*oOSakeHV0T?Gv!T2+0uch zGmEN7x*-+mv@W_0W};+OWmz&3WZ;2kkP?Y$P}Z3F;0J1d-W8}r<6lAk|p1+nMm zK&H*MRc9!z?762F4og-lzu;$vpFv8*)B!4Dy4LRHGin=@Bhxg3dxNFOu{w0;g{D2s z4tXs1CpJ^5(atj|+@NB96A|rwjjZTnOv1&aTl>SBERp)*G;KrZ@<-v2fB*o)8FP}j zh@=$a2hiNUkw;#xmIA`Q@@FqDqkcL3e@CwKU)qK8MN-qo#^z}# zcJnhij!BcM79Z$4xg6$C^W&VSC?~gsUhLocpbvxvwI|s2?OqcGSBj)e5ak-1WFOzC zxhG?HVmzaTuHPZ0;?SD3)C%>^;!yu6>JqF{m6}|q$fF}`t{*sI0Tfg$h`>J+v+{if zQEa@V$bB3Z622bh@CaHtB~iQ#mbpflcC}e>#aw8EjJD@)xp8_ek{(%h*Zz*cQd`&C zSdrlh=3@G$uDF}n$2?I0_j;O~la2>JA(&VXCmq$b_cd~VSo$D17(DC!Q%*7N@o(o( zjHBU_Tm{(3AdP@+XWYu4y71h!T)Odk1u7#zT;Tn~CougbxopwQ9~8gS2~Sb?=|>jQn-SHRX7#H5 z0q4e@cMi{UR1PzIkXS8KV8=w0P$)@Z12_YuncX10YJwEuTm9eJFjrAnet4F^mBv}aU!0;g&e4CeJL^Yl)mGCBw#9iNf(q>n~cYjYSy z=vs`J3fD8xDLGj}HG@!)hofnDN&)>WoU;7#-5g5Rf03p zz$5aUR-JUn0tR1}B)s#XYtkbNou#Zl$PqOYunxhfSBRu1F<_$UIR5gk2M!xlGRZW; zcHb#X{Fwvrozwq@27Y4memuT+J8Ui}*qL_{yd~hP_~sjP$Q{D98~$*80J&~?ZR)Ok z#oZ(qRBoK#Q+rH04X1TEBWUj~D`2~~D&I36LWB4+JXsM&b%?mO)^IZ$J8ak2$2$u}BvjKoleE?>0#fOuy^ zOEqTC_we0MuHS}=Nu7mF1m9-DVXp2X0kCTzAJCO)m5+&Y+9=af=U-$vrV4MKbWbb_ zWho`L%QzAq#H}p+mlb?V3tqfboXz=GP4Qd%2Q2N6mTdrEDD&$f7$f89yzlCirEudQ z6`k8?!w%iIs6L=rd;xe0Pt3*~I$P!CqJXFth0Q>~ z042(P<(!6EBSh?;4#q!eR^}@XZV8gxjYQOQ*Fz=NS)SNy|DHb+CleT#&(k8nCLtN` z(i)wPZTG{*esn%?wn6g!gUREp;}bcyb31T(VZ}G+=eFHm2L?6Hu1HD$Z?KCu*->!o zRxAa#!2zj3Af_4z`&30{#4(gw{$hBz$CKz+7JQiq3)h~u;aUXtU`NS0IZp4MAd zNN15Ivb)BM9h=A!)j!8&l&{M)prTT$a1haxmmuX=<7RdPW?;e9_esY0EaW2Xth2Ay zvsfc>YiLRuT2NI(DPAYaskgOoakg)F2{z;2a|r!=Va|w=xCOB;GmPgij&zft3q~(z zRNZt9joIAM5Oh(pCEb!-qqhr=#=Gaos|rOD&h@8ypX{L2+0jTFS3hY zJYz2tYfumLY>-;9NhKgCQNoToRr1aIPsOTB#D;)Jo{HQVZ`n9BXXMH@1%+teTP z?Le?0gx_&Jc7JIBQegW&&XiRjP(1t2Xlzob^&D9H0%@JG(7&yA){%cg=UE%xGGh9J z@Zn-upPahAOxFUlfxc)!wcC|H3(ls8ifilKw#K&-SFGM>l-?C@1tgZhzfYrElB zTLWyLQpkz(<0ZapChs4L6b5#6{?`6+UA?0VU|f02O+eUCSq9qYw*{_Y)Jj9*#|&LR za-$xpI`8Rb-8Qc#fVl@fYr7mPNgfmLV~IwT90VyAaXWui{-D5|GGG_$PHJUf zwn;ES(4Me{&n`o$&cxSA1kv6D{`S=dOn@lCbMNq;W*0-r0(f>G+4A2KSVx1Y$3Xvo zjIxe$&R@r_><85ocUjXK?bu$8GOsBM$Ehdm21d)M_xU+Vv7@w5Jg{^sO}zS@IM<1 zX;ZRV5o9r#_o}~-_0kP{Y&k770?4SS5jT4|WV7^!!%6m}$0eXn_0t4YzVL2OMg*=? zU|9yEd`*$7RYyPZwVZ3u@lI2JNO0jC*8ydbazGQ?CX|wZ4(g)b6^?${VK~UxUM-6M zjZUGiEJFe3pLiXhGHZdY2T@o6Z-*@L^}CUW5`#WYfHOeJYZv$2ej2RNnLR2=(3Gt+ z_&irP&zo1s=lo0Ynd`tp^j9_wl&)G2PCdJ?L`a)}L{}f&_M$wl6kwnDJy!e4)xYq; z2|zsEEJeE5i*LemL8*lEj)AASH!3;%D-hLtbapqf5-6pZj=K5qX>? zz*(#hGNgwcy;I!j{0?wQJzo+tH6#0hkAvFG-%z!3>i|9@P~oTo7Kg=^hVx7hiRL}5 z9AZN?j?Rrse{{Q$>(5g<0?S?ScNfb-+?{9!1+$b{J@!no*@uKwT#9_xQjX`-{8)$@ zvXh=lh7V;ZJc+g}PE4uW-k$~&eS=bd=uyig6y3_0F$Gs|j<2!i(PVlc?s_0o;g(o7nal0a z61qe}>MA{C)aNTO)H4zM?=lBBSHyBv+tO4eO~}UO_zE5CWx$Umjq!YcKXNs>C|6IR zOZTL!2`XIoLbIy?yL^X;?1GoU~!7ews7De?(M43Lz- za^~OPWGzhi1bxB5RPMz(lyc-lYgNnY?-u|`b%Opv+MZt@1D%;bIJX&uK{WR2^AwG7 z8Gaw^FHoL_?BDM?@3rA$6<6h=Kh%^q$j|Vc2Xi{*S1Xa*JxrDB0ga7Qnj*hbsAlN- z@^Q4qG7uiH8?>$Fc;0zqU)d|hvSR^6OTH2SuNQ0hiG8|$m+a+t>Mx>-I+rx#^+~@?B}-bvF=2jBLW4? zx9ZXq#VbLUAUsI*eO8Y^aaGES&q{NHkG=t$zNeh6`>m@;aj)`MUN_4uYNu^L4d?|( zS=!@v7!%&heqHlj<}1ddagokN_Vk$MI$ z{b?8~Cq$|52~xZCn|9Nn$ty%OrVRk!nbbX|4emyymw(h%u)j$q7Mt!%#eVC1O)+zgj zFxsLA1DatN6ba#t8Q`_wy8i9^F)q{FWQ_W!fCW_CU$-DXP`=aH{Fqscf(Fv5>KX)( z#{gd+gEEA_5W8xHVl_zChV^ecF2y6tw6Ehm{z@O$AHc$V0g-ciIxkB}(sv8npsc=< z$|_LHpu#4SS2Ydiamf{z50Tm3*8_AtY6Wm~0e+=2&uS z8^)m#GE7Gbd%9L_QzTgs!l0r}eXo!c!mpB%h>#sN^nU~F_=tUCd}$SiF|PDaRTR1f zkotUhw9!N%Hx2?g+$Bj5zRIo)juy4UBqL7fGYi&S&o9p$M9Ugy_FbDv^?N1o&TvgRy(Z3hrwr zl`nAl9igv?wED}>>5^9XA*Ai@J2R86lOFx9=}*SP8;s@zGg32$N7Q=8TP}P52`ZA7 zw91FX=Z<9!^BYR!rLyn3ggQITsNrfQFl$QP+ljY*q~y3 z1tsed*Ok^G*NgUm0^)8#qb~hJLqx|LzOi)}$H@Eqy^Xq6-!kHav=oAp;6ACU@9;UA z{gjl876r~vR-yKAB2cuByp-44ceftdd*f9qX|)Ris+pqlvtaxw^LZgHB6^T45!Qt; z@7&7sQjrMR-W27V@LeNC2l>^f0NR8jgK zncsa3hE^=W%F_7f$*mbzKEU&tjv6NLJ#Uoja2gA?ZA}n>rOUlH-Udu1JF#A+wGt#h)LTnSbP~6pM@rWHoBJbABXw zPoShX;#&+NnO$ixuZVtxJX=Duu@t5e{t-E_`@p*_!40Pr53e|!+2lW)HzUG%{PVRp zF}7ZVBaL&dD0E<)^Pg^rvMRPf#+8SHo!SKW3v2+RYJif5DAVftA&Hc|DKrHO zqxc?eIx8ZPSz(QQM#`IEZ46!B;_n^z$;G*1#MAfg{6oXev}VUSzz5B83T zsqxvpR#wiyY{G$@7j`fVA|DGyYUfo z(9?0D^26i2GlaT6KfBs;$-`#HQ`s|#LhnE~eOMy2H&cajeg)9^B7ruu(k=q1-Wo}x^UhZG*E;D|#Y7DESI8F|I)LQumv+&%Ix}o<(UFBTGQNml^NN7`0 z)Ae-JrWYfv@Dx7P9{M?=jwbS!NJhQnKo>jQ-~cd~Vvec^;3T)t?{U!R6D0{GU^s8> zx_i&#Ai)Gq>PeXOL8N`m3pjw$dCET-L?iM`!wq1#aU2@zm-DoPbz(h8FePb{Oc#wZ z^&FvqIW{lon$vL@n62ekU*+WT(!t)qrnX$YYNV<~mnGjJAT9s4i zq#Dk_vCujz?!8cP0GR`HIsqslOhNs>nX*G4_PLJT=sggBe+YK=sg;3(W?K`w&jTS> z9{I*fW^g7LL6FQC?*Z{IL|*HwfM8cx>~qY-QjI9q2VAdYM`0-1Xary(LQ@Q(T$&Ym z?G8%bo3S>fYq#hDHYMMiD=gShZo4B22P@ll;7SkTkXn=ICD4b5;aSL~{j$N{oRu=H zXmKTeTze9}z7WNHRxgQ+>Bu0-Nj@k%rw|_S3f*K)1B)0vnf9I%sD{_T}@WNoo=q_5T1Oziy*P#wW^s?PN@c zV;N_QXRUJ2a@g?1x*~xHnf4Nvol)@ar{W&%!(?na0bo6@YhtIFcPt&HIhNpH9le*}=nDc)pg1dh%%#1d6Le_Vno z^Fx{?8?s>KxpM^ic^D>t#e^x~E%T;W09J@_VSNapbMAJ;LEBW{G!!W|zFi=z{CoXh%nODVcA;C1y1z3DS_c1US@MQzV3 zUvC294NxMaeKfMK=TwKxu3;tg-gF8U@9NN3n$&RU?jn5RrGrahwFVOKrj|@rWtfnZ z({iD+pwDt$r{eURZQZ?@o7l>$3M>P3l#ky>8)r4pqJ1cZ2EfZMG@#;j%OQTH65(19 znZT$rrGKw~{NxM(!=eiVSNK~zfa3gxegn*C^^uNkt1HxMemi7gHrFRii{t2CFn&6wl7i#FjT=yL^@#&k5)!mU_AQ{q=Hm&32 z%%WW;i#Cp9vEtc0j2B_c@KcIT<@->lsnH1(zz4pVQoUHOX%)KnQZd3SIIn_MYV+w{ zR4UbZvmHTgr-FnaYIstiy7$F#gLlq~_~Y`dv^b zYnIVj`x$Q^jU=T+n+lF84ksW|@P+f-C3iO;gh_Z7q=9ylkl=axYj&lUmDvq;Q`r6% z@`DJdI#qP>{#@B#(6>A86-hl5DnHH)oN&vmHPwG7zPS?992DRIKq#q~NLC!UAGjb_bQbQ;Dg1Jb%sH#O8s{}8 zrQOTq<+x`J_vIh_BDfOOsz;WPO%aIk8u*7&prUQLH${mIt^j}2&|&;-%7y?gRKR;> zv|#94iAeDSNIVij`W0Ke*{<Uf5Z<9w^o|04cT?m&70=SOWOvVycPDIJ`6_B6 z&|A*G7_ZpC(7Nuhba|;uc^}QGyf&s9(yLq1WdKTS!@Z z6ug-({6xXMN;txs@|{nlX@Rl0ggey^rx1L6wYb2>qrNv7HrN{K8%C2Idl zCy#YZ!N3a!u#g_~u{v*4PLP4T#$Jby4bfVxh}z)fcMx}5_)K(y>7S(HHfJTN`4?|e z$vX)Ky~ZM1bvycd2bCynAoNjb=BV$k7>EZgktubc&M0zGVKj+FXC<=r`RrP=B8Emu4K95hl|~E7fY8hzG@WF# zvXO%&O+9VJ#t=&Ne*PhlhXiSa55W6E1IdIm$}j~!YGtxU@`cq6h^N{!A(y!V;3yf-#YQweQvnVHQ@#N5Gt0SNvQ>F@m#3Hf59FA`8L(^Co1$UJzsNu zg9UjUcYuyVfTeDTlim?kLt7Ez!aM z!eCV+!$FpO#OK`OycqX*tjL01eE^grY4}e`YhdHTfjUDIx|SbWrbnriyXF*fBSw5oscWsYkZ6AbXq8JHIV7~? zC%{49f#iMGT8o{M+S;x9jM~CP;CAUa9S&PVrqYbW*1!_@-u!LMA*KKHloDYQd{er- zPs@8NUW|TlYaYqJC(E~C?s%9wi~-zeh;Ft8t$aI|Z)OlnR0lh=WdVt~g;( zWzxrVZXd6vwLa7@SGg?qA_Im|6&!Ftn&3DUP7>Z8|NIJ9*`1>ap7L&8%)kl1!98T> z=XH9Vef0xExDeYdn(akTQ(XRknTDDR&%D*sk4*}#c4}L@J!pk_imn~<@F2+3$di^P zSznM4m_(vf;}J?S(%fkq&o@csx;lN5ZGLoI+D}-2-oFMpFX4)xx9>qpYSR;O%J2FX z`?<{7yJq^5)Hk{Y{Osyyr4Z@f_NU4#B!yLhh8^?XQ!2#C;;sbZ;Yn|DXt>1P0aBrV7{!{#q2^v8a+M2px&fFM zVC9T$T2utQ{yyPMb<2!^}h(CXH%|I z4bu?@j|4>oA#w0umoLn!dmR!w(wab@C3==*HP>B?&fzyBv-yO2=D?hIqf()XpgIoI zh-90BSF50@AFz6^C${Cjwj+o?6*5F+q!eJ|*^$3@WhMX*|4p?Z?*a?|B7-ykK^QcR zSI5Br3XEUHsBM^MA$>W@4z|^gle=ymw6B|QL1jQN+ttL7z2871_M~ld9LI_? z?P}4`;B8;bs-$6%Ekro$dz?*=oYC{LuFx8P;t@q%%XN}amsHw9%2~P|pnETZwB_ZG z4u#GDH>3D;w-JjkK-sXtG96( zTB=T*-@~(b7jTPLa}Zr#^DTSK72Oq{#C4-Tb(FMhf4lmBd3!m@4M)2$_ImhGEcpv+MoLu*C zH8Y$sXaw40sw-AWJv>RvbU0ObXhrjn0X(Sjj9yhB`%}i48#XkoMjnlpx-JqqNVSmK zAd`{GI!d+S@}}{Vi3gV7KtmxO4;AozD^UQ4v-5o4n_m1{W#h4zX?1_(pVvKdxR??R zY{2iWxv%W<8_g*067Fyb3QuHjnLgiOsm zDL?pWdhzfHk3r7s2W$ejBsKmjzU;!?@+3OG0?nK>&LB6=Pe+vOqj+0uaLq!f>Muij zHJ7fsz(|K(|0wB&?ZN0E)}761>BGyXoPfY^JFr_pN;=Yd((GmyvvrA^Gj^Q)jVn&Z zn=A?UH)zM`@WdzGhUu#<;Kp=0nDrP2Md4A;p=AgU)C+m)BOz8lBvn1(#^?w&T+p^s zH=`yL19o)}e{PDa3zc+0p-*12b*vEhFS{(09K-Te1XRBYNGND&+V9EC_M>3l>6O7> zp&bENN5;ky6UiwHImzv0DzI&&q~xbQ1cYG29E6V_Z8XFJj8S?NM%>-mT8y(UmxaiJ z$4wKefvP_Y^{SGcX>8L6;ax~-g-rrYBZ{vU!_FcF1#rgzuWc=eC`Vh?3&Da@EuFkP z!ksRQkr#QDi@G!S`D$Ie?n2rX>i5^Luq^!CVq83lU${S|qFqnit^IfgM7+zv_4;!} ze@A1XD9j}e+*HFJll}wAEF|sldK#$r-5c4VFBf#Cffu|`bF1Ry%F@xL_3Eq11*K?NeFB3m*G>VnHpdM(>in$YFA^XfaAlBb?gOIGHeuqF zeNaGjZ|%2K*MG&e)mQ+T4-vnr;_c3Ncc^S1f-eW>x$t zxU8d||Cbg(9!7$JeIdAp5JHs{8%u`YKOyfW7#&CqonVk_=0kR5(Zm5a+bN<5;X!*X zP!$WP#08I5@x>koKZ7TUkQ}=Vn>5S3RX7EB;1roSPWfx&^9)Klb68#Jep<1ZZndnVr`+y@Y~%_FLZ9O3&m_bn)o?geDtp zA1(m_^H#s?tjZ{w)CQ6#X%qs0^mu~M*z-cceMU{m(V-9FDBIqE(-5k>ys%-KBKWnorqGZoG{tqM!cEE^l;fO=4(P zK_=h;5wE{arsE@)1Xsy=iLie%rmK{28a0I8iDz1-$xfo5aOt;SWOFQ~VvY^;hL)FT9dt=y!Yj{|6LwH4^7BVvW4Z4)x z)Gm3#jJydQwKEH|zx~?$Zy3~@dw|o`3&I~1V@||Bur9quhH@b8a6GXbkEIJnw*GfU z4&4Pd>NB0;V@DEC!<}Fr-o<=&=PTe@`w&u^RG2t^Tqu~ZqY^|~a)l6RgK3!&k~UBb z>isxBkd*LUGnEFIanS=GW6?W+Rw$1bF4VMm5wyw}YiC}Pj##n|836)d=1k8LJ>HB& zQBE?@O@@Zv1Fr>X+F49SvG9*k1C7ib!vMYF0?7O1N?quB1+Bf69oQzWn_jj5pIRwW zKIuU4nm6z{Cg^e)qwL_h5m?B4zGr%Ya~p(!u;jsyJEf1`*=I8EAE1BquvS87VFSI4 zW+cKbCTprnD3tGXd?LPU8*)2`(Pt&Q+fHq=l&TDr1?hDh&nyS4sKexKmW%wc;sn20 zUvf-?k}2jvAmuY$wVjewR|OB8m(E)W4kH!@m3PU-(3F)Lpdbh)7qOJE?9@!x_!6v9HqTk+q3e>b5OrO18n`zax?HT22?NKYgFLp-4Ubh}{^5wYcJ)aS zY~Bq=^o(lduwdd2)ww23Q%})_@bv{-5GxHuKY``tqZ3URy&>{~OARz`*|YnNYL64_ zc15q9Yv#jb^maGC-n$-h9DvT&;k@}bbcT~*h(3BoD@pQDp1mK)5!dl76QiV{!fzW- zLTDcro=ni=Rhhb>|GFf9;~%p>1q0|z0H6u;M$T=5R~~oRam71AcY|&OlIJ_p9cgD}^S@JC&s%+6KqR}1 ze=sdVrDzZQxd|UG0$AA=`M??wdFZXE_dFE(JtDT1C1p95IxSp#aEa?4qT9mAq8`}` zS3ei}75}dpjZDp;o#No5X2GXO+8|fFj|GK%q!|E`^03qkC=)iOFmB(1kZOb6mqrL8 zatn6JwmMzIdPe4gax}MN_uV(7&aec^kynp;NZwW!$0)p^Jfkpn1T9s0%NI$+Jd^uS z1Gr@ZK6lL7SHlanZa%u^<#JI}IH9)+PoKKPCcWiOmm%|dIg++GMRWEuLem1tjYtVg z86rpz+-X8CCe4#0RXWUUu7ayEVyk9hpPr)o^ye@p9@&j#CeUo08aqp?(IXcu zhjb!7y{e~RX#Km72LLP@n~B_G2^!u-6!F=0LM^h9J@;9i^-jLV#MUG>;4_MhGn zTQ}*5&;gVuvqB05Ib-&o5+qWp-*Ii5j1wch|Dvx8j3aezrekpNM#;FYZaQX>1MWM? zy*Lhf(N15IpxF!3m%>f_U0*a_PHr9mrI@ z*l53#>5?7#)WoR2MuOi|K1u-xVj$^LS53pTIif?~4zV7!;1eFoG_HcC z{R#6_JjmApmcT& zIJ^TYIX7%`m9<7x8jd!tqGqVL%y!!k(AkS#316`kw5*yrG>c1_HmNA zdBI4z^$D$UjU%phj8bev-jx95X+p4qX{LiRT42%g6!*HVN$uT6+Y1fKiB=)~Q8~DM z>r)0Ie^hlp#gKI}S=Qh-LjfL+ehL&VI!{l_Rc+jhxvRK@U~~lPUC7;*-5s6HP!^>* zvIc9L8sK9kVJug_eFkX!gpfRUE<3WmOUb+@@TL_+nUpY-lhYo2%qOwny?rRlW zohfE$^z&`Rs|TuTU5asG`b5PGc!|sqzq-W#s~3$_l(&O>@!;vgw}IQ6v&_<~WjY>4 z^~fkp2+ejT4%>Gym}$BOHP4?e_ht z4lH%{f%XyEcAWt3q)A_2p!Qy!lj7A$hMdcFLejW{cL*N~KTn-bh%)+-oQ%B2z)pX; z?H#*qse$AWsmR?o+kY16KjR`$ldiq!>|Jkq<%d&m$G7m5E!@gy{E~##@l%WiT5Wh{ zqIblu+;`MqL)tUA%lRfq-y`6G5zX*(7_L41jCzc&DR+@P%d8THhPQn;Z+lyGlPJE= z@TL%*qYvU?9VIgk83Zw533O^SYRkW1IhoEE0KH318`EN`Wq%;m)q67G(%vZ&JuQjj zDXu(Pg0xFTDMziEW{t{xSeuckSd}cTws1LDZU^}whbY6glbvB;1k5_c@FEKln7l%f z8xD1Sj-I9vEtgQ%Cc(vFW>kF=k*$C(unL>{)d=B%$abj~*U1|#^Amb0@Ts*nZff*W zC*69of$ub1eUy_Zc>)GqViLVpPE;~b#W&IV#77T@D{Llp;1&;9u9!vmkrerf*@iGm zy7?z}_$PTBC0kRW7G+C9BKEA|Ye>7-vIs4D1W z_Xk&Xb1GizPkz}vV)c|XrYrTakFU21OuNjM^)Z%h`fy^U8bCT1sLeP+F&>Uea{Zh` z0YU{?;s~Ms0Qqe#s#v*2-3W!+CqGL^Z0{TxWQTBakQ2p{(Ct`ovLLaXL=b+K*_Z`~ z@iG-}0eS1KI1%PTTnf^P1TRr@U1FeP??_^Tgc9gjoa=7z8n7n z$h*ZbE)QQdEl1Jh`hihOMsqDjkRqk$Q1{UCn5H{3Ndvvo2Dp0-cKcS1O0nSZQac$J<4Be3TW^#p6!k|lM zQF_zR<7%6r1*H)}!8l{o9Vt0-JATR@0+Ea}jL6@y~QB zpj^LW=sJ`GKxIMKvYDt?lYXLDTz*?&+|L+d$T2?5V|9$14G%Q%&#|{c%0NKiE9UjY zM-eX9_sp`i#|uM_`7ki6A#KoL5DLrr6o&JbqB(zM!DJRmd~VpfHeZE zS)C-;%Zul5_1n4*h)7S?U6?bk7?g4+Oh5>NMelurk_&ciVP-A!>(EgDKKh>#S>fCP@3e__)Y_Jhd8NU|)(u9GF2!k!iLVFw= z6c{%S17T$*I{iJFPNS@F$6y+7FTuM!%Oe>NT z(1j3WS<$mVCL6`Pv`Q;@r4IE(d7mDm7)z11tKbMMTMb-#H297#^kO6r-K(C$hERoS zTYQJ&a+oOF5^^JEW`ekCoC+SDLmcoJpq+Vfiq`JkD z3O}C#5?+<1rCj5?kvIt8i-iO*I{-F_~`jSq>@a!$~knC(7M9Zl6kaTTy_K#6!43o_M*ci zPDz7I<8|t-8qAZ1k%$CZ{=dg!C#H$RnBK~a9(RQJX0X)%-hofVpVg(LJ=rImLE}LhZyE;j zjnwN)X-TMXx9)}r&FgnGcbI==PP{DA@2U{)HOWAO*oPEqdB;=ZB=UFJNA9cmL8mKQ zgk9nR_rH~4WO8;kXsOC#BusVMi&qw1CH7Dkf{naZJ$~7$UA6xDT}Oq0#(+0aA6r?d zC-9PNOA7B(Q?iwMMv<78N=(=sO*PBCV7q|ad6RvLbeq0P4?F`MjH=_`J}*a)f-BVl z`-Y#K{Pj1|snaQJS*?6xI5Q-5Jk;jVPD^2*&0I6XPU8go!v`jNqq#<7*p39zr@dB; z_m`zg*mu#Z=zcozAn!gH1R^k90zVHGajSQLRgvz4s!B^HtPSQMNAe_+gjuH6GS5z7z zk!?_*k0p~O`cDwwD;pmNdMIm?$<{I2fosNjuu~^amJzNW^LV3Uhc=YODo)fWQ;dro zqF~ucOtz;&+!+(4J^ISg&@M}=P0=`P79|Sv;Z(t(cPf7c58(5B+#7A zdJg0r{}Ld8!JtLQZ}ahW`&4qh{BoH{kABZvh&Q1=n(SxPGi4YDd#ByO z;OKXl&lz-u!a~bkLAi|zK`?8vdbk%RXnEQ8@qQ}}FTUY9rg72EhLAAXS5MuWG= z0~aal^)r9~EqIW}ec`E~Kt?Hza6)eyA4N>2Bt>2|Z)Fkx^1^N$2yZrZnIek}VFgGK zHNy=_ugS|h!h#MqQt?3=PHNcGsJ|}SRt~(+NIL@K_d`VFL)bI$7y7-{#OXwK0&7aV z+Qr_0wsNw)yiBUyGf<_;c$^{D^|hP2niUNoLHtl3*-Z1~(h6LdI2gX}y4ui6=FK)s zej!s&?Pf%6DbkQvn8Ppk_KKwor4r*?vGz;_}j-q1pJP9&W2W@@qj^Sg3qq~ z&6AL$r1Kd5kD8Ac3x8d_5vxW3ISMjmyzuji zL=r{`B-YIb7bPiCq<=Pk1WD=D7idCll;?6Xq=z`{08R33%CV->Vqrx+&_) z=oR0@;gRXcUcxg3#YVbi=y#|+E<;XdX^0@#2;E}iil8DXZp~N-*1fx49eNkiQ@n~Ow>5j0S&Mr~m;7~fNfs2Y){T28=l}cf8Fp8A- z$#pcA?6JFF1ayDm7zB8>t|tK23|DxU<_5vTcA9=a<(^q!dK~|58(OWrz|XnsU^#YZ zX5pIfp)tr)#fW^%4`;ZT>75d^yVl59`@3#3HGRRb_|p0%!!fvAnEJz|cLN$C;-ydG zq9!H%e<^i{K-f2zHie+ z!-Y;c0ho&p*yP?lTmf(dso4DLmFd zbvC%1H?LpYSY%XMDH*X=V}9Y0N&mhDG*D1;2y!ef@Jrhbkl zs1qf*Bx;0>Q^;F<;sc%=aFw$c{`mcHQ58+kQITu-h7-%VxKfcc+$Z5@W#Y=Lbfwn| ze}k7pWngk^iN!Ma*of66s92A1({Q$Q{I`{kDxY66>})K^cq5xW9#@L0%;IY`rd!Fe zb;KK+l6d(K3~PYV)}+o2q91kboZBoTse0zan{$VgegfD4NeO6Ga$*CK<)cI_g&gIO zK*&>*wvZ{qa(H#wlNUCNN3h~TJ#PA?&@t@%z9=~!=j{W!ZzgNL`SpW*x22OAOh2Vp zHePHa{{Zk;)RyW2)#Zd<`nNqe^vKWMbthsj8#LPc|LmF4-ZN*oEYaDON8J0AnNuYxbchP9P_W1L`=F)ti^=WmLhG~Fmr2<@ zT}RJ?DVX1rF=6qTvhXm3z(K+sAJ!Et3|9<^(t`EBx8NR{X=eMl^syr~iv6!VPVEQp zRzbDa5VCPLfCb%I`$n5)DuEx?3}Z-*57!CR(|N@0Wy(NaN-GW|%b06J=qxj=LItL$*o8LqM%#L!+ z(8+wzWofv&`OC^4eDvo|=3)@VwP~~` z=4g9RUGTlZ##P$#BOCk84vk}D;H8R_ax4I+GMHrQu*pgct1Kds=ouPJx;=v{r4~5U zCgoZuytWu_MAcH%cm8XZU0+7k+=ncYQqxq0w2sm(9qrZicj~>BJ|MOFm`~M&Gmz?Q z=U{wf>Q-6!U65icG#(Pkh~+jwZt2n~hjR{>}Im;pe|~M@jC+IVT@HQY>1CAj&~lA^3CJy- zaG$M1YV2$}nOzz>fsBVexh|V@D7OXeHyXDD(`}zcV-=Qh45XF<&j{N%=_-5RRjjg=CnpjHgK94)5o?l+1XnR|L^P>> zTz1^bx!3F0;vIw6yrAStr+pli*43Ozh6V0!U1vs+a8)Mi&jncW(xyWHL&sqN@aR8H z()e;{?lzM9$Q$=%+cxR77oTSzg85Zpvh|N!*vQ>5cx;NtiNry!I6i?F%?(1 z81J{0iE#Z_z80G9!-@}j1`;0MwX8vRi~FYA#t_~88;TJ(JY)W}d-~9%K&-R*rTcn| zbr%@WG4(zq;9({`)e&4LY_w)DACL|!ZF3?MNnST>zcS3*le#LuORqrX>qRF}A@m_( z$-Ict1prJ=sx7XBIZrhw&aygPN~xb-UA>r?UY}!h;r+qXjT^fPX8tc#X`chUIh^i( zj^tJWEPt0GbQrFN z^99G0%~nS{*_2^sHY<+BEjOfvb%Er_JVPiwj30GHgm2cH|=RQ_P2yjrTBu!pt!*`&VJ@?4t&` z7>UZ?kj2W{-`iwh0U$b}C=mtc%g=|BK^2nFkJd!hh)*8vsCWmG#O!ZafTEBoTcORKsY|pwR&KC!)8FX#O;VN#laJ?E@+>vnW%kAXy_ElL_IR z1f6L@qtcpb#iS-=%I<;c7jk|$0t0hSKm)^+I3fuzBT~;2+SudtNqS_02Xg^lJ6X+) z*H|9pZ5ldcch2~kpqYYZKoFp@l3_j0=E0AHahacK66B7Vq+r0XWf-56t*kYNZe*>HymT&-?cU507==@7BI3*x$T)*NZf+bQKUeVoN+z`ZJCGE z(dL?JQ}FRjBFh|eR=Mv4+_zK$4l)_HYaTVj#rIRc;GwD}JZ|DT?*9akCWqz{8G!h* zL|o}oe-u%9Z0yvKC-KFRad}~DdbDZnR;C`=z|7O$_ZzCs`%8f+!P}E!Q-gQ9tY|s0 z+%78mfz~$h3H5rEb|r5uCjQZ&dLfO2W#rnX;y{ z8!ljfivKcMXWo3Wz->?=o8;c9S^;?sBe)XOa?v*Rk^kQTn|}B!xNILADVm^Z24V4v z2?kVvi1=5hO1Pwl0c<0DDmI}V8pryNflmXZZ#T-4~N(B70;`4qirao5v_RAKqZA8iOg`A8)!8onZlJa;Tdt}9P)3?fyovM; zdu5c|YIoA8d4>U@LFyd4F<*ZQ+_MI;v<2$3m%W7_uhK7Zm1NNp(?WBA6m?L%@0`nC z1G5k~Q4D?0PJ$Sm2~KaH=eHut2%4@)b7j^s$vWouAIpJ6`QBn*cZHd=?`#>JKmY(1 z@IPUQAD;4HTAA>C@jl1^A@yHqA4WKO$D*x6HiGLZ%_4wvxgVSx^C((%paaeGf`Tm$ ze3?qmoqU3R!OxSd^>pSz961Vv>H-^WiT$i1vt63cWOg!JH-iAW zuB56B>I{gFji>V?ZOk0_P0RJAj!H@!+prbgkC8D`>qykA0|>>EK+4(|PvyS~09HUx z_5fd5tjT~Yx2+i4Kw72BZ~a-$=;PPuorysn&v)hJvcbu;QCqnk*3iVwe3RgeafE^q zUv3}h>xRE)*>L(TzZn~p2B<%71+A+PCx$wrOurP&E4f>DW`cKkXDHAMP!k>tKyS{~ zCh9P`3=K#O#2rgB=h@9vDO@2UQ3kS`c($u#>Y=+L<9=0I2IXL_V2Ig#WlpB32{;$r8Nw_ZkrjK=~^Kx z8C&|u0#6l-kS_XwC3v%e8ZsqLy#ttfSqhf@^_BLEvCliM0=AE%K)%1;8LVaeC zPCTO$L=wq}XU>vkPA3KyfCUL~+)E5c%6rq2fXh+lU=kBCemF$b#w5x43tM+Y1d0D; zz7I*ZUj4)pSvZ9nwX-E!__l4Q9`{s6pwWz*0`6UV##`Gd0J-Rm^+t>8tV?jpuY=#% zlW(_v43q9V1B+uU{^xrGkdM(UVk^>oqO;`|Vv9N%>Vy>ZGThjX84Yp=fP=DgFptt`mFT-C73bq5C_2qSgGlHsx_O z-Vy=#1fAK|xhQ%j^KUZyo}J*$k2T*sBRNregeg%b-9saLrdm8Qkn|ek`j9UAiF+1v zjUu{zEvt&i<5Ql0turhD|2oX*D&@nl(c1?Cn5BsXq=*B$yM5Wip~B4-{V!DU$V9& z8bx67Thf_~W^pz|PLHycsO2gU=Ctnj01f%)gtuVs4-K;Yyd`153JGXM zA#0x<$YKL^%&QiVjF9m7txJ)rM$(X0x~~bP)~IdL*z!n-2pk~LzX|PV|FIJoraifF zA%ZaPGuGQ8UIY1evc)ga^*Ka;gw2KgrH$P50_bGTFSo(=g}w%s{XM%4s>nyOXs5G>TOQWm4Dd*tlWY9$WB zPOJ|Py-1GS5ZZ;~Ks0$`H`PA~*k4(Ce;e!N6FsIOeC)!b9uI5b zCtJpB5G*R!PWh~SoM>g|qWV7qI4?I&gxOCHv8O}eBFT%5c`3J5>zA#|#Bm3O5&SG8 z9%L94xe8sn=9*?5=08NW0p=7SnE0F<^7NDpxdo=#u`r9r>~9ZTvh!%4h*0yDzLS|E z_J}W2l<9Ff!W@Tj#@erQL!1ogMeCIhN6bh<1iH;)7~nK-eORK`4LZG~PO9W=$wnEg z%vD*yl`tuKVUC-j`Qoh3aLK+cw-@iI(AQoPk|ERKM|fonNU1y~4@J?<3F-2Msk#|x zc1W>^wZi|O#DTcj~@=B-kp%=`c>%DFuqdeJs7by|Ld1i zmhN;QK|6w_W4GWW&HJvNB-}ZerJ{R{H+(h%BmsBP)$~)nF-O$Gm5^U0?R5ZTyt4!LM}T9)L`JMyN}DbyM(#pub8pCGZe6{JDq;@cw<411w?G2wf_yli>t42=O=}HWu10A$L7N zfS<*H;hpdHjJywryi@pA!bSo#y|^{vjT~5re+FGB%``IC8OdZ($ThQarijQXQQTNj zkjr4R)pi{86ng)2uxp#7jTz6*+SAQgNm_k+9NqK%Dnxa5_yuq$o+VhR%BKMCMr0di zL@riYlP$eD=w<9~QQk|!i0>aPQOEfZXGoD{k08X;xyP7cIOu#y#9LO2d@m`) zr{6jvE9Gu4V~-GkZki7R*>e*}|JIZ;?MzY15Plut#RKayz95w8ErqehUV>1N&mFqr zA;p+eu9>sw=`nrT&}Lh`xEsq%AEV(^-7H)GQVJZx0^u3kh99w{rXL)%i1e_wA|z&j z)}+pbU0cVXht7V!C;hV7_E5Bp?L*gtfNk=%^jc;ssi`&W+%(0qHSz0N<23sCllwHGDWjwRikSo4lcy9 zZY@tkP&61paikfN*=|}*z11*~UULtx&h0lr7axP~1auQYBE`!vG0)GV;inNk)+xro zp1Q&+U=3oEIVDUQ4#@#PWL%bzxY@^j6UVcgt_i}cVdwc?zb9Rw%zRQsRe{kq`Uh2& z$7$5nb8la{=sjGn74Tsve~sw6$b2=OR$Qh-&X6nOvoCrQTg^V!v;0ec%M)Aa zJW&HC;qXU2d&?X~<=8{xE)MAD+;POwSmvKm-F~`7Uj@R!uV|W4C9if!8!wIO?lj=1 zpt=KykQFf4<)DxM-l~U|mV*8~mlUitQ9bNCVUEP=n#B>DsQ;`A_bsIWo>`^AsW1s? zGG8NwoB>JGbCf;-$OEs%r&i27Y(&qXD^zHM-N!I6hOarLn0g_E>R_mFn8v zk_F*u!|!-kL+OHe0QT~W>uFk@!0oviFy@9qAwnt!rEh94{AuGthHRuoKt9wlkIWt6 zPSL1Fa=T%0X6rKFplV1>D1{|GsTf$%W~LYDH4sMzrvmLhfKo1&wNsJS@8OKZ}80*{GrKb+i;Ea^>jC{3ehz`t#^ zn#HoEg1P#pw&De7g9&jUj-kg}l3P9U>c|B;^L|HKMKr9~Y!I0wc((#oLB8WHwCfY^ zv~WoWRV+B*0<=WYAh7$>gkKBdul+a!ECh3yq3qx3nC3genzMgGhPBblkJA^rBJl>P zJwMh^f#CxL!b=C;iHIoLSa2WEq?s<@f|ZC-9sZo>vOl))3{w4Q2DF0$?(s!i)Xk=;$37#+ z2~Nb$3FLF!_Qt#?J>9Qo)CxZoM}Y8($ziBAgVE6y&wn{qsJfVDCD&j zk_LMM1P|MG5SpM*1O@esmrj|9JEPu$b9Muoka7Nb7l?L6J1})n^VezB^x|(DJG&Y8 z#GX=;6ZDFp1gtoE>MC_-8b|Ne;$o2@NxMi1kz4oWT`QWrR?u1~Kyhq=nNx-0MA>+C zlqrU#a-Rz=UO}YLD>|mUQz`<8>ca=(dn(BbPxE323CDitbYk5-(}$gKB}A!RK*(x! zDkl>S%ROtiv+gDQ@v|%0QkRq7`}o!=MB*4NoxwKvw<0H(XQF7htkVc=!l#i-z^)Hh-78m98{b5*^0(3nbwFC*{&!8X zKr}4>6Ob%;Ik0rfzWQTzrea1gzc=_C#Q|8EUa~Y*>biCB=fy6eW?~@pnbxCmza1KI_1ufd`VC7yLghSgzOY`QXy!HxfVg06GKUs`>@PR*X zSVP7H;l$$eg^1h=7P~}nPKdCA8&~~Q${Ybk6yV3MBy|BQ~h~90y&$gfv|~%$dH1F9TG- zYJblA1t}#PI?CkZ90@BJGRY{2VAvdHAcu?HWxt_et}B4-E*wcm``kY(ARln_B3J#oXJ$J+AZ zy@2rU7(N9m;FzrTXELERysdQ4-^q&t(Q65N2Q&gq&Bf_H0eCt8A#wrE95w+x^K)&*R*(rfm9Nuh7gW32t&XG~bLIe@f&RHElV@ zLRh@j&KH+GGg{b{`f3x2BmoUSXyZfF)BQYYvkW)`><(`=oL$uBHGwyOdhSSb0vw&L z25~fxxpV}Oq9C(OU2sJc%9q$-t_fndo542^=34&qmg;fkb+GD@k^O{L#hEH>*yq3D~jcv?B3^(dbM2m$FUHp%{Xz{DgTk z`G#Dnb@@x+4(!%OYvw7`Xx(_%$SQ3&m46}0KK~Y+agjG3&{TL)XbVED^4Xc?x@8TV zr%OdlWU$)0{Ly=uj9igB4G&z$9(S7^BGT$&kIQ)z-60npR6GvHSCnM_(urvf%Qu7Ks8NULl|!dh3z{oaD)JgdJF7pV zw;>VCdvlvY8|m0CV>YvUN~)7(m~yFbuyQb5smtz<8_f^c51Z8)-s>Q)cejjjzO%6j zLD)jRkPZ&%YGJ-@4^c7N7^sxE-kcU>TzN>t#1R=*Sz`adTDhkyJ8MHhvAi_tif2tK zsAzxf0=LooFCyIHS}Oz4k2tPgITz2*Fa|oM!CH#7;ywd4L=f@ALsf?5&K4DXF)DI7 z9oY@%gi-FWp!SnlD6O1wpcQY{DC_al6eUmV^yTynMYLBMr!YT@2Q<5tt81^h)1Ku_ zK&{vBCWdo%{GIFT?EikDgnFjO-8-1Ha!&SkW}2#HyDSEh^Og^4Z)i30&W<}$HR^^+ z*pnE(h)q#&l&T?GOEE(OcE@%<4iXCwvqtj-@v1-N<9ZPYYQrY!BXtFfmNtg^Dyy&C z^j;aty*z@!EZS*;G=_t1*?ujYVJ?>vk-Z`#uUfE!js<7Gd@eJ=*(%(T>HD^w&ua*%HxB2p z_AXAz22C z#wXR2@49>5n~$LXm9i5oHi1T01`~q>qfis$O|kFnx2}7RYWuxNj&Vxb2{=aP{*^A6 zqVLlJ-+5?8T`Gk);r8n}zTFdvI~PQ|pMHR6pGl>nx+eB_PUBu>%+RC&sHuwUiFNpM zl@Hq`&r4jcO90QhSmTGf3rHdI+h6pQZu}?M&4uKSjJt=6J-T4QyG|*+J&3J^S$U+C zITsX2v}+`NVhIp=N~u-yRe5e7d*_hu=u-E^%yYLk;o(=*6<@dT{f9y(OV7vlX!o75~wf%Xe+vagJ&LqA7% zQ*{idPIkL;?XkLl?MCcw0ZHJhGg$(M@*F)W#>mOCk9Ldr{;I4Gq0tMP`!tQ9*SL6au7h@w+l1LE4M&xEI%?MXb<6gA8p^48ZbJ zPlBZYhYt)R0X|#d3fsl6<8hECSo*Vw&Rd&rh^5y>(sR^E3_@_8ZuTI!}BXI8>nhX##3Canm-M1`k0rm4<4>rhIsVxKpz0-Om> zk-7MOB_WOuswbO&5@&H`2__Yb0V^Fr+=l*rv6C zK|)~KAm`?WsHdQE0o*n=5)Mx24z}N>JId)%d70_Z&Z*>p%gRO;Aa$Gg%ab4PP)tm` z8duccqC#=0VX82>39{Vwn;IlKcX%>})xQLOGxejcAEQvwhmud@E@MuB*}$}3vY4_n z&prj&4_VpJaUv}5Tn_3x_DW&3w1Pn-W-krXHY&S6wkrevU1wU@tc3hA0sF?~Tt}_N zx6EN}>0LzchaN0DLlbxRB*xe9Uid|$jxn?MT>XodM1eUuxOeCvQes2UGP?GG!Whyp zljhQG$EbAwwz*uDNK9Tkgogi$>thN3daZdCTOOF-(-(HMUxfke+&XjYJ)=45=~WrbIqwJqFIm zKW}lD(o$sbW@Qp~D@i@}9HM@6y%qrqnEs|KHD&%n4vx?6?_Zdlo}Dq=yKjG^$f9>g zbW>*H5W4?kUSco|K*yd&k9D!{qx9s=EHv7w!JO45i6_DFe>4|K8tL7x>jvo4UiJ;~ zPE(HZ9JBza-AfvM$HCW#c4-!a1gf2LEoRD;cLVbHSAvWKBMf%o8|TfEA+)Bpgi~Wl zf=)+C+-pjKdk!?rD5)-x6V|U;5RYlsenJX5P$IOEe(;jgFu5YZ*eN-yw(I0%(WhgY zJA#4EbKrEcc#TLMVN_djHJKG*fN+igf_>3Oo5IjWWzMkJA7TD3qud2r4nadAYB=hY z9Th(Vvm?#uYXRU4i~Z39%balqFiCt%6_0|P7H~s7-p@(r*HEjEA|KR!i%HVlD-V${o-6xj+WuG{y(8i7 zS!k+iMX3*KE-%oQlwSd=O-Sa?JO{Y7W>fc<)A+lIf8F6j(xYTz)7)`+IW0Fbh=fWi zd8r`%5>Cx&xMbF-Z8ZG_jI;ACwtQSC>+3|mbkKPq!6<9al}2F#4m0c|+`Sk%gD7fs zd-m8(vYaw&I58q{n412bm>A_n&;uN&+a!e)vSE24qRZF`%M^5QWU% zp>oj~;dDxWMJSoDU5x4lF>YYpZA5|MaT{Ib2;v(Ot$tol{VfE6-e3D(Z?Ib#64OHo z7sPjZ=dL&ox?k0{gIm?q9CU_a(B4Y3OxH(xG)zQbgG)F%LKH>ic>Wi5;Oq|?v%h7o z*_7O8?tC!zTaaZYTJ}I^y04WbJ|oucLK*Ul%6%afjc*?&K}>ih9)ZHHtupYy#bN@6 zOf}qqVvo;`yhk!ccrSgtxDsNrsGkiSI#6 z$GC9$^1@T4uVn!!tOil3+jmBSBr_x)^jg&=zy`xj16=|c|DZI|eeIDiQw?1>&Dvug zXkZZ9)kZCwy0Cd4ExLWq*7zbpG-Y_sIsp9Uh>766L%bYM@i5b)SBe?Fqi(ySE;l3A zHtzX7(>;oL#F8y5XXi16nz%%(G73FjUDaTv+7gTn4x|p3p%!5liVyLw5qpfV)xE}v zA&Q8cnhGddK#$1bW1Ur{9*HYC3ok@x=FLCO0+}5*#A}v9nUIj7sy8XGEN-}7}El@Kl7&VGY>sg_j+ zJtnQonfMDEcH6yPOx-XQma0gb0+kRn#u3&a+D>|-fIOn6&`j*7GqEEI=>_g;DcGnM zl<-SVXa2Tm%B%okSMMrKvx%l|%?<64KxTX_=T<;|~4{cPLxB^{Yk$;620h4^1{z5s%NI49Y(sMK+W}hFAIMoo zU!Zax=O**whLP_+SZuj=q)hP0pLXB1)-0OfX@+etdz%D>nUgp6k`Ydv$@gHAv{9d- zMF}%xUJIJlLsR#Xa>3$=#cf*EjCnSja*yf}ry^zftKa$XOk;wmX+l*foCci?B9Rn( zanC)9l07>|ZnCKSPjjn2U{M*5k`!5JOQFQnW{|Q>cq9?|O&ysT_fK$KRXJ@~wzb zHIlk5FS_||L0bkIksPnn)2lvBpD_S4#UqMB5k}d$1>1`AFWQrUMWGFthh@fKy$Jcq zoYb8T$8Ph2$Wy_6{tS3@Sa@2F-~<+~4l!D30t~Pww7z2&I-H)`w9xBoXD#^%txb(4 zLxvu*n`KDwaJttP*_4V(VbV87*OX-a9(feByns|U&s)u$nragnEC`S4*uooDZA z7Rn)nC8zSAMYf!M4|q)!>uWO=7EDZZQ$LTf_q@lQxaAjIdt8_|uxfk^&J$cnSWLI2Qi3A`MMzjmn-8 zd|uGk0%u+Ta8$MK*}Tp1Q&KrlksZH?z2JrlBg%zeI>x=SnSNz_EuMN+3N1CIW8b37 zQ#Vn&;+yX&O<~~-^+-A6!X6qap^(KUdhyLh9)_D%(*1^DeZe@X`DIKY)!}~y1RN<) zvRW!JDKhs}S6>FXo>0I)afZh01sIkGNT)Q+knm=Heya|56=3C#2nW1ljTiemttN(% z?5bPKMbia5WjDSS6bw^Ps?cZMvJ2kQYtdXz3_V5Q_y_NW7}bo=GVp4FmJkoRawr(R zOojy&xBnUzShC00FK)ST14{t3i>G8wZ=RH=yk<N14wC<>uKsh31R-d+LdAEv++^!g{Ntx^1$| zE@&_vXg6F10BumIRp-_cZBh|ju(mOL?ETlcIxn8g=*iz?GqiEZo)6~X`?75lqTpYV z38AEhH@x#{9(1Az2*rhd|?A%Vwe&LN4JuzT1V&|V61r6It!kvnxF_4?Z@K(4&+z4 zne__vKkBs$F*M0*cWH@5YB8{%&7>NklH{Qxgg#*IUcK}2F^PnExl24kzi>=l)ETo3 z%~@@Zj;d08_kQiyq&BL77B|f^rKEsVqmKOzsTzTcgt8>eUl4y;6SR-bm3=0I2xjUc z70a-vCV7S5`6=mA9t}E_d!TWV27)Lu(THUtv$nIuBygWApdy1ZeW6L@0^;>9CHM}V zK!Bch--q}=dMNmQ#uDzZ(vWhhie7iqnrJUqFuumqMQvVU%tS71!02Ik7jM$#6|^r!3C<)l71}to zqyy#!$DT>`E@}>WlL!BNDv(q4UjAuw9?dfnhk`!UM$>@fqroeWwZwx_(BYaYam)x4QYkW`M-|R{u9|N1a12OjeY9Xc?-^&T#PYwBy}XEu&%qb|Eex;S!+6tur3% zkOE-iHd$1q7Nw<>=IQ(L4jS5;sjqM<-Wby_Sey-U>HHGNtJxKCjpXhD~ z5U%UT3SK)dIFo8OwGWO9KO`Q-JZGou!m=Q9K6T=2_Bxj?Q)dq8m+}+seJB0Nriwe? zG;1E{0)S@OhAYt+Y`XOaQ&~Q%dO5Cq1Fk{`cr@E$-j0LSVuk(7x0*OMb@)J&-tQY` zq(M!XpkH|6(um~Axphz*0eF;ky%$!&HVa%?&Wl|Oil}VkP%6;_wsFJq=q1Ud7#f7;%mXGchH#G%Rrft@^Gp1BP-_XEN)clun_Ysz8IWME||zmD(uMOS9ADuBYW zZBB`(E|Oc~D4t{uW=u;>{W}v^CncwFmt(;pG#57hM(R(U=a2zU2N7f0e)1R%)BICt z*%I#mK4L*zo`B0z1sZJTfkm1Ye1%6~NY1FHGy%I6-v#w1P1FW30LBqFy3930>8zcK zbi^T4bP6Y#`z1+Hsw;Eirc_Mw;-l(zoK(f83Tyr6{UZ(03l$b+PzMeO8{r3nZe2DE z#826`0@?A;XIt3q^3$A(ssZ7PmV+9_EGj@{`dNXF@4zWr$?R>HL`Po~x7RByO`gz3 zdf7T_-ya?<=Savyr5#+3Jo`Ri&)+bXB%pB~b{sFjc-^2*p5h zXX`=yyBi}qObKUscE^TBQ7gKsLZy#t+%9Zg10kljYaG_RlZIcVjMi_2*rggwks9`j zNKsdzZ4V)5hwb%WFH0c0mRdLzTutM>e1(t?-SNok5JJmKs5f z1JZQ~!SQYVX@bq5dE2SZxU=e!0_cFlMll2iKz8=Fzgt-Mci zwLqB65dklX3$Eh;rYKzf6H({R23@jM2rQnOXQPIJi?QGNYHZ~-97io|v=>ejaH^o; zP3fOkGMyf^sZARDaLdy*&#(p`EqPhWr5c8$gAxpjk^Ogtr_k`NCs|MnS3CEDF97K- z@N-lRTwztZ-5$s2oA4V3q~N~FDHy7!L{yUmyIr$LQhjJ@I;uIXT0zZMw>XM)+L`DZ zC?D+mC=U>qP2UO(Z(F=|8tj}C0?NEsbmBSZq6}4Uv`EqHj@!Bgp~U>mL}aL3Fg#7* zkJ;vyJBU=!y+24mncis|0OCKl@R_!RG2g!~inEfh*3d?`2K2nNc^I5#yFh==aVpfu z>J6(ZL%`)aL>+^L;H(G;6qwz~)tWhdI0eU3E-(spgBAN69|7XW-M54pL+ekWJ^~W& zPcBbobnn!eO}faj)#t5!+2)xYY`A&^H-pLDdn7ANF#cZ1lJW4G%f3mBnn1`j_)gyv ztf{+%B1^szRsyK5-oB`wao)T7EVu+1_vTHBy=U)g!n4+bcAeC>L(`JAmSKp&h)$Vuwl4 z>9fVvUNH#@5NhZPH?_b4`bg1UtNVq0ZGD}hQ@x9^1%!F^%A>XgfL8aRkPL<5Ae zk-xf94%uKZcs$pGBa&}hN>dhrOmY?=aXQjA%(g+yVr$611_BN+)c7r5Fr9E z*Bf`%K;PxbklvtBLqG*;{5%x|(inZy)vyf_nj^Si1W^whnasM(5gVqq!a>PQDg63p zFN%hG?6tMPbgJ=e zbW_B5rp9ITcvl^9F1lIK+re9XObp35Y$tocP;_9qW!lFo4#e831E1W4y7tgXawF2w z_t_wMvNA`yLm%gX5b7lV6;UY8y=rt4OgFh>gfuf6Z**#@Ug&-x7 z*4d=d%rvWEKEI0E<8Hy&Cyc$sv{qd{aMB>DDq*zL{5rf~-Q^J$a}7J03E8Qs*pn&m zRmwaL`TIsweMyVe*xsFX%bqx89f3h+y8=CO5U)+4_aa|fp#7t)j>J0JCCTyr-s}5J z((x7fA?e{6b1oOwl+sKy2&Sxr-YBy{n6f|WI@$3!uuVSFg-+4}j3U^c9hA<1Y1-XJ z$@*q~75$nee=YADUSq8m<(84&@YS=Z&_J6eH(18g1;=oo0$MC0m z^X{ZNZay{5Fg=-$|3Ghqe_T1{vYk^MU$=Pt-E)|J4_O_X931DApX5AcynOC8YJ=c@ zn+3B8W!Qrg>-QEY;%{uSTF7f)+l4_oKwL)n8mV8pa9-}roz1MI-;@1&!QTPytpc|$ z#Y;BBp@%|xPg!}!h;QA(_b8g|rf&9PUm8SqUFIM3HZ4H!M3)nP9mifH~J9cR<_D?5Q*(E$p8jZ9KwFA+!4Uax?tSy zsqP5x4(irU5MSUR9d&wPb`P@@-#AWraMfjh9QHV$`#EDW%cz72GkR4JLTxleFfk^S z@JrKc6Iqw@Nil!E89fQDgP|~3c9sKM>pA~Js%5|RsAWg6}2g?zABo*MX0J6N!MDv3sXwUe4`kwSlFH?N&ocQrJ){uyi?#%H{Yt5#H zWnb7&tbtYxbgxDCDnz$FvxxdBzgJj%2H{1G|QeeTPKlq<|Qj0zy z<}w{|89#7Czo9H8E~?vnJN})&SEP_@{R$V@CV@N;3p`E4!?P7F;|LVZs&I>Uum=ZD z+U~|oEnI4D3NqdfV6@~=MeJ9tN=^_Vgb)a6h!RBXP(GnA-G;?=O;FYu$XM3g!Y(Bl zYEXBg_+2A)5ao(n<1*4WLv0)gLiGi8GegeurXS@D1z~*P!d-q9jeZWDwgbli@7+)` zQl=O=fg1yI<-1|HUXzDg%c)rAoik_hkI3wTHORwks&|Xeo$=BhgrtEQY}grT8Qwit zC?E^p8^5%%AJGQzQ#t=iqbK&`LpYM}<=v~;fG3;dF>JaHHHVL{pqN6^Tyx=`)E-_N zTo*sw_|@XLT1#hR=P8@ErsVWV{9AFFf0HjVK?A8>ti zd_(-GKoWDwF|XSkRwh31dIb(=6WdDgi3naHC|AzlfsT-QZ>17`#Q3Xl*|7?1th-lL zY^hVsyWEb35myVFJj8hL4QzdI|D!tZM{u$P=|M}zQfU(UBz+2Y(hEVLlCSpC=z#3v zwj%cW9aucwU2kGs*OF24`(~I9lv<->=g5;P(9luWPltI3s74J~Gi48sQLiL3+37O? z9bp~HhFh?hqT7Zwa9FM%Iyb5Tnd~7vKu=p$(=w7wu2N^Vr{svrRw_GgkMHBL7LFz2 zXtteLX=fXK^Xq)EXn1M6;3b>M0rVJnI&qA~yjUH+wie=U|L}tQM)nKvm1o2h4)lW% z=$y;ujRXSCS&dS@8vu9PuJteJ29b~4RpWrt#YG&|HtVb`@f6m^KN<{5v*?$Q{QYGoC!E--pkN z+>&^?7UxOdpp1*a&g!S3Or_%@h7A|a#5Vo1ToNbmkD1}!LEpA}wCloYLDPLUXU4V5 zU)RkS2Eg;x+t<0ewCo6PqU|5I283V99^dY zF~z52Tt4F5A%zs$9h$j^c$LSmOp5Ys!}J0RaZoDa?;NDN_#&29Y^;ox{`vJs&x=DDnQKt^7Uw(uK1_^3= zp{T{%%k*gt*N%JiRFb<`oEM?U+gjI-RA$EfPeHwwMirh+f?k`9DkF-F z+O2K3B3)z=WnZz^&E|VTno(_IzVGA$w0du?;*9{~olF0MgSr^WZIJIsr1bB=h{XLz z+e=?d6ZzSxG*opFLvz8h7ROcjmJ_8NNT$LJ@;<;BVK$W3n^!Z*a``@Wu3B!Epf;%L zOpwuX=f?EI^$1G|=$hKfwjn}UWh?G)|0WE3{9f@k%Tm-fg7h0wev$}S0~wwLDs13YFz5kqLo0DOn6m{tg;w6kyT&hv|^YJ z=~>LEN~cKL>8_-AgNVo@%Gs^EIHs61$)qkV(#7x_KNX~2-2sL!=dctgz%y|Gzl&hA zA_p*SoaJR2Maq&4Mu25DW2T(I>_93hWJyfBHRC{IOAvhhr+1nr-HO3x12Ed53#hbB zgQaPr#O}$x4*hB8FEEf`qO_@>;g{Wkl0LB@50soA3D#%CPQc(E$&Q&W;I+YkRqX3h zNW-g>+t9>e%U>m8jGgE9F^J+?$rq`@nSJ+fEVdpMyPHVYqVhLOiiW1Le{KFbEVi46 zZ#XHZc*O8S-9f)(Q5`!;*Sf)fDA}W3&vVYpc+S)y`oE zQp3|^pS>45&FHrYubQSuzRA8;{>zdZlzW6ZLWrr+jGqm|RFIWH@LVxjnzuylJkLqu z((f-}5|%o+7(qA?NN-g=!F$RP%AVJR#&$@uAh$-u6rX4igdhVn0u#L5@Nq*3${;r~ z?$8t&PDF_s|KWmQq*+>|Y*Ilv9`reKb_7~M&X5ocqu!y#V$(3qufwmdoF3YeIG8DI zfocueW5g6-Q?a?Uebmr$`EA@SldSND=mF~rjkD(%V7<}Lr=nKv+`i_56_b825Yi{j zAH8_PHN&GvW=k4rN)u+RQo*L|SMsb>euN!c4HcWQ+8i6~KniMF6uLf0CYGs3m6PX5 zALfwf_7qkm1JHyInQK2$9qf>!?{U+`iaIPexzQ%i7IkvC{X)$JwG)eZMS+11od!?S zC7(juf9V;y|E)fN&)JPp=7wvd9ydgU#t9SahJ0eu8!7v~f=k*}_0b_0x6PN7K+9dm zLFMY@?l=PWdeSor55a!0iDqqMNTJzv+R2dBr$I!L5E>XCnSdSOV|> zEdh|YhOd=f$tl2Urci+2+i*d1$2Qaq?-ae{uuotM9Q0tU&xd54f&B_7Zg6bVRMWr&0cshxE zWy?d7tjH?V(d*#L z<;$CpB;5qKX9fa{Y%y-RTzC&@ITp5$$^dt=v>xEq65cXmReT*835$lmZl;sc z`w$-QOo`?_TwQhN{Z(fUn`StS-BlN@VhbQlXbNiB^9f9^H7T5czmVH;9>=I6K9gu# zJKtP1;ckxBhCtQ%{>eP78@p7&Wr!=ki0dBTknU!@3fAKfU`sfu(+^y9`C&?+@0N8U zpDenqX@5B)8V{=*gXBEZ{8{B#;ID|a)34o6eD=C3OKKS?7j+>Kw{B-b5_cj}5k1HsMU!A9yvbF|Gyo}0FH+v}2h zo9LX8apEq*WL^r#HW{>@z^I^zoaXXSvqs1VvfpYQ>x^SIjrR34@E&h07aw-@B%>uj zG}E)dq30&NjWG>E8DU;}8jVRnE>6}GDrqs~rM$T5n)LOGnXsNs{SX|YgOr?C{ZIGT znwpLDnch=#$(5T+8#+#auiPa|@dw*rnj~0udy#1@G$1JNek{$}<<&6DGqN!6;be z1Rrd3YLQSDpELRqdP-?w`KU$4)#d)PS;i0J*2yUeYv5H0x<|?QjAIOlzU`qALDqK< zW*|}|CMKy3TUjn++wy|4$FmuH-{Op^M^$YZ7~P{TtI)_qupe$@v?g&)ZsacV)s6FO zM=Of_`J-DoDG9Kf_=g~z<*8z=pT3Cv6NS(RE9>#YB6S8pr2+0NB?pjRl@BdGz@L;H0j3{< z_I!ZLp@CQARg*ruMhu_yRR}1h{8m*HpW!BZP}CrW6gJC)Q8(D#3wrDt?94vDwHhS))4QT57u&;U+wUDLkfbpVi3|t!YoKJ#a zQcC{C3eR!NGnk(C-8nALe5Bg?A;B1l2b~6gPoW+!RDwX55kzgD45+;V7USo?$`qjB zv=O@tw$T6R0bT6LJ{?3+XBOR zpie*Q-T*5-A7$d6z(vq_*zM|4!6dBg1Q}(l2q6%mS)6BcaHRh$$&keX_+x{eQG|== z^ExMjah&C|y!J~;La09pRpkt=2FYA^r>mZmh4D$wPH zv`GQfC(~bGDd?UiA!$|oR%0;&E)dhB?ROflLttJzA;Z;5cV}QQl}MWOAFXC!Ei2rI zy$q;e6k!^Cfg`^iLys2F^Xu6JwZ+{PwTc%K(MnQHbO{!(cJFkU4MKYy&40)X_=oM2 z@Q&jd_#U;Gr|6v%Ql~oD#qN(Ft|E%9_Mz(0c#l3$qmNAw>zUa}<`H=UGYM3Yzt=I( zRvjmaoAH$Bsv-Ab6&@t&G$N_Hg(=r{w0*?lAbENmwRB~M6h%>Vb2biuvQG%#riD$Mz9R&@XIRMem?BrVU%{cBpT1Ef80{hH9>dG?U|W z4GGxTWKUaLerf;e8_Turs6g_GiJ@C@e}o*uy?w&8rr+(dO`~YChLXCy-9(?t;bH7s8t^{pM&@oEUX(9{3AdnT*pa2;&9rx-6 zHhSPQ4(eu$p;zDoU$1fP0ZihILN|!s@>cO1nCbU1RIsbrFj9xK0>A!Yva}<)8{>8! z^+^e68DJ?-**X*ecuJsrxNBF4WjgM#eUM@_)?H1poIYFaDxSEfgPTQSDj)E2pPobb zQ$DdONOl7%XDSc=6pUJRg03_}p}7}j5wDFNmTVOtSH{9dhEEt$R=x)J zcmcTY7%UlAuo~D8NMV(9&xB)5xb4Rp(#v$AY#X#oOwKVrT_Jk&dkO9_d8CL$grVx& z6KEBGZq)OHk;WMX`V~+3+`v}cAnqB2KCchOZq;H9c~M}5KN#yA_R7oG?1X!^wy_|m zDpurm4p3Bv((EzkfvVGhbL`x^Vr+_92hb!iFr9lWM~KYVcKd=a?5K+ce_O(4;tU}H zhRLDtLz@v{*bGC_8}*Ma;#3!;eFy)3u+ocsXPA28FA2dhFFy@W{UaS#BlGY^6rcfq zhqX?~GPsk$Xx}wT#C^9RvzP=rk21bCs~$)S@_cVeSRLaJi!MouNI0?18z<*lGFq-P zrPEOuVr|qA+v#1Y4vuzkXu5wR64PKdU4PejL#0^5bNDbN{$Dr%BV0|$11B>DgPId7 zZsi>Y9v4&sB~*QP2x_(G3)We}|Fw4bdd+D95Mr`R?&W48yT~Z3+5FQIP57*wji82( zs>$=pEHz+1pSNhL_sM1MjAICL)PJ8)BTMOyqLI!IqAJBe&n?*aA z3OVM~({WzeJEO)`pSpy2EfYp5S|mt{@8dluCT7j0_r5d~2Z=8`8u8XL$DZK;BZLyX zBd~TJ52)usRqwR|8Levz+a%7#1kF)_P4EKPlRD_rRVgQMEaKA_O9RYqVi;zEoC{4k zpfJZ#`NhG=l#rg7k#7zpeCi&;rb0KL?7Po2l93ikK#DqpQv*(V08Q`A;g*)%LMk!O z0kJC$C>QIoGo@>xW1#c*!GAKrXhjOayqV^EK~WV101SFNUcc}y*&63QKmb#?UkO5q z(m{r<_63Iel-^q)o}jd~P!4CJMB66+R~6%dGk0NwQ99xAmKk_0bRf8apWq4T7|tBa z@Li=ha_-O?Tl?kV>BddEQz->pa@Y_S&cU&o7o7eyD8R4jEAu?2%`2vu#<@OO!wM%7Zca^K%9j{m5d{@Akps1$1zno?0tOx6QzhQo(Fd^t znR=nahY}f8{mj2r1(GC-4ys|SACqdFT@S?JlpjINpecp;&S+pUJ>B zU__Gn#bUJzYB?*(h7gXM>;eYZ&!QQ>@d>g;K(2(#Akk#+9L>v1py=-KJxsi3GDKES zDJl-Qg-3c$benZl4imgUJK!cg*09b|kne}kK)y7&XZ?WXqZLcvo~wQ^$?o)KwV2~H z_&PMSTr@7Si}s*5DS+C89-+CoT*NsktsXSMxeroJ)5<`OXR=)S8)ZU8PLpXrmYtrg zCF+u73)y<2I@6=@?X%t{%<2F?I+!HqNG3s1u+RD7DWu?&KT~>2NO|`9ZzYY5MXloB znwQm>sd&cuI)3Yk;2}0dkAJGFFBbQ6LzCk0w@Gm};0B~*ISk6jG0!)ReJ#^ptw8Rp zP{81Q^0V$=rKF%r<`atVz#(E|5rWzC1C|TJra6mUj_9vF@KBuzSOVU(2i3g42L96W zm}ye8XA0O{+oQlMnbk7AnG}Rn5ysGJ*$_M0O3zAs+)s|dB^!b_O&rsNCo!c!p*Pf@ zG*{0+Uz$u=Qv6=B-KWdejn~ihS@ksRE#G_OTT76U+QakAvy>aiMjF6rIZdd+WEpom zI>rWZE97@`U*2g-4OAYa%l*OubL2i2)?RXiu>E&J^#6Jyj~sz)4b|ue?E)a`P#9iI^88ZAb(Bxstd^o60v$IR z)(J|5N>xkvrgu1SePQRDLVTpW!%hV7({}SXw5!0p7WgId)1n0AR!QE7ZGQUR@Zxtn z!uJ55{&GwkO@Gw#V6hPVB#U&Sk>46CdA6sCQ;c{7xP?&LwW;V2ejTd%w{jxiG^M-N87H#g(iW#>& z7XG0{6dJ+bj3!6sHmaCPnw^iB4n1m08a!=DiM$YN6e>3 zN1aU_*_wDwit-&z+irX-{)|@v1xFtEVmYE+>&-@*VS;F6FdR@GSbgHDO*gS&*t4db zY1@J$u+p0gdYcQ~`!sC%a*Qp!%dp}&lx4*;n?5&K5$nv&cZ5s3a?tHo?0 zu$$fhO&_%Ts|iV6E#!p?&g4Nzq(0XQl|Uk6DR-k%P)eo5QJ3*(&U}HLib;tPRYo1r z|MXS5%Mz)Ys!FsX5$GdkN301)umB6bs$U;FBbmV;TqZ02*_!KGR_4r=Q9j3NeA;HE zo~U=L_s(p=AObjtFi?rQEq#r^8d0UaD>e2(wHCGlGlRovIsEj)glnF! z`4f@NFHQzw#UQAr{FdWqqu@qT5L5%w7FO%~tX(#6U$%Y3#Q2T|fR{HiR;*_oNgkYa z;P|oTyFMh5J{ua$Gp>ySrFgeoESb11`(QN592KD`nGu*~rXp!@>&@ zBiH#n9xt`?1CbRN%W)t_12?+SZQ?0}=r81&0Z&O#`|$um$1C%`VIf)t+R-~u*9>LeIyI*N52vWwF&^() z8S?@KfQGjrChw&OGEAi_OAPC~XB${U>O$%kmpvjq4RCQ_=mv>M0C}mM7rC3mpLzE= z0efKcR}e}FYuwwz$dY&qRonEnri@#5@Yq4ZY7jHmlxP|C)RzHfa1wgLB5OWD@LU}; zEQl(vE{{XH`HwB*tRv!AfD5EI$j(kEypE>Q+`|0hQ794Qcx+=6-6Yo|a`z15j0ptjRc#2&Co|+8MmA!B zwvI0C6}6N6`k_S@mYMRRfYN4d$jlAXeT?!I>4Sz$ieKqSCA)dS!#%rvB9Y3@19DxmzzgsAcKJR$njJjJFoy=hbYC7FOl{57e z9D1e*ex%hynoOT#U(WQtj3gK2@=L3Q08ve<4cZWuHe@rNa<4#8nII%N_?N_<-t;VG zLphzAyyhmMnj#p9t&=cC9#eC>-a3aE_hGjP201`f2j?LW6T6B~fb+Go$p_0^d@=A; z@1BLU+F?3LtVl3{Z`q;djlU{{Uh$*{RL{JaNXK=_OK21%<(*-r*5gHv97#0Sdam_G z$dIuZ!nV+)Tau=X#oop#3ZeGf!6cUkGE@W9Xn-rS5TN6ve6x_e5_Un>9AWp1mPXdw z<|!9UbJ<`-gOk)vGk}$_Xex*rHlEV$I@pl+6YPPsU*dB9pi+5ke5AxmX^WEe<{{#~ z0dirJv36j+M*-rzg@ifl>8Q}hDHWgRTgfxq5e#b3p`XT4-2O}Bp)yGN<6yY_pw>sF z@OjO)%(q)cEX&1r=4v`>E$jTdR`X!9utM7liB>4<>d%B>sA|`>{tPn^7D^xZfm zJq|yZ%2)Fkb%0y)S`7{;O{uYbUBU5pqhO5RSw^Cdzb}r;d8RfdjgkO&tTjtT z4!R1E{UIaIZ8)wslu+BEdcI}}^~Da)o6vN|m>&IOd~Ikk43a|aw9kRkG9?v_r|xAf zuaE{^JSa8rXk7r;k7hP*mlOe_kfB1MyD>ss+NF3FczeL=tEV&xkC=%h6DO)pysNr& zGD=p_!gslIGYjGd zwv1N!hZ!}VZCwXclS|XyH=(QaUZhJ6gb;eK0#ZeKZwg8eMN|XoFej_>m&MWytY_zragJG z{$f_+mHBshhOI}YZ~07KGyANOBGlPOGuZ%bUo5t+~YC&Nm zv+vcXTrW!F+M?fc2dy()Zxh2?7o-01>e93G^jyi9nL8jTnc+hyMAb-8?CCr15vjfe!t+-t-3hlbWf3( zO__EnHB??7k-IP|pc%U2FQ8WXL8tJf{(Fix!K~5SN7pWvcP@M@AHK`%YjOSf`_u{G zG~BQ7KFeR^BhpilY3JeAkZrL#*AnBH6m=bw zXKs*cq`E%ePG3Pk5Z6G=-6~6A>u7O9wI)R)=*y{bj=Qt2tkxE_;@_v(T%RWtZos0;{9-QYlFz$G5&dYABT$T`l;ToO35=e)?Hh zUQ|?qY2;~t-UvI(z+an(82IczpAJm>hLhst)*aQf;?U;yG>%D;`>Zwj-g7X^%35No zed7n=CS&H^E%jjgvg)nU;N0QR@ljSae1=&~bQYDmMNy+L@4Ta3eS9C$=>)Pj--)fY zicJ!nZ{)0g9AEmOI~&J?kn}kdp`@BQPupaslu=coQ*8jnTYx_jKW?F+AW|EdleoA;es)p{K zm1crH8uM|g`D5}2@dzQ#0-rV{&}Gx4UhF&RaQGyGZwkBf7)3*xNiBQ6Ag)_CuGRBr z1C?NDi}sAAV*FRTA9LfQ**HewbQ9U3mX?#GD`{wcOGVkawN{g}1%VzhYAT*zGW$wo zqE+=gWQ(6+QjHp%8x%+@T9Te-oK&tg&Xg)!&d!m_RaMX;zmXUkOPFraDC4}gaz@7LPx4lRMUX<-?e@2qo`%$CDc)PO?@1=1DG6@uSKXxI8sAX= zvT(+$b=I9`@S8#P`TmvQ9Fd4YlDvEyfmoX~!XlZMkX+}pv!Zua$}by9>K#=*6K3a{ z=u;ngK*rkg;%7(Q`EC6~p;MIT8ENS>wLzQ3V|^|u4+(}$ypLtg_{JWo))ecs4={}1 zrPtOsxZOX}bucD|JC-_mIbEjC7aP+NzCK@I^&v6TkB%7xM?dea{}fr3IAWzA?{#v^}*#Q{0+s56WZqmHA5eM%Oz`bNdk^d)kK7dgkIO3KN%W>v!h1*;s7!6<7k6hv_{QznpigXp%^8 z_M&G|{9ya%J7qVLmhiVkW|Dyr17le*kzN0cD|pnA8L$Co0mgB$@#ulb#&Aa z#wI-*`D)Of1m6}mFw3T042kFT0#Z@0gubPvsmxEjHzR&oN-$&D8b@-mRuS=4QX`au z2(6Q^QUB_*BU*}~jMD^zdAFr^agokjqjWqRGvgRX+$$y|i1qR~G4dsj{miaOMdAvy5q0|txB*#PSd5!aSB;L(dDIGX@ zTKYF_c};DMwboq3@if2k(HB2!~#_pp8tAvDO}UTORQbin`8!lyEi)K z%UyGuWm5PLZlO`5*(GvwAsUvfQS{(VV_$%$_2J@hRgrh0pJ>@Pq{r^nhRpyrrX?SP z#SVgYTQt9?_T^_= z87sOIE@vxUdlmQeIERKUA~t-XAge8ihm(xY5_Nn8*=VN4xL7?Cc1tnl8<`2On0`4~ zOPV42j3bXbs_kw?j9xRN=H`(vB#}Ylxv%A}9!EDS8HCG3_h#6%zE9o`^o$vI=$Apt zRLFZZc_>dT(aFbTOTAN$iru)PcJgcNG$C)YgZ6yK`tS1&x}T|j$$o4s(>_)_?Ygcm zakrJKeX6WQuyQD&>RMuoe;=w_AjL$?j6&%4C0gt5U;!(eO%$VLxNb-AdM}39bkc`u zqEzbI7$$gpIt!g_^L-&H;8$Fc)#3&J2P%Wa4@Ue6mZtp&ZB6W7D2+8(P{7Y<;-}x1 zC~w`$v${l)N>_Zcvpg}`tmy`{4pJIJuaV1yY;)i#*1$O+)B$&x6jrUziY|K9Zz=Xrtp+t56QQf zv#KERw>v>X(d2HL)ss}V+2!<{Ea}zj$h?w`*DsD{hsz`cDK|-9w>G?%95#JAMfYYM zmk{+@MsexQ{$kf(2aGkz>2$+bqg1r}Y`B$&<_jWoi7TG_-?|Xcp_wh|$0IY@IVBX@ ze5zWgWftKuy^|;~Q=`dKP!>DhR$eMC{wkf_oWbffSp0crZSClGE6I=fhM&h{w%y%M zR!YizxFhFZ_?|6l__gd-?AQG2RXw?^A)^6H5Lgf`p9ejW@&r)h4m{0>c&Gq^nE z5lBvJpvJ%EL!GTbeU#Q=mmZDRIslpM zTUxeOt#6wYyxmjr+HK;-!^^7&cwDDOGdSRlP6E{uB)|7xzMPV%`HVwdFoXZT*&E}- z`rSjipzayti=`LeHQ!Pn4qvN_BoOHC6;mnL*nWb))6G+j5QJIE2b~od##$3atjDvj zmB=3%NMA6Jxwh3~&;yFEM6(yAi1Bo$7c=@%5AZNN?I;*-=3VEnSr$31e|~A4TS-^_ z#XTLGtAbfi$ZYtE^5I+K{H6|HLy{vb7grg26{KkSNxcZFiTzp@9ZDK8qz2Q9%`7*k zn}ND#u3s{*TnX1XuJ3OIEgXE+rG43*kNSgSZ5~MsnTxKEaC7Vn1hkT(f!A$T4~08A zS2v%r?<(8>t+PxMDw>G*v zIZ`^Oqa+UwT3&RR3^fuWi~CAw{Rp~w4rf)}x=lpGLBaBtu-JammZV_4?qSRJ>Th>h zXS-yf(JLmRpUL=aaZcWEpKc`{js)dQ5?P7ob`i1oM~=ET;RQqNQXg|PPRv*aT{+6Z&5Km zN$Evf$0jax{=Pi-4>#FmNIJxb_f$1FPXPZw)srZ z-?T*3TEeh7UF+d|hh9A_^_er|P-``?CqFl~i2)~B+!${>pp-o7%gn?n2&~)5YN%w9 zkp_m%svM>>&rMHduYXmg+)Q<-y)V`fVD5_*rqov|eGsY?Wb#~4^QZT{j@IEs!Jx>gG4DS%mMEn9Ig5`M+!czfTX6X5O{uuZaloNus)~-^&_U<0(E}5QnBZTx z+r&3&DiYnRM=0mahPMX%I0Tn16!F{CVS03~%``g6RFly`hu6+;v^?)?0<9~!>(^2S zvQ4bYCZ+iT+FAr$0|Tqd=%lxN+z-`J$Fum|z4e_VMIePird#|$IT0cnNfn*cM9W!! zCENXIQwVKen(%Dx6#lb`^1EpPRjy&h%eVm!qK0D|qJ4S{i>HmOF?X*-n2P$9@I)jP zx3wSRyQxW*eKkcsmJ+v0qDXNho|j(xTxDE{m04&HcjE7spv<4y;=W0pKr`$3_P3OD zqjvc)dmAV1lJ!|zBR!roW91q z7w|vA2Ie9rY|L82?H@Z{Jb1ez58i@B%TibSECm1t20$3TBm)N!Du9BB1eP>}dKbfX za1EgaXjmig0T5O|yo&)SMA-ImB_jA&23kNQc6CXiTn&QT#q>4+Qq*gux%UtePd{$OMUfD{0Bd?v!;BylO|J-<=sQi%3(Qp%sW zKsi)l3e7IRgDX>L_i;@c0(RmC{Y5=WL+$t5oQB@#U#1c5<9BJKfBk`xO(Xw{sUfD= z*Bwry-{oP}uL;EtkfN~!b0qT8>fIs=f59MnC{XTyX zFhQx^@emCGmOY*e1z2|-hH)nv2b_C6l;qmwckIl-X#dSc;)8&9R|fh+Ob__?Y!b7B zBm25&Ah0jb2SoPl5Q_rLo(we)5Zl8rg5vww9bor$O@QPc4<`=4hhYSz_AwEV-p3k1 zW*-v)`Tt;reGGu&J|+Tc`xpSdeT)JI`#x9!!`*odf#Y=oM!Q%9;$d+7Kk}ygcqd
    M4$2c4APT4i)Fj*-MSuhxniwz!IB*W!KrVoX;0(AA=8*!FFd_o@ppN+N0}nV5 zEf5G^f@~Oo>tG2CLG3I+iYNnRC?N?-kXFzOD3K7zbHiYm11*pbKg*4Ule5zgDOwqY zM#ACr@PQa8Aqsg6h=#-Bg7_%NLouN>P^WA(FICC2=>7Zlam@InK(?MXv71hjC9ugT)(|LOo|+PY*%>7TbrQ&_u)} zq-16%J)KSw%z~Ue1Kq3wJiOcpE>50qW^TSdF7DI_9U%2yYvTI)g;pWwB@7}N4HJg| zMqE~DCzs%o-OVWocJ_z=UMg@KoB-%jhVAX^Yyg~lvb{Y4^HdtHRb*jzsRQ5u6~ZND zaQW{tcUQP{*k(JPt#z@O)YD;6W8giQIlDmf0jk$oIj1<-zsB5dqNJ*$` zVdU^QsG^}JiBZ$S;W09j>gsBmS~zK}h743$Qv--V4g^eabK%;x0qBzeICKKy5Ou7E zv@8y%g~8)A@ff_OEbLbrua42wl#`OxR)a36!xI<~M*_Ck7=VgB1>orSg766N4pGt2F|u*; zib~0A{At^d=Al2Y_n-CmI))SQKcagRuqO)x%-q!qsJ7Q3vwJ$gdiOMf^+8yO|L3m{ zE@vl~GhD8LPM%!B92!<{!UzYF`Snd*GX{+F=+s(;6Au}bQnSd5D~*?cmj}b zz~^0FYlkP=<0K@zCJ+v>Q597Sc?@SXsF?Qs4 zbWgy=@h{K3&)dR9xx*iTGOln5?aBM@sKX2Hh`WC5%mB1Q*#T?Uzub<0@T}kA>C<+3 t5=9|sryb&*Snae+{i&(pX}PNhE6Af1AMXr!um1N`-)X(o0sw9M{{d6uPhJ23 literal 0 HcmV?d00001 diff --git a/media/moss/follower_rotated.webp b/media/moss/follower_rotated.webp new file mode 100644 index 0000000000000000000000000000000000000000..23d5aa9c1b3a4e4d03e711a9c878ad138d3543ff GIT binary patch literal 213252 zcmZ^KbDSMP)9zW@wvx4N+h($M*0ycicGkAdtZgG}pSyYAi|?O1=hrjO^i=nmY1CBp zJf$opF8(eE2G9@_R#aEy)Pw~90F+;81`g1J1dtLDQN#xQIt74Y8`#-dfqx-u8z%>4 z31MPQEp1|`BLK+P??0P?k)xfEqN41-lmB!4@0I_ve_Z;n>;m1tx-LEnV>p8)2CN&q z6g<|j8UByd|K|v6Y~pD2b?yBtF&f!9H~|14v|m`!)yeK3_WHu;4qrF*h2#EVv;X3v zf7tN9xb;6Ws>&i?GLv7J*vQ<#_zPcrVOqogk#F`tu(g%*zyJNW{d-b)6B{*^uOs?b z!Uu=~EC7xGJAf6y0N@TF1}Fkp{y*}p|B)8~*nUa71024}nE}iJPG4n&zHA3o`>4zY_DmcK#~+wLLEW@Ajkpe|dr1003VP5D4t}e|ge906-lF007(e z|MDm~0RR*@0ARGu&cMOoKh=SK?LkdV0f5_5002P?06?4lDx>3Q%EJ7g>mcyL006`m z5O_xp06--I03UHc;9CI@_)!P|fNcN(y*6JXhM1of3~<9rmJLEZ3)hPz5Z=9P%puUz zQ>b{3cEbc?X7hF(=?lDTc{T&4a(|15Q`=W%`-OA)k;{5yQSL2)5zMpGv-Pq6WP9_O zX@C8QKk0e=zD?>o4?I8IUAOTOKv!S_{#wy{(|gTTy|@*qe*oP50uKD~efmt%rR_<* z5B)^@JSsXu1M-gQZ~5|xx@jx|FCSjk9(-R1y|93v`U1c=<4+JE(DyCax4-Ak_vIZ3 z9J?*u>p2F#0YiacK;UProiFZ34>0#$;Kb+Ns~>pzwB4l_1$ro^02Eq&>hlIz6D;HQx)k?{YoRrv-lo4+#9N*CY8IL`2m3?4fRIS&tKW^>hKm zf1`!c>i(LTol_B=-NR`!#lNoKFTY`-BKRz=oEm0A@JRbSrCOH|T1?nT zGH20BYqJuA%~xyHNC)P0!9^RgfbL@QBxFWDvwrsfR)sFnVc?n-M<5@@Vhx3L6?#1z zEGJ@%PS%G)tIjY2(;--PG82R`g9J+=nB;r{i^s=pGa(Qp4t-3 zXIRSg^T^}R@Y$!wj%{6qCwZ;;Il7@6HXx!cbOwjP2g}=)vM;{LW&UXhk!;r|t9||y z4QyXG^3fa@{(U4tf{q~Ppz=JK6P%xss_u(gpF=twbOb%gA4$H8aCw2eV2?cGrK45-krAa1nzcFeM z%r5;WRNzT*>ED7lfwu1|aEuv@*3i@+e0y&`LF_)plj`Y2>_Pvt2g_h<#!w%vBi2_; z@~rIgNKPz?$&fZs6@*^~qUzmx{mazcoImkQXP}ic0j~uJX}-MO05}ZlPq$8%%~qjQ zYmi!2d>Fi0%2-^|12%UC4a6emo<=S@3WmJl@?TZDiDR+@*M&60u%=;czQYPEslI+! zc3sdg(ujhfa|Zn$&Ir2dGLh28cNO%fQ~93QBHq6lA1GvM0m;9lqO)QRReL;8Tglnp z2Lk1Y?q>1uWa~m0xorPC@M0+M%>Qpo-$PNKjkU6#A%+1a43cmGi!O!QCi)SNR5oGk zlfsvaWBu&1zdJ(x4R=vkSLeXWT|NEUfvsG!i^+QCPM`QpZ%q(8>qJ_t;0Qd%n?FAP z7C)D+*U+u-Q}Yv?8yJk(rB0+ppKK{M87TPE$fd;9+a^ER-3ap=kO@c=(@fNiQ7XHn zZ2lsT8i>XBCtHw%I*ys3?>Xd}fe8cx78ij&nqa<%i#L?k>9Lp*EBRKe0skg|tWep> zKg5cDO={q2;7IakBM_%C8Rn1?WEV(R8lb(sC5=RBkW$v8*ti;MrEQq5fk+8EMJ^73 z)yM1)eoj`?!JyR%rZpgMy1BUQK|GeN-eBL?CAEjY{;9D(#Gs}6Y>6ZpO<2c<4lX>w zU0l)~O+IH9&S6!Y{#1hRjJlW?A>^^CII5k+KE7SB3wqGu(m`8^nYoX}CQ#h)#QX%ukPa>*PfMUDy zp)2oaFAfao$f{lt#5O`?U;eMwfT%OTtX3;vKENZLS7EnHSyfIOrl@R&$*_YwX+RE$ z7n?y*wU$QH9XKyF&O8)XCa)rQ#1C&}2)9dM=$%UJB0P32a_cq2B!Cl+U<=Vo3Y3MiFB$!T(e2ppf3J-^jP4R@| zo#OpNJm-;gDWIKuz+l(|MW+#xRp~Cd^KGD`**-zUup3N@^R1Q{l>9hf;aPp;A)>o*!uK_-pUt z%&%CK2lm6wVnHc^6}{=as#X7r8s{!M0v}VS>au{(;pkz4S3Nv1eCI#ym}1DM@p~(N zdJc_hG##F>TNmPqVhHK~S`ZeWgGgG)>|ug7JfFG1>j*>(dtgjjZ8uV)L=9RmB@#gb z7Bpl=7rVh+By)j-18diKMBZMiCFO?V*?Q%0SSrU6W_*2^(t$Ou%_mG%ewxY_2u@Yi zJGV0HdD-oREbtWHjh3F$O(fQsO%(8ACu8~J7bPs7G#e!JsFl*C}!gtv^)2+eNLaeg#BDg2rhDe;qn@{z1D>~MqXE(zbeW$`s>Hq zDv(^xCbO!ZCA+AQJhz6gFKuEchRNu{NnSzrT9)Ly6kiO4dAzl;L{81k#GpoM~=IC1@>2BzSj zP71oqW~Q}|Kdw}rHc9TsN%Klwda_{x@*P?Pb>oo4#=z!t;qUA5`;OQ%l!apj*rwaO zGn75H=1*7G}$C|a}=I?l3-6jXW4e(}LZ;tPEH&JBx-3Jv5LLo+;5^oplhu$NQ7%NymMQG0Bj{px z)2zuNyFkQb8HQVT_kMY_=x$U{uwn7Kl;$PjKmmF5tNvU?vUb8LK|u;Ur%M9osgVdZ z1@i#Q)WyZaIl+ENoFd#DQSrQy^b?U3qdKq*WMWR^TZ}FpOn(boxH+r0eP@C+#fGJx zhToxFU9kXfiG9kuHprBmgw#X&>&&b!V#Rh#l&{lsI0fEkT;~u5-t|U5g z8HWa!^R2DxLx=g6)TONwwdx+%X0k=~x8;|y>25lo38<>M0tmt7rOIs9ME{D`#`T$Q zTV;fua_Hk8rdEgLF1+WPApcGBt8w2LbT)+JEqj$0&rW*bWc(LHVw{gtWV)ZTm5;;? zJmNe-h!S3+%OnZWz~>eAQ6GVT7N`{LJ7HW(ljQUMuEjZ2o=6_YFh-;##^P@cQ8_EY zU4&#F3O9ZacRhw-poy{dcyAB2qA~Cdw?*Zyt`Hdsdh^&>pc~KsGMbM|YvV@zdE-J< zrt%RcB$>BlXCco>YP@kN4UNfJKDuU321T~#0!_Tx6h|o+s9Y8TOYI6zyASG`$zc{E zk_Z>~LCiNS$^6=A3izK@XqP^MLpxptva-Dpyvv7op!;d83oJ@}X;4?*c--UYr9 zCvB8ZB~0}AGV53A zmpBYQY{tTA>Evl&_j(@ves3Ox!>r=j7!KHhLZes!;oIOoH zdstHtvn~TUab~dkqjL3a5;;8I|GjhEPe#gn!5`8&B4m4k3&swvcQ~=QT(F*C*7N*n zeukWz24HjSNMzdxL;13G15rKOId)oD4@BOGnwDGHzuYr*NOlf+@x}jA)-gwJ52Ue} zZ`8fmSY{Q+AX9;Ri$-%*pCv^cHW#D;yZHFR;8x>BP?}rW{dM;_yiUu?SL;5VoZPT+79+&*D&Tu8vJcA^YB2HK5rB zOlKDH<;ap-YZ7l3mL2rNTYq@OwEI}&puII&D8n`ulNT0aFe85>UA|>=@7`0P>3~8c zd?w~f^oCs3lqE0wN*km<_}+PShrtVd^P>zZloTV1mbFK^}@iX_lg^1TgvoeDrS<7zH( zF@jJ+q9!!YE2Dky-i;|;p)4avDNGj2V#aE3^*}l7nI8N7wtC0$m`&Sldmrm={*kkk zqchsMzJL=J$BIfJfYT^Rp`KK_<%TaZ+?bTp9{Ni$@7VZ+c;eL5sd2yk6OfM9pQfXA zo427!ID3wAbkS=-r*emG(}x6pn?Nq_Ej&+$AZMRvtdhFNwM29H8`Zjh_t^?p?7*My zN{SAjG3CG=R$7tBFc>q@M~sU9(|_K}Os}=&dk(6^*Rwgn=FG$Ez@&uI1cnBw{eGNetwILrzrVLe zMt7}4vzo5&4M;7Ync2mg=8{S8lA8Lu8=kg_O&D56x5P^p9q_xPey?xq8--7iapF4C zh8%(U=$S}Lq6|#huMS`gcRqpvh!S>62$izn3w5t{dO&3H{}RviLwMN6R?}XOZmbGwT`0v)<ii+9i3`fqRn_A9k-Nv6wfj zelr*xVovs6L(WFB;+;PGF=&&iAJb2+g#W>tXrJFmHgKpuZ2 z3xX3W!G?=jLZD2uHqbe;QzhnEkP#yLd3&ML(n-)%u-l=MlH?nGArQf@gObZc1o)GC z8eMp{a2h~SnmP*EbS~DgV*f1^N|s8)3KG8$VUUiG{)MaSL?mW)x0&o0UItF=m|jsR zHU0g{=pZb=<4F}0cyM|tx`W^{h{(VZS6f z70Kj$5>B_E6mklJL08BeT9O`Y;6#*g%A(cxgOO6X2%DYt^WB}dwGGUfA@h!ExyGB=-W{wIhX0oyn88oqvRoKmEyYGG>L z@7h70SI69k48q;2Z&I1J5Y3KO2FcI@QB(SEB&wheLJw(obYNNvcA?i;%`k^sob2=8 zanZXRy@s`6wEkMC%1!ZxHEX8yM2TyU*%OnB3{6aMhQL0(RJUOVR8>)%Ktpi(HM@_t zR{bhcMRimM#DS%{+ZLyXaX^>YenRT7*ZpL45p(BHEe#~v)i#;!PDhI{F?u)t z%ZL{~0P;xCbKR&~_5iSVFvu^xI2*sD?pKXwm`xz7<(0qj1+T;4wcjNPLI-|h6#EK& z0CGAV>P+Y0jr2673x=epIikSF3^9Efp~twx-ylP_q=5l)j5%U_hq37i(5v!L1#bba z6|IO0|G67DrY*>Ser6QrZ}k^P<u$_C8)31+jbY#C-S0lPw`d&UmzC5v9 zwV%+0OO4h15^Zlv+&7#a03kr9wunacmm^@B`F=EePoM#Q{ua9veNYOnB&fMqP)URc zQY3FavhB^h;7X}8hjqR7S=|X1s`2Eb_8@pXK#%+_Tbi3zP4a;n9jeGWRDZV;oFWr@ z@tlDwO&H%_&Xm!e2fUbGbvkczF8kHCzH&BXMk|ShWygi66IV#jQZK!@i?K!_X-AP# zMZMTlNw$m2vz99=B1iwFvtvCC(}FlbkA1O?8svB#CJRKY>2OB{>d0UUTteglB(j?} z#Z2HZk9)pmkfmS~I^m##hBLBIO@CJfwD&b|?HoEg;IN0j92&^lNzxV*9)|aO)okmd zNT<7ypF8(b-Tc$D^%-;HgAs#L$4EByWVfL)@TI{TSEf3{Vdo|rOvLLRi(^T(AfwXlKiY%!qpuK=L_xpG>S`xnoR zFp(BO^Ew7HZ{{v_hLQu}3LOHWSH+h@-Yp+FWIM@}JQ%WY1{6EWZd0`iQ~w7DnAWY_ zPv>wWN)FZzI&bAI`vNx3HC>505`mx$zhzb<7cgsjb98t>4w>SDH%wgQU!@BeCG0sV za7aB|K}T6&KD<1dQxohX-eq5+xBmmDIWzft716DcvDkvSx_WK6b(g=8b8TN6Y)E!# zAQw8_pdO?LSo=-j-XW*j5_)(S`qkAA${=uagRVez4tu0%`OLMHDs}HpzH7)Ex`f1P zlluHzTMy$=JRf(Tg*Wb?I6ztk?nE+b6%<%`{wnWJgtKp0i!#P9Rm-Y9`i2gJ_EX48 z1%by0VaN*q98Pd={PariaCi%Op6EeEd1~m;#v%_g;*KUnfx=Clx#I>GR{rKeZyan^ zn^j&qAQo%lz1PgBa6=Zf5AL9t>sVA{E*P^Ni|Vecx6cMGw@j5XXf9BEFfsI*X9OhT z$pT~-jzH7nX^g5J%@5{WEruhM*#*>s!o&?+K>ECU52zW(LulWNHOGvT3N^(7lbLKx zSya@I#dA;3; z)WlVWec1kN(A-r8QsL$>Ln%KmVXz-R{WyfXmWN;|eWRcv=mH+kMh9ANA8DgguGMNZJV@2X<+|IaR@lVg;)Nn9H{ZxXt%9Lk@*^n%98n3Vt zxm}__E~XY!3%E>b0|>HbB%KG9=E6%)QS#&COj-(2(V~uk!C&1qE8I}hjNt`i;$_pi z?`l75g`qT|L=GGR&BtzpQ^PW|{EvERG5qu>tOx})J; zrNY2Mz(h{ma5ashi$icJMtV&^2Z<8B79R z&b*_yZKQ8LD3R{*gnEQ#dj=dhxeN6%rBr_V0q`iMW_fyYDlbe|-qH{rl9QDOHIj{E z1I{fc1vFO1KliE#R6e&EZkuq3^ZQe@jzs_%^%Lc-=t@)Sdit8%hnPs82pX@=V7goa zz+RxBT{0ayOugXz09Y^nQd@k*j&g&u?$3C!_!?d~V&Dxm7&L34q)ZwEIvmQ72MF4G zo4j&-{vwZ1`e?{ey!dn{3F=;}G0uz_sKdlF*iE!98^$oano^H47h-e$YC z*0oqK9CU8W7E%&=65&yskr=v2qXYS;Qfm08Tw1c73tla*9xa{lza?Zc`CO&_YhTCRtFs%@0)eVV6kywKkLPuY3-#Hj8Y1P$O<&H50boBcV-Lhz!K?brQx^gM|foDepQVE z*Kxi-^`bXAasER5pE`{^vyh?w&k|@ zJ5c#yDGa+x^%IJ3mKS8Npaq^#D7AMAzyt4L|dL-bB31r z#SH!&2u!aY++KiS7sD#gFjaR>3;R9v{)meFWvdFTLI`;$TU5RC|BxfXvM$WUpB#LU zi#|`&Cb}1UPs_&mHgbSKYawzppBt@9$I7TqVrQsd9y#w<8dMU}P}iIi#7s8iQ?H(I zn1qD#?q1I1@^j2(!DA2&~xo@gU8iOpIV zpFcCsC|E_>txv7pvj|npmG+ErgH#AozJRkRj-G9pQX&cId$LM~wu!H}k>v80W3nH* zrOI)oh-V@2RWyL6pa6yZcUb#@4dZVxrF?m!e0&uSdxlpu%mjN*wev2rKAUykxVzF@ zg7Vo}U*O;^KApn|x}|%a0;T&$r>{)@m8h2#CJvftXSkG@YY*rj*uq>u{?vJhRLU!z z2tFF~8{~B!Pvy<8g~t4Q+KRgH<`^v5Q|;Cmduekd!>939(MO}dP}ni)4&nd|+| zI@FR9LHhPa*ryRu|J}cmQY^NOvAN;{%z`zaqj4-5<@gV@wFMS*#GKJLGMAXQ9RJf8 zeyqH87rJZ2AeHw92nWjSs}zfj4d1*GApKdu!JLq4zfUPT zNWG_$lxM+B6C1LY6cO(B(VIHttv}n4<8*iwiYA+Qi%tWPXC_jAw?|!6e3j*~b$3#I zkW=TEg+KjorG3U|Kg3nx8v=;n6a>WT^vSo7z1UHOEUfIEe9GC%QWtF^S?Ysx!R;9S z+N%o7&h3;@SjUANll})HJz-_w5VX+YxK)Frs|(thRQSw`ti8m6wdn16orUS-n>%;! zIR-x393e_5j)EMB-EH7z*DLE%57I^!K~HFI-1glmT$|^XCNu>F(_E)(*GfGMT(jT& za#MT`cB@{}H#hL{@z_Z)@`T4BOA$6zK~;!L?$*Y6*n_h;Z74>Pkk*C@JNQ>ni3^rN z(qnpjNWGheLB2d4HN8h6b_UnTr{&M_k66@7dNq@7d_jSHyakQY<35CpL^?2!2e4Vo zu)@WoI!I3$jy_crC^12K=G~1H`9iw$VJ<%qTqlj9Yb`ZUveR$OI=|K{vB>ZQ&Vo!a zCsB;?GA63eg-v%9E^n@fvu=FR`@AgZmAK(yXk0lmz>b}xLGLLw5PYh~wJ;uTPsTo; znjp>ofUTL(!Nv2Vk(vZeu_~i&osG>(V~O*F8>Ny}$-NYsFBbC>DEN<^=fwE1xBF;_ z3%i-6Xz&%h&)cZ`^jHEP2%EDdeAY0Pf?Q9~-(F7r1`;@BoNtk~R1N?^eF(WoQcR`( zuk&jmXVJl8r$I7aP+^T+36l~|wcB)}jO~^_gOPj=B~Vi6870Va2r*xFYEDxs`@6n_ z{)wzE4e_tsS=^dGDRZaIlHbm2O2?Ic6j*{7xKMtprh}eh%=n#{d+GO{58}Ql%alyb zeFkbxSQrcfQsDEcSUT}paCNMWOh-a?Z-KVfJp5NEHDoDd3^WN{LY$%xntZlILhl{K zyg#o_EOQ0ds|AmBV~X*v#YdtHcdw1K4t%W096UP4czA;E_@I0tPyGXcrE{!G*Iw|Hu^SZOYtCXPdpf_}gvbdD=^FPg8$;1*B* z2`I%O#2ELxc3{m0@sNeUU)f-vA~ULE5>t`01r_J|UqdgNef3Q`%b?W1+ z#z6KUJV{4$7eO=HH(E}`Culnq`j`Y)s@{GlOquZA>36+IP&t((_JrcG1vzS_d`F3v zcgQA=>TIMR%%TQ~O;kEsNPbfKDtftQoe0$6Y%}jAf}-Je@4*zATeqyV6E2?vQ0p;- zQ2|*QJl=$Z!ru_bm{?u(f)W<@GGcyU4+%Zc_vG}992-&#aRAwaBAgge_a zlkMCmT9ke4DN;B^OoP7`izBmyF;2iK(IFtR>BLEOEq8w8azov0^kapy2}S8+dqaKj)jEihw-WygwHSm{Q`Ao@&Q*uSy~x66Z| zrn1WU>_dqRfoPF$YX)uS0Wx8$GNGBHQ|0*rf)#17FN&jJ`l5a-_wugs(;65e>bg@Si}G18%0*d z?l4XXgq27z(Am^4fkV_$Hvwv=l>*uURCw~!3gw5+*t+K^ z;~n~czakyFC=4mSwv%n!jk@!PN!*SMide^!!|hAohDP1*_#HIxmbO{ndPX?oM=bN? z?jjLa-Z zCAj^0^?IrM=?2>jSw(zvyU<3Meskgzf- zGm3jSWumdTeT&{dzqv=)e)U*t zX5isdJo$|EmoBeqVEA9(r8<;{!pp)IH)5)C0mm^y89 z!{sNSi{J21ifkk7YWK3Ulf2ptL^@M;G`R$NmzXM3y?eIn?e2FLDi;t%a3=e(2E=&e zmHBkD1Z_)R&8W_=wPWtV_@BZ|tvR#L&)Il&#yCGAF z*zP|crVn(?`H>JKIOQJVrIcE`s{RzS^Xv=n3$f)pO_j`sg^wZNx&4NF(0{k)wr)m!K5|jhQmn!$Dr4IF8Zz0gS250zU*S_b7$W;A-@``1d zpm=MpkrFE+H8}rWy+N37U;#rKb_yEnKSym~aQ}&Cl zd+Pen=)*_ zkjUKy*l^-gO$9zl2z&81{plDB@RmR)2fI`?6fnZCn;cA4Rts^;P5$0SaK#eX61aw` z)wfcn8`F|jY7BPIZhNDXWt-v|HdCU{hm|)W)|TD-f&tnELJ75G)ZXg&lAb8wtT>Zr_QwzeG| zb+0y+$_c*YT>f|$JoM7F^4lRx4+Q7f&}FoVNX{%#hdiYVJb$G>7i>1k_2~E}Gv4sG zK)Kx#ef9%%Ic4|IZ_tFKp{1vwe0Z*Ze@p79f*Q9?sg0Qu(W+%sQOa4OGR3$l`*FEz zQ_B2Dy)u^5&HF%8=VlS5E}1iz58Q2Ja-jz0fuixGHv51*hbHU5%Or|AtQ`Bn5&>#(B%;H>hmyHrGxSHA;&L=m5ugrr? zl-(awSwkse*4-jTKZ}$QXJKq`mS;fA3&+59Z2T;@79B>pvm&p53C;JD_-a&O zZ_!b(%Yl+lhl`w?`HFj@Or)}jOn)?n8W(-Hf`K+~7@8lCj$p7cL35ryr41!N-9nqP zxs#aLyjc)gbH4p_w7A0@Z`(~ru=)o$8{_xx;N+@rgzb2rds%r2@4}jQ?rNg$QARC!~1#iZeFVFp0pC$^EfP~OOSEdp2zAGJJf zuCn9#Nd%qn@C%2?uS46i>tOON!A@1|IRrai-}A#l?NrdqHmVmgl7)qS&*}<`vW6 zDOX^gS`LXz7YX=@ja76}&nmH=WQrsv9D1+nLDhVC*;km?XHJKKE8TJ`%7xU|G_vEe zJG9+@-^x&4vjRZtnL8;ET;bxH`+6lD=$lc^10KU?`Jac3J$RHLC}rvGtw z=T%Dz%(G9?8)x#OBWH)jo1N%B7Iw>G{DU1ERDAai|` zaxz!pF3k{e8Qz$ZBs_m;lB%GBh23>48(lSMM6?RHCV#z0CGgSccLl@C?J|h!v~~d7_vcdHFIk$gg7bbF^5yb(nkk zCtG03UQ};z+t~61Pp5ESXv{Zz#s84cxcRG^3n3?h->7!WO~4#OuJ_$W|GJ+rgu$;V z7M{&X@FkN%w+)ntDPB2J1d~jTgT9`Dt3;DyaJwZ~WlKL)=rfPwQ1r`Lr)9TDW>i_p zKXOKLpXD3(^*H{!xkepG5+O9_Af zQBajaW)_FDl~tjV6KYRG%YJFf(g=mHFGWEx!O@PxbGryR5j_i5|6#G4_uH|;PP#cu zDnxb!wHm4dPm)(t?^7Nh5s!~&p4(|-O$w`_SL#`e5Io+R;iwUB&gIp!EDA7F46wMQG0tq=H8EnSqqrKikL4(Poh2sG&)?|D{Eju!|HrQThn_7auLQr zZTyD*p&iF}ug_fZkDmocu(*;GyzU$|AdnB6TIvY3NB(%y(bFh_OJq=vi zpdDE|``TuMyXz)on9&|{pQeiyLg-ne!Z0u!Alz8HRDx5|!sa7+=_R{w!zi|$I``VL zV{ssm#c0hBiyQE2Mw_L;Ek4rTl==EL!LfOIw7=A2)@GufH%1`VXgB zK1+`ap4WGY)5ih`NeIzAh8VT-gDE>WEmS5}17-~$?6xMB<(>rve@r>(v{~W;F^u@vS!~lFP6yw!y;l)^+?<%=?lZ2pc zL|xBE-u@@Rf!F`N;=`91fls)&>GMvTt7lAb=V3X@5M3q#e zXnLeGV6F76zOxY?!!!A$K~&*ErvWn<(!tUC*E#L8>m{h0#BEsEterUY*z1bu>7d}+ z1e(OBT_$$yYx$0#H5Opvu-%N(h?5|0g04xro5_mG=$G1Q_2Le%@Vr>8NaQ{@m5H?F z)ZZivNSzACt#ge2V)%8FZw@4EXf^Zs?x4CE0^Icsrdx&Ya0DOelsn4MtQ!%6osRX3 zGvi?Y;Z_oYopH)Beo+7nANnrogp64`hZkb=z`fB3t2x|100zaak_oj2iAZ-&U{59bb`C3w5&3Pr-y0ROtL1BJ@ z-q~PX`In`}E5v9wd_&;6LH>Omkub9{NF~=sWyWMv9uOXx!&3{fcx4N8C6)M%4vF+q zXE_Gn?latyir zrF_KzCww{dRsHgXzB?hHmP@Gxsn2Hh^!8~4|6pR&wdXM7iGzddrn&!-_0_@un6z?~ z7MX$n;ye5UBMQsi?jgdSeugrO9?VEj8$kh}^KrD3U=c^W<3l+t;Fm-V)>-#9Zp1U) zae58QPR?L-_Lr30w%3*Q>Koj{iz=jr3Mn`p`5Yh-W)VI^cG6x$P*FQ~O*=?ynZw|M zJl+&gweGWN%_4Rd)y)r*C|y`=TSS5;J_pgs5l#q3iTo#Mnn3}x_AltCOv70qtx(PB1f<(#Zb7u4W8LWYmlXNKNM7Ic2*<*e&(sMO~L8$Jh1-vJ?6-%X29fwHAF5KYn7sMe{CGp z%z%EmGLLf4L;FN>J=rT{1Q;91(sgbvUV`CB8CL2EyDPeKLYnO8eI219vy}svSa%C|EJWL|{I5GcP#k>BW|Y!=VFP&p6SK+D7rw30}6Up;yy@#1|;X zzt$rk9>U6$X%eJ)l-NlKw7I#{O5}-I^EUsPELgmXA#vJ}bxP*tr*S-p z^wW+-Pt-2n&IMu~es(2j=T^vBXQT@ykeL-jZ=$`Sd;X1-C@Vl<+;O$axXCOR%FffJATCGzb1*PT2WSWXhl$-7{=h))$k{82W!6>bKQ^o*_L}%8OUP&VrJuE5WP9H?)ef zj7Wd{j%=u3CeW(WWnfOij7bjYX^R#4x);g*mJ21~y5l7(dJTKeZ$!g>;|!d(OkwREP6pqq@C7%_9L8yJ@L!y^gVSSYGLexKbN?U)J+pw!i|eYsEq`#CG&Wk z0AI=*ibbA^q8~wtqw7w9l2hgqwGxRUsLR@07RY8F#M&QGTZ_9UjrmQR%pWge@&GipCULXlYRwOYM=aF|Fs?$)| z;jU-g4NP7&BnVd&_#y%SsUrDy_nw2Ep3naC_^rlv^@dnlD4Nzzl@dOW_+by%lG%d5 zFKz-2f)f=hTY?Bl+^Z-9QT(S;vrk6UlWnaU0#j30Fx)w%aWF7P8+4S6cx191CIDDRkB6L6KWb zbMC268YKnL-ok%q3*`<52kPF}5y>0eNFoqMOH&Rb*r3~Y z<5Gp=DN7_bO<6ZBZ6iqJxoUB`;0n|6BHnG$3z{2apLj0zLck?pTtt!Ij@&LB(iJO zvsgfzlX!ys^pRQvzH;=O&)_6>P@bn4Ep^0%O?(BT%+W@G?3#pMjX#pn!ZENnAln%MsP6>o%9 z%=xK{=nui!^*4MpdfvY;EONW~=zrWOSWP1QNPz09NpbL_sz@dx+-0DcW)XEda_@36 zB+tSdi>xsiyD39TyKtyp7w_D$bI9r`?KpacdTXJZOB@jo&FFvY{KiCr$t&Jn)r1U^ z3x+`vxz>QSyyI6pFa6?^t{DOg-QSI@+KSIZCH{oHj*M~~e>@@_B%`3x(j~j9&4zpL zn>9cWMhrs7#*dfm03clqrrx=meNZAMWeiEnMBBc1VkT><7uyW2dU~ z1mk$=d;`6BbNV&TtNa{{Z7h#j=yOkT4kLgxFfeO#$xS#U@kQV`1{a4K(-t9 zag65#X|X&f@5*!s;lFYt%9uaOryE@l^c<6bc)2E^rbaY;B26?*#%!CAtS>xXM7!7lh4y@s~-#qioML9~u1J|3REdPWdI6;nySHI<2#ju)Bx? zJWZ9=o}199IWBQhdBJbCw7aX2!-wXID^n|LBX|^=lmQuJ|B0Yw=HsfX($%d4W1sAK zr1ycP{WmmkzhAVE`6X0{VZyhI_LK{6gZ^TBAV=y=$Cw%pC{Z}elUm40SoIDb&HGsyCG`qBG^Z zpwxP<2S@h+#+LG6kmk;YEGKLzf9AwkqPI3-eK3rmb<6gV1}&eh7%c#Tt5$jQ%`d3o zbJ-B6>BOayVrCog(n=`HS_bs)%RLt(<3iW(VE^L#8RpP1-6V#XSB7M=l#4K#yxaGC zA(4|HU~}0ZSOwTD%2m5p3CXxC@>9X2It?JY)N}J9RnR2egoB?%mCXqXC$T4%-Sc!& z{=-~2=PKZBhqFF0Lg1a>C{i8;*~oQiP0m4VhR;^O{;}poxl#-6&-pCIZFspu&MgC( z7NmUzZ>lCSQfJOQI}t0GnByv%ID=a#8Z--(r1%hwws-@(%E^xD?YId;ME62I#OIDM z>KU-Os$GQzEtyuLC?77n`@ydJ5v8}Mw4j{%Dj8*`d2sqc7<}vVqySO9s zZQAQq_GVGJtn(p+sfSFos|FM5UEt|x8L`&+)sP5X+=Vn_1A!}T)Rs(+f*DzMr;Pa!|kOW;Doo@}<>C|pvZumB#uzO;Ju`}3D&Rf09#5Y)eh}d?@pEZAnunpii zYaUTddp^&vwazH)3q)!GLc#ASQh?}#<#Nu*6J%n*bqwy3)1TARsMtWID1lmug&%Sp z%o01q^n!$g8ohIZQqXTj29tKQEQU-H`={cJ-v8rRD_k~)Q4>T$6$h#6WA0~X8RG?t z60;xGB>HQ%fyk)^-JYU8WEdK?z02Ld9v6T`6#{O^rI=EHGT=r^cznD}kIppE{0#%p zVnYnJD3jMy0+Kv(d~eE%1G^lbFp?M$dpjs7*NM(}D^$QG zv-kdm1rp+&cKXR1y+Dg|+aWs+|V*Xkql<_k0T(M{g|H65YH6?eS`0zA*c3O{9ynNz~V z;Mij{*9WKn4GTQ4J@3X&^_vKU*!F4iUUk!%G`iku1iABQ@O6!pWJZYK4%YeJaI8U~ ziMz+Cr66SQps%(o;pW_R6-vo9Wx&E5r}9IC^8lh~Z^M8fCDgO&IJ9wIpG{ws7}hLX zFr2xkNU7?QRbI^DP4J2&8`hGe-zhpp8-R19-5RJXfc|MoG!9DWOUs=*`Qo-&wG9+@ zYj$o(zeNflKd9NEMja0Tq87ocU_49n3;+IafO@Y3ug0xBTBn`kwR_iADu!T{LzQe( zM!DWOqBVqM=0`GzS~JutY16q|mT~w9Xw@CzRIh}1wV|0c9rkl&C5V8tBw(g~Nm*eD zJh#tQx^si5p}K-z>rQij=}Wh1pQ=QfY?_1#Zvr*=_W8Fm{{39yirP_0uY2A`pw$ z>UU_U5u$Q|*?+^j{uB2A7mK=6lwT=e$PeiW<=1GAnJ>p^wU{NUOPPWs&>su>R;gb0 zJ!~n?MUH(1b1JPN%dOVlKKu6sB7C2I-xXLJ-DgTsA6z(goi~K=~`j z&?tJ*ef&L){PCq=)M9MPTj)L=s>KVBQj|TcmsMoPAnm}v)Wm8AB>|Lzauup3?`5~q zMP%uAw&)M5p42E6h&hFIP*=XJf7tV(%=kjfB3AY|lfS^+3_ol?oW@EN03L*e3wAsr zvJHYYPnF%?%$2?#Aa7@agI01bJjIv@tBaVd1lqU~72!O|X%WzBbX%6^ZNk(@}BvD;{-!Ewxk?vT335GAVwdCjjG>%EH?F z3P>27vCCjpLlBPp;l>M?hR|Qj^R_}6An8prE0om#iQbARd9T+zcV1w;QxH#cjrcWP zP_MZ3ULk=McG?EI=&k0jPhx$cd;S>H$dLYgT8k=4Vp)TNG$_nLV0%YQ$flaCdNFp z17Ty%gg^!ZygD2AQfFxIuD^K{k(h@XGf==8JC2_~5PbO|UI2GUaPhxPYO{1zbCKdA zKi2n_6zTg9w7ax!;~84rDvDCG+0nTef7*^r!JpJk$+k=&wg-J`z-t6hCR{ev$xLK1 zXR~xs%7}{Ju)99W!Y|Y?qt@Zun5N25En6^oZ}2lATPKiz^d60WWuSg@VpJ=7wJNAc80+zq!R5;36yo_lM>IbMzPSiH31U zr1Rm;W8w9(_<8>4xTYr%i00Ko{Sjfy#;~c9&CWGRc|g=$56udn`1*MEoc-h!agcZkK3AIL-1-de!o0=TyBFY0_P*^nF3W`1zgHwzaY z-%_Ffg0@lU*!-*mck<~OT8|FblU(I_4$fm2gGyHL*= zM~08nAU8H;sjTJtZ^`#UD1AR;U!B*WpH3;o)p)2Lx`0`9c z))ZY(K5n$8#F;d+JGe`n1?X2!6=SrzKw)|_hSFRRRAFgkk|A!a#4kXwBWVF%RC<H)uuVNeTuraNLx*5B;r~DU`zv(bn2B~Ti zsR!?$g`cng;-$uC2G}%^S5c6Et|5FPK{U0IpX=$1&H7UK>2I|-w0(T%PD$A`pmKz~ zUH|*NDGrbk^2k^av>#agWd&?PW!^({pOG>CJT1err)r2>yGUhf3K_cbVc$T+8h0GlKr~4m8M`<9n6+N8?d(gatxZ z8f}ncW4Y&VhcE>$H=;Kc2(?EnS6Yn`WnT&V>|Dcc$hL z*yez|)ORe8EKT3YEyHP6I~Sz-ddXEsq0Y<|F3eikXhZu&089RAaZLP-g6Sm2ZAII_ zXHLL(2oUWAvRx6UZ<-vvJd6$;lQrok`bZHkj1lh6l?HvoufpIcHXsz?wN`$2;2!Xh zCK)xZ8f^qb%~&F5^2<6;DX&{~(Z=-`f6j6D`q-{;GzkwnDYQ8azvkUfY4A$|9Cg%X zqB~*hkWlapQsr+KKmw2^TVdKIxX({|?P5-&^!E%MOo%qy$O^gaPbwr$!(; zfTmLa))4eK!zwR^9{5OZ5s0(>*iMtChF{|@gb06NLM$?!()X` z5^Py~L45H3qSmnnmpTOyp33_-Sbd9uU^J=x{;kOdgpc?LEWsc+XzOM4)KCQ$m^##woUYqF?9USmfd)8*zKs+CY}Qo4 zs+>wlOpu5wQovO$2uz-!7a~8h%AKX1HYX-sGmnBi%hLV>nYPRg4Wq{)q@UupSJm#i zw-uQgZ@Zt@FD65Vc zhFp0Z8}?L^H0u?Xb+Mw%5S=8jSx`3LP}6c3(vFJRe#8LT#d;C#Rp8PWrNuWbyXU~Y zW(n|CC6t_W)E01A$@paQs6#ZP>-{$(aT<|$+V3d+!sjsmXsCzzGvaM_Mr;u_mm<|%|^9MKpmeoP?c0uKKHPWC;%*Z8T_$+jJ4+t%oT*o*y z|H@8!=+vso|CDvC^_?}}+{E#|t5;50k5?;LW=oJ-PsuO*Q;n(Sk*&K>A&4&PeTY{9 zHEbY^7v$aX9SgXveKV;+Oxr=-1=@=PuDvxijko?OoO7v|hQlKizPxl;x2PK+acyM@ z-0&z0Repr0U;@}h95JSE zy=>ink0zea*WfA5HrWS4(L4-up!!)&svWdy2D(~>o%e9S7%keiR7rr>?$uTzs2*<; z0Jl>ynhmtf*tNg;$yMj(!q@M!B+hDe<`6z&x*;)s9nB4z#>lB>Mtba?b4#Ear_BSE zM^umizt9H=<@k~NWyj@6f`y1boj~Li!Hi8Xo8<6#&6nXyt@1}60A_+l{CBfBM45`! z`|%}KciS3;)`i5L%CWhw!d=AGj4$b6$>^dE@tX+nj{Qt!ywKg=&izDa z*s$w8`UoA27ZQ-+i2u!Any4vE%d0`(`rVO0gD7M754{6R0;}(mZZFs_);5bC+CbNJ|4LMU@8jR%hRs zXQKzV;XDB`Q3}?Xyq*7W*;f8W@q}q_nNA9s;{f_?L6?_blp2M+(am#J^Bme?kx!!U zBOGcHuH64y1t7`2YyPF2e}vl-A_Hy}U`q{BXXM_~AkRJFBZ5z&N!QSi!F)?n4dNU9 zfivRb*BegdYm|R-VxW)L+mE9rX1yj-!U>?*@ z40xyWtJZ4)0{YM9NR}V^ij|vsM*^UiBkOlnC_17n3|Wfa)qKvd>h zK?a}7)L8?`j5hB!W{z@Ey*Suk2B_z?r6qNcC;;%7W@@E7oWlWH&Y%@Sv)F$x+BQL0g$ zmC-EJ!{<*Hz%ldroX2F-a!qKU*N0c^}+fWltV@WXPdIsSTLd3*6Ds`N@klre8FoGovnJ%687;=#8Ub#AT9+xf*kc z@7Webe)2Ux(*Fhap%0g03>Zb*qWw|7=)_%iGs&z>O=2KI-JB)}D?~(f;rR9SrxT^$ zNyI4c-pIa;fo3Lw|*R*e`!Fc3>Bj*fw-PIOE{rY6ECivC5ru6`7%S#BkV%2u{Yyuwj{H*dAV4m6 zsDfkFM5o=D^)er-{RqR%Znb4JM?8l`K7c2ePqbi z&$Aj?@&!fEv z&&axpkWGLvk-%l&Ra_wN=H-ke2PBB)_1^HR<{-hWXXXR`r#sJyi0m#&Or|2k{0Fc- zo)gLNhVgCd|CGc&k$%qa9_!=aRCN0)mK*Z%9Yr~>)dioRgsv({zj#DPmQ zKK+$jxkZ1+Afke}nA9}Dy6}({xgbsSv7^ezEBuOMFxzzE{zp*54hakkw(yGPJT>O( zkczrJbhA!Q;Ud>0<^g0TEmYka?hk#lKh~{e9a8ei=UQAC&>!ZgLin(Q!*=H`oyUkm?E^0>+p_TS9 zy>1x-kuS6?u^d8xkY9g~EsXy?>Qsh{g-eT>N=pK#V&V7dEE=0uRbH|gxoR|jvv(U- z-M%>3LE+4L?9f^purGc;h*ab&ueL3UO7%#Wr4@$!MY1XZwoaM$lW+3SBUfgdISCad z_WG?fK|Uw7B)ozFUYp=8A23i%atYIViw}gtixCg#8J}HkA7Xw*8#Pnglu0AIb$5^v zS33oAbfQYGe|;eaL#Pj#Bn?d2PcFeL%2?Bvw#Q;dx7M3OQ<^aS-a{)6TzKxQxLTo#QiUX^`C!e$LtF+ ziUh4$@t1bxCEF*Mtyci>X{Q{XkT<>GnW}G}^T?-& zd&c3X;^-)_)b!jp+VU5ls@4)6 z=L`>;k^cHMD9S-edK=G~k8SBA;qgDktL@X`a9H|Br1ypd^obnj>M!oXi=UcJe z3upDBl1zs&zyJ|dPBS>1mk`t9ZqZ_otPPJduC7n`8$K78l%*XSoGhHKbFaz__TcSmAh`NM z|7+dy4pbEug|kE)#jip`)qWw^SR%Fu;_O<SbebroNn0w8^5iCvvkhlrH$ z44XieHiTgFx4*~Axqx}5eioQYntvP@1mPiV^Xc^mn!oEvZ&(r@a224A$pPR3U68NH z15;hPI3@H6nMgzJcyAY59g#y>(4n&1MGs}X@HRsRl#U-kAx8TOkSkI&#;`r<21IRu z_SyIAP*Fzc&eKv86e2d?TU+ZihhUSF7e)nF-lK@sXs+W^NERcyxnol;iN2oi`@28r zNiF_X7OIbR`1=>|UF}a!Mv=*{PUZX`HKf$A+x6e#Tp&JMvO)BXiQ23w!wT(%sQ41^ zor*V(R6p$ovkuaZwuLayG1~r<1ngBUSO*6UpPGmm)_eC11(yyL1%<^oCd_|&8WyLY z4_irXl0G9b_5z0h9qqvDfWd!oEbp7@v!qs-k(*z!{vufSh{R|c`UBbL9kqK8CV`#j z_T0CdB9$%=EX;-lq##Um;L|q-@~F2pme}x+Hf?b9UZ4{mNYssZcWL}|J8)OslZip0 z0AxH?`klxr5wEY0cE$*b1Wv)q30@mDGer-vI%1XSYIU#d_iyQum*jv%v_5h zVzt@Q5YOgL`NF;AvruCZJKE%ZURxU(+(24R+l*uqVR! zQ(vqjDZ-nFqcz|lVqgxuT6(w4GTI@D-?g^n(LqJQa0|oy>YOu4%)d#-Muj})IgdP~ z{HFiC-~-ckdS2RH9TP%nmX+?SOYjAZacb%G!RQXOJn{CmT-o$!Yc+Q&r01Bht*>mTxy$I0iA?dU{H=b>$+f@(X{Fh zk_gw)|^GxioLe0ER5{lDWZnm$tS_ZxH?N4L64Y)lQ%b8b=k+q$T;bMM-wJ&EN4)7ZIvj2*c;e2u~ zb0@E6k!N2+VH-1+gV)wtb1~~wf)thLvYNy6KJjuG8}exT+VSeUGx}eXJQ5-BikF*) zJ6QCQr4jnF1LHI^E;rn_RG^eW!U+KswU>+Px5y`*2j#I%>?|}}3BeI>q=&-2jJi`| z+vMe$DX%l?x0DuW3v0rCydejJDqmc^&40!aDT5o8^xwiD>btTc!hDBSa$nJ+0 zgIh7=kmEl{I9g|?9Xav$2N1kXC~~GY$(8KxYCeDl-VLB0mo>0>&PQHV$WjMP0a9ra zLmCkobyHDI1(*ZA+A1*50Jk_VlwUWq2q?0A$^JP8eA61&L`_gs*A9Fw+Cnl14{gA; z+^+_!x2KXpIF9dIGS$!+*D)iMBoU4d3ue>zcl$NrM}T~}Nlzf>gf@q!E2v>%U5aQQ z3l)uE%G4e9n=7{3X^Hge)kn?~N(@xU0vT|yCnt7^+By?P__OK<)>$&bW{{Erlhp8| zL!;`qa@S}3XtaA(f#5g*P-NZy*_1b7i3lao7M@;JJBg0=Y|DpjTj#xQC&x}o$VS`h zej)>tBXS)afefon2sn9Aw60WC3L(a;s6@_8s;Rfok*Y1N7nt7zijIM2YWyMRXr@Pv zB>Q4;%$$R<6IZN*#j!GQK^OOUXZDA_v)z=|a72hr3(2g!{+_Od5{ZCv64pFDaY>NrDsf2lz=K$xLD~xj~c~V{dDScteoT ziI0bza(g13E@d71&vGyPd2j$0q_UI(QF*MinFKK;;FrW4htM|*~1;mq;^`1*F{dp1cs!3ECXqgk>O+$P-8;^i;DCdETWEmo{{Pk$8< ze~+n#&Uw8=N3aoFt1^iTUL z5J6O_mt>&zY#DpKxDW3BiZ6jxLE;wPR$X%=8a-E{s5sosN#fcEDv8YTemSVYRXt1U z6~Gyn)WAkVpqynH_084zs^hY!EXXbuN55gz;Sd<{d=QN-fwUC6{L~IryN5lw@5sYKq7e}3 zl|>X9xOMUDpM!!GTdN!M1S;ib%wS?f77)a2@US^tsC@FOCmZePYB*f+uxQijH(jgY zm^Q9d9Z!;@1?E;|Zs6>c25bBFtGT7QsvLo3Bfxg)E5hhQ=fNN_di|Mg8)o z0@65|AR%-Ik1j74F%0~eW#wLVKeM5=@SP%Hg$DZx*DvYUSWZb9xJGj`Z@VDx2$M`L z)kxeQ;RVpP&1*a3=gYY3Rahzt?5^uojD~%1k*L{+gmt2o`AL`02I+gC)Kdn@RAP0{ z0EITG!nwfoByzXue|`;C^PF zDmPLUnc6hf)#t6jmK3h5lQv0<40UGUi4>iOG@O!?FSr%Nv5G{_ zmE{ZqsM+<$@0h7A8s;&4>ZK|fC?z?%`qO(oqn>xjD|DUKKrT}l;wZ{9o4wv(l*~F^ zt%5t}(1Q8OM|#NzYRgULD(?XqsYcJRv`i8WPc`?Snb@@a>tS=8`?3+|0k$JwIfOMy zh|Y2xoGbl|kRJOld{O0YOq?5ilnbppUA&Yxyah@zbR?e>7{5NmAc_68@JORyr@=io z_KY)({5s9o!@40@gW6`BelqQS<=;G^9h^=j6L>!E{*sz%<*ueE7HRcfstC?I>Sg12 zv`JQ36t46QqcV_x%vyXlUS&CtR9N5^0&`GtN@OsE_BrxZ&}~`Ff`$9>oD)Ms|x4e_UvOFvyw2QxxJrt9b(e zefC@FM*A?zZ?1!{j_H}*YP-6S>rA~vEg)3UZC})iK|5J>@I;!Eq>gf9p>h0+1Tt*s z6WQzW+W&FGq+}Sm_<@jaz@_k#sm#d7wQsN}7(!~DV13t&3%<;BxI0d*wMMVpo07c&R_e>c^`$Nf0#tj}AIscCicaA07;pNiGz_n+TRORnmIZI-1t8 z{L@ht3mq)ZAm22;Qpr?zuQ^}DnilF}_p@f9SnK_WFz!Ep?Y_OF@_QPByeC`{=Gx1b z!Q_R}>#aY6#CF3lZ-zbpsK-QVk&PmlJ>^VxEPnm1cXaCUwa^za*L>Lra}R^a8;e54 zJF~@9z>lAq_w(261Phv6^nqec1Y;Mp0e@hoLQ)JdWZ9Uac+~^3u=jtX*F@`i3_Wuw zt`s4gs62+&inQGa7@G*l-3UMmA7^eP*{@WJz$TD6gDif7HJR8_>&-rChP&}lugx&( zcY(WE)l6svFUins49m-l-z^X{Lrf0cLtTzfM^UyZeDNfs3sg2-*<<2Dn9?0T$!mJK z)EW=^*Tv9D2N_d^xijx%6QfnVisZuW1~$((5pZ0?!q%4Kzx?LmS!+nfL9huGbyb*U zKnj+=TB;IqK9YtdB{99sj){(>SzZ^?&r7y|5#pJ};Hifbz;($?-i`LW8tscuG@GL) zvN)sG{RO)I9dDV{U&bqnTZTlokc z8utieQsOpalv-+JrM|Agsj4^C)>Qt1+l#r^?O6ZuAjqxIc44<8L5h+e~}#t1Lq11P;mwZGTg2ggK%D!uc8^b&og zKj;gIQi5K>7+$dmBh^NPkZJ=1UA{)s1uR`O<}Hem)0e3(sf*5)k_VIRK?dD*yCfq@ zaGyQ-X3eZ!FLdduIo_!EzT|5oESaBhAF?0meD#Uykei0|`YEKrD1A&_cxOa`?!MN% z))+??nka|K)mkZPV-hcly$EdaOvo}t1+!x=b?|PbNAL0q0PWUuzdk+Ue<9+g14Bbj z+z2092E+jw<5Xds!)Hz4Lnr*hXf`Z9(R;1f<@adwp}B^Iw|p))UY}_}7fUo!Du#@P z#iUY$2da&I_&P-fQwNZM*v?LL9)Y{Rn&Dg{UYnsm+5C>Rm-S#Vfm46#Sn=Efm_*BO zHUu{Kw5iY-8T;OQ3h)~0OU5V&Zj{#T0u>ngTa)rWOmm07@;jOc-swR-+EMrJ>Q^#7 za%oYqk#&K1H%zOa#e8<=;jJ@X>M(-y%;!g>F^wlE8SI&O(wA9b^AW62p?o?L5X=bQ zB?xH|(GOmKxk)oIkJy3T?7X;4$OiN&HW$DdwrY<@I~tvsIBK-hCJqI$GG^q}fG669OpD8sDfmI~%*!hg{gQbqJOv|2YkQUSbJL>6ZgdOkK@I2BcEXtk%TR2j~o9pO^3=1E^rq_mYu!HvJki_#1RQ zuiUScuN^lWU`%%}r}2mFv6nxFF|r?O>V5dD|8kg(cB=Q^v0j;|=zaXsZ`3Zee5-eL zBR#Rq6UOdg4740m+h%O(4K1F;i&a!7tjYkj3M?Wakg(hGCRzl-_({Pb?%P%J!XJ}( zar!|K1l2EEPFqJ%5mr4$+g`=h6R;FH>payHoNlu@=DTS@p73?t3Ib^AiXht#wcn7o zF@x_ED&%FfMI2_&@pgEjD7MxS$?hFJI4sr#wQX=<0={4cRkF<*qI+yC2sCNpi&2{& zxDT!FJ9nX^qG)FR!qv=ppVNXkG=kGN6tbqH`fVEmbR+VP^}aefucC4kdLX1!RARE= z{$q_x;_X3;z#>E?n92`1fx=9c`=3_F(P09yHdj)hl!$wwkWQA_*|Vq+V}^iVZ=IFo#{5}kztkNV{p$Ls?Xo@|MzyqSR|D6HShPqfRe~ou#xF&+ z_>hHXy=X8)nkjGpvTds@r1hTIX++U{-Gz?@7k_&L6wT*0z^3~ zs9WznT+=OL@wjP+f_7nin}nj%=u7bLP>G^4+Mr8xtk<@CO`d1IZMZDU6C8Wn@$_z0y|;e{rflA$sGdaSWd2u*hg zctxbD2fP$bKYaVza5IFwzs>S}g6XSue?|OD-4{lnppB~Gf*VkBuGNZ-AJ$39m*_u# z@cRAgMs>I-P*Q)lIxUA?4(rEObxQfW76 z8&vdKVaivP?Tg%9L^JsViaOrFHwa>8mdP~K=|r0odBcLtai{A&hJ4(4p6o`76tv&* z-1>pn=5bC6<4<%*XoBxVWDr%s&7g><9g#m+@$AJix@SnCLuFw5H1O=m=pU0N z{IJCwY@HW5Ml*Cvp)XPAIbV~lF2Dk3nY9!nvq$2PVzLPdTk1;x5!6&w9%bvh66-=? zKs~<^&aPD@;X&u|3Px4VHB?xjkAPnvm9Sd(l)~Ms+54Oayd+~BqVf~m^LwYnjt7iQ z1`Ft}&{M8DaZCO>=YG}7MYzJN@3B#_9@%-4N_?`CHD|^*yUiVK;O~}cM41l7>o>H# z0O?WP>z|%HSmSnkqvE)Lb2r`Vw{c~6=$(*I(IuXW$b8Ih#vwVH2^Cos;HZ)1R%TAo zF-%gsK}5@0L?#DW@VbU8a_QpZn?Uw2Vx^nEy@?G>d{2V5kwv`^DmnVgZ(HV$=OJjiD>k=jY z0B6lq2z90*bR%c;S|pldxNsB#GswOujHsBYy3DoVQ|m@VTtH&@Lkg;|OQX~-(nz-Q zkMqPFaio#+B73j^4iY4!p_55!8j#STkBRu`2C!8HVikwLjy!^uIz5U$AQS6?-B@sQ zX@EwTeefCBgH<$VbjJyub#e(@xHI=5cN~fN|2IJNrpwj$pI&$2X88 zcO)P&d%Omp@=mBF9i`e+Q+||!JvxsCf$KKD>kBo(e_*URL_WJdgGlxx$~AJm2PfVu z=~8`R_St~k^hG$!vskv!{$R}#z|Fv(`Z8nEf91$qq{4AqWh%$q`>o`3o(qKkYc)`68Ti5u3GXI zep9J|zB_CNH0Ah~fLoLF3$R|BJ1GuFu*^GdqlE!OXQw<#_F9YzVYOr@2qN<@*IDV( zy5OB#+Vh;=z4v%qX7t4O*PJH#=5tc$E>uNpiDa&D;xQNRDN(kjn1Aw5X`odQ0S69e zcrB>=;t$)LKBqQ0(ddyirVX9(un|LcaD$?@jP5?6Qzq{&>dWrU3PmD`+g*ejW~6Xm z0@*YRlMHYwLMWhv5q?In$V#H7buOpCCNXt zScy3uTm2_J4ffDe@r+1NB6B#vsEJC(IUnJC{Op3CBxnSRI;uEa@j@JhQNn(3M#{LD ze1RDjs#Ip-7W1l&v)3$`?qdqcKfzVk+5Key$ZUfKA8H98ce;F_@x&}UT07$<=4#_L zb8HJq#GozJ|HrBCvF>fEW8cRZ;Y0?dL=YVRvFY2GG&K?-;t+qFN~)@Rgf})`I=2wu zCP<~TuK#c7PSf`x>)3(BAB73a0y0Kr2BA`8Yq)F&-j8Kz>0mN5QjFyjAo9_Y&v;lZ z$yFq{X$D8tMCztM)N~YVz?3fOF<*Yy1vzE9$mNSih{ zeY+3IZYFO;e%jQvd|EtWP=7H4^{lpd5t+6lKEI^Ygqpaq;Dh{NV~wcW}}Hx!JIeRQyS#Bag?cCA3Z9c)}s=OauA+3Tk?%3rO+k_WR(9CdK87Tf%kp|6g#&2&SsyM)xujtv=T$?qGH_SP= z;@7rH>3`-Cn&gcg%@%FXI2#_H?@rEYci0(g00I8=-65(q%F* zJ~oqUo%J(U@^cPGK~9+OH~qm{wuR>N#8G#?T|C*WC7QZe;JGg(e%LS;lbvA4q@($4 zrNy;UNhhv`nE}h3R17@`H7HTWqla1Pya#!N@b0Pdph^Bj&g-j_BL_sejVBEq0x!Uq z%R)*0f?~DGxBM}@1Do`QbntFd^=^w%yg{GOMPn@jOa&M~tfI0iT}(~@r$`K6=83+F zHq`q^Hhvl_O%XtrysZLp&6EXUm6{Qjh8{n6zOsF=pl9pSy~tr~B}ZtwC4*0eVydhm>^})`Ty(iMwO?G_^B)w4X}i(*MhA?jShSI-U!^-bJQxE zcLcBBW;RqoHZaEhgj+8y+0Mk~%)`Fj_OU082*akI41Tq}Ygtc5Vgp@v<2Q09_XgnV z{as;0?AAqi+BQv_`@uyrx%1^=Eo$=qYUjc2p~*OR|9MuyTAKb${uvh?n;^cc6PK)P zw$hJAe-xmDm%eGC%n?#I%%Zo?3AymH--I6HP3X9J3(9+6(LN+g*J{f%$#|Rl&(~7# zz_qI-9L0O%wnvMcq9eEaTP;ZTrQ%Vx>2~&cr=uCP1$CShChik}!q1$o#T zI`n=_FS`Gq{x@K3kEQJfK!|cNN~C0_&hlRWf@+DSx*>n?w(;yqr9s6eU&{$i*J4&d zBej&3_KlI_nUn@ z`l^l;1rN;j)&?cu=W}~U>=|p!bwzxQZ%SpG4+(DD!M4_(v7h(9VgS^F4qsvNK{w@f z0C+%$zt_PTnb4z$HwPiIbB1x-C|#3U0JK@B1%EXGdL6iC5P-Pem@yB&Dn%K#x@gE$ z`ZGoLS_a1o|xEw7k8 zcV;WbkE=2ko4AO8VY#y#ADrFtGYjjKkOb#8uvrxI-!HEl}K(S4WKH{r`C0C#L*Q9JE z$VzqdE;P6K9-^3_;NQim@)6ziV#D$xF)#a-i;zR3F$HJFyA>D8`v=qB*RLifmFE1k z5&+`}6PV|~yAYly?2_4~TlHXYgu1ZDKWD-4chcdPT3;0r-qlgRTPIkcj%^6IA){;3 zba{mEa{3mbZsTV|a|7NOqJo2k6}@}uA#DR@H;Q~bhTijB(m@>SHvck-RUKVfUocF~ z@7z8BqD6E{V=fx@yHfP8{9i0cj4z#D-Czo`;y-t;SS-0lntIHv0t$3rgT61{?b5sb z^~)E@8nV1cS%0jhLWON8SzPvD4B2aec~|y@5t)Nrg~@Z9;So$gI^UqtUb_2IK664HEUj30RmBM)C#!5>v|O|ekDu_W^e3FO zgGSn)7ciOz#|i?5&(16$00WLc2x$eNYhN|fgm_4AM=P#p){GStc5!GM948#tJ|*&u zu-WN$Xn$VivX&>SPe;^=5?+R}Gfh4)25W5|KQ-PmY(iNJ&G|XHuG;;A&_SI2RU-aL znRV9}N3_Lz+0G1OX7&i9;Y1uLlz)KAqxuDA{2tT^EA}NP62l<)x77;cm}$UdRo>tt zma=6=>78lT*sJzOA^yHzD?}Wz+Sbuh2(49h9aotv$*aF{U-e78qZefSO}G?x89Q!q zR-!Eaj4;Uk%8F{;7_nw>d>>>BY@)thm^x6>XdG({ZF%j%--LvxX$eZ>h77jB+cKNn zfD$r2?N>4k7r^Umo4Ti=F5lcXe5tX*jI`w5E1eWXbrtkz>pG7$>G_yjT?u@C5Yh`k z)}ODoC&1x5Y|wPs4v$31a#D3jEdyXdd(4qDR|htL8Koc&t#Y)_1DM4noApV{TS|i8 zn0!@FV4D6leSrKBpI2O{jBdBtD~yS|b9(~S|NVujXS+GL?nU%QC+?`kA*wa3U*#X| zd8pssG(JdsWdqf_=MQN2=KE9r6i>lXaGjVi1QBx=2s(9_HNc%rs@eG;i1iH;+Z#4V zvSrOcaf8!8;KsoL)Qb29LI$>_MW+E1g#06@rb&9nzP%{|-3%{au%l;j1sgXrxSP_Gz6_+wrAqhZW1fR+x+x!%@u-)v~*TvHs` zb)OS~oq>tPxI_iuSni?oHJF?8Sul-N`!tuB-5nWjeO}OeTQ?JjxB>SJq*Pi!Y&MZm z8J1osf#c?}{a#wnw{1;P)y%3@k`xGJr^R_}TJ4;7lVWnTXY>0ET6|EPx$oBnNZY)e z?Sdh&Zt)dY*OKqYU?wE&ye<4C!)(Q{qHfFMr%)A9!hnQ1OcI8pg#klRd3aCKjIYQh zT@xFjYanxILuaQtXe>Q&;j`17G=M=om$t{(cN|blu8J=Gx*ZEj*y?km0b?z6Rc3|r z<1?H(a4jlG5bCFyeoR{yIFs$8J(#nB%#l2k&yQ}3--9HL*0tM2@TRr%(Y9@RnlY9L z6~E@P{-pkD^p8q3{> zGtmQIY{WNHCzE5uTj~j+lrr@r*LIMGY^tC~);LEmuFBDQ#0-K*CvR1lKeLi~tn*dR z4}}r$IFJ)?fxU)xxFd!-z2k5rBZD+_jA7RTR09FkDrE6=<{XPo^%5lLFtGy`>0baK z#NSLiPqGMwp?Q!+xquf0JD%GK!RO@*T2-Dglg`nosxvtl^$93$cDGmw)edUV~E zfw97Xh!eunH7C9H_3Ijx65$*Bec2}F9<#Ctzl-E$?8Z&csSz3gb7)PE;+dnk%=>s% zra{A&M3m?H8i|>;{hEPmjqgH!yI_eaXU^N)XNa}@T#A7ZEiFXC8C(-4)L_ipFih`g z;Q0|2;SFqvU^E#g$5jRX&cs%9OzBdP+-gc87LWSZ);QbzR+i^{UCX_e4rgxH1x@{ve*9Ti^{mBVon1MyRkYdj&ai+E;Ts==}^^V*2o+>p- zu8{C_6um`xG3O0KgXs^?>@TPU256x!v=U>525dhp`|Lu`sXyDNP@%Kar%Yzx)A<>$ zBARBUhyiYH=n`pbHOl!&g0;T$)4fGKY?M=;tkRUconcH2|Wf2^>?q1Rvhu8DPUZ<;0n~ngGGhf(_uVOKF@M5wuNLa~a zS--|`2;rN1Hf>Amhe7U9&dOcg(X`HkW!K08B2Vo^LPSq8z&7T7rR(y8NG$`2(t$Bd z{kxQcC`R-J9sz+mMV@qb;6aB`MlWfD(wUW?x%49&cJNb9f%1JkJfl2=V1_l?`r}eR z?;Nvk2=xt^n5g^jemTovgUO}g#wB`gn(+Ev0LY)uvLqkf7Z&eP-kY%6+j1eT?wiX{9)RV}5I!WHDc(dU{7hvO|4cHug%-E$(BqVE0m~^f zDnbWrU7t?Kv5ek4QJAA_^l<4+j8&grD^ydc5yhdFU!=qfNOKd_DPafGo;56px72#t-rn)@`UpRpJ@Gem_S z+3-r1O%@^oVqADHhPRt@9XYkF4>=F8j4FlwxKixg!(^>LJ4JvXiSzJ@2pwb9`)kd_)@YTRE7Y&}BI4v+vDE)lEp)Kc(bh2?y zV8P{{^l4KTaXu2^8H4+9UxZd-U%e#uVEcxWrNLaWUynNx0zGKd`b`ZAC?rPIn{ORk zsWcY>f}=KX5K1aFM%8&x?EqH?Vdg@-BD!(bx9 z(ei;kT7lmRalkoxYQYlZY2u@!FZou?)IVL&(@9Sf7FVfDn$Aqt=>ih2UwqCP(&?CH z#|FWTnHYTt7Hr99aE+Z5mpDtKR7y#gN~_!qnk%~cDdvu{bqX6j zI&ZpaV%DGZLLjsaj(@S{S?uM=9G1Rn)jEo!g#5!CCZp1+f4pFTYY#2ZItZL5hA1J> zSB~0dENZRus}H~yP0vrIstlWzaVE}#zK@JZ!|QGo4nWS%j6sF7fa4f=!dA4mI<|O< z|HLz45&pu$G%7!?NSLZ*tN7|C$ws7cJLjo}nOBGhYn*Qw_?q@nSDp)z7$HU(FBGrR z-|xu05TDj|=1+wdy3iA09eZviw+t9K9;t;7LQm-x#lOt={oYnjQxxn))UFiyrSs>( z)B>@tM_IP)Q8&J4Nv)q42`~!rO}G~Se`8&N*-RgV)w}~c@gfO0bRtN^yl>$)yQc|~ z?!#D3BQFW`)c!z2{<#perkI%R)QU_22nzE5d4Mv=M-~^&*pM9B5KZ>_P_-jaOu<%8 zHG4i>bB%17*66}mXsTFR0k7=b>G{#4znjkM&ZiC2G^d)-ba>DDXd4_Zc*5l{hT^QMM5q&PS;MGvd}fPeRCwnjPsnwN9ZckAs9&FcC)2`$6Iul zEm-5r5W+a&Q$(EaYEOC4zqvYJ_NFm*^rs`ta<3M=P?hzqkYDFR&fI+(Fw`nQdZ^jL z2LI!Mx~bv`x?!F`N}*q7ww}@NoAZY2end%70-pfy5e)IKri*~dag!0PwY#$YEsj`4 z&JVGkCg!;S2=xK;fl3xX2}>ItbDtblQ|4PyyTzd(2%#qZ1tXKj)H#$w)RN-z3UwHu zj5;j=LKm(N1pKi6ZW^~j=tjD;N5sm78ms8-ONt#)=S!wgR(Z$JM`O76K;vL*|LGg% z9p$@Qh`TtF*n#1ug7QW6@@Hv<6@2b9mJT?- z{raNWw20wwWq2d`nW3C|x`yX^Fif~Hq%BIBAl~D=cSbtMB)m6lVIe_N(Zu^v zdDp~+s1aTzqB+}Y;dz;MCNDl zkGof(_pt6dq@(H|M>b6v%RN}7!Kt4^3 z1M$y(BGqZn|Ter#5nTcG&Oek2LDZBn*h3(EKbhLd@OGWp>~`*FFRbF!H%LlS_8LK?6;dgqNE& zQab++WzF$9RglIs2?!p)u^2Uz5HIuWEUD1_z|$=@W#KxPCpzAI zU-UsFG{V8&h&JxzX| z<%Ghd+$}XI3L8BzH%Dz~)i%{Qb=44USxD+|Our!wA&TN87rO_c7Bk9P2zWY=ip0ay z{uIaH1xpWjnX7?i9hNs*%j^= zt8p-Z_r*hWAB6EHtwArf46v@%b&R@g7`+`zW<9NGSYhzTg*J#on@d>PNwx`zY0IGwi&F-^8e!eR=hSyR)d@Nx97eFzwbeVp-nw&J3_ zfQH=Os#;%AHHN>wfvKMH)1S=Q-~v_9C%$I-AQrZu&J7@k{aBPdC5?szddT+}UpBpD zqJUb9uvu67f{@C9)R8)2s%Dei(AL;Z#VHd$?N1ubk12xnS5{Hi(DXGUTdvHiORiKE zpI%V;h%7+;Axc@HUWEv`(m=G=v6PD6ksE&s8lOQV+8epS2HJ9Y;8S1Wu@C!?0?qRA zXg+|Aj!D9wq2JF6(BEc~T1YiBb+c#0_?1dUL$>JD9wPY2aueR?>sMf{DDQB%b>oe) zxx`xnH@2OBCe%c1Yp(62SA(ET+`MJk7Wq{hdq~EW(sW>7EjH4`f`BsmH3J)?#DVb{ ztsyd3c!a%jdE32z0hrx7*GgQj>4QNAt`wT$r!_=!H?#;pKbZw}#BJ8=ir5{f1MoqN z#DbRH@>1tVf-N7IhWf-v)$B`^82lwy&DQN0jJ1?@=iUqi^$V1`;Uf*w>l=4x~V}c&~pv*ws0i6&{U-cYtCVnmASWUD2?`6 zZu{&A>FefD>$FGdJf3jBj*Bun;{C)1;yJd|m&jQAcZJePGWNGr5*{E)@{9ml<2wFH zszQU0a83{ST}6b^^wtt3HM32PuEkJ*&6jATx7mbDt+}VJOdC>l;K9Ve8UBF2&H2B) z86qw;XqV--^ZW~1v$N_y^Of7tq(#HzHl-`ANIZO!Ix!<;*~K(^I}kq{X_YqZgg%2c zM9>Ym6zLQodFpre-uI{#p`^*h?0HygV}k~8;bv!E_t3d-p*BT(;c^US`3IDs(bd%5 zc4fuvr*cr}yKq;_?QnKxBGF7PnBY0)EL|(w@ucrRTfAn4+%0(Kwt$=+@2J8Gk%@D& z>ejPyvX3a7l9?Y%{DxyxpI1XOijcC4bTV_TmSJQ&@-#nSKS2_?32 zav4Kfg3+adUI(`t8H7fubntwXiBJCsd)EW!)s@&azxR3PU_HDEvK%HDszaYVbDcdn z_A*b8gWY8LA!i*?fI*@m?2#$eUsGivEbEekGQx1AhNVlW-x@t!Jdb&tj;&hkyfz}i z)=V?wFwe=)l-O2_`v`o(;!N?l+Z*n6$oWsP?|wW>V2@4r&I=gJyh2dH9ok`8QxKGV}%*0e^4SDiR(x7eC=Y` z+hDMV0AQBRQ)Tx_L@*~qH+H~&&ZsE}aqXntwkLp3V@_8PKp%Z;5h3~onTEJ6unA?P z)A$s$&!La+xbJ|$1Sk*1Eg8F`#(yK8LkTBaj*=T?3cCuY!0o4`4*u4h+h_kK@=7=j zM3Jo7=26>R(!}?^eDwVIxA0t=Cfp@F0XqPw#HHm;>+o=)QubTUtg)yetj~7}GC31% zb$^Ho>I=>IiP5HpacOrL!)8{Bp~Uvc{C7#tS($yuu`e)i8&B00S4bgg3Mr1v0wQzu zc9`l}wj0`v(~hEM+FTMgDW0;uHypQfI>E@#wVRz5T35k{bvgi^S z?j>Xh5QCL7#bggCVE{E zXNX4w>m|6WR@bd%N1!yo-tWwgOR@BJt0V%8E`=?Yp5<&>bin%!)%R>_jl3W!h!u&- zf?kOpn87inILIB|XzINCN|89CuXp*Sx#gZub030Z`HR6aJEJw7tHSRk8 z&T}lPhyzFz^Y?-XaCd)AI((b%x8B(v%kv$;Qk=Ub9Y_vcA}6Mz5Zdd%dBe* zBWm|ajcmA*pzaVXHoUP^{|Xjsa8{xVt8d;2?)Qd%x>SWk^4gh7oby~)OI-%}B-P)l z-V5qTuZqS;iB>-h-%XpI0iSBJkeu#uf`^NVK{#{26A?Cq5{G6}kl@~FR##4lp7e;S zF4VwF(I!gtE~WA3J7}P0O6Z}VfhbAH>$v5B2a+No-*O(0?3W8g@oR1MSXyBspuxtn%gw%1eN zIz~#c<_l4|FgjG`H`0U5J1J<$>L#eE_WkcZaZ7M z1pC;Bkq^Mi6?W*65IMyosjT9U&G+`+24stnZ`u}4VsRolCZH1Zu!M$OmpwdS5Wmsf z??|=7uRRNNFVj>3ehZfh%T3Vu`1J%w>8v?UA-0q<~@@Cn&)uG4R)KC^t31(LUQits!c8`cXtFz;n!n{#04T5N5s`t@jo`LV251}=w#!Qv1b)O<%sp`mwI z4K)(8jTF#CtUgzMCbi!btQph9HMylThJ(R_#ZsL!#`^kl^Ytv4Y(p8XSlBN(hKXK1 z=8rf%xrynf+oLAgeE82%w?*dzeB6}Mcvotu;{V4JDb#(j^|8DD?yDmYjgPUBjjAZf ztz3G6*opsQV^wO#R>ocCGvp}5i`6c-r0&7-GY6DZDY8#D3thIOrQ=w+!t4+p#;5y) z;_HlK5~SoC#5qt^TT(T}$U0%s`bGP6i&DThrTd?pRAB#9gKI?TATf|_RV)4x@hE<*B_*yc^@28O0nNI;>})BaTf!Pli1YCCKyjzNzJy4w|TN4rhCuZ&d$ zQnD&!$F)(SEh#YEwKFv*QF$FQx?L-}QOmM!KVr}zi5Dy@4@;TbdfYzL=;)^f?ir>& z2mikK(4KprwFe7Bz%l6Gy5ALdX^hrbrLn!t5^)kP7N~YzC1*nbRwLrblRa6=ggTG_ zCHXK@DwlkYONrEyY+)N|Y?{N2P!E4iu%~LgX|zY0{>`UavrVV&_t4;2>{k8xCSwMC zoZ%g?0?!9f1jxVOF@G<5<1d+f0!coYN6|cK3cUyzq`s&TUiAbYv+*=22TYR_WJSF@ zq}bJ1f3qW|ZLH{^*4(KubC}2K!_ciRX~9UUO|_#eOg$?DJt!@(>TqQN5x;4&#KfC| zFe}R46dOxU!G;;)w{<>OEvGZ6@PTK-w<~FXUNVrsEr7hqV~A-Ngt|GhbYrVewY>G3 z-%T6{&988ea2PsqgkHuT>M$+dDC#7W!_4h}+_vPNe!W|#WSZdhJtd`OKL4liKR7S> zv}s@7Yi^4Nql5f60%-8HY*IW`QKja1@wMk(F(wKvn^LIWC#de*-EEjJ)dNiyZx7C# z?a9@w*v*uHFw2zdBoxyNv!n6}#^=F6wjf!MdFO)t%Ulf$o%~Lx5P$4kxE{-4| zGM2N_4|JC02&tS=aid*uq{-=-%d(Pd(T28pe|WS3p|Pc6P{NFc(YDaz>j9*3Tm49B z<|9s^LXu&DR7P1t;_pDVjwd#J3Yaix_pcFD7pJmoVwhTuJgM2Mms0UEQqH=>NmaC3 zn*gc5bl2d>YrXkv4(tqD+QhW>gh#`!y!>w8gMHW)JF6q+*Pxfj*4X_O3I|fQ0uiYn zA(@|bN|Kq~KBsKi7bZrZTiE@Ym;rW1XG01u(Mx2 z=(P?o1UDa52UOH$2!>za`m7+AId*W^*Xp)N5KMIZwo0tQp3**+A6E=z(ABH3KL zW^L5#(Z@i98H*?uSVwFRQ~R@)mqsFr*J^P{uhUsf3K|ypsFkg~9EIZ<4-&=<4Fz~l z3?h?7f*@k49|m3VoOfpbYc^HvOUrG0UbB)*X_6e}QKmrPrKm3LF31E6!wFT1)5Y&R z!Ik0NlFI_A#-0z$vBN{>-Qf)>!w+vAWpr;ieU@c2W_J`b?c*e7$%Nq~7rZF*ClBz{ zE=XuC;<7#V-NQZW3mP~~t?o92PgO{mL_rj6I=b305qK>t=ErY7{FAHMp8LFu-d@ND zJA9DOeLZ$-hkqe6ljndekVc%h3iC8XN1^5NiW-QRIO z19pIc&zY&=*k{leDE#G0%1Y8QUG|eV&(FD~?zg6EL!ChqGdRV4rI<5CNf(BH|1_jc zQ@US&j|DqL`J1}uy06&J&^=n~v9A4*+5&-+X~1@9I!ZCY!Am=gWQV-L`peXi%(-;F z30Hu`=!f)#)|EUt|16SXb^w(hOb_B}pym^#PlI}5%DEZA@bpKF-tuxASGG|xy5exs zV;S(9JOWwjU`>-ob&H?G#eKl@AdzjfRqSAkm)a^8McOye z^iUwTfjA)sLqih;@MpYL>~OVUhZs4Z?KqYHjnmiqWbe!HiQNv3O?5-d7SRI2mpg#) z>f%NC*c23CMLnuf%BD@PF51BsVpL9T9dEIAKbfchm05N8ow=VAA8zVY#rS*SSnp79 z8)th_@>sw<_u^^?_M0)Dy5=wz#OorgW5!EuY7xE^G@m`Ptz`_o>cLfrjq(xS8KyRm zt)axz=@(7HtR&riWaU-lMu({}#c( z6WY;<5LM@fe@y?t?~OYqek-G0`!ZRt#yy3b*&QgvgYS`x#P=$=6L<%&r&QgiOCH_) z<21`Fmz3Q3v+1}&rG)LLv?ru#rLp}MGOkl+e!WZo#&(x{EvCtWx!s1;w@t--K;|I? zAcHNcRA^j~=qj3-ZqkiOqH}a!W|yu#rNysDwp?ZPw^b*q9r!S%ggRzeYj^P&vG38F zG>I@`KFTWB+8LId`8f5fK1K#Xje8RwzWNu!@0vb?RuutuqFYR%tGI);Rq-S`C!UlMPAEEX6Vr5nK@hY`a(|5zvc@{#ifA0Ui=m|Dt* z=UvrhQeo4ML1_oElNK<|dKNOyl#$e4QaL_Ujdk+*vPYC)xZane5a6m*I*$}#>86yI zr{G&!JuIt^L?gn4!rs8vZ1}y83>%P&E@By>>}&>gIZS}12M-Ptg!fN8?|dZf9dqX) z4)8K+J>cb+28lMPM+Q2@S?#90eA8srt|CMbYn9bF>c|2pP%eyt`>Ql7OFESxXauEn zYK0XrDf1`)r4*OEn-&tGNLA25xhC#r0enAj(D74$vdkZ`4ue|59 zLw@@i}Y^H%$sb3ATfHS0V$y{$6FxaGmnNFDa1ndafy}fs2Hyz2 z*>l0+BUYO6H5Ah1&J3CwI~efO0269XK2C@Bj4`uVIyAfds?SFJy$ywLBC zQc0N!!ux-NPT41CGYGYUD5zQTB?STf3t9M*2Cy5?{}At}AF%;ZHMr(E3=j!isS!<2|$g2Oa0d0RB8iVW4rOI8-ai zUYw*XzXM+wZdb47sYB2|5agv}8pi-UG0_@t$Etr(*);3N7jha{9WK3&x>g1NQTTcf z&}?GZB`FRh^V)PAXklz-un_K5Gi6$k z+prRsF52%~fSWD5M9MbP%hQQZh`3XSacGQbq}D9z>ma*VO|^@~%T2TIk88?SsR}RU z;BSl1gZb6;p1ilFpMlLpu?RkGjuosX@C|+_cY~{LrS|a1xVeyvjl6Lo`R%#UYG-q8 zm>LQ|uwfNv3Sb#IPg(t*gd}-$j*8-5K=%ph*APV%W(yqt*RGK2tRzwx%k_lv-~cdm z%+FtDKu)vZ5iwJ~LFF&xqA(@}~%NRxKKwDACI(5<+@i!s7Yj0Rm z7<%eB{zRysa%p9CT)qXgeSQc3)nvY@>B=xw4|NOcPV?rxb@$nKRasW(;*0e#Jj4{C zPx0n$d6wZCG8R_%CkImGTxC2I!gAjOFsoRtFjO7U8R@eUMko&%UfpPmG91vo_t|}R z&}gnpWadzZYk&5VmKM%a{Gmd?J6LuNzsBK@IOGa>>JCrT3(J4L##+tYITVQ{*90?i z`&kDathCl-nq9OzFzNlKNG4g*`Dap z#W|7C^}O^y@lZ&ywFp{l{M4<|g4>p0J?VCjh$c_yq_I2lu%xs3T2jOYE77y^8#TxU z^EScy0T`WI^Jmq!#e57iLi-*~;SjM)#9UB~i2_W*rhM=e+~}XQ6l*ePwq(P0*Fx=` zw~b0;CsYdn0zm!L0ZxeXr&mYXS=0FWDYbSYHw&z**zU71&%SlmF z(+@R^!wzAHKOG(W>Ny0#QSm-MmU;_`a9*uK+oJi(;<#s=f}dksV+4&^2FR&jT< zi!hp~JO8I~PXDRRIfnlyT40=;m`$dSrVLwfP;32=cy`xjT_*U%N9z)?i$1Kv^acW%zqU% zX^)#x^fy|nghap54pB;*f0u5v?P`FdM3P|wG6ejX+rO{% zS9L?4*sAYg^Hcq$f zJ0ok&6P(GK0ZZy4tJI}qQ4qu<$;Em2fOn9-T=dA!!)268QeiwiZI zzbQ7{#vf(npwOiEXNi<{^9_e4oX|1wUqMsyJ=~OkwORChV>HM8^P~YT!2Y0buo|Hj_I^t~ig5*AfIn2AVc6m(VW=zvGew+z5s`vbqRik$f_mY@R z^F?+3v2_nQE@xSvo|*S3A{y*}syj#v{<_(1O0(%7KY{KN!`P7Ik$mkip3s(-Sv^ z?dbGY4^8Rs@bAD{O?1X)%^s8${H6|t{Y*&qsOsN=W-ldwbw~^9YHPzSWwk^@$d8QT zc_JuWEfcmgyHCa8kdDR0zQYIcfNy`VXCpTARMj~Tf*Bc{DKQFbDIS+u4I@IP6)%j~ zs$W)tX=kdOwAXBQa18z#5O{)ZFJQDQi=cqG=+p=#u&0s>$aid^lq{zBnVa1iUJcY! z)Es5Y)6+1Mi6tZ70Ej_-Z_%(`(D)>8S;qUtCaw~i8_RYW2H*ds+r9pY(Ay(A0wo5{ zWp(&i@l)>Tg$XAHrF0XgU^MYB;KE_YrUxN~$W_)?A{_R<4tU!nv*ELzg5ZoHH??Tl zj2x2DP9GzvkIl4C0S`Kcex@t9Jp`VZrBCUv_73(`ZGMQ&2@K01yx8}fprxM;3?Tgk z5t*GZC$JGbkNS2Gy|0WjzT02&{0w9tB0AvJ8kq5F$6vu$YM1fj=icY=^f!u9qQ%pTZ}F!^v06lz<@B8Y~R@M+0K z5=SY8QLQ>X)8f(}0Mrw+WOfpCqWgwFqh`UC%sOvJEEzze-Ejkj2R+tEmb6f)W=J~G z6K06AjTR)7dN=GJ;{T&WcIDEW1#Ax^@nZStnL;ARF~>j2Q8n6m=_?Uy2u~ z(R2WGngkU?U?P{VA>f>&u7eatFEDaLw_xJoh~a$Zo?HHBGWW`nS2)rj0$xIVIjBNN ze?mCf_R!hXny8Q7-&=S<(q!}t#q|cLaT+t}zs{zsjUe=%K`*BB-nPFutslb z%ZK(0exhuH^f$kmLdX%*vNkw#h668z8CIR?-0nXa{M=z`ZbfUukJjRDA;%tN<{sVo z9dt#8*CFCg6VhCV5{7z;&$n|J*EL9D&$Tkc<_aLdrw7dkb^6Y*jqEE+V)|>MRROJ+ z?z-1sEA9qut}go4RMY`VCrCIF8ppr(1&}hfvY&@1YSV(ZGtJA+W_CPFa3rUP;p|(NL@py{YJa0{Y1ttqYg4j zF+@LK?o)zMcOc9s3aQLLR|}D!1jU=;Rmyzh?bB40z>nc!Wahx^u|_L$5wjFc_K<{W zK92!>$p%@{9e|6Yg)(M#BmM#S&5vbi>o3;4qZ}j>gJIk zoU?y^*Q%^Tw6|}>B=&yS(bk@cQbGSR-*VM=meO5 z4yOp3mwJ_|3Q!a_dUW4N);K@lV;fCJefSM2jh7rp_*2CAh&->CiKvTy84!KAEtC>p z<>JGCxht^wZN6sI5aiDi<=g={6AIjb0Re1s=znlofCPu_YhrmJ`%vGvcW?ZK*fZHc zjvr~uBsZ|%a>SQ8|ecZZbG?j%%keM8q4vd1KZj*cjKWWepzv|*h2!X~xBk33a7kDd^!~gGN zhn{DAyB@rs(EqUAS8=^v8gBoMx)7{hmrt7Owy$)M&lhzH{b;F|cD8Pa{oG{;bajkT z^Cfu0@${$xCdiF?4g;0teQmAl@y|)m1xAc4nbGE<94)@gNbD5qJ$U99ntk>*t?Ib;pht z0u!2tM5Hoxj5Kqk&Af$y_yB1OLUP8%P+%xRnB{Pq57J>uQwYaakbo=bQSv`<@V{sl z)2fF~?#YMR0zZ&6!0Hpx*tf2m$&F06-fp-Q-t&a^LjEFDPSD(I2uJJl9%25>qmzu-Ei`IANienIUyYrpU6?U*ZurP&)8-*E`>nQWr7BLd+FB0sR}M z%!XOO_KN*|iPdesKHTAg+z?0j#A>V;+r;3=^-Z_tH}SvX0T3YNn3*Z)E3?!7qZ@5C zQPKs{h+#pQL;ankw7;WXY23XcuXLD|{VHKn&!3-QS4Hj>0HssNBq!A4I%jNz?}V-R z_)&s0vd%BTvNlNM7RAnFs!ColZT2#JM|{&8{`ewS&~@}+q~(Snoi;;_rYYfa@E5(} zA-!}cmc9r9IXm-_5HI*g5sI6~3yBr5koYLB#`vSDTAHl3U{~S>X@Yy&)=2eIBnxgz zfO#A%@c!+_%II_eH#7%B5|xH?A;0yyX~8aUAZ*%p-rZxgEi=q@l(~T2jhnrffo!!d zC9nG-)KToKWOo1&)gUOuMFMx<;JZNKiN117;bR;1$9XP%3p0MN$1aBT(&y>&;syA`!gUrnt* z;e%%)xJVPS>M%c{TqXSvbvXd1m(E3NIMoZ(kQ`*le)v%oVt)>o;-wqMXI)C6T7B8B zbL{|}#i5!VArlw&L5zq3ZZ1m_fep|}QT^bNsNk{7KLQl1=45;l5)~?A@#Z*9Pzba* znd9AQt1JcqJj6TX#Gz&PpbT(HUp~%B(3$Y)lGWStT*LvWx0%XpJ00$o>rQ;Y%N|P~ za2D0iC;T$c{`QD4KX)Z;8~DYfn%sIKAIkoCZPFWW@)2PcM%msb=elMXw<-+bR&?}epwm$3wP#8@vmaPQ?B(e%4+@HY^`Oc7qYgiptLjQc~ z7{xQ$;&n5Q-nc$oAfbe7&`Q6=(ek8FzcnkM_%1%;(AbXo$Q3ne0fvc=aJT zlJ~lP=pr^Ej5*MELGuM44AX$Rn}f;l#KTQ+x!DQiLIrzXLwRX|M|*a>A%H7(YguJn z4wSv|nWPp1((Nc!2^jVE`C)mkSM}w8rY2lqP3DQ{*Ckt0JpB*oW5TnNUzdvFB$b0v za3ak*b2yKX#8{9T&m`HSbu+b>upAV!>DriVr`&{8Q4aH??aziQyltZY?Sbb7LKxVL zV$hycg>yX4>W_pQ((zg{q%Lt??K@NzZWRR-fkjVor5+4J9F9Aw!6Z8yh1jd-!cc5L zwErPQg=mn70u0dGA=W|*43EXq86(piuzyMo(WW}9L>v(UCTfBXp?MmMv@`{gGaiB- z!;9)azlMv6z~BQ0O&ke7+=n!kd?4g}@(9{V8Hr0%sV2ts%JkwsrPWU6jul7Y+&R~O zSKOQkhqoE1ge}eDACzIP9gocjfRJs;XSmUbc!3iVm&kKxsYe{pU7uZf;J4kbHO3Rc zIxOz$2CE(kuP=tX#FTZTJN;_U2Tcb^l6%6JCER?4_h8N(99&0W0bkg73*2U(Vjk&l z%CRBRN%TXOp)}kM5$0u=b$R6z$9CL*#2eH zS7j!xAHdh&(>A3xhvE4Bi_NbOinlGa?G0(lz4n)cbQz;Q$EjiUAz zh?6vkTH+e-73Oo_WLRL&`v$iD|wBM_vpYxge0ykyBPep{0KxVQ7__<;m}Xy^o>MaQx~%M3jxj z>y3v=o_ZEY%QG;c<(59)>&$?xpSaZM4)sqJPMfmNyjH!2ND}) zHQ6JwC!t@_kal4K=~y?k(%HdaaccUVnXGMIuw!3g#L+~v5WsNVFS1pq@6c>2CGAr! zc^ELurOMKAXwTeKb#<4V*|fsZfPK>Kt;PKW{b$JFh6VV4sxeCz|M_XcgoEYUBufz+ z#cUZDd!%UuB)mrtms3^7H=K0W6{oF)#)DOl3E?BjC|D6-^g$ZI=dIQ}JaSYWL@FzE zD{Y)fbzV(sm{?gEVF<)A7^fIcaz{I?Pb{5NU}a6ShGW~dZ5tEYnb@{%+qP}nwv)-k zo){CKJ>P%s_TBDYtEvmD`h8e0YDd*oC89q3*OkI>JrZk??~U+QTS10Bi!2%&6JkfU z1QVe=XDXFJ=lvh(f9LOvq@5L+NihwmL)`*RJ=CobD!3eTL7_=B#r%CJi1|J zC6FajJ8z&idIV4rN4gd5+Z`|h;Hnte#lOO1(Vz;ZGQEo23Z2P1;1PXa1obcc1gBmB zUl^ye8T2+u@xldPCdMy2a!U5K3FH~dUAEG_Kp|bB%FgKQA<5xwgdvii+7#Dcs@iuO z;J!7LVsv*9`!?X$G|w~|4$0g=f#KFM4`3F&a`$RrbeC-P6XhQTcv=*tkmjT%5|C)! zsgwvp4N&jTh9C!PlD4hGq7yT$E`FI%m9qxURzXQ=8Y&3licFvakB|@p1LxhfoYn8I zsyNHXTV5D!NFVoQ!m9^SXQo`+!6eZsr?fy9%Ld+r(}M4q&d!R^-+3pq zeswD=Gx(@WK{BTu0SDX;VpdfSwOxzdU4L7tQZ$+Nm5Gy#GH^`tZdt zDI+W(aWb`|#6aW=$RXev+qq&qK6`_tL-h1Fq^VJU;Yr=6U}%AQ4OXhu9*1f}a$*Nf z$#x=1*NwM#v-rz-N)5dY2ULvA;-mfkY8-j;;B1Frq?_e7^LXk_NqMn(QH*0^>L}t4}a5 zZ+-E+0B)Z{wK~?UxQO!P5c0hyc+Yf~-MututwhMjwN_T|>Y&2yOdYyDWYJ^Qq)-7I zNfLqjV2bhEgRUpNsktqWhJ{QPO`BhaF1V(aifJgr(epOv&UZ%)KaREy>cr4f*e3as zX!(Y*7u)#f`l^%|+SY(CMh$_l#@B)~^e!^Qw#x0W1`PF`S$#KsXytRQR=j4J-JOCL zX@Lc(TbNF~p%vpBtZtUbZ0e?tQRl14YZ|oNqL*MXfctqH(af90w=e#bW zU*ggYY)J*f?U8MS9#nh0bFu;Eag%_7Vy4^2jBYzPbDxxkLN5UK{^eKPwdG3qqW7AK zK7curkso7Xa;=;h>J-V@*4QJOY9P`G9)+f}sN8k!!x`~wrD4iRNV`}x@i89kp1-jo zD4gUaLXmaDXI8tp&5NBwdGd|5lZ>a}`Jv;oXLQ|^{Sk6ozTbiZ_P<4}pRY!(P`RtWV{@YBkV?Ob*+Gx4uM?l+;( zE0MA@MeCywp_yMuI!(*!({s}wuC9^nEE$hVty-jsG6v*_Z3E5@}#vyKEChmcq9ywGf_Y6@sEB_?urr}Lh(Z%wogJ)H#)cEYc`0-e2#{wI5n{^V3NS>&iY2t( z>gcKYvj_y25j7{p)|QCfLK~BLDu=t#?w*O3xRm}>hbox}a@oobgi_Z$W!*Jx+F^S%^6m0)=T~YC%J2SFaZ{uL0Rv^aKP6N8Ua_K&`CmSBCd4cYz^vL&WC3@Ry zB`^`=84Rsz#H8Q!O!0> zV5yVv2}I`F(5`19`rL;3CpdKY=)I3Y#)M@*_dS>7$joM-bqIk(GbRM>pnkluPQe#P zZ_gwd&IJ5iN{>N$Fbi>l^nx;8ZnmZgARXeocTGr{q~wd8c**(>_5X7@w>tw0nl2eD z3ZC`4+_Y&*Hc{=`TLtvaiPcsWom_%Alnuy3R$B7ayiWACN zT>g$61=z^Fm1biq;N{0Tcpeg;8rQ$t$975{-o6#17NOBDW&2uDrz}|;w?!J4d7$lh zP)}DpFgjM;Sb&OSx6mrdZCIK!RxfmI72Xh*am$jYYD-0XP7F3?MV z9-n9oj5qHu6{X<~cqY$H_q!@z2>u-F9X(-@z04$nN>80=7DAM-2OK_SbN(5oGz5)f z5v6t@j2DGToLURV$f?7o#F~rFO&HPTR`cbASNo~9!|4}3tzw|g{)I+xP9We;pfrbQKY|6VwFzg5$uMFSX5)8h6nFmgiqHsf0xgZHce%W zB*<9rWeMA<{m$?-jI^ihjnp0)=p!Q6Aew%s2rSr_E0B)BB-2JkWbM$r<001PviFX) zVXdrLUZXd;bb9L{TBdVTBC^`TcdXjTC zudp@sAq@lE$dyavq5y@mSPN5ZAFU!J$QWWo$(kWfrWvC=b0liYDOT$K9{e7Iv{2#- zEp@#)85LpLPp}o@P(WpyFnb*q22djlo0rdg53QHAOx)!Kl~*_x(5!Ib%vO1cl%l6< zSIHpqM(WU0xw6>*g9avqjP&K92OAG~608c|W0&Re=&Ru}J92Kc)E4W#eD#+`^ zU8T93zxdww6(j2@e*RNZn&^W&vy<- z;u(MOPebnLo(s2x42~oN0+DKMvzd4tq$<^sCTq!Km=yjZ=$SkX#P~IsU3p0&?9Vdr z(yW6Cum`sV8EmNz!#MLTUnI@rjX_=;P@fc*> ziis#Th|T&6P&!0XSbzoCZoOy{`FW_mD--A(kJeSPsOQTgTER*JL4tFW!Qq@Bh zf%r4{%tum#wM9Qb`}vxsI?yZ%!Qlq$vZ(SB&V5Kxl9=gAuYWLDe!78NJMc0!Xuz)j5NL1Qhm1zkJGv-;i{YG4%$Yk`^F= zSQCMW79wxXfr>aN$AA?KW_2Y=Lb)$h1&E~q;hjk9SFECMx@CO^BXXD*@^zvpX@R0) z%%PNL(&^_vB@UsF!njhImlToItY%U!}FMw{9oe&$=7+Y111F_)WdF2Wj;7J3W-BtJ4HdpXy=aK#$iR&GYT|}79D;Y_q!WpdP}iz$u;R{up$6~6Msgu7TD0p`0 zivF3=_JZ;uPu7YW<&n>_DTlX4R9r5!$u~CxgCW+6c4kV2-M}?$@4D=)Z~2tjxR)UE zw~@@W5z(}iON)gylCO!F*2D^%_nQpYL$wd!n-Z-$Dy0}tzT;Cxw^@*!=6_~cNM(Wh z$i29`(7S+svvKnFuv!CirYa^6j}6_F@+P|ze8GZS*x(e7QZQ z=?Eu?$8&r2GOtq47$`Fvz-ah5`d_Ip-cmT;M;c3kypMuDPr^o|bo$sRI{~T^LWV%Z zqnoK#0UorC7Kbg5--FAPdqbMM3t9H0t-Xb?KMME12~)RCB{gh~_vsN4`>Tau;Gp^nx1I%4?1NObk*Q0C-TVcRyhA*0E z$#u0sChIRWix6NCK*A1|m@n~(uu$x^@3ns&oPquZnt)lu1(|zEGu@_QyPizA<00IST^k%&A+N|}nr(PZjf!>ChiQSl+`bW)7+GICPa76M)iW8jGOmws4` z%A9!&hiFL4Z3k7>A9q2Um9jZWujxWk=qHlaD@xZXmsCEZ@v|&qB;e)*E;?)74Ol$X z9IpbseGe(Tgx>p+a{^dh3-QWEIORs)NBsS0iqJnI$Z0{Wc?JdegtN{j*E*jeW^z-) zd`}9@MnU-wKX$0nMT$YwTen$!^894WX@pIIQ#cGBOQAXl_ zC8{t|>_vxOd=#<`P$h4z@8IWgISmiqc^pOigT+kJ+5$#59Au!Cp_*H{SR=N>h9%NG za>=Kno3Gl6t>k;=y2N$*6Ob9=)+lTH`g2%h`>F0?%$f3ka6D&5!$Z|-l?7O zm4XBlf4JOYQwmXB{F*R=1R>mQNvAj8&1SZpHk=%=in(QZy#>hyJ9K1k@u6RMRpq-U zU-ZpSE6#N9D@y%t8`sZ~sYkpSAZ>KV@)pk##Uvsvt4Vzk#yGNy2Pdc%^2AB4?^N|w zqm9P&zY+N9v%;V>n%Gc23T7$tq|vQLt`}55hrT06oVpzJyQ1c5tL${Ip}#(!1_uO| zY4dfw9(lp+RY-9&u8#;-XhU@KEcychQwg|t_8yf_lhubtxwKHa980xx z3OFdB)XuWsP;^_EYVrg zD6RqKFM}#VKJ_m_xxQ8EcY*kr`wTWQ=nJ^0%@c->fxKM*n z6F8b;=1w+oS1En&rf*e(--zS0-2oJ9MUF7)+D>fH@UnPgX)^dbpNnfx3|#_xIr7{# zY#sXgpT`VZ7_S04!6ds874lD*cx75z3W}M`sj5UQVleqSuuZSz@Ik71eKKz&Gn_kT zkMWDHbi~k`U}C>u3m^HPcINg%9-BD0t;SiZRm!_@^g<*RXA<1<=FSLU5}kyn4_9zJ z(k#B$6QfVGb_Wa+sDzk0G?RL<%L|RWyse`29H1eveM%WVVDTe<;mo87FUfx>Wkd*D z-6s%ojA)ffRjg@Q+RnxZl{Be!+8R>df*2K`1)MCYQkKhYf2T^_;9dUYeC8A8cKf@x z7qou>f`<5Tg1shM6#@KXw>e^{Ht(sycY9QOVdd#P^W&K-a6F| zYcBkFY%oMbN>K@bYhVNnEBNf?r+CE7JgI|FsF$)G_byuAa-;1L^w;e{FHcftts9_} zXS1fnVEnXnesNAp&UhQx3rs zQa>BDJrpPIxmy5uasbCn; z`y+TYGeIIDK)9Tq^*))tK7X;LR?02In|-nV?WaEMU~f%_=cpLWu5ZtC_hxuuEF zc6$!~Sv%YrWT+ZQ6wt~sF9GT4XsYIJf}Li+pUTZumyr={Y7ph2*MDc4hh71Ro#BB} zZVcU}nuSZdl?)I2oz+VC=)FqRFnZ;fm5TH^Dx90eB@6Z(tKUc-XSXra)5tjk)I{ka zg={_B@Ey2JHiJfTPxQ5Ciwx$qoqOJlq1dn=av>$T#2uN3!yf17$70O^IVnK_|>CtAtI&sY~=$> zZ_t|2e7UTu;x-drm!Y)cK%Y#eK&HVVfqV4D+M2?luMLY|x&70!#kJ;VG|=@tn2|Cn z<>#L1wutqLaHi&}A`9OTDpj*^2ijRZ4NceiUreab&GLS@(%%LKdlY|;bNCZg2&q;b zm!TX1VY1bC7nKTH1P^l;%(|5bM)`SBZEml`Wo<05y5pT-zjbD&{(-OZtvvh&7*twi$sW(e2=td3wKlETbxGt!f}>In4=X=K9HMh~83hj$`- z+AlFmQFfTum7kkq4|V=Q~`h(WYq0=N(~~cqZkn> zCh8f>M1ps-er@W~3}7c^!m8b>CptYe4iqQ4GAo?Ck*r{ZTUy`35YQ43t1g0E>K8YW z#9oFdlhK)c+PF($=>CoGtEq+zUQ@*DFEJ*|K_$21u_~VyqX8KbM!mGuVg=; z=9u*oH(P=AEZ7ge$c+Z7ktgEFto?Bbn6d6O-_CAu34@OsRJvbpA@!7$G2?Pvs2}m9 zxq(;%k>2-@L>jcK`(d}|z1-1S#<@j-@l{E_*}Bo6;x7lON92RXR_7z`UCTUn2E`GZ z>r8s^Z~0nMC+y_jBmMA87;4ipJ)56kB9e9-KlI%{AM>|s^Cf*g4Q4g3$jHV6=0 zUcq?Cpa8;7cetoJn|QZJRfpZ7od$8jz$v4(JZp%jUCQwY>_ z7}#n;A+8@~#S6(=qZCGGpo#GX5M}`{@=hiGpQh&QZ&vormBJ4Wu2djE~AK& z%vH=O4^qa=1NFCLw;4T1kNOFJ$eO<-a*7~gshE*<`c;A16sef}`={|g4A52a5=bhN z>x4@`lN#;DiHg(pCK8$0q(rX6;@fWHtTah`Gz#wM6#}R$`}3La*Uw*fnoV1XD>^MG z;uu>GISO|#*H5yTk}estN7)iMCG5&mW#gfnMXjrdr)GZhP=qrp??zA$wXL`X6$k^j zU8E_PSRI#-)etk;ja$~sfny{M$@Cv;{KZW|>2-MUSnJFT?;j0K_p{=T&oID+au7k0 z$d9m*IOCc0a&n{%oxKVs>t(3+mTRCrRM}g*0krHoC?+s&|4GF;?=t{I6YchVFQ3Ym zk*1NAWT5ZCz)b2CRJHNeb!Vye}k}GFWPbpHB7@r#*DJpEz_K1_dZhr1RwRFmcFc5C-x1|?jL7~Lp zj6NJN&j%#+j_uR!ZE8A@LRmw0zDvlfOC&s*cmeJqit@tEo#>meTOrzon(;iWIJ#(H zhzjWl-Gn}y&~N$>u~(rvW-7#ljofRY_@^{BjS6o@Y% z5v5?yo0b+lBn@}!*>9O3&;jG_4Qv>S(@OE=F@-)|}r(|jEN1e|+v?vYZOgyrA5N3!4U0t&)GL-Y8tVP7!FPr<9T=Y{=zDka`^NQ3(mNQU8?m@?Y5K!m|DGg$)<@NGfgc6U z(KobKpo#Ye1KkQ$n*=H%WN8kZd{Fig6gFFg16MN74-O<09v{yXCExKS=8iT>b-fA0 zk_~kj=>0WhmIqhe=0x_$iFE;sy{SDou(OTNoMx1&T2u%{PK6LRJw!yjU~!QwYIJNg z)ee=Ar`4^iHj|zQCi@4=@LH18IzDy zNlTOWdn7K92%YESkODgIh5(T6Z?*% zx@L{}2rA}m<07JKg-s#p*k4A-mF@obepr6@Gh(^Q`6R872U-7m!aMYF$|liNw@q_8 zOf1!Ei$q{l@_PL&uqcuXn|x{Wg+!a@xS`mQ^xRGb{asx<_kHgL(Th9tCUA;7-mxD- z_0$MaC6!?w12VaB;TnCJgDhBTU9d;y?B_LFto~2!m|7WZmcb2VN-aBJW`3_e(*kD@ zCE1RZge6#2G>81QtDprA7E*%CAEZ^5AayAe1!l{Zh7A#pKRoxZH7)se-+|e{?LQwkG~Guv zU6)ZTc60>6xIMP;A#P<{x(BRNC@2M|F|pQ3?h#C|y!y(;sFl1ewZqlf0wW;7nH(Qt zYXV+>yP2fBrQ5;4{Pn4GAVUl(3uk}@NxV_H_GfLG{>2RU?$Yg=7swT9#lU5BG#Hf3 zCIKphAIw4&d`Utro`x0vU^B2L_M9X%)(Jsg_UkaB5w*mH54m#y(NVXw!DDk)X^+Ur zx_6$lH_4prZI3$y_JFV-86oAiUOt{=G18F(-ZDWJx8ZIdbI{l^ri-~I1)Sq6!c8i7 zR&3KqM_(}|S|?K~V^Tv!bSA8C-tEjK*kX-~FeWIW@n3zcGV{2kD6NS0z|UiG72${m z5sOWcp@8>(Ujfo=F)TlqzPFoLNAInULf*8p$HUz0CrP8WSLT`iE*#fXqz&F9V*dn{ zg~NPSDg8Xv6S|!_@NnY3qt;ulcIgQeyRFD}J0mk-+O+Ux@l=#~Iv{B=W)2d4^rx|{ zw!?5b9gn!;WuLht0>2E-&&c}EASNtJ&G&bmU?szM6N;=j%O4B2#C1zLhoohXd$?Bl zJ)*5?WF1=85$c~XF03t+K3~1&1SV1DHV< zHaQCeGF)M)$j4I&z_(@(6wYs6@c7F1mM10`EOQ=Y4ThYi1vWZOh2YYGot|WD=;p|z ze10nnn1(%h|Df5}Yf=;5%I#91HjOaM5h}8#Qn*cA>!0>6Lm6n$H_#PX8kOML= zi7UIfzM>0L!KWO(>hhr4Y7KDN&Vvwc^uMAB#otUmvX-2uPfbKco41czG%<97>>kX` z<)=f2F2Q2R>nagIpUcvw8?71XF5ju98i7AdRxV>(R;j(f+TMS|oaub*g1sZy zlX*!|vo;)9OwIbqbS*Y#=qAGHJcH>A0C|If_05RNjYyL4XFjL>rRZ(i;Yb%S$vCcx zVAgm;kw?ze$0pP&wc^onZrbumfxs#103XIJ;O zB+C0e=D$fgVdy%lp&>GxrHKpY*M#TouBKV$&UM3S}?Di~eH zUn2G9IFQQkk5J#kg0&HjPv}Ufh%Ts{Qr}9nzn;H8$-f$NY9LVgR&IUwe)My1>L2&Q zjOR88oj-^mflD6^zqN=Ac#GZFugTLxWRdP&@(Ot}4waGpI+&zu|EWlUsK|V(ZIpm{ zXw*{mv6s5l|93fjrQVOjR^?jylZ3eF~Z>-_)*r)sU8HlU|T_Br^nlVxj~x} zjI+;?w7Ib0)!RE;U`?jYu0wi_k)6JQa6d|G23^QLKU)=F;Puzba~c1>zK3{>K2*>5 zLso{*Pep8|CQZ-be)|t~rDwoYAyNfY+4{oaPjK++6+4cggzTnQrApRsxiL&4`=@!9 zBMc!mSGd-KnUARzhXQH^wx9(r-tw+;ghrQ?;3j3k-m!B4xI=xeI4{xyrl!9Q46P-n zYfl%{<_W!Vl%78hd=3Lz?P=tkR0h5%IA#P06w)n#*TblFMkyKO12I(e`Djfb7nJM) z&HqXt`f+wTCd_Sh(|cAA{lhCJ*CKSFp68GzkY94LLFIvfq3jSv zGW?PBoguoYl}dw-mNjItSpV|3N?HGi__)O$H_dCOuP&6=}@ zMUCGAIH=}hZ0$x}x0#YG%lK141)MTyDFa|-hQGFjHW{#LS8PA{ZET`4?lV;#SlR;U zAx$1HK&rTiBzYXOX;Zy4 zZdUYZEByPIYz2+|@S+z|r{P%t2kmcg9w7T$dl zmiWTy0;60wk)eWYNbTo{az3;FFbKp0`WWiOJ<1_80}N9y$&k7lrU9UANg)zmF8dDZ zE40sJ#*iEt5Tf_-CkbY0dYpK$N?1H5SXOG{z8)6ZS{J1SlXllN526tGN-|dg0|mKLAOo#!@djEE<)}clj4wiPKh$?+>!LF;7&1jPEDvPPRDYv z>M@;tzpv2NfRsZ6_#6`sVRhDnA7;bRNpbCZz1qr%09P$r$E7kngt{|0kATk4UR{J29!@X&zyE~&d-pfn!O>z z&%DRoLOFjBQ}y4Q4qJ__s)2_g3Vg%BIA|mwl+okS_TG}#zMO7(8aq3y=;6_=X^s5TKQR z^Sacb4*jKeKQGA4-5>h$kqdqoZyi_Pu{cK{n&{1%6eVZAoNh>Z&*hehw&thTcY1Xw zNe0V4qN(~ZhZ>X9ArH|V_bWba1&CY;JtjbZ1uoekYdGXHA>dsfDj;deGQLqDn^`~3 zgOmtOl|Ry;6C;Z^t`$MjpZNghR0q(b0q_W;XyQ=c$30+@vz4v;k7{OL)A-iQ0Zqn7 z1114uFlZ~7)Hy0dmigX)+XKuVT>ZCoNP)sy?-aWeG;IWBo(qrfL+N{3Do#Akof@>B z1uH68XD1tqNP4-B>NhJLGpBFhhykR4d~v>%0MQI|Rf_rFsuL7q3nxpY^}dtJoE0-r ztjzo0h*q7N%#~3}R&(@zHukpE;v1cuN}7xy7|#tqmpFEI#Hq+kBxjJ&7hmWK%zMD+ zPc>!LakX_tXvHTnOkX()>_o-|TMR~ay4YRk;SKHFK*1ZU0b~_Z-)mban@=epPLt^L zdN8}NWE|12D$mEKsxU7@?Y0o^Ue8`H&tw3MP-V)qgiLPpKfF*9w*_sTEm+npSe{%a z2hVm&{cYq%XYfD;M@)~x4CZ=)MGwyigqa?XQ#saBpL0CA1-c%5;xiLqRh4ng#=9# zRxB)^eVyl%YQ<$5$C}IZKo4qC@9`hCOL)Gx;62pa3~CODlz5XdY;~eVDf#}KNaungZio9DJl|>-pZI5r*(I_ z7sAD|#t*WQoKEjTF9zo!68P{DAeCA zWp1_ZcY7Hki$DNa$OC>!{kwh&Dt7Px@SIU6VdE;;>6&dRfUVlURRNaFPE(kB!Lkqma%I;f7>H1Y;rK{hXUef6{k z8F4~CuEp4ax0(bDXm$b$1gkTv2!J`lXLw?4G&2VF_Qry86YG4*j9ldJ?9yNnHVgf( zG^I%@#a*#4)<1yiMJ~bLNR9- zJ|M7yeM60mGN#K{bIWsV$6Rs~VODWqC$L-P<7nGV=SOd9>1|a-^asgpTHOG0x&^LW zDi{Rpmq$gw7~p3)k&ZU)H?5UX3KgPUz$80=+5LBWNGXw0Zqt%dv6No|5Wfc76^t96#Db{v@UZ{HE$0I* zT1bULqwseWi|I*fjr4rsIo@12Yw;+e;ll|EgtPXdi!sk};9F-8R@cAGQ<+(mkZND; z&;+|9F`G$({3uyz=ljj4>GJ+X#wu08*ax1reR38y_JtH3 zic&3XLAXmWd_ajqKVNykJ`gka@PIaLiO-v%{x%gmhcBh^L1BT|o-BmTdz>sphq^0x z1kJZ{6g;rZI|R#4tM)R&a|)h|Tu6zwvnbvAkm!Hb82b1S7Im{rec4S5eeNy6iig7> z^Ma%xC%OFUzo4uBW`|;|3}r9*?+WM(8yjL zkWnZoWnws&1lomehU3@N_$e@YtlN9b4Lu{;m~a%sSVu7v$rwJxSac}zLrw)Z?CSB9 z)%z{;iuX4e!f&yhP}PKV(|4*p$XJ_}l>*j>#RWTvRKpdWB&z*?$I}w5Xj%2J z1^1yCJHuZyBxDinAS`8VebX#uG>&OX&~B0nz*BO5HMMW_o)3T#E%aAE0M^F-{FxpG zqKmUT#*Pl*t)R2%1@yPRG}&{HrBv&PN}3`Ec-hD*Wm2LFlfN~KDa(xscW3h)YW_a5 zT!2q``8PIbhi?Ac^HZZMz-=uq{l=E2^1D1;prGVGN=YbG>op9 z$;s>l9E@7X*^xYME7{ErYrTi|x7)$cXWb=qzhp=`E3NNq$x`PvVpWWdrhxb}W;Tia zgV#pI5~jG^rgH)*k?6w030RiliMG@V;D671EIj4TNeh zSYd#nHyyk;mQ`r?_B@wHEl!-SdkOs-I0_gRsEqNu4HBq1>@4rh&8!Ezu;MPpQcI0f zXD|6Gq${?#i=>+QbD8};zC>FQ0J|~16zjP-QKQbk%IN6k&Pr_=9(}jbW5-40Qt3n+ zVkX)5Ij)l3EC;KoVnLy$>eEf~39-bV|!4QL6J0nBe`=L80EIgA~DMiDuvwwC2xfqZ%q9AV3i?=Q7S z@^iWt|7Ud|=I{hS<_iNjk*CALh@2($nrIajx9_di4N-YBbY*nF?0W!RD@X2cq=Lwv z4$*%{B>?|umbkYB$%pXdp@UqIVWtY43Vg87dKoNRNF>)X6W5oD<}h$yk*ylw6~hnT zwkIAcUn%bo-33hM^hTU53zV0odb9uo1Zw0O0l6w8^zRheJTGYp##s8U{Rs$n9+V!& z(0%8F39Am;5L3yT-fch~zyGVKfWN^ZIYPMXnD5p=&e2=|MA40?}I?8~-Y& z1-2%ZU7C;K} zSq-+>9c)3rnjsMhpT*<^niA!Sv%>xmO5(+?;n#Ku^pHKN` z??-@gwhrE;^Q5wcKDeI0=@TB!O@=b)Zc<+teL2{PNKrK}JMNE=ailSR1Aa%1*t3cI zh6GIc&#%8Rm#Qm%*=ZpBDkn%bjBCdgqB3RzUX@nC)FuBiWR+dA0BW0&KQ<{D4J9s; z``n+(7B&_X+`zMii0DAtkT>#=d(A={7gXX34+T4tw;?D=S6~6(W&bOA=2fLet?-Fb zE}MfGsV~%5yL*JXf>SohONuUm6ct~N=BS&Vv3ahcZ=EYur9*4DB2Z9I8|Bi3GTBq= zGVJC5X&5+k9_sh%AZU72fGkjw7fgI=P@YBa7m!a5g0_,H|zD&c*?fNP+T=18QtrC zj=_$;k~yY{%qNKltOl(Rmk{(w2!oYk8~#^7zy=Eqq#%%tXZ~j{|GrvI3vH^g1$t=R zyTGmss75p8*)t`I1fYV#u{@*JD0+-PJe0Ktgn)(03qb%=Wb{fc4iP1lrhp{|Z^G>W zoRU%(1X)731S2TBe-&BU&PZ<3?b9Ex+eGfY-(Q%xaVVg2@_fZ~AL$(EUmVp+0Tcdb zlqmcER?{jajc8SZf%(spkcf?fjEo|ObO(m?szO;%jChTnYVCJ;>X?Lr>SbJi9>opD zC!Oud#OYZT(eR#PB)KBk!He?q^Ehx+ZUYPZh^a^dv}5`b<@{upF#wcmb{b>=F_!`d z09k$!!U%@mBaT7?%@zUd*y2_jyfiOMMv{)I=whtuhhJ@JSLxP)f}*2x#fErlJa?Qi z6gBvv6M5Oyw5!yw!X|`bLPq7K-2>ZGaM8S0=d0btkQ>;l70v< zhERkPG(xu)+N5hh6yN|tH-GlYQZ=;8DM_^U`u|)xPkBkc5HN!ww`oD`jArxSkADXQ z{zz;gJek#o#H2L&JnITmokaa-Mpz zggOT>caElp$1-i7-F~ZwY4WE^lOO$-cpxPH3*IRl6yl+gHbLSc7AzXeXiWSAU?GTcp${li|mO95G zJfgTwlnOZrGbEX_FhFqtkc7!wRbc+`ut}cy5;k&e{;eJ3_EuRoA7BuuI!zw=9-Z`qV@D!->$p3#hS4dyr+k=LjjF|L-S_qgRH@3&iI+2$80^75)|; zw8V|UmImwnP1!MsyXF= zDDNOO5xmfUDgJ*a(j!(Fg{tF&faMTn^uS6a%tA3IOAEpNpI*wOqbk1%Z*5evg&{-q z5`2U{R*@F7K18N0b}QW+$wTQlE%K(W_YWzrB@n zXG#C1;9Fj|+Nv@BSJa|S0y+Rl#~%S+kdq378f8BPlIUS?TCcKZ?G!O@Oa&phBx32Y zsV)H#VGNlbN7OY`gA6DgHO~N%*3ZY;V)g~#I{z4u{}nZs_%)5Q1#S;SNA;NpU{{^o zB~0SG#+3cVfuD6#Fd2_P^kk*<;l8C$xR)Hx%gkYL>;yxQ@?(^EwOV;*nDE(O)f7YB z=1b@aFmIT4%(jfvABUWamSUn@T5lIK=0I(^fqHSuQF&PrL-XgEIvgveLH% zBVfV-?Xp9TbnyNpoR9impH#Vf;sJ&9{{U=2lfUPg10VKV$9p^35IObQ(iOm2_o_J? zZ&Il37DbGN3+vUZsn!pt!d&MnTl?%3S6t>f0JoEtfxSDj#=9NKr?bkX6SO9u*<+!k z!RD&whR4#7S`3-#({@|69M#5f+=b&k2mEghNI4CX#VkmVqro`XN3ge2Zotw5b93y|m71st z!y=`_Xfgi;kb47ASkELcps4=QJy5Gnon;C}nx4&;ul?^GsHMdLdjV(OsNq0R+3FoB zVS^Ylk0GV3u?}Ig)258q;v>d5sw1QNtEB6WZ8J;&Gah2JVb*NvYE-Nl;OTf~A}ur( zS+eW~O-S`smQI6U=Q-07<{r>fs3}dYS0k+lBZ<1*a{gCxu;jsu*Iu10On^=L6##1x z&GLpvnl_ThexF&SDW`r{;j~Qf8r&%$O(#bR3=9#^a}yRjC=P7`%n2i)=3~4CD?u3g zGbD{7GxVm%`ONL(xKC9r1ui&TGW)A}vfSE<2Sv-@QJST@Pr->a@}9%ui09u&D?N`z z4qCKD*=oV;h>{@w9NG$)#|H9ues&GdApa{8_ zs5xtl(HuepA(XiwF+I2LjZF_&iunZ{aM9``^@AqA0(cc%t3A-%=UNCpJvyG6= z^U4NA^`#F&ZkaiPO!)fqk2{T1amuofXn*63{ID)~p$H`?3L7*>xJA@$je8@bb$%)y zfUjR+BMpMSVmg!4rv;hk0K5oqW>x_;sorR?EGjjywLNv~)N{)_C-hmQ7tcVF{%%v% z4f%c05gH8+XHT(b^E2#gbu%`nkb3Ig+s_D`& zr+BZmqPnFyEDWz7*iL%FSEe@LjF@9fJat|5C94Q*^y#_tnZwv3nb#z;vUW82mNwLO zfna^S2)3V@5ThOC%ZW~iX6tyx88ee`py!q2Vd-PO_wC+u*u%d`uo4a3M(*dQal%=3 z21?Zc%`Iq3WiZe!EVzTL8j++He4fXw*JmqrpD2%yBC^>6I>X%A<6z&Gfl7CqDGb?) zIaIlw#u-<8FU_i`bGn0$_u&V`Ko^_Co6ilNWSlNcA?Mt~V6eV!4M&dqH({_s4#C;W z`j3H(AKB6@!^CkMoWe=RGQ{^~>n`t2cN4Cg&Z=NT$V^AHogz)fxub6U1Zfw>cYc}z z6-B9}(w#hY&tHv@9!Yji(#c^GQIc^Tt`k@{9NZG!h8Bt+NiseWC9QJ!_O}OV1?5=g z2^=Z_y<_VjiWbJ!PORV4-N6(dvRwa7IIZ^wCFJoMHl1iv?0jVm%Quia2_v9hMzh5T zX#x`YYaQ5vTx_cTcM-Mcy2vh{ZQ-}4YHl#rS22Z(a2x@K& zUt=a2Wds|Jb^`}14cw-#JH+Pb4X$F;0{k@@Eym=tETs%?LQWl=^3qZzQaIF6szN=BX>#5?YI- zfPP$qRHC1{&p{jFk?yzSOD_!4j#?S98ju`V*oHOnfq!OMW;SfRT<$U3kLolFk>zTa zstvPC5VbW~1JQww>!%PMe+&-WAhVQm@u3rXXkF_YmVwL<@{P*eob4$j`|UBSbssl@ z*>vQ18}!g+tTL01zT_^I)p%0kmyGimHsxbeJO2(+(cWOA4>917n?~xo zAddT&+GDJU+(j@gR~l8>D&G|j=pag=-Awj z0N@xP$#`zy8yhb0WO>~v4l6aqs7zQoW@9wfhUJxGkXX`GddDiq*xoca5fd9dHsGueS9ZfB^2 z{5TIrFm;Xjt9u;9p|dEUUVo$v2`(NH{$~Yn=hRv=b2HK6QA~BuG9nx`AGZWjNn zj>(V#L&GzinsO7_TLL+Zv;ybca^0p{gM;1iR0_IZR!r6R9+L;4@@nKjvo<#81jQPI zz}#&zM@J0*?2vOvh_(0byN<7>!&1QxduYkyHGz*(-ZQ~>9&h^~ zSWq{;%VnWS^M8I7K7(^hB+JY#(prf!)O&Q{0Q0?XjY~jMzla|4Q{`whbVFmJ(79J0 zCS?Of_Yu+Z|5BrD|JSHCMMWLY5K(vsUdaVy&w!z&kT)cjt>9X7oH&{RbR=~l zbkFvjx9n{H&SxoSPa37wf(OCLkW9e-&-wjjewUv;vA2uc{EM2@7D~oUd#C-^*WrY<75(=%<@3MAb-n z^lo(3a{HqkE=03 znJ-kJ(OjZ9lr_@}p5m}LzCNP!sYybxzDrcb{&$B%Kl*|h=VrV~PJcI}3D68DAQp~E zUcSE({#N_{S<{9)vw-Ly!f_)X$kcnWi}1ZX5-*ox?KaK(Xcd2}@u%&idD9HWz30SL z)f)8BTCfp*-;~34d6FnWNzDaIjBWwabt$u4t`y45HJpG0kkXBIyRs0z`A~jMOv^q1vcpQ|WcrrIp&~YM7i*x6bT`U~Z^as|)7djFm zc||$TxxJT2;k>n$$y_h5Ld1rOjXg!vkqls*Bcotc`45K!?izq`Z(#XWw&QH{RR8 zB<})H+}hg7&@hw_iLj?Lh+`?Wyt(s$tIgop|4hABe2{4tu-?qb`KqECMQV#~eqE}~ zZD)sygbQ~-7wehB69G3oDGlPf*za=X-R@t}F~O3)q9jz^dGMEHl6+53tYxk6sO%*v ztRIIO==uaa7}EY-j*UBKGScs@u@r&0lVT!XYp3c(MXjDXMf0o-vNuStIsPg8e;Yw} z7Bb0SHo$-v??gZ(jWZnD8wcfMoNyfh^9m*(r*nM^t=c?iQ1V0q+a*(}1f|)myA2Eb z_j+|uF-^D_(Te1Nacs`CjjB9PdzbgzIsWB3?<-goX3|1Bv;PF3n*qKLKho5T{{Rn|DoBUi%H>k7^1w$@T@O!CP@|ruF^IIw!Da#@lXX<`E2gNQAcD^D; zp~JUKq*bv-#(rmL<140OUijVwADE*o9`*!SU66dDyh)^0Lh~=H&FTN(NzQmKpy|k| z8;!7XcnqP+Pwg$cw%IS(U6cEL@o=HD)ug}Di#Et?Qypg}CxlooLt^NjpSK3IGzUQ5 zCtVl6dhh}|CXZQ=OM~}_9#Dy~iRZ`tAL|ZPCM!&}btnv78@i6Evgd$oE046-7FrX@ zbTm2@?limKN?gYgFn(oiLI6Q7blc>j%clGA>;pk(CS5nieQo@iI$&6hVi2@m)Ey4> z@$TJMpPD7Yx`+C4@BETlmbyP`=vMjpiuL#8(K%OJ$2WD?4hqtVGWGb+HI3Z9-5y&V z842dfq|1|j_wV-U4t`;|X{TsJvz^n)F8JO^ZcR>pbt#So!)Ozn0NRxV{y!dy+wNnDuVLct&8Ir%Oak&c-o=3F}QtSvIso1(WCo&@%I>I~m+SfBb zSi+e7V|v9{F8jMt9Ss(>d*u&VGqpm{LLLnRQo$fxU8e`(1(88O3q?JD6s+cSnCnv) z&fgJOjCRB2NN9&a^dGL|poUuOOQaUaHsh+ycS1gv?J=6GOVidj)KIwd?2icJ;8 zV&NYhP4z^#{~Z4kbd_EUPLAXdGoOWLjv@!+i5*!(_>&BY91xt?2bu_iL>>JMkeA6J z{D&B|!in=M-+@PEBqJa@VNa626&H?(QJM1kC} zgdIb;?)B6C!CMFR{P-O6t-sQgrY8v4=$0X?HM>WG4&!#oSv+z9BAE4rM>V9{ojS79}SI1E-z)+9sEwS;kBd_Hp}o(LpRzz^iDmEgihxxw5c z^J@&JL0N-+<;J7kcFxgFM90FzYo$Dl8P~7Cs&ksdUsTCsw(swsfpTv?N*r;I*|p>$`)d!JZ^&QV6jnVfQaUl>k}|7_EF0rSLW6g$H%x!;utR^f$7rJW)DoHQsXnPNyLbT5!wl*()I z1uTJud=oo~GPJn5LfwDW*F+GN+Y>2}+{33xEJxi^RLJ`!kGA;EL@8J}1{*XkcEBG7 z>|$4Tm)5zvWwo5m?&yj zt4|u`3{06c_j>lPnAtMSIGHP5wAA{XwY z%haIx&f(=#yYMt2TDoasocSR+Krv7PLi|hHX6@cRa;>+I@%f8k~$ z0`c=_i!U5&HN5kPv-{afw+8 zbe?isL&qjC3**3kiFwjN+{Vj(0v@ToU>CQ?zfb-8N1_$jNiM4*XMU~*6d5Ia!+t#! zTC<=h0$C}T_{DAJ3S3DUI`0=myM%cKAP!?3fA%pshZW1hI`KHkWbF1zY>3b3$XK#?0i zc!%-E+s%OI`I0#*V>S3R(rwX$2Ug6Rz_2%KKCN7-wxnflVoqcrW~~?eygbUIsCWkG z`q+Cm)sCzZa##_+9w=hWN-~^+I)16N*V25GhQEx3HYipgSFuHV39$q^_4_JkN?Imc z&Hb9vmryDP4JZNu@tid;mpSL~z1#p4V9^cFpkVky^1{ZJA6;|e^h`=^FAX0jRf~$qo6D}|o zN-$zL??u(`9tz|>l}i-Pr)Q;68YbRf`ozKJ&l4AU>iUUrk*{h0=Y3M)zQMgmglqpE zX4|)wai|9@aT$)r=&<%+wAb(Y|1;_4grqFOn;40I)Ga6~VevQOdVV$&Mq&JDui*WL zuKqm@urE2UjWkcP2 z>Kzl@cT767O3af;d#z2ZjvirWJ-7yakOCBy$K&qxNF)uECp_OM5q`K}EIdOo#`KEY z^yDU#UK)Zu(@#5#Ji;EtHBsu-hG)d>Y|-92Jx(TO4`Jf1NkA}5n`6li%p!1eU%mH0 zCtMYH6qR4ZTEu|{312A+OsmyyVd&^>6}1?71C&R#^ue5Rd6pN9ti#)&+?cZ=8m zmdC;C>BqdA;%3+(xY-Si)#eD1q)rC^g}p`h?x+f{7lgwzok7q*ndTX7Ve0C>IIx*q zPzOgiWm)Ti{Y4PFrsuZO-;C#aY(S-;^g)%$*P-+WYhxo>IbOs2f-wy~6{yK}kknr! z`h>{oQhDz`PG7$SBPqv!@*X6ZMMcSBYOs4j5)71eDoMy%3}8TM<9TtpEY^fyRXJ>j#b~ zm_IBr@qemCoaNRWwYnA}%Os&>tubg_UT*y#j!&)VbE#teTFEaVk*?qRvJI{BJ%A9r30(D*~Y`sAkq)^<%=6;{u9t5P=6FDj5cLAB{o=6S+GDBYSjuDFOpApCg@O z<+^H1e0|1|FSt!S2xC%G%0k%zwlnY?04j6XdEfv5h7eh^K;QYU45=J%jLjUlR_N)N z3a+-5{Rn9-IHq+84XuWtcgw-R>=F$K<3_+$3g}%tq7K$^~Z_ z1CkGNjcxFTqty(p@pMZAGp|`Z_pkgEIAZMfw;SHqI`|y%;bH$Kp!5H!_UQU^F5go3 z1u4jtcp4(P`@?l(j{+LhR&u}?;4`t@j@8A1RM40%F;)hZi%uZ7B}M>D@4RF~&@+a5 z6r{u4(N(5Vu43WQu*+~);P`jYT9I62IVI)IYQ>qg$7E?oR z@(uz?K1OGEGFr)kG#d8Dp}@VYe!apwSuaw-C7WDy_Q!~agRg7#Wtx5oeOKbA5B=hF z@Zgb(>A?}R*9jVmh1st}LQ6MXj=RBi;3p<69<|XL$@UUU@L(9F-J;e` zp0pFiH8t8VjWir1eWM1LKw~APmbbtktA+GeFk}fGqt8qkPThe*bX30CtV$;`TQCS5h)PsyVh-dx9XMuXp?LYi)H{AQ>^ zfmDSwwh7*~ee+7N8(hM?cR~GNY~Y~#oXg!tp_DvcG(yIxe7OU{=&_1&v`hxNVL|2k>J)q>9wO1a)41 zyQm;N%c?V#AsfD%LG<0sNkM9-g*G}V{hXJ`l+VXg>) z#_JPVNon^7uV@EWIBO2^+8J6MY^6(NE`6Xh2YcY(PBMK}DNagN~3(e^) zge=X3E>t8cu|*d}iHn@>Lo7HO0tJ z?LNouR7L=aQ483wv+Ra+w$LX3(k@2!0ZNaBh;vVDow5@5`5`@ZS37672UYYypkV@! z8htdWs5g9>Ug%x1&(eFrKN7AOHx=I&T0=XV!fohdogP@}WA*c;qZcT9#HF`(*FlNT zghx|8iG%y{M^{4XQ~Dqb3H;uaaw4{logyG&Y}H2jRdJ>!zRDa&2=P2SiFn`9rW#+_7GuqCZH_nPLKc-EP0X*4Fm7W`0%J7 zP~%93nhqz1%eFwJyN5#+?1_FjclES3p&g)jii3IpL@#soIxgE5uyiVP&bZdh zBmci^R&_&rG_9Skp3M=1q4&blpRD0eX|5BEzC`U3d#Stz%gKS#+mPD~DPs0mXG-&C zXmwtjT!vs}gTTN!)#nMIMSS5h%3~P5RA5*LfM}rqjkh=0sRP;?9qGhKj!OL6G;vK#(pG}?JV8>e0WvBT(LE=c#dfQCSE?ZutW4q+ zJEhktMD9RX!LVk68QC&D>eQu{cKwZdeQRVczfEzfWwF6$#vU}D{U=e@bWfBIZ%in2 zOOM`TBmy68h-oesZ1Gvvi1x**C!07uc_53Fv7Kb6T_-5g^i4~T86hI<3tVQo2&}Kt zei=oz3K^iMbs9tH%T{W92k|;VR7JP{l1wo%M@BgcebcA9!B`REaoesb*`ls6KPa`r z(>*wGkxa0$v7X*IY5 zQveMWtqUFy4hMh=_kqHVO@$~3dFXgv0bvuh+V7deLtD2X&P8Q$4lf!Fa#*^NlI%l+ z`=v~v0<5r?kjIdZtY0(CgZ#c}X7BkJFXRX@nw2J^#$Yvk`~1|+vJtd%t`^Hy>7#Lj zKXvFFFg2pkDKcr&K=qFsU$mrgi9G{ME*Mq5ACtyk^_fQ1B0ponW|JgTsa;bA|4y^f zcgDqf#;W&+nT#O~9c=J05PJC)`7ANeV6G6r2X4Rh06(8!vcs zx7hWu))%9$`tNRJt84?jfs!Rilf@cun7?~S%?MHKz^b;xra?7xyS&8!?(t+KGw3Vi z4$h6Z$U*CnPs;2LxSsXn3FykG8HYr(q`p6a>@$s}uVCL9v7M7yo16Jo+m?l{71$st zc#7Pd(gNY%v^&Kw21wqzVLxz+Y3Bye*FewcwI?4fuzgZ|7BEHyg((!Et`fL zqA(cPhzf~XVM^l>D0*y27#fpYCtc~|X}NIRUjT&{QGE~+a+IWln|%FD3H000@Y(tw z#p-$$kFRyD=HZ}=t&kPAPv@TFm3>m25^VbMA@}D^0+CVuO4FAIogsi zwUR5fd-h>3XnZ*F{`rJuU{7Bb7Z_d9*-Tg4`f&q=E@leH*uQvcBBT6a&s5akYzT_a zl#zjw4(~m%q-$59y7*AU4S;xf7hgXmBO@9RGzj0VkFOmT3V59?E++;r-i2@L^cF@H zmV6+{c0|A~`apYrA-*ci;52soW#c!kcB+zab*=AsmFn@G#h0-S{U2yk&3o9IxTabm zRVI=d{y2=k?qJ$TIAaVe;M$xRGc&owXYr{215lX#dTY_kHxV{AJCRIqiUM<5cE*WN zu(=|&9#I_fX-8I4AE}*!?Qx70rMOEcH=jeEnD|CZJO^9YpFB znzcvW@5R(tqpPjZlk> zHSUbBHTSmE;@T}5$DOnlp{y~O<`pLo?zle*>?(|^*q0o2mF^~+gYj(klt5Vqfq9Hw z;m&0Yhr>xsBj0!^@y-B)UO;-3OFA9Nm^t(wa-4 z1g?8eYmCi{=!#c3l{9%=4oJS^hZhUvH^P_V<_~!An7MjqcfN$Q00S*;r+Qhn)YTXO zl$P=!l;fT!_?>pyt?zm`&=T2V=(c8nV3>l|Le&)Y0WOc|D3wiTf|?7SF)nj2?>%<2 z8(QDJ8F9zUnA$qEUcouD*=iVrW+v}REDl(f8+}5`M*#pGuY_3%wv4QbPKT89aj>FE0-cWX}!KR)Ul6kPu(rr||jPFWR1_>Goc< zTmvfNphSP3iKvwE3Iycby4c$J^<7;X1VYyYA*=^ovVk{5YE1&0gxmLmSYw$cXTUta zD1FJ^1hv0RHsH`|1mvEj#`bi}1*cyBJlPu>kbGpmw%Z;BUVo8i$tpJa2ziu*GXG~dZHB=5 zjR7=-8BsmO?i1Q^npYy+JAVq54-rY$tAQhaCVZ#Ir1ska$M#BUoQrz9EGLwry|Z)G zuK#)aOMHngLMp5R4rK^g!$9e>KoTcQtf%#z#(}{&An=?R~BQ3g;~3N>In(cGk|oeN&fq6Fi}fo_#4l%)wtw_nC_|XBvOeO>AD| z=n5|gqM^`Ng+0Kooq5_6r9cuNK8SMSd?a`B=F^5i1W2h=s9400p9-Eu-!~TJf!fah z0q$&QT6FNml2Od-+`Oc#amwrh_^phQPDd8a^} zY|!6kiXfaHLzyhltr5ZF$q)j@k4y>skAqX90{cZF0dyv$k#a5%HN$QdlIEEbv%Khz zfzBXWw!&uNgh6pkX$5pB5R0u~63WziS;A7WMM0g4H&{dDs?oIld*-zB?{WKpU}Et| z*SX-Ia&7}Ce#T3?oRlqw13lgrx70Ru3b?6dQDg>_J@BjmnN`S{b*4!UB=N=&NJ)hS$4t*|v zMvJyoy}?99+2S>l&sky<35S9$IH^0rJ(~KQFb|)2 zl#jtuh6T+?r8F8#o z{Zr^SVJVX?FX}dc=D&AnE4Gqf)ShgT8H>ko6N8%Mqx?~PfP(*gK@p!*P!{N)kp#@! zVQ|y=0N7TMv9@(y&|MpwU(=v>7FwDtW-vyk$D+>U;6j%XxHFk{xjA=X9>ex}s;*km z9{cGq1hregDcuoTerxmuf&kXEO6<5(u`!af>Ya7m*66iPP>=w4zCd(T- zzHb*(l%3UxY+(YCv9W-TsGBKl)=vc0vg0o>!v-m~i!Wj`4majT^!a`=S7pOdZLF_h62bGjHM|v(W(o#!hLQ$YCl!hP@Y#wha~ZVsi>}DU>gxuPoxsl+vY-q4=6OoBCFIZi_Ak6!@fPjJ@r@L2CFj zB@xtqWjath$DxF}9IkuvgOXw!rlwU&%ZMj*dB@lGCtqfB`8_)KY0xGt+p0ICNh9Eu zTr0M3iwA&;;`WlUTKr8JX(^s(aMO^d7g7~A^wVg@S5Izp9|rPNQD7DZ%Hx?-IygRv zJfVTdkE6m3!f-5GvTHdR1(4ybi1EJbTvc8erPlBM9JUz}r+U$b?xOY0a0Zu)T;4*$ zLYx6oP&<7=&{aQQ9HRk{eQFfwN?y}4Vmri0Q~jzLPbvD{r*^nEKagS8z7>_?`c4eD zXz%*fMvXwkPdcEx7y-7u)1zY63}@NfIEZ*o;-*U5aCkG4b}s{urm(UMvc@pplY>7P z%o8{z^Sl=lqVu^#(#DCQne@(l$X{l}>aOU)l=94Qzl&LJ_sZa3cnw9NguOlh$BYw< z;&$4>b~AIKX|1*wJP&yS^!_I#M3-S#XXv&^Fx#OkWs%>RWHPw=wfpZ{b<0#2@XUTr z9({^wP2u5o^p;Z7*LzkE)F**AUp`Pwh1{iMueroL9ohmT;?kv@`1e*g)~s4{sCSja zLDcq<3~BveXQC4@M|5Ium=g0Gxb*9DwW2GH{|dJI`)Y&fu8cnf6sSf7ns3W@P89ag z+%g5recapp5)OTQ5&qfOMB-eJneu0i}p!2t*4W7)bAMw z^NKBh+ymCB{zjb=(6Jp8mEVBfgsQg|bHVMA^U=PU%0#VFLuPGLkE$-}Qjr-bfIV#L z+wwsrIi2hxPLu}Wzz`J_R2hK!&8whvptxf``Zt){*VYOMMzQ{9uK^8}nRMeaJy@>8 zKc|yU@~f09;_UPwH)0=LpCPTqQKa-+Td542UQXg>c@o4_fty=8#WL>9Ho0F>px z~W@ zGo9(15QyTmEjyCpB}qsybpgNvYV)ESNior04nH4VWG#$9>v#*u0kf|KDL9wQN zno*q8BPY0)N>V0D1pI)pWDf^~<;xy}p-Atdrgx5I1tI4iOkB|iVW;Swikp~-i=fVapfuSw7a4h$ z$Qt9jh4B@CRj)`kEew$ND`+jkvQtR!2p6g8q)sMv59L)r)gNlxGLU45V-&vI2UU#w zV-v^rpKb4~nB!?C3|0=j*F&kFfpe`t&I(db_N~j_8crGiQV+G&QL8$4gCCj(f&0*N zE)@SbEqJ=3h2Cae>F4byGKR`D^bA8nHgAQ`*K?>m^)bdblYxsRg$|^r0>7BWR})rg z%@S*ywHd$%b_?%N28*bDJbE6bJm+o+tbA4Kl@oQgiwVWe_^;s9V&eeq#|5Pc&xg#? zHEMHuLPEq1^c(L@bs7eHV(d>tgS~1dxX-J}BrchEg4kReB>H^ZpMK*sSp$k*u_6@t z3f@tWO_2e6IisjpW;F6Rj+?V|%8}NAt%%&YI@$Qs#0988>?OYJ>Mbe!SiV zjJPWN!}4Kmxr>NyI0hiFNJCZFM|@db)LEQ_Yr=J!ozw{Q50-tw*pn#ku zc7-Sx74-zuA^Q1_EnzzVQcS5RF>c5bXw6D$RBTdY1m2130U97%um?-*`27=Z5j3s8 zJW>t}bLd2d@> z4-^&_e~I1=?gR5Ft1^k8Kz*m_1J5BS|LMpNkw8;@A`u``c6i$CuwuO}K?J@V@b@sM zCo{?ryNj#_(H++7Ms3YNZA|nu;qZg1C6nV7Eqy@hW#**(S{V}f;6IJ^ZKHM^4fyR4 zZL#|_XbLtz>YfRmpCX_0c?Na?Q7(BBdK~%vvjy;n#=ip%7h8b=lNA+5VpCyF=a7I@ zk04l(R5DDQP*}Odc1U*<6vMudE$zde;l+(fWXb-g8+_@-S^cLuCo_$mw{hO3<58*5 zKOmPN{;?F>^x8F0~&N;~*>iX*erK*}LusOr7Y3 zj~uj+McoBS-vtLd%b^S0hkJ-Qda&t)&MnC?z_s zNR1Qwj=d0}Y?(7;qo3FMYQutzI!wnkVQ$Cij&y`pXLI7H4M$8H=m9YE)0q+o_CZ4N z_gFu14$|rwPL*##LI`YpF6(g&gRDFk=ezVe`eoMuxE=FJl9`Zpq5t8+9rXnNAh9|Y zuKnooqBpBq`A+xGr+t+&yd4DO-PO9CH5}!3p8V>$dZ>79GHeD^0R-5zrK$uP1z@GC zqe#4v-})-}h(?)3rz(#4h|B3GDVB4F7hZI^OJfz-SX%?uGLlp@DfGHfDRI0De|I^( zf2mlq1cc0p5uyxc?*N|8wkl<%nbuPR_vd3NFkjey*HQS!B@i)=9BZ;$do7hq?m^?p z%5(g4COLMTX;7L=$Chsf50y%K5okb>EhI*~urC5?u<7Wbpb$nPSiCf3*Lnj*2gekR z4mE2+9eexCOFmJZ?Ei9~a5ZxmnSi*zi3gx7#t)E;^-pA|=OETErDxu;@r5~lgT(oV zYy3}FAaW9L?@R~Ie z+e6B<0BGj_ju|{VP5^|A&ENn_MJkE!&Mgu75pWvZfA=>t^i#gS;a;S1K>gSdG#W;0 zr65`k2s?@W29EPZynxeX%7$qJe|c(Cp@8W$~dC7m%ARR~N_t z5uWF(RMh=$K1vW1zVbqxDz<0p9VNlwW`ll60#!pFr6||J{}Ey3-&1AI1IeYzVIc@K zYdG84LoX|O&5jno0zMR{Igytta1q#IKnj5^IwZXjrKFNERoXv~G>QReOrlQh z#cy*$i=iD+hBrh;ZCUuvq&zi_cbd;SH5N~-;7-#9sp+VIJU4 zTHi$Mu5BgqDlrHC_8bNzvt_-5_*hN{yBNbr=IkV&r6hWSUrqJQn~FM817Z{P(`+2? znJ6^WW5I*ER$!o+_DIh%B0K5N{OK0X^Q!q?!gpt*5iij+?MQ`X?Jn1()w!KZW_AYG z*b-st3BCd>4O^KdAN`25CIRxcd#|-*wkv;Syk<~U3D2m`^$!35h#=zz5$@80-(CPh zRHY$TrKOhI8DWMMEPN9#;3z*uO>k7S0A7ueA91DIl%v;{KGa(?JCI^+KO9s_i9O~H zO=7>^F*b^6)a>=5fWrbYK`_j1jto9Eq&JO!tsmUlvh`okn#F@yXKRQ_3uA>2%BwaN z7Wlp}r7Q{NGYYH#rnSP7e({aPJhHV@qQ#ZC)y;~(_M{MDhM5@DX&3|2o&)tC$!P(` z_dUNw_@A8zW9oZWqvA=LISC= zW2d?Pm8s4;98qri-GW?}^a-fd)j^467Rph#)lB_Er0wq6_WiDl5}SO_4sU`KlI48V zbfw;;!OtLu2jI-0B9=1tCaUz+f4K88e1lbm01L1QSaa&%{+45QZRln+HUx1bPS zg2u-Tj{eGYuOhn{wpMmhbMi}SEn?md0&dp*Qah}n2$m?_vl-%Tom#QdRa>dbjJtj^yYNlQ?%8ripC!~Ivw z;cxt6sq6juZ-dW_k<X1@6Q& zz9pNDrZmuiFUov!8}}pX_=TcBB~S`F>j1#Tm97n(1J>u<{6+fV^HmRA=SLFF9B3o* z;S%%mgJFEfBCg@w3VRtnz_gqQ!^bUM6VJV8IX@e~Zc|g{BaA(j6>67&<5C=ipk5D| z72xGyL4ZHUkmHdqN5qmC2-7Ug)zY2EfebpZGjTMBu`XnctN@P`QEjqQ*beG#i5m=5 zpMR+Uv#Pof^kE;*o}qNCh)}S}#^!_i>IZn7!Lw1HRT)FMB>tWGNZ^P`48r^x?`m8u zqU}eF;d&g2!IPee)|oRNvtTcg*9~&oFz8|60(b3>1bOLWMa7*%`{A?3cd8VATJ4Hz44_wZg-?fQE7IBT{l$c~41p4B`TGBrsbAd~XVJWkh08ab1X3jW7B9$~KZ!t-CCpfg^JhDWcx&mm!IID9Jd!85 z=&FFibQ@|Eqr`Jyena?P7oLy7qu5r;w9u_;=W14HF6GZRSn)#R%?Bwl6Ih*!M&nNq zE2ayZiqhZe?;i+yEU`rB>3%cpm~Kz@br)mr8Tlrf^T#D96}WNMaRtlrWjI@q#W7W8GMxNpqFxDA+$j$( zWDEZjNAi`IWSsOasGzOTcat2i*5H#$E8i5_d=1_+IIQo#|Ts zzF5+d5dlB|!ct-!JS9d##C335kW={>x|C7ch5WuH%(VLzp>pIh_`o<8^W_h>-DfBaXg|M88Y?x_NM%IH zp8(<=@$&ZNC3iQ1NuXndvm(cgm85x8DVHP@&`Cnq4i~Bua^!TCjT6l|M78eLqse!P z{~xsR3KO4Cx;9?m<@Pi@45P4nN><%C!@`+Aq9sNXhP1-#=D4E&ym{^rUHn+JNAv!B z<;#xy3X^T|{jtzgMj@wF^)CIwxbQwk^t7+h$0WV&1vgkg>Y)al9bX)+q`$$4Z5rVEn55I=yMvy|42s0?NMu?>f2-?0xgzHcxJAiNm--Gs_% zHLAc%7?syKfgAo4_up0>>^n9xf2ph6iF*d)Vv_MyV(ZSgS55hK@FwVu!ST=dTt`gB zjPL`4MiPEDN@(ZP3=tm3mGG$^+N(UT@Nr@5hU?^0x>#9AN!F-fDzna;0aNovGv_Y` zUT^lgiAY-m>kx+`^mV4;oS{}8-dmLgS5FR75LLw9AAf_~MuB`BN5h6mFx8Jxko*od zF`c~Hm6?t%-kJ&^N>SSdeKs_j(XIjl>YiUePp|G}IIvoxuK6+I*qqFIY0tV8i^V#j zMNRrHZ)$|7WoV0^sC+ckJqhobW6?_nn=Hb9v5J>zX@6dJHsIPtk)?2AL#Zz{rXNI* zr7l^T#H=&c8M6HIO?P<*L?xo@B#7G&R-P(-#iIZJ@%T{ZDo*tBQkfGUQCO8nY|+p& z-p;58OW+R3ErOtTKZv-5pg764d-f({0C7#z!=ntpPPRe{vo5y#kTMZF=<2R(!p11C`K#Ja;^ALlBi;3armwY8(qZ!lqr0(hT>Jd@Iefo9MTP7T5pZwnP z9CmRDAlD5hYM*%$9~l$~uDa(VK|{?+q1YH5f5`r@)sK!{{EFV*kHo^2^hqIhT{TZg zubd>X19Hb0W|NwJ+&PV&A+4xgR@*^8bN)G;Nr_qyrZt=XFv9j4Lds7{ACx>!0j9i+ zRS?FMYPY|E`W>QK%^4y#J#8i`0rN(ZSu8i-Hdw00<>)IRYU*1vxG6)l_Q&8Z@t=S& zqgvDPjl12tRttRhcR}7DPi1B;hc3KFrmB+aYAg@UtLV^RfzeNTTOluJGVKhwpE5=} zTp+b`$Y6z8@Xda3rXZGZa9Z6gQEEw7sXI}#2wkshF9!xsPDLWnzfs^|&KHNEs z&1-%@)n$1T`Xvt?s8!YFRI=7J^{GBl!YOkEF~Y(&h)RX)Q!cIGM3^xS369YsFdm3( z#n0fjIVvxM3dK)-4LHh#ht>;EK0|XghHH8{V1x`CbuB!=$uQi;=cxvYCk8>-LLn+U z473@v7sH-2suFv(w8d018KbeWrZLyVrj=-b#Ot}R270%PSzQd@VoFs->Sk+iu1H8} zl#iV&GCvno30Emw82gq}XnqVY?Ty$Yh$bV7AuiiNrK&|GOrrduOULq!146U2bL26D zw7@PLtfBJYVRc^`)Gq%W!zOK_3b|5e4P1lO_0DQ5DDQqsBO&n0I)U&jV5{1(Z`xTb z-vFlrhL5~Y?&6>UoF5(d7@j$>*-g0E2x{i@IImPwXYR_vnL+5`ZJ8}Lo15(dfg`n;?uSNUt48N_u2bE2dN zNQ)2kq1BwGufHR@tV`Mi{GcqyA0NXZS3;3gPy}xBT>kZDOgb@XII13D?AyLa$!eJ7 zT-6KR-vaY?9dJvKq_H!_xhj9`9hT^4sgmQ&;a}M!E9vWxFovPdk$!6EizCcV&1Q!QSfY=u zW!Ns-z&}Y+I|h+u)AGRzh6s+1BPOWq;29<&yeStE{Mb%KKB_gQ*so z+VXD~B)Vh@sHW0aQ5>90mSioRm;>QWDt0kQs1IZ_Lc{KBi2?5|uq>V-V(Lv^)=iE+ zqU*$!!nG%MdOTkyynR-c&7eesByhV9MG!$_S;W=c>>Vo0m()Bz54UaJ) z22OWPx<*PzsY;%$Ka?A^@Hf9Gnc(?4OhLYetmkH!@g5>BWP~Sd=>jB^rLBt*h66MQ z^9apL=@}PXAtZq^2uD2|ccQy`I>4)kKFIIt>nzs6pAOAtP3i&zY+aR~eISK>$+s47 zMQ+L+xo7aow8GC$7^(RMcr3fG_I5(^u z@*QbIn1kr?^rY*AqA%#c{Vt=Bv}r^oRH9#6W}gtiI@0lZhxyc+&DDFs~TiaSw$R34aRBKtK2L0D7;gKRvH+ z>spANBS%AuV(bIJ3P0S4FAFUc*6q!Pj>^Srh95hceV3*bqxU@fPX3irG~SDjKwLdt zf>iH!Y5MQ8Uu~Ht9q4>s+DXIEW8`3aW59o6be;IcMVLXe_RzH%Q<7LdGPtrdc7CzG z+h-g$xM1f94cRueSw%FUIYj&VzauqD;6EY4%_FXda zJ`4Jg;khpKX-O>M4cKJ!I>7P7BFQWU&1-1v${|azN32alfaA987%*bCaw6FOlP| z*tw=rgFRf6L3ox=iPh7|!K^zRY9o{Y$_i^yoSbt9c@y;K__R_(jKUVA`f%TjLL^_s zBsz$}k)T{zmT(_iyfyA~U7w}#yBO!!Q*@y&koT!Is@xe53}gFy2D%vEDAAKxc5=d6 z3rqEu`%x4a_i)4xFbt$jdN#ZkDovso1w!$Z(tUcHBWat`#v{32x!sL1E(i7pgCHns zsvWJioAyN8E+j}L{Bc8%2Gb61N`fa4L&BrkRRV>!S2U*NVoMaxEz z2dPE`HoNYhBpE+maREeZ$&BWF%)j^D4k_o|fL8a(tBn|tP{~%J0DajnWz~Na9PoJ> zbPy{c7HWq(d7#I5upWT4h(Q;0>G@xp>6mCTuSw+X9fRc3H9uIzV<_3NsXDxJU{__U znJ=srLC-|9Yv#q!VjZO&Pg8YVT|i7L(9ynFWADsPM(F4gY1?061#LwY45;J5V^Co1 z#(x7Bli=Ona#q1*{Xw#horiJ5je2}nJd?kaD%;_6gEk}%x-(@M5~e09`i!)a1l5zCN@ql9=!5@JB26G)5^q5Z@`+^&Gok)=Bu1q^p1LOmXQK7?<^F!{fAS@qrOuT9Oij|y z;&O}j0BkVQ`vhU@4%As?<$ewozbKy0L^qYtXFJ($i=hY#fEkJ^I(ul;VxcQou{Ncf zXL0o`nk6xLxtVrk0tHbEuRu{vX6Uu=iqYko+o&z!KrBLYOL**`5NN~YfU2~1#%;b< zdNjJtcRnNUI?F9ZxUIKBl1%2KQBMkLd?WHrf-029=zJn7+}~gOzjiuev%UGFed!o^ zfDcw!gaD)fSlJ}9pOro#HP@$Z3mLrWoqNNQ0qW}SiEIM8*(8ya_6qvGNfq}=tNR^> zdUm7|)HI0ElxmTeWkP~G6s}B7kg88|zUf=T$rW;bt*xX4MjPz#o~TClYGV|JMY+>r ze7g#q1g-E|&&wMogu433N!#uN(3bCjOLR}$F9UH-!J~INzMRO=34~qZh*<2zGcm;XH9}8F6;{Jhavy_!z;{}&E-)8oCU%xO_@*NwHg)H+~o-~$G;*h&~ zifPw@MS4cT0e5uDzdz=9(h}Bf;Cf=k2j!9vth3X-wqy5 zUDTAll1Vp5(D*!0=qLvU4FD=39MKoC=^C>%c&4~?p~*^350&&MR@CJL#;IJS&bZSZ z@5#60xX{0gIs(EZ3b;Bil@HZac8s?O)}-Y~+A3_v!vm4HpJ_xqOaOF$b|Y3dfCAOG z16eOJ4`#aSxQq+BQ(ES`fT0%?`~J+8@3^YIFa3VTWtiASxb_yTkq z4N&Rf;v}B@MYa*{sxcnmY&%!Jhkwl9k%+0Ey+O~I12cR*D2?mi^KF7h$}W_m7mV7E z9D6ERs5&EW9)iS4i$vU#D>yGDiHJo*@*l5(qe1u=^1?<1I>>uW(SD^leM|!9Xu2+5 z`mRO56t4>SVzbK_hW>K~L+oIXj%B|(rb_iJ6GGd+R)}+Cl6p~ei@5TX;A|8>oJdO{ zKBXy#haJw9MIF4x7=Rlg;{4RJz<2rpPNFA+WdUX*j6aCDdrT@Q2t@pK0@rl|J_g(3 zQ|bgL@hv_#!>&}}^3@-B?y^Wo0dKS5B1c}5G=q}0#TBnAf)-#jdJe!Wz#Mcwv&cj@ zNm2+K`!Ja8k4TUbk!9CUkt6fvV9O(i)z$U|N!FvMfK^*u8&#O#JP;iD%v^*F%;V7! zybr`fQnX%paQ?Q?w3UF1q;crdqT&e?0N!%Zmp8gR6W6miP#dF{g(U;@ z!PBD9G)-vL_yC@t@o_)~8vQ$A>PlF~+=#tT{x>@_5!@I?mZcPCy8wA}<@&h0wRMA(3fI~6OrgmMS5g!VTRd2qTrhJ5b~qZcQ=G>j)$UCpHfezi zL;G}b2!#BjC{C}&;a9y9ZmVGz)-un0!gMa2Ic*Qx{uzofqqnZM+6L-q-K zSKZjY(IxHkdryZ({1+2zjoMfPeSSQB7bU148)=DRi63rQ+*leWa4@_A{ARVXbd}9p z@ekSw3+P49K~#_N-!q1bkJyqgPQ{#FPzn%zE;oB^Bm_>ES^>x*;<(08^Wc{Bp%gt;+yXem?YCHnbi@sOJZ((}_!{HLKmzYXd=PP@79p=lshtJPy#=}|I ztN#c${2`MiBg_6hwC_~nhQMlEFZ1bst$~1-_s+DD%#TKs&fK(rsp_e+Rw@$OO?2s!kOC}JIT6EHk7zly>3!@W zXYHL!ZNt`n>ntJQiv>Ob>7LLa(|b2iqUA!s5kCXNUy&PR2u5{`LdLFOc^9n0Aqq+S z1l9xz0Xwik8Ws^>0|5|AyQ3A_`75B@!F2y?pyI-JP>)ORpS0f0g^6eGfdtcG=$c*< z57q>QGav?yjc1Ju;9NT{bPOY7;qmY)(W;)?D{wS$n%q$d+#i%$jCER?8u0Eo0r}j- z&spw!mdT=U1I}VsW<&90yi&jdN6)v`qO(TqeFX^3Hga$gixBSOX!1#}ZbH#0$a$#Q zebSryNHqN_1Q|i=2xW=7ftwmt0w@XtXmr+bKWm{Q?OAVS;=hcdLx~^+ab5vo$c)Z< z3)H1Q+U4h5fd;>pcS+%DIj12vNdGirVXg{?}vA0%mp zt6_vfb8FDu(XrM#-5z@gKrWQ?@0$b=4}jP0wnX8OZUM9AZL;mFdoc1;M}7BtsEjCB zhJ`qnRI8qPr`(5o*SFb)61Y7>a9sE#yl{jQ4zEPSl&jCm8+TB1pBYAk zAF3WH68fXi{iOz$0n&CLvzoi6XL9oTQEqyn;xu!)_Ug(?_L${Tg_tQ1`XbslDUNYW zmDJ)`6U=&H@ZxSTO;+5p7~3$q?ApxKrdY7_^KH-H0a5BS3JqtLIGPndKr$(iK2^5n z&9x*f@^o*BVMlB2_NzDu8i%~u*G!5*XX_7?x8olM`2q%ePw<0!BV7oN0!QzxLR9tV zr7_?RP|3-xDR}VG%t$wvhdA}5b%Ls12+&uCsb&JZAx7V*{@xKX-KQs*#f5E6>iHP^ zF)TV)yQlmw76oXomWU?uNKUN`w{s}AD>1={AM zO>@Zh4X^-Hnz$;$&G^Ab0`;*UcjJ%=@hgi3ilW?cO*O>p#Owk5ZV77DA-ITvmFAui zY^+49l&J|h7NPtSVZDI)ovMPCXv8cI_Wk!nG6PL0Z!H>lYW<5o>IaBoyvr0vXa%Mr z4-S((>j+-gAOL9oIS@Y4B_RB~72kM+4e-xI18}x-HtUG{j|#zfseHZwUotl}7y*!t zpP8S$u-ZXr82>M!jsET+|Fr(LQ&g0IV7ZgYsB4!#lpb#{-=%tC_NuPQxlap3GXpc= zigrMyrB};P{aah55nQHZ?vOt9<87?*f@>%MPq@tknl-<|&}ug-2;Xf_4u;&4lO1jE zusb_x@~p?#j=eYw{-&v?b2ITDJ~^P;&{M@95FB3FlBxc)OnwBxDdATbf<2olxM*WO zjG<(QJ~7|u-$c;R_#@$m4~gl7`zNL9QSC>;urWCmPJ`H3EoQU+1D8*hONjm8qh=aKGU)j1wyA_S9@nw+%V& zxnHrd_(13XxLP33@@dk_J)L_2`2@?1e=JZ&Le&J_5o6#b+t^4HD-(%78}q%K_8IKd zWVt|aP0?A9*`z1d?XeAZ>!b2n3ZK8F+4u&zLTDYDjtKVDM{EA}D=C@#R3boS2LuAg}25nKR zaW-L`5+!zs(hY4wt{ZP@12$}%nDg>}bbYs^QeRLuSvY{2vaG{Wt$pq=(uL$9wXd5H zf7-D{1B=3dcC042aDI0Dt{M2K33U^IK4|ki3?>Q8GNG$!yfka$ld%ta{WDs&F>%;Z z!Rl_GNA+3n=8eE)Vg3wRiaFIByMVKtevLL{pXNU3YiO{T%`7ceuO}-KjIS271{_5g z9^X1-?{SDm42)-1FU>N^y+gAbL&b zDrkNJ)&f&60SWdb;7P3x1{{|Wi+ILoTfsZ2NRd@1>@-iBa>w=)Cw6JA**N@%!^S$pwF~$?!?t{k{b8G5dXT~X`*}lntr4T zZ6E}b1f;5dUqpRYJb_c9UHPA=K$#^1(5#9^y>;pkyp_Kw(_9Gvr}DjDlz5bkqDGNU z{21k9^ka~CFqu|*TpaqU89l}UR{2(l9DKF<%5m1o)^rl&iiGV_;XB<6hjViUJ=9lAA#6=FVl&zQqb?nLHc+xL0jxsy!G0cpmsiA-F znJK_N__n&4e9QWU)n&4T>@$5>AtyKF+J@GJQOCt<8jq5XnsTqfk_d9tCT`is0H!2Y zovIrSPhj|MN~u_m6qtW$GjR~GeWmpG&bAqo586ZVr;_cSxPDikDw9)d!4|}LDdZI@ zQ5QdyZGLo*n{GNif8q_u25mHOX^X9)zg?Z4ZnOge8$l&GjpaCdfx)gQM(vD?v5~fz zo=*Wye7~Fz?Bh3~ z(4E(deNEgUklG)C!rMKyI99bTgyG}QrZbMYN!j_0`gIKSOz2k_&2x#LO3-X?(&E^l z5nF7$jlyY5@l)C>6?WEj2m5_+VqgHgC5CTG?uSk!VEY_$1Al^3ejm<(eL^%M&qDh?*yGO)><*t@!>Vwov^?z9@Y9|0Ow<}+tTzjLZ{~nBL;IeN&rRDP) z(FM>+)G3zSg-J!gM~tH_Ia)S}s%)l4l8dWQj}VaH6X!rRv~vuUD|0UD!awqVCIyXa z2vi#R>;lFF{&{mX%pdk%A1WeQ0?OjDw&4? zTC+xz{#OOWwWxe8sSMsJkcI#Xt&9}tRYif1K=Sc^ihd894xGg>1l9&m(UpNQKO=_& zaJ1=J53n9Sd)|d=4yEFI41mwSz|r2_h8FS4`Zgc3cP_U?5^b!C+ehx6Kj1j(kUwvQ{!#xFPsmE|mjeotxZavYgQlY4 z(1N&RH$~Qe*&6A>M#ze?bTx2qyb=-wfygx0@pz#!Y!mKu``JC!BIRK_LL^(ba@T}R z9)T;u@T(Pm0boCR{=Z~WoJvvF$8{M-?=))9rJd`}4qDYndO5lS4-s>Z7VYjy0#z41 zy?<_tz{p|kh9v}i>z%+_V?^%&aJ0w`8n!YTKSA0z7e2D`jPmP7V2 zDZ1l3Hmhx&{FTe#drlgfuX~ZuT8L!j>(}`SQJ3^ADaT->ZD_LqB8rn-F#(gIhL|-m zdK4FnE#NBFNCWe>093MT?rIGSnQPsfD(B0oQI++617^5wA_aO$F8lEw??%&_v*FHJ zwgh-32!@x-zR;3s>)$123NB7kgbyCh>S=jV>@>q!8fY>#=Po+(yo6 zywrBVXVm>0=*U6uxVy9kDqTA^`(O@i4kB&8!NGZKrEl$bWVgjK5<)jSY%Ij9 zQ?%s{c;gTZH*Sm=IAi)_vue~Z?x$JITRn68UJFY691eviz;9l1UzAI9=590H}Pk@{LeEpE(1>_%{GCU005NEM%gz$fy)Thw9=~p;XP&WYco=9 zf57gY3K(uH<{|!sVyg3DR30FoK7aN0#9u6l5^IIQ-=J2U?{SzgDQjnl>K4HGV=vWi zZ}*=Eez=AYuJ6^J8C6v0)ZHt*yZz`^)*yPdg*5^LkWr!$B4B-Q99_%rXg@XpM4F0Q zG6aLh2U*=D;QgozrqN-Vq#=cv~=et-Rg zq6*p;dH(omg>c64!Px{?!joXl(W8#-@~NsB-UKcWVbTo4Od zE#FP~MoR;^j68(S{CtG05pDS|u)&7W;}M5A0mQ5btqZ2)O=_bFPeDrZQC)JDqbE+g zt@wTj)sI4;&f|yS1kEs~2@YYTTuzL=IVfhLzdR34s_aCl3Y}U5xL|v3KA^t(N0>)* zfnAMxQaL1TQ7&0GLfPl)Z-tz<+TKH`tL_I_>--6HM+G~S{ojVWCu$>ft@8EquL*wP z)qd#ih+-{AKJT;lboKlZgI3Z9Ar2HbxaP9x7lG&OvxZ(vi2qeB(jh=hU6rN32vqI_ z5}NTven!sTcyb3B`kV9k*6%sl{2(Ww=avv=4L>#QEr=R?+Z!{}R^Fa7jR8dEHFoOT^D27%_)6qDpLz7D&|=U*j?l=g5vi&|TakR5E%U#FKs$@AqD~NN5)T>00NjF`HaH<*?F2eTU5YkhRw~_%v+7PqQ zs!*4mV_WhjGStxR&lYR=MvS1DFM{v+s>y9cWH;@4l-4nJx}w%TFX0#CzJ7?NB1iTFjhZp5FVgtc zBs_LxWPV5Q@RmW!rzC|q^zSO(wDgkm%t&;IR$!06W;@6M#Rg|R$03HY@!u{E#4 zF$$x-*Dd*|;`Jw2e>0x$J+YWQ6+@rNg<-T@{fPK@5S~N!?#H+2FV2%9zMBQ?JLYDN zsp}qWn0^sQe&1Algm2g>ey{)n>JW8}Y}8rpdKhF4BM^g)7%qA0Y~OwfX3*_`w%1UR z8<@W-#yJ?9hH~J_Yy?|njzI8iUFOZ=c`EA$1BL(4a_Icsp{kC3G9FMlI=Ts<~Jj0NZdzkfT5 z`S|ZfBfh9G(}QBoA-5HfWOE8z7hJBN)NViq5{#%Gn~-XW4qcLE_rNN@z%jrDWO;k; z;5HDOY1b`z4Y%)0-~psV1Aw*!;Dh)B0Wk+vLuoPO>X0welEY-Hh&QYOb^yj7edVB{ zXjGFI8zrTvAZjjH0YjiQX+8F5kCy>HV~WL~q^1aaOM6n+21@4e+-wfq@eUH^#3lT_ z)17`*jVE;)#^;R|Cjsz%XNR#4l3(@K$vqPE9*5OLaUN-+M8uyZB#9*ueqnx5UD50= zodl3Q1ttO{VGwidY?S(<;_2v@lWL7IFKF=X^I5_&i=)9oZUePW~?_x0OYse z&)`*NPfxg^uMX}k0L+jd(g?3ZHROlm3||i-aU!pRv|4XcYeMPqxBl9l)ztG)ZKD-O z1M4Ft8*2U~aGb1DU;^zn(iAjA9svYSIW2nbaFI7SCPi=qXLTXtxrMXtSg!<^7V)+qdWF$WdQGASkIXPx}M7%Rq zY0BtK5Y{v0-HSq+up)eg4agVD*}>)`N$ZINjvwcFJQZOMSsZ~*!7#Su0@?7e1e#r! z&zy5*u#c&_0>Qa8yLzJW0*CO#B2m%1aTr7|i`c!7I@C%Fh6cU?>ib{n!9=w80ly*K zrgeE~+yLZ(Ta2*aOdi7rA=nf#&uX`#m|H86J0|sIp(=Q&x{lZ|`>VyR`Q0S<;~!8J z+TemLS2KfPf5q#1qDXk>V53gYL5fFV=Ralk;!yhFsg&xY1-~XE5*WDD6@AZpFZY+( zzsh`XIJmi+l$G%Y0unUp0Z~nJ91KEaEJva&%W)M+we7O@EO#C2f0|H*I2ZXo zY13RT{)Nd5Qp!L|*Y)EuP(>^X?_xiwD1hu@6*N|rZT880KwP`RbVviF9xFk^Wp+p5W4Z#toKbrE{Z^<S`hGTb%yDHKKbAcZmz?hpZLx~=(YtODo0rC9X`S%Kg{R`1m^D*k`{MDwQwR z3|y(To8}38;jPyNfOEx|;NwqC1*OYO^xppK1@ZzCXp0@$5+JWGG{X0;eixi-Gz?*i zKX2ikqipHqex<_>#m8#z~Hlh$?FM3xFnw%J0UVd?Wo|Dw~W501P4$qQEvF zA+-b{VxDPx#EjDIbDtf(0+JOYzZH`IE_$Q(e@5TLUgAeV+2}DaZ=%|!RHqtj;mS8G zkAMJ6`q^?6`^**V7q9jkH86erte?oq-vDd6t6NDGmxo z3zA=h?XU)geJYj0xw z)CMq_w|nqv&SN%B`4+K9e-&p6M8Jhkjd*E0{U0K}YeC_xpJ?L@8mQV35ec}7O(mq$ zkC}CKK&P=m^JOWuTT?sd*@O_uk#a&CLBBX*lw)anks=PlsDA(O81a3zVgNlcCS58> z23qiEj~KR!^NaZZ?sJ2XMH>k7hkOmTV{$$Y;dBtjUfQHCH4+9ZYkUxi8VPQJRNT13 z8gVsQNX?QzT$8JqnedrnYfkOFux!$K&u>@OY*z;dH?_k^+g-Vjh=!K zTq5j0ID^*DoF@`Wh|M?|z1&r}71E)VvzP*qB1K0GmcMTtG&7f;THs_>Pt2E844LWr zkSoJ?#p~%Sd+i$lb~B&qej%Bc>&IG^e`AS3l>N_ux)@7FfpS%U*o`$eSQn_drhP@k zP(QHx^gsj!0!R(+XT4+Day@M{g%Ok~T10Diqj0l(-^naS8?t#rVkM3CtV1x*g4c>i zfYTwTE~Ee}CqEtZYKLzv&rn#fHC@}&Ig+dHp$l!l;lnJp3+yB~FQO^rlDJ zaITNaT$1d7sY6$dww#|L7SyY}I+_!?aL9FFjIh?V2H8?KpJN^-4W!I-mJ*SrP z=rF)PbeWrWELJw)_i#_00(I`=mD*egZQb5T0mpv*Ul77L_v5>|SMI&U_ivxZarjx; zODiZV%qBYMjW@igSp1d=Bn4#|k^EDSrwGqR{5pIi=YeNYftIej*6hObwzae|^B4Y2KA+W&U)SlZW};;HG8CPGV+z4%B(5X2R!>UeN^)56a<2&yn|I+bip7!s zVz^S2Xy{Q$Q1QBCub6_!IjOozoF;D#-2ev;*j~1sHki?y;w2)9dVXT42zKZ;xL1CH zs2V!(PD{Khwg`Y$Gm2!LZhP3SVnCm~6620#VwsgsLzh8xYO+FS45foV`gH90Y7v+b z?;kwfkIkDe_y9M82|y*{wTw$Gf834Y)U{{*nB*4NfS*-gB&ZTfAP4RhVUmsxHTRrs zx7eN;Ps%P#3s=rP{g5W5O<(dAr{u->H4V_(ltlcJo0SF{NZ}GX@~a!E+vDtr{ec!~ z@*#iDA9E*oU2}mj;cF~f0K|RisNtb02P4{3abzt{EX$t7h}S7bk7&&2@>UPr-dfzp zAhu3Q-Xw{!?J}ta@wl63C8nt^#%x#xDOK0s@4!wdxvy}aqn#_K3kKnph5%*Q0v@&X zLJe$6NXyOrzJ(C5XxU_^$yLJ>;2fQC5(sv{KyQ=$pzT(a0*oHImm5`XK-5Eq|Li@R$4$2OVAz*(zv_?ICv*}ovnydnZR*3$%eKNq(eWH$ij zwEzpNEqgVAp6Rwzl~J^b#-C`!)LuKceBdi!r6k zg7!K?8k!|Vn-E>RN`CNhSg%@(@*;mU7biL9oMLM5eR3o->^!c?wE8>pK_{gzK4 zKc{6WajH(&he_CQIU&m>F=JFE`x|l3I?nv0*kJ;YLNAZ6Tl75uH)MC{3JbZ!6OiiP z$Sb5v5oXThYZEMBYe?$jLmxX^S|xaG(bMC*1H;NE5Z~ zX&j(Om#NQ-3=At1iV#IX*tDbX(JBva;><|vhLKf2kk#rNh zacJ1vd!+AqkgzGt;vTd63>0pT8IiLG&f-3eDy*zW&;A*&Xzg4gJr+HdWL*H_dE{V5i-&KH zu!l8>p-f?rd%SB3MK(y|45=t&A7>^uloUc!Xm^&tI1*d~6(t=q-do4PZOcDCQunLk zLE;C9O)1t7#-lG-A!mF>2qJ;@fEKI&yuu&39ZU!@<7EH76KhsRO7|CDL)8QoW^Y3J z1x^vH*|+YZqcfmod|SM}Lb7VoHMI(+c8>7+8!F|A`f%lid(f_BRLctSw<^ncpSY*a z4YT*{A2lF~ug8bw+H@ZdVF_9J0fQn7&9`0+L249IxS~_}B+r9`;}zL_-3;sR zob(5|i0xFHP2!=Y^9zST6kqE~trv6nZHHoyi8yzSVq>qS$@&5OD25; ziFD{#KzLy08u-+wH+Zk53y}sDxVbZxuBchF8T1k@;z9pK79O(O;s&u`23*~@GC z;MOk?89twiEWTIDSAM1WGWWkbZEvQ4zucO6qll@Q*xWConZ?V{5}m4$u52CyaGUL1 zy;ZmQ;tgZJ7+`(egwKGh-g?Rix7QaC)?_!#%VKaD@#YJV4w>`<&#w5YFy1q&`&q7l zT7-M~t0yuG)hmD-TDlQ$x(Tu_tJNtSZv)ooeV>_%d7mA~OL8-4;!&L*wL~#07%`RS z)Kt2+E`4*X(s4Ex60MCMjGXmw_9&6E#MoJ>jGSVpJEn2hj zD0F1wmlqse-zn!ETq4YQzMQPyN|nXiv&}5Y--i(Bt{#D3U0pUK+lq#|DI1@ESNx2F zZ^>x-u#nNAL(Xrx`9p%1hg9nQ`Kvu8+nN=xl=wW|3Q<{RXtkE$b30QRejSxtRUr-c zWNwbLIAOi5j=~-fk|Ew*%+7-)G74^w;VEY z^CflF(0x%VGOtu#u_>d-H|E95sdhaKfk4Zfc5v>>0H^08^I}xB$AjV>VfXgC_4-5k z#8K$~nfC(N<*<@waREaa3n#4hsr9b?;PnkwebBw=alZ&^&P z_l?qR90IjtWA2qd7BtX(p!$36UoyX{>H9kzF?P?!gv5Z!80~OmHEFlPWH6d3bd zXZf53!qO4Vse)Sh=i5QwStVI{LLdBKM zXVPx&sk2xFdBbqK&nMtfz2rf?r@ z93N;)9mRy2grU9}4l^r=O?C&C=voWpOWksUSAGE_6TFg@yNpA(O1GFg>wvR&io`&Y zd3dI-sbjqM^8M@7q!udXT2hLlo+@0pwccau0jc{pu|~~9#R6PwsnD9d6()SdI^9|O zGVhoTRBd(moh~^KOzPQ(G-W+vd_#3X7E-$AybJ`#uL!#zW?jnd+sI^~wCve`xSN8H zwzDg_rD!pX=s6i;jm@1vmk!WCc!H_!bQI;to}ie1m(Yjb*VO$%>S?3ui@yMJW!9e} zHl#NClk+AQ{VP@Xa^lJykE#)Bs5NE*&qlczbhn)`Oq7^Na}q%7F1 z6Br}OqRLKc2S$*~#g+_i#C3f@rvr4*kgUTQdUV7NPuWKn>vvN>!h{lMRx#q2%M)(Ssfy@iptNsP;K&sT6`Ggv^Vha!4|hbJq-c3-$ytFh{5Um zjMfw)xGH^<8e|W*|8J9uAp$)CW-25|5zNT`R6&NvnFB@j7|UMYT_@XJP03p{j~*0qbLaaVoOW zPemtlZLy}z2^+?VhNU#>2lBSI{eANrH)`MPd)k5u$I`P<)SBduHZA4a1elf| z={R1f!Px=PX=|5CIiE#(&ow%zc4|mkFgLJuWhN4`MJFh*icgCT3$E-0R=U0`FfSg2Y6U&MD?7zFh<|X2vZ4J zVH3;qNECZmY0gM=bL)nE)$|=mxSS{-Ig7~qHi)(y)+DZ+sRn*TXhOEO6ZGBtS)Zju zGpsr$bL$&zHbA)q=zaT1m`c4}!w7WEvA3L|&t17zxX$g^iGtXf+>W8qAVQ+1qVksKgPBZp8L@EC|rt0RCD1Zo5l~o$jD|hXKTZKSTp?el8e- zMxC>VlY>dyk=G5s8dFusp_McicAibiOjk(*I~&>?0n+M;m)fJ=z}uvVX|6Y?GywoD zK+?Z|_Y15~F#t+n?d&$?7J&6MnDo*Umrv%!t&U_=#!UIlX1r=KeksWG&Rnm~&c=G{ z07qg8G1}mmDr8$0fC3rDEBzZukn|d%6-kQxHy}QdNumUYBO(VvAQ>pv9J6Uzc}N1Z zin6!8gT`y*DGuw_+=X3YhX5svf#isWjA?Y#19LLb35tXmQ0JiZXUmxr@G)}ApAimt zaF?xmCFGeY6Wp%V@HOLw`kxf4Nysj>wxBBZ+XM@x%q>px7U(iXr9VwJc~eccV<6v#!CUoV$+6?0);B|qT zsfCyss*&YE%S#p^K$Ka_8Y6~pdW3S+vRL`QQYcn3A7 zP7mz6Eu`@eArJAB(i%EkdKYu7!2Opw*4w%p=F;S!Tn3{FA15POTl=K0K6yZOM8)Mp zbfjra-1j)q{}F}w%ykbLZ0AJ-1R%|S$n4e0B$F+qviky=wRiLvIvyjY5_&G&ov$dP z%R1K5+(L}TQH^$yZ5vA~`>H(+1}dPrJI#*RddQs(jb8oS^ToT4M&l64rwNir7&~3` z3K=>6KC>L;OJ=Mwg2TYL&3#@v+$}_c*+$8yDQx?jvz~DBJ)BU)QlHm7u7DYGY`38q z1c+;(A3W#S00Tl^qQ242HF9puvCBH|L;t%*Z<@hSNPQ9`wDY0d?qhHSh1cC z)9dUZ#|<@-UwhAqPhY<(gb;+;&M$16DI?;;p@3`q))QPM>rF} zmi#ts3ED;wN+a26YbuJVlYNH z?eKV{f4`|+cTRk&&oCprhh~&SaiWj6yj%zMGay8r>@EYFv`L6RlVP(o$3s6MlJ^}ly{uyjG1COAuyg5lXxx@e4EtD=|58&l^RdzR0%|tZ zxJvGtjmpi!V6WmMl$;i$h}GYh!PqGVG_#x-5T1y-Jy_E;){9*H=@ro|#qmo_WQvmz zd_A?mo-_Bwp2;%~fi=u1+euDwn$G3Vruhu40Y)jtj2^egm1 z%A|f84Dl7#H4(TCTe%Cu&L;5ws;EI+63p%R%X^9g1(;pk#<_8vi4TMTldXn~6u1Ko zkVo8=a&n1G#457LEN+v1x%=T_t@WV~Tz*e=oJYe#yk?5Tuc#GFAWz0k)RLX3$H z^08%I1lmJQigrp^&F|ZOMHJ@oC>0(O?sx}t$Ss~euDnjjQM`^1H$+4+A89s)ORsiR z=9-b9qMg}znfILw(ZP(}M0fTPK6wD|gvcE3Fogi%K4=6GP_6n9r`huQ?S^UvDY_za zrh;@JBc3?Z1fGt|y&kTe&ZO4_huyrPw$Q=0)#GW_E$cg(NsNcw>RFO!N745qKJb&Zhmq}e|T+z zCc5t><|@2{TEk0&wJ44){t(;&6wNF2zlrQ+nB!l(V(+>6V2& zxNC8fxxNaB7A)uYn3YwUgc5ud=^P6oaAzfp98v7cs2B~R#|JjGVz9_EqDg6hsxHz`&AE3T!OWOZt!NqSsjm8n+dXDwN1S3PW9cP@)MJ=wxqq?Jj% zB3a!%3i063htkj89#4l994=hJy~U&2CYqqdgp?6X>Ifx?n6C48D$uC65A;%=J|FJl zkjwgVe(<^1gq@D#YJHFA1a3PKS$yj~!WW_LMyfe7>&OHAxzJu^F)4f0enGXyEvE=% zFlm0>ms2T0p}d@^O{#jbjgd|tzN$3GU8A*%8LIynP?dqszv07AB6`;~0uaZz?*j&A z6kautVQqItR^!1cP(Z5Q=wXP9hof*asu$5$X`@iVPk~NAbZLMfi_F%~dVA<#Rs(w7 zH7O9Y@MZh68H@k`9f2i&2d0=&vBPZbcff=oOqu+>^8OmrUf>J=r3v(R@$Y4huQh0K z&M=#PdA@I*lx05JUcShYQ;|bnPHRq(Vj&Aie}hmrn<0CDp`9UvSXK=HyY~xW^@+V^ zHJpIoN?Y75;lN0_`xNM11yGU_LBK~J;tdlUf--DCj^KAAL*Sz(&n&fvIVnWhP&$Vq zG54+wl7wjjzf7hV@-#6@V_pELTaREx! z`46>qi(2ZLJDmGD1J)`FV_Lq`5Y)e;#N<3l#9^gLQF;%IzO_?&<^F?ZVMkc2$!*f# zOoi2!5Vz?wpO_zDE8aWq+Fnx+Y;{F@vMb1uLKw(TXh?pnoS~~c>+?n)8XZfMH4#3o zSTW2;&4qk8d|ZZOgKt+G7Y|YMpvV9K;~o4gmk0Is+3DU?3(au38h1P>6u4u{Uu~DHq7w7mU8~g8qkAj&7iQBOS2iAOl`Z;3Z1PY)2yw)aM5UBr+hk=e!EK<&UjM-T;fJ?J5Qj6E10Cq_ zVW89D$L7<`(N4F+VKVgMjb~jV1~IvQ_GAZy8X*1&lL%PxQc5DxJy|G%n_rsX25?g3 z0_FXN#8NOf!q^}=%!xV^v5-(^J2=k)3(g#hH-jSW%z0%^M@ypm!nuW>jGgLv4nDZLL1BQSuPdgpRmGv>8fB+GeatFr>YZ z#W`}FbjY*7?Ku!e0lde28k$>~yjU~OxOKkm)6{(>zVU-Uq{5#UrC z{mKL-K4;`JyJ%z=i6zj4i7**Os-;I_%F@}&(&A4+gMZrP-15_>*4xw+qFQcPP`zUw z*@p5+#;1a5Rv>CZesPm@1#xYVDt}+nXuR}L4}w6{VL2km!i<_n11vju0u( z!JtQx=hlYCF^L)>$2AcaK|Q5KOTz}&FEY{%=FK`kMtbBXs|%RxEe&&S@wu!Bc3959 z04Rb_#mkP;r0j%t3v3ehp{phl?&0oict<%BtN1q&xqudLS(~ z$hKyF6bCV^G9wTG0uSI;B^khjn5ZvGYiJc~blWb%ae%)qW_yo!)?nKF5f%|uCKz5G zmM>_S+}SFd60Ft^RwU0}R$fTcLD$Fqu?mSf;M9EFWv)q|^-}5q`--LN$!9Y{2W8dD zCEGQnH=fI_kXeTo>aCZ9olKKNgQze?< ziy7zLhI3PrxO;x!6ahL6Q#i`^gKWX za`8SMIR8Zz=f7i>J81jEVeGJ3VAvjf3T=t*c>8hCTO%p#KPc$IJSti2!q+q+0uO8n()Gv}Htk z?5`Mb5ZyW)UGhb*Y=hS-M3CbFJ9e7?ht6L4c)PA{tx`vPa15l`oU2&)1mB)^a4IF@zm3Im0V6$uAq>N-g%v4SR*JGW>E z;n16WN_~DLi{VeZaw>Y~GY42%VjS z+QkYEU*K$~ECk{dlg1iQ(8wu7i(|05bmV1Dv*o?Pm{1BDQPx_eEwgBXL)DAs`Z z-^oF?59iSoXtwI_>!yV+0NkC6`ipsZ(W<3kcCRp2FJ9}r^5X}G%t2n&_NfbI)5g`1 zlKSLG+?qKZhweL0suJ2+dRzLHhkgKqkY^Vvq9t^gwCU~RqW+-+0gu4UJ^Pp>qtuB( ztU!RPeTmqJcDf?0TjT9Xck2d`A=({(~lIh>Z*-HBwS;y#UUnh zE#uVH`-&CZ?lgEhQ~XFPCikrBd{bB!i{I*E2i%YFyg)< zTlCAUVnd42+Wj%8{qe5C)O$A?3fSTkYkcncK86*m9Lo)ZjM6XkC3Oas(*338q#gTX zzC8fL);>lF8}q1%fFC2X?Z}_^K1u6=>>jNJFu2KxTQeWfIJk|N7Q{M2T}!NY<47e?QIw9QIpE0|LV~zH zS;w^eDYzveL#?MRsP>@Kr}>dE;|n7u^TQ$8BGdU5W_Nwj}|86_5+8GJw`jfcmNf=~Rmn1GuNn6QWCQ1Kuw*v9G!C zvhyF)_AFId5%Ai|i<}lEXKOpbrIPJ*bqbAfF1dAkupv}tKuqszBU;8yG9i7wW!mZ| z4}akPiSca83-fh7_Po3Qmr8_&u0k9xEUb3wjv8(oTZ6M9lQ$g-Hw75XI{ZLO82dQj z3MG6Z=Lk~PNhwS=qu#v)YP7 zxP`1&Lu|VO4Awm^mTrmGi&@)=&ErW>J&94ZkAGroc8e=rP5B$(gRd$ zaru*U%`;Y{3trr7^9AKUr%7#5yscof=Ig17nvY7BcjP(>j!kN?Xor)u4c}qNo?+FR zq2dvY<^1H4tSrw>of>B<2r0guuz(`f=LdYt?8sI1nut%#`Oo}+2GL8o+g>>yL@HaO zoz#jk81&5kzv!NB{|4|6jjfIq^}=Sr*YC{S$n>Q<(lhW$L)$HSQ$5$~XRk?)=%yK^ zD9A&?Aw9KsN;_77H)Xe97Du%J*jcW@RS`^b@5NwS{C*?kbo~=yN-PT1HCsdt$YU#+ z24TYH?KSwuJ3fb2pSxFFp$YsI8XsFkNSEDeRcSn=dImj&yf_5mBP)67Iq-&P$ZPU- z3-g2Nc=lLKVn0&}P^6Sv=G~8ZQ;7EUXB0Z*n_H4hjk_!ZJ*9d`ry`WlzhPR1ULmc| zSgx@=$tR1ea}*Q#q6gP=#h97qg#J(Mmo;B315ZrDylL44_I9-Gs6P!~QDFcWcmz>O zkvxEg)G5llNCcLZCjga|oj@3dmlD&CCpQ^yjozQSoHcf4`B~E6o2FnVj83<$q60d# zI1E;*WHnRo&%oY$+ZR1gTCyyCnL6Mq?X_a5Cq7M)6MP^m+10C96;{blofrlL!sQXW zBH*#<(KuGlZ$>?u$ky*%uAqi7sbBbP+>OQ&UMOKeirLj9opg{!DNCt0`9rpL2&#Gz z$jJl+J4Tz zpa`j@S~()=0fyI`F>J8em1a-4*6p5gk&`{wo9tVt|HZW%(yCQ$N^;-_p=#YN>1n42@HHEm*@yzmVLgzO96jqPJ>^i?0s#jlWI^?D+S^Ba1fbaJ3*JKzlu95 zG3X5+ca$$qT0^TC_bBdNLs*hDa+EE+W-P<%v8c&%nc6X`^m?p(l?%c(6r6Lpj$VQH zk^4BNCs#{YR8YZ@aSLHIi=@hVrdM3r3<%4smC!}YJ9GD-Iimo3LL4WT<;XCkUKD_< zLyGJ`-xmU*ZrxCv;7@u$h&~YA@A4{NT|e@TP!c&6gq|d97&4-$yR|a>AvC5$UT)wK zreWjc-#aBA9lFN7Xz#m!%InaJ9`?H_95#En8}a~RgeMs5xOqY^E4A8e2EvhQQx27) z?4>cTpk+Js#?%dI!TcS{sX+n)oGSt1jW(^GUP2{|1IWF^;?@p#EKb6mr&#$H_7avK z4#xDIiQZy`UvaD9wbUPX)zN+KEsF`czgyThxR89^p0M!uT)8(d=-S7M)9b(1QtmAi zPT+i`DJDY6*GPJXKBDufM$dEAX)k6}uV5=_3c#Mf4;+b6j|Xpp$TZj4eg(vw5yJCR zIS5!US47~w0ZN8Y)oEExtBW0UR2|iCHxWOD@dmpNZVR(-%A{IoaouoKam~c|!XB81 zy2pmArr)tos)(hQ<0z-0MAfZ^bqygkYx>E8SVk(|2iJ9$`zm~GX?4IP#9pgq1e7W1 z!}inzr9nbuE#iQECRsC)tQoSjXJdt3L!KAewl52gVUV3GBPpVwpq;xXq={?692v9L z2kw4{)x{>=+DLea8wux^cTM|0d{6IlocKo1Y_(S6AIsgC_pt(D$6v#w9dUy@aW%??Hk;y;3!vG{`{yPPa@jn*J`?(p0 zz4-jqPC>x_;)B8F?hFlzlmsH?>j3vX9X27;q7wHh)Fx6wC{*xM)50L^g_x0Pw(F3H zG(?iSo5r6)0@)t%D-1;bhu5{YgW9oo#K{nE@7mm;pQ~`>$zWj3)mZCmwAZFR@;(oK z4;6TBxg~))U=sDp%VhT8l(nQm`_JF)>squ;iTPKJ8k`n!Z@E})X{515Q2#=YiFMg~ zcbpWwQ+v=cdR6w+M8oPh21j*r&CJ zq2~)x1xHB%XP&ApS;czov^O+!@C>E!AM{j?)Ct+sNuzFi)zYU;;LKT0HLp3mhl>WIA4l^fP^SHIR^j}n=K?xJCv_F znke4NK-{R>Kp0(g(7A0uw(2ij@A16aTh7cmDLDpp-nxWA#}TN2X_)+PFjiu9+7&R2 zN&BPs<;i1#g7A_&jBvK`(ByyxgA;+!?8=9Qq?Cj0(kYg(wa5d|&r}!z!Zh~SQ6th3 z8md)NaK}?7YdD)o!%Mn@Ps^_#M-u#=*?;*|A#{3V&v@H~b@}T!hzZG^7%R#A_ zy=iLXZtKqvuK!PMaFL<0q@7>%734#LC}Bb#YA{cYf1PNIX;p)u1lPica!u<(h0za^ zI-n7VuDyB9hA7k3`qmWQ_=HHG2D*3vN5O`gK*&U;6*6cdp_xYD{3gzeIa)MYn(X ze+XgvI~akV1U?DKU#=3q;AYA!?2v*fezDfenFK!8lfRtIQmN3)6A5hSzZk7Nf|MVM zxqF5`FUrNG36A>3<=BF5{NAmlQgJDA02n(|$Z_l5H5w(u@AfgGM{+CxT( zGiUszJYlaL3U>y>wgwKimti2Q#Cyx>{B+ZDWERDeRo3XVfHgr5b{njGqcFM&uCQoH z|Jj%$SBK8WfE3gUak9@$wKji^vRj1kmK+J}WFWQ;j=W5m0l4SaEg_%Zoz z;QI|qvP}ayA0)8WNy9BaTKShD0~KVbLjp5S0aU_O4POk3eGh`|;g-!a95f zJ)*$Oz`Nt0OiCrqrr7~rpM28moDx<#b|#JDLy$emjx6yh5bHJ+ZuF*CQ%3%p_dOA+ za6@VPA2(s+26}a{hq<@}22;PAA;WgQEZXNTXFu2SS2)vzenAuk)>u;40@Z!Z;6(C< zaPb1r{I%N54zU9+AR#wI7@I_n{CGgTl;?_JGrZP@0C&{@ft@&k0Bc@~jlSf*MQ%Q= zjy_xOG{R<>T1XCVe60FT7wcck z^`xcmJXeKAW%C^B8&w^`NLm<{k0n)@HK39Tsnv}1O#)`-$_@2VH>NG={G;Z9f@QAM zyR=5DcE9h(4_izEkU$B)n)hIVwqW_!EzjU{j$1ZyWnfc!an~tY8%gAY6Cs0XXjUFt zjl3rb%H|8WdJcHMhzqBI$6phu|(tS+{mUZa|`2H3v)axm9yj!tfA zw9H=ZJsoCJhULhsTlxq?)91x?~w7SvZK(8=JJ8fQJ zUH{6rSvY8m<&QR(B*RX0)<^vvQBzn&&l|5S3p_03R#yNs_?5HhY;-B zd<&}s=&Ye5ZMa7_DBZ+2cfFF?(+ON=fW;CJB6K6dpnmu3a>LAZ$7m>dtUwqb7RQfh z+D=G(&r4Y-4c^lYF?$Y%dIS|fCcVZTWki8ksjuIVCk;po)xm9Or}7IQq}`cB44;wT zhP6qUb`iVLzrZ!ofFPu$psL?GBGQA+4?!>^iE;NXz^iEHnl?qSs#|C|0nDRC=TAC= zRey&*ID72~R}fhiBn`eJEBH(Li9Ux|pbb+6PaM*sjL`ZE1fCqbkjpMp9EZR5rwa`QCwrgfL?DT;dP z5G?$rWvE5gQ?>)2@;HV}sr)DPRIkZjlr1lSzDqXG$0b#*N=7GQG?(#8^kYv9FdV4q z%x7>jwKj)0o&;)cSYknGg-`qJ=_8jExA9o%8pm>$orYqA-n+;Hy^?y@MU>qxDfH?? zqELT}G@PIGD`)H=Z&`en5F<|z!WU;Y)UNzziKOfu^u8oVluOasO1d)Kk0;5PE^fsB zVUcIj1Uu;fL1Bbar}Wnbsn6xO7USSi2Tn*uYV#qK8yQyCGG_KM;{5Q|6Z9aWcl^>+ zVhX7W;HR>01}kb}dd33)B zmXyo;L@QIrI>_reBocL5f(I=))xMm#7mQS^F=|qe(46`D1(!fctCx#d>}LIaFFf~= zAEgm|x#IPTBn5;jl2dLYjo^~#UEA>@av;)%`@>Kn@glu2%#9O;5YVZ*^z>Yd7{YR( z8Doj>UDiZ7t}mC`bGo9)DVNE2%huQiE^gN6TpbrH6CSV@c*Os`Huec00ffKwpGr8QwGQqHQ_w}qY=&W{&;Oin@RA2oSlDb;;!^0OvCMlW7e0#BdN2T zIE$J_6R-QN3F%x;cb0qY8Gp($=sZ|E@5&Aep)=K`1zT>4*vB%MvhRy<@Csb>TX;Wg zb>n1@) zP64kMOX(U+UHpG@w6tjCm%Dpvno2qy8!07q_T8;IRO8y&3PJo;_!P=9I4I1Tx4?Mf z7oLLX1jx2gH;$g%eS{B=g85)xlHniTq&d&_GjuE|i$#R%WC^V@eBiZQC~8Vfv)+U` znZ~^4icATdsc*jA@v%dKj$KSbDtFj9a7kcAoPR`5l$4lwph9dbyHyi#kA|N9XSt%S z1svBveKJe^xIQ}>O_HNpr%DBu7`5JX+dcX`10NKAqQ&ZO5a^ivI?503UR%|MbM6be z=MqHlfCx#iXGWk>i5qtdt47|mswxxlE$eC1;0ZuWcLrFh0(*N5x$ zxoIR-zabCa*j1qXOX-PL+*Y+Uj-tpoI0;)E!nyiRlSacb)GYoX^H$e_zQ8&tAT2+e zWP+ZdJ$xD@?mp;Gd!`--efkOYB;!?&baA_b1Q8Mn!E_8Ljmts%lNeofEX!qxdS>C{ ztwv9*`x?WbgQW59JhGxN%02l@7K7)IFI^>{aNIra^AmlX!{f#Zk!5Wris9-2bHR^r zg4i7gG{OmeB;4LGj!oQUJ%~B&I*I1 zM(k-Z=eYvQl%R*VJNCeiQ~F_G&@7Y+{(<->|+5imwP3NFDF0yxxT%Wu4!N zNmBoiPE}61vR8QcU#jQ@|7sT(7)wE$O#Olz(n+9IuNwi4Qm(PCz|g=+Lk{)F9%fH; z+I##CIM?AHepo#~)vM^n_J%WA#yDS86xJ{|Dbe!c>TL1`jYGkiJguko@hi;>sypu^ zxm|4n4ukRmB7xqzccm)}BAKP2SX~L8eE_5oz??4}y1jPh{Cu2iLPQhBTwt=_(HZm0Hu3nD=JV7;d&XIY0}t;d0h#XgPWhzW#)#`7D4yf z+VX-n70!RuoBOWV&$|hHkTQ0;#NJq_8hE6APw42B@W`N@5cpm?T&xY9b7jq)1S@sE zu$9SW?_=VFJNtJNDd3H;aCq|ch-40CDPWF`G^JU@eBW4BszMM*A*5(R3V?EOqYr8J z5wE4^xKFz*RaKR0Yx&Nx7I{z{F_IpMwiAKU6qOD-YL#99?-9guu%p3x!>;&GRj`E4 zDXS$B30wq8n!qmdR9$rA%o0m%r%ZM5Pkie!Ij(x5M!A=zDock0f{!MpDWUvr|LyIC zHKdc)pf9yNTY8kDiA~F|o*`cEnX`nn^^e}{(3y~v2#?$6YJQ8>iSwS;0ce9Ko>%kPfE|J~M`84V4t)mdjpUIVz1| z?OT@-f%POsxIZOiE=zAz(;LTXQ0V9t?1ICklf7_+zM)uzX=s%JD zpR9Y0Ra_=Dr2l~3;3;Na*G414dh_=m4+8}p&mSguI?oU#`mTEq34jAybma`;D1j3~ zTg!FHt<6qH61x1Q@;%@m)#}6Uo!3-HecR%CANU^sNc3s;3j_4X<@+$a|~#(m-@DRYh^4fqnSvu2VW z=}D5rJJ+JfOU#@6a=ao1)q_Y#Byyu97~#Vp&KI4(u=uqEA;J#1d1=^Q@4rAuz54+T zPd^2-5eM?M>QE9`y5^tCoeUt%vg?ahGv>;A#^`tT-I{I(QkZLAl@v0Va;&mw^wmJ_ zP`;K01*cGwd@Pch1tS`@M2DT3Q);KFm5bDJ9K_69gT#EZyh=&;UNd=XN(X^Uo0ZtZ zA>p>bV&qe1BNWx2_+O3&hKeQ)QJ_lhCe;)crf)X3!_0tf>B@!B-AN<~sJEUR7g~ng zUCP9XL;<<`*if?`VZ~maO%`eJb@znjwq#t)Mva&9i?eqEYY_9$;YszuO#A_6VpK#d z#E@rEotMtIVII~Paf@bJoz`q3wBQ{W@n&a39C4mwgvii*wGPIqvAL(x@vP}PsuMT2P}s%DC-cqc?P*0O*i*?!>vo*>KIfl0o@aISiZ^* z_08lMRvPR-!Ytxc{AxHcu!(~_pRq+`D!q2)kHqc0t)KrZMQieerr>_*!&=Q9Spc1f zhjnJQ58LU4krIg(mxAQaU>+>b>$g;$LgcH9?pc*GGn3NZV&+S-56TB~(^oE|l zc05K$j=DXORlrkz7Z_~$oUe@vpC8TRZEq+F4ex@(qDAC3_F!K`JOqy`tDbq4$a|hi zyuZQ4Di-hSpraTO8%BX-a4#U5EVbFmjJk~G%S?$QwOd=R0#d=ULxDCfv!Tx(i;l>& z{uF1KfTz#MU`|m1tm*_wV`N*s^KNO(f7LbN!1(Ao3LS6#BV3Zr-hg&D9C^{GOK!D; zK*DGwY;@ap>nAPHN}ioW@4Ipo?>PeUtMDVukt-cFG|oa5|F>^YsZ#XltICH4aL$+B zWp$pWl%rm?9I~fKc9yTGJ<$M959=z$VwxDl#p<9VL0?#zIdv}yNR9?9kMG*;=#Ema za9k?kaqag4`Lq#4@-b2^ODYK~W>wW+8fN>?Aa!dk?PXkb3ged88+i-pU}S&WytK&< zhlMq+E}TdNy15BeAhi!;<`J!!$`7+_oO3#kbne}mxV+Y*c8#U9Pb9B96Z<}r2V?OI z6GW4*PiXSi&ID~AXJP$&G^UUBL{%fyTmBf#z9oni<5e+IpHoI6Oo^ykAqK6WB>R~w>1ndL}FIYd*6n5qg9%&JYWhwRz$mgPNH&K9Da3r^1M{u zsiPDQ{}?EB8R9*v`PCsfeR~VVc1e0|%yNr@)Pvu25MIWl#23bwAGFqWExH`2gwC>9 zTqm^SSHsNBYpPN%%K{=Db!jJ&Hi_H{NY$2H6@0ec=ma{vy1um_K)EbEkM~C4S3oLq z3|o0md!ghEOu^FUvNTI`hm7b!R>=FUA!D`J2*j)hD|GB2C>aj4&#LMo{)^23Y$_E% znK?f}2sTnfFxhQ=iXK!tsyUo4Vt)hXnaT>MOa~! zO<$Sm)|sSpO-%c0)O{3wZM1G3An=;}+gMjNxyEm&3;Dh*S+8a=u`wfxIjoRaLU!_p z%6F3mhZx9=7{B7y-Yd1y5WtxXof$dRwTmxnXec9w^1i^zxou=^W@WFm8jN_nKTo`PH*Z>@94<1FH)-9jU_n-ZH;%NTLRlrja8 z7XNT=CSvVTcPkSU%lDtzkIS>-g|VWB@Ci>h2>v@rZX<6P>{C#}>!!=j;vK*Gxg0^89U5*e&hPyWJ|1926>5$@f zOpA^H-@$=VQnRSZ?Bz+Qnss>+znngy|30O_(_-<$iK|Qgj=2PBj=E#1Yf94Io`~P3 zPL-QOq-(TFlL$nk@J2hqvCUUY&$!u3i|CBwRq&c}fid|&5m4I0X9M_-^iZW8x76R} zc&>gGJ+CsGol@f!>>i3%wZPBPMBBPXDHg?BI)#qxK3^9A@A%V1nBY%L%ijOavpmpW zfCo8%vRNb$K|9OX=fpFjaOYI7iCKCD%s_;c{;fL^=u^K^Yb;2(t#<2 zZr@8+1NJ9*O!}ry5cTc~8#|B1kPEcKXKR2Q2$|F3hMr1>ZQDV>c-5+kTTN#Mf!YQJ zHp87uyY$Ax_I?j931H}3WPb>RHQO;DY!Cg}{V%Szhn+qwzV^|(W7Z0M86cx-$Po-B zw<7<^m3O#}(IR8aq36z|oi1%`@*xbZ(OGc-ICIpBx-Ov(nbYn>=3FafM+@#oPgu6X z*ki_Osg{-WA3FcFc2XF`YJo4dDaf7#se5(9Nli2*aEJ3BnX12?D~>fp{s(@u3);AQ z*j?=kh%6Ttx!%&rV!JEKBpFM$(ugPAt7ZMpoj81`1J-e@(@$lw;x8BO2f$jA4mGxr z$Dv83%Y+G#!~3GcNPE_C8-}BG!2}axSi)KkW*gP!dn{=fsVLkpYxd_O_KDf0R;w$t zG%gM16Dd|xR(|5%q2L~_f8x--+C)}2=kz>b(XIaZGPWoDGrkZ-)$|NqKrZpkF+U=X zc;`YODGK{+_*|PAi9~-0B{g+r#Q9fYFQYOB?E^X(!9UuCa!K=;z4CMiEI02+S|HC=SR=_cZMorRLr(KD}kUBy?T-zIk~kzxHk z8ARXBt!<5Y`$N<8=BUh#je@!B^kb=$JW+ zwOOvmB7svzC{(sXhlJ0h2>&|wAx@%THzZ2o9@{`l^>*KV6@H<}T9r;uOaQ&--3Kl@ ztiQWolv)T@*u)nGL{ zK-65k_sWP4fuWlym0oODAx6BhRlN>m-xLK1xYW~i&!oMsMen{{UG_mWao{=Izo=?3 zhMLYRBN97ZVRvi+AD zV4pw61rOi~3TK#n)BOiC0?6BE80mGCb0yh(ygxcKkwZ_jSLshu9aNmXbepkAk+!D_ zmw$UMC17VoNnLwdz*E>EfW>R_FM$Ivc)-;p140`jXH#TO0@g@k9pgcrHV1O7ShTz_ zQTz^1A{?-1ddzm(z=?~UV%=`Sha8QxQPIij?GtH8=!&Q9=qWe5r zP$0-5(gnPZirWt|J@gI|&Hckbt=c@`lsS839#w(27?jv>!sdq4DxkS>&`BLo_BJ(d=&aUWj#GbSCZ|>r~TM`Zr)E0=odZi)<%0j1&Oe z1SMu1GKB-?|4%Lt~t#9iyU-UKG@o-f%5by|$Yn(*%r9y|BS$^Qp z#M+_YQ>}-UzU!xX)4Zh>y_j?Nq798>g~4IZMAbyzE_f5C?E1AyE(0m?_IS@Rm`n0SiUl4(km^$P?Qi$nvMhR^*zkc2B2TZ)K(sFIM`C z{H#quY7Kdj6_l_I*rlXubqPwN2Jwn?~(4*S%?<-I@6W6696*Es516$;9M`@z{u z_Pou*fq0pf~N`2 zh*91s)((#gd{B9iwjOl2RJHxT$K!w{T9?`C>%W~dOc#7kzNR@{RY{j`e}Zz_s5ULA zv+%C+gXD7ep4i07yuLloq!q6@=z~b$n}CRSYe{&}bCh|l%xN2Br`OYw zuvJqk>G>pQp@BwT`j8JWX^=hN7icoG5Ct{NknD-Y^1BvAnre%;nkmFI5w;A>AI?}X z06jp$zlTx%Yimpf4H5KYX72K3SVLGVpgXCE`wJrx_}v$ngcBbB$kXT5z&_Qep@34J=r4tQQ)HfAhJD4DQ+`IY zD2%X;2uTq5_}MLfQ=R$qfpO|1Rs{Ov2c|Q3V#Z+r1&!G68X=P72|C-lJwB~8W^4rw z%RP|8x{bEjy#kM$v|i%5518iilDKYS->-MC zQt%zv75Q?hEv*KaW!ZO0??3zglU#&e&Gp>Iz+ltt#GF49qmj``3U-KlAHFKACGB(JbYy_?3Cd7Wv~=NA z<7t~F4NK@&I^{PrmW9bfj(%mV-F1TTiwSJ0pV%op~6# zNMnR1D(7fdKj!pGmIkRrO;V^3{$CAE3cOHuBXdiOingqECOfUZw56~^2}cl~iCzS< zhzjT=o>Qi#g{23f4gZXyUkTXmr+z`SySRzJUORechQTtccUTj8Wij5<~TwAu-m9NMXdZC)QZ@k zrnBAW^4N97wB{AO#u)$CI5C+$kuJ*#yFyj64TZRTz1Sjj%A9Ukvkmi|VXp^ow|;@* z>`dLQTS2h?`bn~KvjnyFCMJDB#T_CI3T0&+eB;oWTEdtSjMzkfB9;(YcQLg65*z>- zUY8MAJ6-=+xo#Srg*)LsfR4eD7PpI_gi4|W0s&QgO}E{|Orcj~BRmq&gfNae{hx3- z1JHv>$cxZ-Vzw?FNcv*Wx#2zBf z|KN>{264+*Z?`NeK^`at>-ZXZE_xwt(iS+pxqDN^PK^GDY`-kGl>ifubY7uqYn98U zA%!&6y0cwWxL26hItq}IqtJ=J8OPn0+Qv9R&(92#Gh%|K`Gc-hn)Wa^a>`Fks1AS8 zVR33_j#{ig8Vm90tpWz89VY&3RewH}WUp|<3Q+SOzV%od+*CasfoZ)Gdr!ze{1P)) zYwmQTa0Ne(9}>f!xqhssqN9R}Q{kR=lZahiY4WcS}qK1GbPwU>4e3ttQ}&LI$E$ zB`F4cqCk^?6b0|F*2dhRD<=?sI(y0Ab&ty(8Q&oEOwE>;?8YKsMaTvws95Q${h%n3 zma0}mg_za+%m(xN@Rx}fXo64mGfibMexPD%ps6@|R2%1#EgDOGluJOi49PW#Z$SM( z7nYzaaz>#R6LIeSI;fZ{MkYyIEEHQPg7uk_kHdVaO=im{H7sy4yu0Q3k&Z&u!8_*^ zS&NoE*>d;hcGTYiEhp08Ai9wI6x(A9>{djcN8s+|% zKY$gesYb=-x`(Lx475{!ry9>WM0XYhN#9~fu?Ji4GAZjrx`2ezg^35R&DTR*3NfLJ6)qQMs(X3iqH6YCpTu0RH z=Y-xIvqEFKUxfxlG2&3DMK+F|d}|mQ3NZ_jr$k>_TmHJ6ART|`yo~z`-O@U%uCBa> zj}07EB@>?8^buko@&40@Y3OgtA2x9Dz{1*E^C^9?AWma=MYEbld1Yv&~PUKHYSQs{4-I$A+JJNyYiFA~t1r&E}ZlT)m~Z>jm@<8a7FVGv20+jEjRKA1)dRocsp;ov_~xSd+GU*I6l} z#IeI%!Z4M|iDzdXRqJ1GHu##^D-Duz_$olno2kwVc7Ar*h?SP$j>64HDE->pySoD_j!3j5W)bMm{>n=U`eJPsr%vOEZ`}5@+(|UL|#Mb6c z3Qbg!V~^chEbHg+%=M!rL*5O?9gIGiPytts=^DfChb96TDim5=;H6z$-tC>)yL(N-G< zo^hhUZxF2~GJDYSS5R`A%xZ!<=!}avaaq>cd_3EtUbl#xwc^WHD)T~u5PC@bpvQkC zkkGHcC|M_q{)MDQHo+)1PxGCX#q!|?(WahGm`-Bg!sD4j`}e~bi}w4m=WFS4ep9fR`rJ9t1OJ5=w`KrTe7VQK&j)#L z$PBsci`FsVfSLClkf)&X-}TWGNjJ`(Q_VEdkJuf*d*BfJ;`)%m>a9=Nk|TFG7~&O4 z3Dmo{%;!R*6pqgYML^uy|Ia`RuB566tq;DppDsjj3_3p028Bsj0X|?*(@cm>03XL9 zql|@vP)v|f!qZ+ie}^8C`9;~gL|wmmQX{$L4C+aprm(Imf>sMg@WG3`?1&+dHc40o zg4OjF0rmg50pzVae$kYOch(}_sofaL4;hnw@*hgKV&*W-EIOuVwk$7l-fc>Wp;O3> zgohkO%s48ay*~)8(ikQfx`TUh&vy<3?SjUu#*W1{b2QfPWDXByr$-W0uO7EG%xF`2 z6^*IRorEk%@ZZ*e6T9>b3a>0miD%6_F~PaAc58q@3@bb4QE#kCHRvnE*|y37yoK!>-qqjsJ818Yq!y;C z1N?=f__I43;Z`Mk16@eg5;_i31npa2X>RsSzu^NR2mZ4t31{P~uD+dk4^iL0C@_qe!2a06#O;W`nM%XcGXM`CnFI%L z(}UnDH+_w^93m4|3>JHHaK!qT=Pz7zD?2PJ*-|Dl4*2YfhP4+$l$9Q=M$w_L&Qbhw z)We2Uehj!yGG_1Fo+(%Gr;F5tkQoJtdY9=y^hA)AbH;!_Cou)t#zv!{s zsM=)u{?65Va1DmB`Fz!BidDu|oCM%ZccKJd2H$_@4_R-MYnX_4ObK74sl9mr6N1Us z=%6YVy9W5$LEL6ytLp8E3}j}ocp|PDar2IAj(9ctcr1cikf6kUa@G}(f(_1K^{03E zaJ?{)P;WHUoeVJ(9xOJnUxNY3?OpbSF6j@+BgXlgc?Y1#0-iO>-S6|7QJ`T3y&L)s z=R18L0tphEX|6AD+Oga=3-X!af?20;4@}fbZ4JgaBU(uXZ6KfFX|8tZ-nZbb_v#hV z^f(~>HNY1fl?8X5b?W)NsPX(`d9%18fJiPu?;eN%wJvRonXKE1?j68~$~KgT>o{=k z4r;ceZ#ZVQ1#USnjRXj5MS%Ldf=`2VU7SHeH8mT(hH#a1_=arMsZp3!q3A}I1cD7o z56`n3c~mW;y%h1>w+K_CxAz$2sTo@MD135|^I-kH%|y3ZMp!XnX+XUm{1 zCox)WHe>A|Z%Sv$OObJeS-m?LkfG#^86hIg`9q0(z$Coe)AA5k`gu1r9)r7h zKJFZu$e^ZSq5Y;GaL7we1d)<5gEaOUpefo4JeXJP<2iSmIAw-i5q2P-PiSy7PhKTL@W2{<3o*e!hQ zGw?!JHI;eonQ6SfYujm92QKssMzc>k?zHm5D^%(r6l4;yI6av&3xFIbTk7mn8P7eA zKiGm+zugWf=BvA*C0Ii@9ou5E}U#Q&cQy2nOJLpc6iTcJqV@uqg(B6%Sc-D*$9N9WJYslsa|iWn!kxa%sm&;mHd~6yO3!{JcxWg9^+Hidl{vd*oP2 zo}0_!(Tf1=((XR}w1`oBK*oLK)01e%L><4})WBOyBwpp=VA7myxv`Y9`H+<)c6`}r z;Z3{1QPZ-x)buD1vLk|4yTu^c>Uq2`7nLz$pz(0YCPI|NB=s%fqt2p)G*#Kt#;BSW75T+`eaa{4sszSz!E*1zi6kT8;~OR z%9(*aYRxT&sZtVid&=PaRuOzCIzda0;0*w$>A`V^EV`u0?{_^wFR!d|ScBV&JpC!I zw^TYc$Q87a1llr%3g0AybI{ko)?MLF13e%bu_`VL=|$y#I8k|D6dlkyf~o^_%Vdif z2P3KjLUVlY{9!7xr|EPmzGF`2Qsp5Zd$=kPy{DwLfR2c(>4Au&+!^V?=QWZYM;;1C_}Dun zraA0*Nq_*N2|_7bIAjqp?vJ+WqU0EbVKyevq&j!65nn4oG{LIv>>6>X;0&kYKCm6CW| zES;L#f2*W*tPOG%{#kK1ZHN?0jdk+X$o?=^(V>di82p5lLRj4_P1jn|0sq91NVV`; zhKd(GeA^UkBsukExcqY@uw@UE_!B6NB~mIV#e7;B!5)R~=KH{#R5@KJ`uV9|5}KmR z;8KbXhJh`FiZuf)H@V9CJLNf8h%J0Yu;3h@+ll(o3>cG@KV1r4ZLyM8Mxq#`-fdC5 zBP>ht)G8MVP)f3!l|+quXx-guyI!20?bfKcoVGM;qt2uEJYhyc2#4s;E)D5cRa2x@ zHhfyA;z!w3J*EdVaPtQ0Ex!=XZgGA<3#>w*POr>BKpzPnSvY1XeM3>rWI|kn_ieZn z)DUDO%=}?u|7hI@5>+Zz=Tny&Q>;dMQ3Mj+1@fjOVyw&Un>Pr5DHzfDd8~R8`luUZ zhD6AsD1&7SVyk}_;hUi)em2wuUb41QcsR0$K9KdRUz_`J_phG6g?_(6%@cH=9RrYi zKW7`>aT!Q%%jID5U`VY`6Ok#wlH7hWQf3+eg^y50|lkm@Ly$spKS6X=fzgb3mjMud_T!u>{XVP zGTHlYXtc*8DvrfX0biN&C77hn25cX{Yc!H(Jyq733&u_ZhGqiO1xiD+O94I;gE93X=lQWoV?-K28qe#-$`XqQ`Yfo?dXGn zz9)TF>>U=&lLJI^2_3~}P`<_8;G3@e81Ws^Bze+Cy(rBYN}+V1z2x#) zN?I}Zb1}W`LDYa0b1RQlGUCI@pY}w9k%dqI`tC+Rih7!@)0ICAsx|5$3_by&)(plNvf=7XIQTuc_I7r6@qcqw2CzmQH;e6fOy<-y;EWy(m++@w!4O{DmjJp&3i@0o(sFA%Zgc_-=;7e5`HOqt7;v5Y zZ!v|71M25fN}YuZy#T~O0TP?A(5dZcgLFgw)!NaTKwkqrs~uz3NIZ++-AED&i@-X= z8=BNtv@fuP4@tpN=9cB9I1)*Y!~v1h4+FAdv7wg!%&s^QMd6? zfWFq~p%d=!ROvkXZxap{gm~im15A$>EKfiW3~{aq3&WIS_?%*69&{ydiglH>CpL?I!-5D*Zq1vwey+&5+?sLrPNXyCx8; zmjsRtc#xVj)qU2;SsbFXXv=w0Z<=H!d7^GJn*?N%Ru-;ONO^U(6d@qY8x1L|1faF zxwGhkaHpgECH>w|^6$OnW+>QIu(s4Hn-ZU@E)0C_#QJ$R6_Cvh>-x`mw!gp5U21=E zjx(NT=`SHKX|C<(=01B&oA8S-Xi@(zy zc?c``PB`~q+UI;(C{p>5w+2Jy?^yx><2{Jx91nG}@nv%=xCEirpwZyW@Faaxr?Wiy zdrIlgV8i972+=LGOAAD44pAiiJEBLw3O;wJWp!9RWSoJw&IB4+335PT0V&(^bM($4 z;`i6>OMqk4{z{m}CcNTqk4P-^!ctiJQ^~5q)>^vNqDYO%H>k$}&>D5mvYIS7KfUIv8c)ocRlO&SNWe2{pa z!KMHM6mjiUn5OF*q!Q8;)PeT2axX*YNOlaeo}=eSJu?!S^t3f!*(pAKPsHj=_U^Vi z`H*md9mqEkx)MDbm>l&%<>l>4%w8)G5jxKCR`dS(=YYaknA2X9JZC@T zTlRgok5xgf2B6HJNHL7z#zi`YPFx)qJ~S#1I?Maw0bxI)64ilRP3Zm;5>0aR%zz_T z=p$RDY%{*9tab9A!8NOHH|iD+HnEj9d;z~e93G#CmRSJvYQ&e8*^ZdM|7U{BI@WAp zvSb31quLl{KH8Fc3i%m($Y+2~sa^3?eG?JPGYIL7mErI{9kzM)S1v+-OTkHe+*4z^ zIaZx;O6~|R&&=gyCxlY=0rM3QT>d%h)V_TW<8QUA(SP}bJza{?zLsouNkPb_VF$#T z<2N`s<5Eh@pMGB2Rk~sG4;MTm8_eYcQB2hjPu*9-jfgU!I(~yeh@XjH(EP^4r&Vv$ z?9H(e_~@=@oc`58zzP)l;XAM%wXD3D1hW8E$(3BW>>8c*UsgECUk20TIFAJgky&bx zuz8ki8V=1I*QDU_=;sTDX8nog6Pj$ROkGr3w;~inLm?OU z4OzTi4uV0H=SUb-$=K0g1oTYH7GZs;qTr7jIz=1X%>}+UQP+9)g^UXMf+|g5wN0QM)0Ac~xm8um4QFxQCPCGM1*m zzjyVQfQBbI(t;py(F{DdtYO4hThoGO9;wL61h3sU^tcXnu7dJ}Rs0dd#9ot0Yy)b! z)N0eAe2BvdQ9sJKCXJVnq`CkO&GV@?iABw_F&nV;IH{ss~R@c4218 z0P}VJoQ-+4qByeeVZb(H(G0}WkMh{gGQNbEP!(wJVTL}6@RgsQ>77d#RC4vFb=qUD zi%g8kwlftMO6<97Ay6+k8|sfl#d@NK3DsVZ3qv42Tc&e0m18>Q`(f8F^O(3fPgtU_ zRDXLzN7FQ6hGc-wL}EO|wFmM1MLFeDpREsEKqng*SWlQwd8T3*1#@r>h_8>$maUoE z+`x;~$~M9mhGCCYcGvauR0y(I>DMxXlkmpeCQp`VfQwIVn%|&ixLt;ZO05eb(v?;# zz9;c!=e+Hzx^f?$NS@t(J{H{SR4Yoi)%vo;sjZf=>xK@5lXhLkubMuWoXUGwc@NWfJkuyFl|0%3ED!qjyUgp>bg zHc&>!Obrz-VZ^Smv)I+BJr27{4FR2*#@SQPK&*R1ra`Owe~~A(yz#k1T7(}}X**i6 zCs1_L#3%G_A096VZ%d{xs&lU}6Z}we!8MqA&93Zmpl+zw_aBO874bAxQ0Di*@%Mp?CX7|PnyDJl6f#+eZpgB3Oc4b7&ka(Xi+<2y_LHj54=pZ7Ifyb2zpkMa{&!bf zIVr|{q^039HNPk<3EeyNwIZXQxF*czPzHG~@LxG2j(hVL@Hq4Aiae_;kkh%MsC{UJF7%Chm0|EeABzqACV|xr&Je6Zsw?~^~$7Nhc2B%OL*#HkjR!1)H3KxALVFT7DIw2^MYc`!wUT$ z$PO-01h3o<*|K;G@%~M&HE?hKG6zgLfkKeBn3bMsac&;% z80htuVn5{V5nY^WbG`h3K4i7=hn9&1SF{~IJi8MW@7f%@*>rPU`cft3hJS%O+p$W* z=zo}Vz#GTO@Y-M~8i3!J-n=Cg*o8%iI!WSFC&77h=#cY8G&j9hma)vzAr zmnF16!%Ol!cpy5s8R>3)`9z+b5Db@olA+2MNbqtm>08C?VEcxnEwJT{*W z@Mw(m2TaucW*x$nyv@h@Bp)|j!|s4+{|#?B=B`3by(4bj?-NVF?5Tj~JEw z6kXMMY6<(DY%X}AOgap!G36hF>3RC2t zYI7q(0p`WG*yD_T+I5+QQj$@sBM{?$M!Fpw-DL~bJUONdC4IJ#wW=AV6XR^_X|pl) zs+mLf-*kIPVul*#A$ucYi=hiWcR!D~B+-IEi*(t*KQZaoWBAi>|GuFRpPVasTJ3^% zFA~!dep+wau3`9&VmJr8CbGis%q_6s=g11YTKbi|*(!0)m?=BM#O%)-?*dJMUqlS) zk2i?92I%%+a_r7;3Mi+;qH(SgzpR$6px(IRy0SuDKPxC>pnKGZzqKRLT*Ke|XJ9Wl zQ<~s0i)D>jgE39y3@!r&;{2bk)1dLF-CbD#(M;2cC7ZfB;7f!QTwTdc6&4(JvXY zN&7tez8!TJ4h+Wc${t2i@7v6$<84T#V-ERSBo87GyR;o`5AJR>dDe%5UdjnVTCQvd z$b>d_7P#9{n4 zUA}*S4rl$DK8yy)+n(6B;6C%a=zX=Ppo`m9^8S`)IE6nl5Yf#Zn}-wr z(ow0S|#dyn5oPM%9w^a{f+_dbPyT{Zh@;msm z%bRpT6-hKK19u&mWye%Q%p;+?7={mM*k2Q2@XVzaSU#+R{VIXgp5d!2Ny>$TK9pkvE&~Wt zBrN8cb{V?u?eq9I&{mLnF{2hSxH=S6GU!?~ukHC4T=F+N#kOcGQ=Sj-fEoVt3C1}U z3hUK=tcz?OhoYLbN89y|_AwJ3asT?>L9qN_x$ii>1??e*3lw<^@9JW+XEDk8U%{te z&!^zuud8EqYY064Pndt2)j@Hp3I7J2C{)=CM^MmU4b=BF)t3iCA-^4SJpHe?u*7)8 zz*jRx)g~U#eFt{#4*<)=H$bomES@SoJ0t38FPwi>F0VIQ`t(V%PR$f=gL)W1@7@}o z$FC>j?wOxJ;vI%dvB@=2jVvw@SpQR715cN47HpS49e`SI7fjl~RbYF2pR~*Pln%#i zYq^x7b8-18bSMMdw@kYbcl8{_CSDxyYdQZmAw%N--qJi|;M0c>*#P`V?bf4!RakT~ zne|RbZRsl7{`X8~yEUPKM;gSt>n=8Pm`(5)UMA4sE+umqg z4}%-RIgi=$Qw$_O2xY^j@3V7`x4y6tfzQQoA}y~Zm}CT-3Ah@a&wGHVUC-ZGajpGZ z=G_N#{$=yjsDPJZ7|VvltOE0=u^zF}ut0EgCBIxkHseGQXSl3kP<)GsmK1%$ec;#- z*WOE+o%jY$Iv9^%u;mFE9gLTyw+`oADu__(@AkWzS^wD2-d&A9OO%SW2mV2f-|CHm zrYd|)rX}f4U+?Zvbjlb!RgOfiy9|8%Z5F|?bknIb?0r(O7#_mLPAJ;Fp1jCA2`dS4 z#Y)C+d@d83+sJbKX*Uee>o{dCA6vId7*s8w4?DrUDtO=O(0LsA!B?(FZ{i^R?h?5B zjjvX62$5KW2L6C3bx{ER=hiOFdX62-W2=G+Dwue^$4%qT@3+9K!1U3L9t96ke2R6EW&v$8qSKz|(a(Oa-07B>*cqszH>jcuq*D1I+(U^p_26snXT&j;yLp3>rfpe4uSxb>?MRBzc@cTra{h*U0yNO=81kvP3x#7OKYJ*|1Fwi)(>U=&4d1KOc&&ex ztt>O}D4lEk%=Lar^P|vJv49pBvjVUv>!E^3rtA775Haf39ylTcKB#tDA(&-c;;L{y z+1s8qcs9fd^>e;phgaDc+`9^rE(cty88~01I3s$Trh9%9W>X_S%omjN(UlPUi=V$S zQyS{a6ih#T@fFUGmg8MPT?*$SPbpVFjlU3$Fk+xl@m=T9;QPv$0af zo3vLKwkx}~k$d@F^TrMltkX>Xtb&W`*5daE$IH(*Q@<~zpk#HY!xNB(zw1VqR0fuL z43f7{jsFc~KVJXJ4f^}dbl#7;+h1$7dL8wkvZD*UTOGLepYWn~j*&y+({S+0;xT?D zO_ku41#!gL>xtQU(+BjHVsXRMGV3|foO4=$> zEhB6sX}s)4Ql^{unKcTf3)6EEc3$>+O}&F-z(B086n0;Z4AIxF;@6_K+=K1o+-V*Z@=X(lv%K+upq_Ec_l5fMpFu~!+C5WkvMs`(CrNF-yZfdEd zcbeZM3A)P_v+w53CZD;6u=NOOW>st@2KO%7IA?#x8?-N}Iy#ZW9m`|q(A_mJAva7Y z#A@Whi;fH@Xr^F0PJMQDc1zOV3W9rK(d^U|QRO~9)W}gQ&eME#0=o+WvJP^X&&nJ_ zOuNzP_`KYE?gKk2C&R}7J9#5ABgyj=z&ZSRBo}565wLIWA|jz6!Q|o(GB>3cDG#*S zeBZBbn;o|w1}pWJLT#=>i$J8`t`8-6{4N(*KVfys@3l*L_N12u(I5$^3-84RB)v73 z2a|2|iUHwYskNFuH|H2Lrd`HQP9^(~12@uU#A4882E~Fdi(qffv(eQPUtC=aJ~+zx$8s{{xDP^A>&#DdN4xSvd(NI|KMSYEFVk#J5yMjO-&ZPaps*c6bJ^W$gbV zhagVr#6Ef9u#PPc9FuGcX#-7Me-ik&FVjK0#n+Ob4?^M{L; ztjZjSPL4fj4 zU2%tJDL!Ik6P&4|{OrYfCgu0tn}CX1&+}>f_hcIz%P@9hI8N7Qoqv?hgHD0QzvOLk zmwW8_Zh1gwFGYj@Binf{3Q6Nb=ErCjHf48+=7;hMBbom>=hZ#*MhZ_)Nbx> z1eCP#mr1YW_MgSuNc8l&VVo-lZ-Zt8o?Uk;lwuc14A`6$yZN>%+d}vS4tX&2Du4Cj znQ$=k&yo6mORo#*>t{I{0aNO(n3MY9zElR)+Im>G;h#tXHn6j0Znx8GKS9i6*5(al z1PayiVcQx%turZDXfNdXLyfM7V~`^>6r7nK(li=WF4pTO*8kew<)9pKA&5qj4Uqo& z@?Re6o~{!?Uxx$V!+VIpO1t7${l48`PM>$NU5SaBxVT2UG`POULwwqtxb`_52?lnl z^Q>tp-#ql-_=2|MfMyZh{FLIAFo?spVz5u^u1ywN4%ovS@%JIZdoI}B`rD-06|ltH z*tE=05%o21{?pi_kjx0<$+vO#;)OFs^Q8G7dy&&qu*OQQ+a2jy8l8gYWhb|EPom9U zcy71_NrE%o^$;3n^N{;3s+^f;w%U?J@ok+3-9?3gRM*dM@zOE8iG((1)$X(HA()u<(ybDW)p)T2U24sf`SgD4@$AV88Z4=lRfqQh@o_%-;qM_z@Nijl#(2=y;E zA@)O^6yVy9PmUZZp`l{O#lPKN^d~xSB`JNoQ_!`<&kI)si$s=(VC{z^)=_it zKhN6Ccur+9b8KurQ|RgYkWoJxK2tW%(v|ZD=9I(|5*i8k2MECbG-&A$upDBrLIgwc zBLORLpPDh)6e({i3uAK>IntpsDP{!ID0?bDj;~H*k}2+!icKSVIW62)g{6d9dsLKjBF$@SJff99Pq2=#-yMqJq zkoYRf$kF3)l6J5d=7vLvj#)GZoJdN=@gf_ij|3-pM%s4mDa6r8z|!mpD#xs$2oA`6 zwRlC)#11-&Edmccj#(A=>sn2Tno97_JG-FBR(8W9!zV!dn(*qxfQ+Pr%}a&}l+14m zJ&CR2;EkZIQv75HVORdK93AY%@|2WnQU(A{s=lQu&T*gPu(bi@wH6hjg28dGxNY|} z_rr8DovvMj9iH7tr+;n<3I2i~cb%hTCZG3`~SGyAs&ThQ2)_;=9z!8btT~@$GzY zdaF$ikqgejzz(OfLs3=2SG55zq4OW(a)V8b(E+&wPQ~}B_M2?(kNoEGH$~GI*-T&z ztENHGUck0cBG3dc9o*)IJh&5Ln(iAu&C0WqpcjwOXLN5QheoAmnU&i%38#Tp!UYioS;oSSp&t_ zGIX`C$?%UgN^N=LQ&%t0x>zlQAGYiBZkCY#J9ax#N_t8#jm#R5rU(rIQ=4C1PL-1L zf&6<5*?Ra(u06oJl?3SpyEVS&&!|4t>Q$_M8K}-UsoU{olc6n7d+hN3$MTHENT9oR zdYJalhlhO%uNO=Xc)x5T`_R9j!5g|(#4x4dK+HIPMvDp3EsQn~R6~g3{k1lWzQEGV zwDUQklWNRXvAe2CUW6QsBKQ_w4wO;0nkm@NtLxedR%Iva)duz-`vT!_Z7c+ z?XS#nE1S`JAjAg2rPMP?+jMr3cd;icFzR!-APHQ}hRvG_swLDoX$O<8yI^#+ATK?K z(Wj&xPsbCy00A9?gyI-`(?%yDyJReEJ=&UtoK|s&EN}n-0aRO)WK;kGt=E4kVE6Rq zi_F6GyIL~1y|nCF<6J~zqapw~^352%x6*Q_r~Dd;q|b@?*Cc#cNkrSlWptJerh5jF z*whAee=J>UWM@TGZlQ@&wf#RM@}hey9gc~vi5Mae6c+HH__uPeA*uGWl&Raa;V0B? zuP3?Qm+=2Dh&`=Aq4@MxjEX_j+D!Ova~1bnH%)FVD<}u1xfh* z>Gn$Yt_#F$pSDWk{S*-IzFnBj@)t?3ArZt9%%ezmj7JN)tZfbpBqPM+XShG;4-Av< z^ujqrxKYVaC@Ipn5t}+`;@0Jm{*9o8Ni#$}{ESX=6E~l<5S~_LX+jITOG#Q9!Tc$_ z;A;3P;E6g$vJV_`y|w(I!JbXQ)%|LkqM@7@XM{Q^^PGQgMgbsT$Z=c+&rYy>HK(s5 z!6-FShCD6H>D*dVc)b(<&i;j^14lY?2Q9_c#9ilqZAP)n_AAUnt~sa}nl{pQ-^MO; zfC1FtcbR!8n4fjw|3pS7d00SAG z9C0M=>5V_tIy5^!))fDQ%KuTEh*E0ptU(u)tkubi?x6STx0r%?XF-!AbL&_FluBXD zD0KoPQP@wyxTrNnDa2N{bfF{*rF0u{ozP1BQ$NsjrP=T6L5W{NoOatQusxJ7%sJY* zsPRTE$c&(I%7@gqmg&@PSW)Xs_eGN*WGj@aG-`i9;(ox!pEnn|VT&YMS$lKb6qO6w zst{X{(|3omcUHOOv9avRpZpQ7?Fz}^1>ZWMgBg}tOEfgjWyo6BbzE0ep)w0)m{ctZ zP`&qOUUGd^T6l~CHc3k`?V7zdZqyQX>78qK-ei!_u5p(i^Ksf19kLH$#&IkIV3;LM zYT+t|ybC;U+-aIr$>tn(YW432nAD9h^J6D4E+T% z*ONbwO9W`-y$;=1cxsJ*_d;8OKIyMN8T@t60Ui(3+%jxqC$!M4?~1J-G{7UiYqB;q-N|KM<7Xuh}uVpa5{y@;An3OnVnSd*{7hAO#`7z~tL!6y4$B{tz= zLN@y3e0QF-Vn^$FT4+U{_&n+!XIU5Kd{i@JOr)siQTJ3+q|uufrKoevWrHo3hEX@9 zYv1qeIVnB;-)S}ued@YIcFlPg&kn6Jh{9PzLS~Ykgjc5UP1Xcat4i7_=8=6cGQ4^H zMe(GcAkjkPIog&SU!Wa0>(JU<(|w4O_-=jwgKMAo^jaIuU(xy)aArITWbD+&|AFc! zf3I+UZQ}^?wOKIim`jV!-qR4vwx0qFG;!-DtRDTrL*WGvnY_2cpf`=3`8zyjs&nF+ z;ALYKu6%^ufYZh)#(#O~F8)T@YYZd5nCoD>xirdX&Xe$Vqc=EOAbIf2)R$Yr37@=G zJ#w+l{(e>UG|6>qYWQx!Xl4nmuW(FMbGp^td^piKUEPV_5{ZuuIvUg{0re^)P_scm ze*?dP;^Dc&ILeETsS#9W`N~Y+a5`0-?+766-0w(UuBea}{#%H7w0&E)UfY?1?^{~S zg+BL{PEno^UPv^-N-Gj_HTGE;qTAolLCHB2Tww;lc@pKaD2vxZyX=yYodaklN+)b0 zj3{q*GMhFuAFVD%(U;=S z9k|w{?k$5eDWMu|@5)b(KkD5n*jL(Dln!Zj*q;UOw*w5Ld&$94Qv~2DEbIQ{Mm-yP zek#n|E(pwAAZW3;7W+VilPUl+K+L~^P*+^d{q|xLaJb3{LKN8nHDS0ljFi`)k=7>( z8nv|O!Ck_%gsnHUjJYm_2DD058LiO{K|=;dW|eG^E-W=Uymrj?I0;2c=1&K9(zw`M zl}Rh-aCHbHwx?mNKsdDB;6VI@WmKdeg}8&Rg!)+KIu9zg=M3bWxegEkeQT^hGsY+D zudPVNwavM(V7}dIVm+4=#81rU z8n~n*A`Ofu5d9yhpSku9?)ue(0EpZ(yIV0HR#{yw$R5i=;W&~4u7Q!3dk+;Q-;MtO z00IZKso|m+&V*D5YinmzvnWz&Wk~g?j=kM9haP?v&j!=7Um~P^D;pL2fvqFc4QvWG z|MK?WmRxv~_E-yTOq;KjEPpIL8$ImDZ?QPVNmF8%U;!AnTF~HX^o`QNar5XNJX3T4 zC#ZfmjPgPev#Us0dbE3OA^L0h{NM9jPb>5yQB^FZk<@uOLE70tO5)XVQ<04ZBuVM( zwz zO}MIM{(X6X^)y__)oaknz7z+XFS`Ug)5!FHa0&RFJCh+H`Fwr~eg9bTA9`Ef{3+K2tafWI&yYK=12X3V zu@jJJMw>blm;+3V(8-FXXwy9X)XGR&1X`8E-)BF3EBjkN8&TGo%m4t;Z57fmSR~G9 zG9H}(OAdL7)bNZG=(6;hm8WoV)>>FhtEtp{`Fjvv-sAB>+4qQ67g2!mDGYwZ7tN%i zSDd{dW90}l(-c!EbH+xl^Xqyf`+ro^ z6dBS%B4U6C*RC@NvtEGi9>T3x(1Q@K1Egoc*G$=*^IcGv<)Y4(xyf2AT5vbAcmcE2 z7O7|~y)eHFny8CFstuo~?zkp|RbhV5TWcZNmlVK4E&5b66t^X=b|Q}d9f%gF+)qO0 zDJNQ^*?|bEl@3|Wlxz#B7*4S3)w_q!6{%_@iTAp<31QWo^!Eb~r)5J& z9A;+99>)= z8%vdU9>d?K!eLhwNsht0VGVVd%rWyyM{ zD9y}0BZgRX342N=9a32;na?RyOvSNAVbj*$ZlQ+?!x|=i> z6PbZKQN}XVg|*tce@-4w7`2wWcP`RVU?Le)Uv&b=cU2I4q{|4`4qAMyvTPoE*Ugaf zuNQuoh#Ely{)7ym&)c)Da?ks;xn72>LyrFlzx}VN=C0)7YChVjE$^38ypI7LP{CSl zOa=06tX&1H9fgS{p4FSr^$qX^vwg`?zmfWBZa|^k)&x^$A{#|Zq_q5efL_zYqhoxe zQO&YDr}P|2+NMc*h^D(zha&j~fafwW{)1LQcJgRytCbrs2aR*pc8v07=C8soLbd0|}?SdA#Q z?KqMb8yih;r;+pL&Nw|vZ0_OX{NM&R&!GFX6_*-iUEzE`a02Rk9wT_QxYz&z#_#|~ zup?CqEjj2E6Lb`By(FQhlRX>f)<`+^^a3mV7I}bVt zqnSHxaz4>RWph0dx<*N3hzxzl@kB1)#8I=EYY;H+`|(WBzR7CZzY~M0vwLKGCz|x< zOIxnSq1gs$s#Jf%oICu}RaR1P%6+0ydvwZ}Ra1B@18)&Ib^TObw1Hb6qn0||_HrBa zcN-G_yd!@EUkh?Rg~uA2s!d2O{ozgk=Bg%Wz{;aI-lGyQA4bh$r&DDGR7`xx@0R;C zOiR3ZtuZkYHY&kvi4^ChRA=EU)~GrD;5sY9z-IChYA0GQuP;g$3tJ&HX!&Df$hwE0 z(os4Qdxk0ZjxULSiAE^#zXxSPGN+6;)+cg(uGpSS$tQI*CId2*&u zHOf`5w>+f?unPR);{6R$s^Zyjq;uD;s71WEGN11@*2-Dgx{$I+&g9dtpP%I2;AKi z2@M50!dTt@zF9<#1bvbh~iDpsxvZ z9@1gy2})}G(Wygp2b!PM31HfR^YiFxZ{Tg$u0ZN_v>y7}Yzd zg&@A8pzOYYMNSY;@ZNUyM9l4|ICegj3^`PZA@}>tISjP|3J!$W;A@)o_j3RUws8cV zcj1JRL@$ylRYcvnUMBLT#fNhF7W7@L@HSDB{GT^u9FWD^MR|t;USfVnM0lbe?ZX|g zUU*yYdP@YjGUX*d8+VrBUNM8B!XwUJ65;rXQ9G07U^kg1x4O@dtYC7Sj%ebj0yiT7 zB)kY@lu0HeF`e;>uP+0sAW#sU(FZ8A`m+X)BgI)9JI?^f#WF@Ql?jX1w{o0a?VfG% z^2zAD5fp%s{918>6JcnA?x2qKLO>tqW$b62-k_uKCL_+~1SmuthFZQ%DX&H<(#9~O zsWInc$yeB%75w$w>_wKe>Vac+LwnbFJ*0CuiIxHw z!u;HQMA20b`OfnOdgPgnHqJ#$?NvU@%4mVS%p0Tecf;(kz6EkhyrT-PbYn89H zc^#|a)%Ht=h69k?=HpTbO)(51FIQ6lV6>lW9(s1p`WAj2pwcW+T_5dp)&<`s`r?V% zTu#T7xtxrV=DHz%b|+MC(1M~8^>yIzf-fm^(59Om*AJMZf`MR@GbRLLT`r@6|FgLj z*#h-Jco^7V417992O?}(1q}JZ4fKC`$FjofdM#&Pe#Yspwh@td!2Q9L1w zYA6xtNU_RFRN^gT9_UI9`ZPr^1$Gs-a)NrN^oE9>oAIP5S?lG&LuD)iSyFziB}Q>N zCVLJh7|lvnAdSQS3%on`iaN?y{l@G{8u_a5T)ejt7OwdaUepeqv$c*tA7TEL-YMNE z64gt{R8I1Q=BGkY01hONfCD->5=n7t3r?Kzb}VWW+tj8sjv^tWBA&BsmS87Uii9AN z-Zu(G0p$5r6N_bxYPFOccbS7m>(N7q7XJ9=O+(|Z14WfuxMcOz2KpL*vPwCQ9_h!# zTEy-|tjX_0l)5wUV*6ppwaT=V>4Vu!_;^EtpaL{5ZG+BzK|KA4Xw+%q2>LW~FfL3U zI8iquP3Q#qkV=JE=(0>iedvZF8J+t4eL&^GmTkpr3muCEK~Hgc1UTM8GeaGqEMl`# zPJXw~-Rwgcx2^u?q^nj*0`<|evYVD(eom=vYzmKebn2b!+MmEWTUc^TL*bePQlI2tSc^1PB^#00xSAZm+8G9&K*nnXZLq&kKuq(^zmw`15NybN2b{I1JW4w$l(z^9cbj`16H>kbeTJ^0Sho_h%;C zTu4=OpK}D;Dol;`eS=sa3{F2REvzbDcmUADji_0q_ZiM20b;R)wP{Z~z^mw69rs7y z@nnGYFry-C<|MNN+Fuc+S8EY zpv9-k0yzn4uW?`eczBa`=q;Ma`AyF5q%M!%-DHex$Y_D!o<&M5)q%kPemaL6{T~E= zMNn5aPR0LT_r_lhHK@Mp_^9?MFZW2|Ypyc};UtEEr0i{RM7n{=vU#0)8R^u+*_;$^ z-3C$~1#y@<8A7pdTH&D8K1dN391{e~^FtGM_I==%E zA=#->LfOKKS1Jnw1`BUy-`Q{lt`%@)or5;~YgNsRRI%;}YUb?@_Ed)y6D5Fwj} zLW8W@<+BE8>=7uCWowHLd4$0Rl8KjuH{cwLo`)VDzi@{EgP=A|8Sbc6Rq{+hSFZR| z6a!mk^_>gsL)wOZd+YB{8azj;A2iiwYnF09|Ke@4xBI<$vKvL~E}Hbdj?K6kQy1WEcEsJ`v z#_riT)alJ*(Zf$TTUS4)i5}Mb?PTs~0`A2j3HN{`C7D;P1;y4{E?M2Xl@y^pK&gxG zO~A0hhe(E{&lTUKqzVj_Tb{~zz|7GB}A2YP&j>j3ui2Z+YVt&tf5VNqs~{%x7P z5bXLM8q)oie?QT>Q^?GLhc3+26QQ@Sy81kY0BV~8r}0wMd^eDUbI4rw`-h6hiS?u9 zI+&1GM4<^qOsC;f;cD*JP>)MX1z}cgzaun3;RLi$9c5iipyFEScVXWBTkN}}pf49= zPWrmm*8V;b^WKpB_ju5F-&bQ9)&u{RVdfx5@@eM^6ka>U95kb@^yC!BO^kwH1etk( zQt=b(Owg`AFbO5c`1oKp?_iCuQ$ml%YR0MrM|>CShH^M|YJPL@mwkhez@$X+6LD0$ z6uQe1Rr3?*;f}!$bcJwe)ukj{;eZGGG-?8{#R#;}8~#LlxC$t z%jjlkFO)UnQ+`iohfoN&vnZ%7TUn|YA(?=>9KMTN$v18VghVLS24*#4hJYe50}t>g zM_7KDCgty|Lp ziZhja)u4$%286y!R%ZkRd$=2Z?4e0AuR0 zqWlvcbf9BJo_;5HsQB4itVLJLI|<7dIpX5F9>6*~^uN?Oj`*D3O)UOodLx&&yNd%3 zVV=x^3nat@G;}yN#&t#~!yzJ3<`M0APU`$(szn^mhaj%hTeW(VA^TuSA2EC2b4f6g z;;6*Pp1BqfvtznoBU}bisbkZi&t(RUgRYDDFvuin#-WfouMU?1m{v9vx`(Xev^)lO z@f7A2N(qdzzT|k1;oxvaDD{grkoO?bcW~xTH5xIr8y``UqnG)&`zS|Ju=&Le!B_s~ zB*)F)sPBD6!OTIm20n^~Okb{7FEr}iuFB=)@6(^iyrWBKu@Ytuz*f}Of}4L1>C zyyg`^;$}P%>M1N#`HZMeD$%c{7w!&i3$8+KHSvD&;0?-n`XD^5B)I+6ZXiBOfk}cV zbHCB#)o7*7sfbo(fzI9I`u1eCK+`gF3Ti!O=nFl)jr(W5%DB0+$3{3CY2Km-GSr;R z@tGl+O9As*o7T|}8`ce(i1i3vAskGu>8@T3+4UvMB-?uGXbXd^o3c%axzi>Z6HE8L zCXn*E$AFI=n(u*r6ZA*MYg2SZD;wzK@nkR@+ekX1R&wXmhV1QmCh9D7i2sEH2oiW7 zhne@yN$|`Z5UI`ga(3KG?d0kSyR+w1}JVN1`C0erHqn4*K2B(BJE*(gnE zZqaLt*1PVGcEDM15deNbJmOwn7nIX{NcEvO$Oab zS%hx|N_Buij)-n9pOM_in+ifA53hsHP(6t)96>AbC4%}`*l1a(*At^5Jy)I`MCw9 zJ5;+{TfH66@8j*tqxhYnQ{~!EoG@et#V8t?TS8$|YVKBe^kdp_mxL!uhh_MTkENiv zk;k#d8j^SZf-2y|BCS~~r?y&FH=6e#o1b66v{-}nr^f&*Gj0G3vMQfo>Rpmhyh%tp zo+ic>iwPjNKbHENx*ohbfOQXAb=t_=#jcx;lekJyC~ecBrIxQqQUw+SMwzx!0r^>|hhXKWfIW5kEX<%^V@MVk$pw@et)HwS}bgbYc>#dD)9SU(l3Aa-N2 z9mZGKF(sF!T5Q!@j;*8{T?HNfX#0AT^t8aQns*cKqikM~;gh2nN6!+OZ&;SRJIW;& z3irMYOnojYu98rH(i&eG-c0yFpE3=^zth2*x1)`8YUb3?1S`TPiz zAcLOepC`b6xlo1APy&p9dyAJ8OJ}foT^Ft6m7vq5--vV!sCQsxXQDK85LYM2%dS;^~^#tU7Hg^`bD!i(=;|Q~ZduQ*617c3n=9r1FC@erUcjREH?(`6}&- zsplc{>1fv={*A5-y+#Z0r}2hes)plEBB20^@C?7JB}R%6C|gE5Mt}~N5e+sI8zs?H zq2;roIZV~)`{2&1)~(_O(zxXKFDL$aC0nw<5$JR=ajTDK9!iLo3k!#OCw6kdxo2=i zgyaH!@C=OMDZW)XyK6qKLN6twN@LxWDBYrc{%a*Bfky+BiRo5Mfzt7DQFiOHYI~CS z{-m=RF4+OAcPqiI*&1MVg9Mx9B|pV{O42;3R$q#^DL_iN2X&1^Ks=A3~1aR2NzFv02l zKotE;ryEl->cnG(aD2GWW%b}-*0s$%0d_Yz5js9qLR>OfP;T->w43)*xZaDymeDlezr(=`ISWKX-}%jIcNV zDhI(hgA;d|b`;vmvBGqF=8e5DEcs0`P!Wan`$5sdDVpJvrU>CMs*1RAK_if3#~$gF1U- zU-+71r4Q(RKnSr6oDP*G(_*^T?-wO;*hd#sS57eYB_!S^K!PB0HFx_f9itZppO3kc zx;}XXW#ON!8VP-*1uXDF!H9YqNa4co+{x*Zv>k^D#GhW6VmLSPRUU5|@PBT>A9Zdq@Xc+#a=j>+G9 zRbBGE6-f|+jwh?ELU;u!z-U+pi!=G=%XbH{Tgx*YKsDzH*0nt;G&KG-jZm(X|a5y)%tFyjT)T%Kks%e#9))}7ui7iyD1*6(? zQU31`^YLZy4p%Xq6y;`YP9(vQD%AkVg$3@Vf3+w~I|dDoleRV8C$|;;m*p@Alk)l3yp{t%7nD?aGCUNNTrNcEU*X< z)g41#l3m9z@kWWmk_1lP<=1Nl(o0&9W2X&E;3c058_K5YUGHw7OwYdrD$_ts-w2cL z3C<`G&e66>13?Lix!o5+EwuDB%W!VdZ%J=hY~NVCNsl)40uhn7&MO!Jb43H{UmSk^ zY%RMrBju%+AST!e0t%n6k*;m=VS5W#t6!oxiuial)KfUWx2VIgj1iJP4%;mJbP$}C z9uMchmrtQdM@|K)#5ifib+3?hGFGLpJtIamF>&=cp6forgG0(WE7Xl!7|YV3Eaw8( zgy{WE1Th#oudBqD6Hl?5PXGRF-cm z!iciUYU4Un`EeD!^A{kT;+3*i7O%i%g7oH*zCm5H`dC2YG{Ic8w}!)2S-{&mbsU zSXhJOxJATOJNU`l5=9@CxaaUrvwqe0x=yzmw^vZYpqlAyUz3b4rE#q7 z7e7D9(K=TOR;8Gr(jQ2ITf2No3u6qWTBEa_Ai|cU`k}9bm~A14h5P@sKfS#)>NIOj z#IJ(uJG=vQaoKVJmJ-1D3gqZmF0=Yx&xB@vCeo=V*UUw{P zi$d?Drj>ENMU2(M-YU)BcdfvPL$wVTL%lwkLK$>VRGvAfR&!$pT;}jaX7_f7e@|{g zPI_iM1F?A1l7b___}YYKO&3TcD(=R8I1s{YXDf(tj(@A3;4N zNtGGdBOCXY%N+lKbJo+rid|}>`F+sd7Hn^cz7zP3zV$IxH5B~>W-yOlR#;tnsb`r? zrW8#Q*61fk4GI+$?0sBx?k%=x)7=c|_-iD_cg$0 zhN>gn`;E&)9!X11zI)Qf@Bc>2H7F(Y+$I?JTvQum*k14%`W!o|z95vw-}oqkh>8yK zy%cC>?wj2-0gQ=;xTKq?!BWbukGs#}y1{vK?oPrP{9YH`mp$JNw4fCRb5*BIC-@Q8s zOz81(=DGmPAr^-V=cU;;I+cNJn$1w75Pfgb^+zWF7dbpXR$vXGm5S? z{W;85=4cVY=)j-Qw%)xleme0a`qHlDV0>d-l#+ycblBs^Yzzm)mH+!d#m;~&_3G8;e`No(0j4tbPw(VJ#tfNh-`dw}VN4nXh~9UZ z&a7|>SlkqRqgGRvjk2~(-$~2YwRaP zmp@d zQ4n`npB%x?^3N>7Aey=kMX(|?(tq;H;`n{(c_a7iWV5OYBLQ2I6OWIVDrz`xuYJA! z^@9m+AS#Niu<638OrU-R+7$H}SK9o7B`F(!hKGEz6c7DZ%U$=|8>x|5!2AtPVK9ZZ zdpCI2Dt6~;^oWW+M_#r$26G?{>K_ErXiO6RA}pGo{(SSnP_#|OERx8tTC}VNuXLQY+K8PBi-~DqGohN$# zHZCGDp&v9b`+k+1KYZjh=c671;YVh=)YCM-4duGB?QJmuNi7{urM?}OdhrMINgksA zoBp5oG#~+rdka1P)Dm(0jM+1j;2DtwR)IXCW>m9&s0st?fCz97Ssg0#`@RFN^I&|RF9FR%@j@{vsLMt}!=$=FF+ zVOGJh@vfKw>reDji*5s7t`dT7(>kfg8d9IUEIhJ!nz|x`%Sp9+YG%v@Xqg};i zj!Gvmz3t=iJk-Z~h_1`Hi=Y-X=2}#|->od)4O`BuNlWUrbjOIxTqcozaZJ>&8JO^D zy}$doHw9n*Ufwt-H7(Vto@ah1O>c51TGi-7 zaC-)od}o-IFRSdJE{FLnv87VMJ67sXi?BY(X^6poP0WqGNd z8aefXD;-j)q70yT6GRVqJXa~ECEQ$v{fys?xi$RBf9XA7B91gegRkM}hT-vNr9lpG zC?lRT{&UGRjQdtd`O!(T4=})fc`~Oc-!3D<1qheSK$O;Y1;J2qM8e#43O*@=iZDHc zc|ZRAb-gD;GqM(seRbSi_tt}Oyfh-#0PCdcTb#X;-bNIeYf*sAD(=A09a&J>(O+qJ zm#z8!JDWovaPD8of^n5TP=VTeM#J4s2^%Ykt%z8}@-Q9tGG{tf`eECz`loo< zH6|6x)Kq5{r zsgu!hi4AzZvpz%7f2fB1TRVyn2=z=gEJHM z(Q;1!Sw~6b{%|Bs->8j}xI^dwf_AW4>ZM`|b?iN1hZO+y>@s<+n`%x>r|SMwjPy7i zK=J~E%bR}g>cEz9rkz)pW+5$BjQ9a6VI{(Op4HI=b+2uSi;S&dTobiYPPzIj-gk=; z#P23tCjch0Ge*lo>0RlKg+#q<%d(y{BRj*$GOpVxMQx5{I=>)OO2yFm3OX%H` zuIq{)Wx(CS<#JV&|HX$VH~?zKBJQZ&I{yxypJUzaQp$lYhZT(FKA5bpqCmZG?{Y{0f?VoWDYi*hTD!EE5n^8G*-+>?)QWPF93ejXxfCa$dSOI~Ym)M)yJZArj%LO>E;ZJ+IeGRZHCeYqfoMOWi8zF;*`RimJw z-SlsxONZuoS~P=VH2h;poddMlBi}H&GyldGI5oro6#wI}Dy3O3-HGc+Kjc$C;OF3* zu?<%e)m^R@m<&MbKX7T>k4qTYaSG{YBG~Dvve&8TzhtLyB7AghD#!9VaDQ!l=REpTy*UN?-Q1OHfNtS+Rr2ICqBTF*AP_t zSXLgJV>N72Vg?oRRv{usXfW1QTeH#OWCB$g7Q!$@cY~j?1QNu_SfaDz-_3Zal??d2!B(+qp!*E zfCB{Xizm%H(rC&F-8ZK$I?!Y+{21w`LRivv`_casacaTdK+nz5Nke>VsNy8yg^|G! z(tyi`YVVyGj=U~HbcnubguL(ICE{rN5h^&#%wK+ebT5tMj9cK#Qs6Ogkr>SST##B9 z2$z~mRE{AIyOLQq@w7X231?JB#qTq|Q-OWq-I~Sy;Y6=rtG+jdU85L+n2r8l!UBEm z6=PddKR$%3^{c6rDNn&j6b3rrfm=n4p@{;A{)Q?bH~H7+mgbX4G}~C3pY`y5#6-KS zWdR&b=YGah0eh+BKu#L&CP8wSdwSBnreoZ~1FrDdS)dxvaoyx(m0}hD@Kaua)Z!)yQ+*n!F}2n~6s6BZ3YUd=}BihcOXiiTPE@Uq*Wg&fGM$ zV(!CEck%rHOC#K&n#u6wr5TdiMxOK8ep<1_QJY&L<*yeVWPWgd+>Cic3ixD%6w<`H z`TDJC0!E{&Wm+K>shQq9z5zqyTBP#32OOy=-}W)0F}SA1L%}^waSYlSbglO5en~C` zUXkyYhibRd2kdAgn9)9;`nR4t9whG1<7|AAFQ0J`*_V!B!%BNlpwEVqZo_O@6mxaT zLvl+ARM#KA;J>OskJ|U}cYFyV3EED1w9O^R%KbYHgugIuM1YK|fCo$>3K>}{^w#MLxSAB>b)e5?nVWql`n{`!GMKa^IbXX)?%G2PHrKhy6EIP z8|Xmx{D`N8Y%z7s5ladd!^X7D&uO#xSSst*_eVq5+83nHK?n-OW}7Q%Y@oH!eRU6+ zK}!W!78!)A*8)S|GR+X77XI*8Vi>>VAO$y?{YxAX{T(_~yZ>09v$XvySbPkC)y;l9qdtbh?lw}TM@=mge zCHSg(Q9E(aC=B2yRS!4O5#5b&XLYlort2*GdbF_D?`$l>e$>pAZZ^gKUQ zw@|m%kPl|DGX|_JaS3BF#Pz`!>#kgRCcq+bqwzi1nU~3FKl2b&ML@~k%{>5kStSYp z69@J(4XeNr<>CYR1QOQBn_Ymr+A5^Hmj~_^Cegv4xo=W@XYp*w8AGqE{8 zPM$27NM%L+D%gBD2qE_&AJ4BVu-xk>h2?3vQtyLjs+-W}_-P4EXDeD4touNH?_cIo z4!Y}dM_s+Cf}tA4lhm$@>zrR3XZaOrFD+L#>F>$$KriNnBctKh0~TZ{d5IEoFuSB7 zR;r_C_jk=UWUWl>_4wI!&)L@4_sf(0cqTP^9AcWElc7aahOplJK4hLsd5ZqjHkE#S z;0Vy3GsLdvos-Ty-(E*o;qQ7CXPfUTor%Sl2ec=3Jz$%5-< zxX31B55Vb<>zw~ z_*k|WB%ZHSK{x+un*eJVa6i>{M3JUbE!btlajs8{dT^eVvG*PcH<0;xP3qN3JobwD zx%qiE>(q-uLRBoBLUW8~SX%_&#ZgDO3V8rNDvsV`3mxawiGu;T+m2PZ#a=u^06bU6 z^(anm(nq3_wg^u0+hCw!o@r0aR4CH8K9nqfr{7`Caw_W)ri)B}dFdlF(by<+rL5|OY0TW2`@hNLP3(-Z zr(ZXb+gRXhZCj698Z)9pX(N(>N1I$AnUml*vo;$-#$(K9s5tPUTalQ@>bx!qm!8m6 zy$9=#c+OQ#1WF7`uZ1{Eh*p>w0mEz^aTp=z zqVoDibijRdziq@F2*lxtVop_ z5jxII`4orZd?+OVPKliudB*SSGSf&D#}%ASvurjXoxB7{&Mo4({3@;ChmWjTW+RD@ z>~x`K2EoP+aF5Rfn<&(hamyT;kPBc5lmuNHPK{riGSo}=xO9)<-to9$TV|!lSF`?w zntVbY4O+I99`c*AVrj1fFrYOB=%d|@Af)Mht==`%bfCUAY)lsVJT&&X?mqOp2l#;A z$*A8|rEjtf5b((qd4s$@j>K*Xk4- zo&ZCVcAgM;a*Tnhi6tl465B+@8W6|W5M`V%8k^W6B6C`m2HbO{R_0BZ}hn>RqblAMU@`Y#RU34-hc0NXtU0Zrv-vH6_`Bx-e7#b_b84Ba)RG zMDxl4E9c^7iEd@U`K%DYJWT5_*AkZUFSa2i4X_1H)KUkD{gF%4(LO!6PnCdtys!K1 z&8E-Hw*WMM$Q9UYBUvCjun8Gqo(K>gWd6lPne8bxF0zN>YvD}B^@74174BE-o`D3< z`YhFLF=1`9u;L^7-9C4*V;0s>xDt`4&oMc3K9uifKR#*yMoe%^Wn_M|f~$ua?^)XZ8Uy$`GR2I}I($L)CO zI&}+C=YwFEu_-v8rEB*-t2U;66R&1D{&at4I6JIHnF;rVlq>%0ThzJoE8b`@* zAUKU>_U5j*?+V5fDLjUxX1JdnoKzy}8xBA18Iifs?$*H1;)b(x&V-#ZyMsKmwq|>j zs8aG>aax*92eTLHc@}I{oupj)k-1R|{m|M#>PQ;(2v2*C4J4K$LUtHX)#~j35K04D zNmr)TB#@y!dRQ#q@)|tLLH!m<%jwOrA`3$Pou;I1^n---^TDfl-crobDWVY;h%aHd`3ToA@X$)V{* zdVy;nt`%r03p<&-Kb<+>SA_?pPG`tMr+Ek0m!@|Z$+GAq0=2=p#f3yZHMQnF4=8s_ zomF!NQEN$@1eFjKfat|%<}-_&sSR*IagGECq;$Cm#H_QF`ehpFMvGPgu5`ubUUnl@ z_5~@cmy_ZCvRl-9*X^1d1XrX1Kd{ z91t&fFfKty3hxe9ItpBnd|@=B(}KpYbt$-`OJ~I{vPHmU0XrLcXaqE|YDs ztG%dQ4K%7uKWU;82yLNT_k&QsxEDE(dPD;On7 znyuvp0L2ZCwm7|TuBrok=)sMK{RREkG(8NVT5Vi}cp9;0WkZGX23rOqvFJ}IkJ0H$ zN9(|1ZIhiQb>`}(aW>yGN&;j{uVaMI1&stqIFvU91VG8IlA{Y5rHpQ43}-RU+cW!~ zeX%p}%MVNjS{(KIMXEe)E&2hzwc{vot}g&fK(xQ}5ejOZ>wxK;(Sb&QLf9mIlE$*+ z44ZMLHy-NbwEn6z_Pmc7iv?$Qc6`EtU}BT4oGKs zNu~c43EfVXFPr|`j;jmD!n_&tLw889RN6-J%6axAai0FwHZcn^5PfT-GHA|egyG2Q z{6}tBL*KA`FK@hDrJeFop$2bXLP!9w7SX-W3a4*d6wc16qubO(^=uh_;*xy4>t<#B z4BwSK)m`fO<=x`1QlK|1K8w(@NigP*@4~*26DY)lytE&am*!|gQsWg98Z=#<{(&x> zK3=fU(jlqhi@!?hRUcm%G6&$^8B9LWvwm?V(ojkuf6ck`BAt7n`MkKSD$?%(i2_Dwu~!dUI8u;hF91BK#w5?99kJo#&Xg| zG=1rtvFxUw>GdW_jf8Kcg;2((%rAJf;#_CzlNiwKD8q3X@H@uc0 z=aNHafM{pzaxFrj^+j^E&-Czg&^*Oi*Bi_BsPf5fM_`xTdc(kKyWfa$lb#?DprEb* zuY&CMWjd;Be1jaGWt5@TYbhzB5{)>-ocP7Uv7qNmPAl#eLFEvB zWRcci81^4Vv7Ch;Was}BZMEy1w7NpqGzO%5o0R?7sapfQ6^AiL=ryNwalrORKZHvzjUNHd}RI z{kv!W-EsR*Zq!Tm1-4+KQxxbxN!hXbo!A8hW63c_`ucc=kI;%>ftX4-ZeLiUUqQ1C zMP`rKs_7*Cg1L5Ke~q}Ahc@qQ1C}fYPk2SFF?{*5D1sUQxU^P~A7mG|!*D4Z(O+_8 z^ha+jnOcj|5}-2cuP~F8qLfh9*RH@Aqs^c}P)@$Q6_l<(9iL}OJ@)8XsDKTM8bwy! zHn&4hTY{&a*VyY5k6jw7mP!hB8(`Zldjm4QC6oCAS$_4RL&M?ZrVRf~B=(5EsT0SF zMRUOfSSGK}%mLZ(d-&u6%VD0ft4b!}jWMDmqu4BRoPJXR<$Jo(NY>Vjt=$Q;3I&G6 z@7=6q9HI-g_{XXCy3~zl^J5hciU-}|ulS2{q<0ABjkA54_)WJ(KV> z?cASTrT0Dcw-#JHq2>#y^#)vUxSI;2#n}4@%FfEValcmV`IFxKBUg2-_9j;cm5Kgu z%SD^7$`Y!Gi~dmW`|=NFP%4Y?g5=e|M1#V@GFqDh)*jWk3a{G#Pj;i_WSUp-61SUL zXK)WC51S-GD1CI;=8~`sHt%Z8AGFIP>Na-)t6Jga@SboC{-038Y_5&!f*^Eup_q|r zEv4h&P;S)(ET?t6xVcDqKlO3pZ)pg;(va_^#Osf!b-gQSl40!IdD$~Ei#Lrh@@@{x z0gK<@cfN@n>c3AfxfZsAv+Nnn19z@S?=koIss1k(A)=rI&#d`hGF+VQ^ zcJVLOv=;-graqFnNVGQ~zjD(!#e?lQf6fHsGw;tbf62D%II5VU%_(S|#33_=Ad&fE z^Uc})7ye6v>u#OCd7QXQkkz!h;ku?0a=swP307fUcSmbJsyXQ&{qWsvyei>dbLZ6o z4v;tP`R2=IDpzPL1|d?1lcd!(;a3$x1r zEyYk!{ot>*TXAogs(;pFSvcHa8bQ!cuW=iS7JJk0ye%X1lkqxx@n zYq@=?$Gy`$oFG2N6im(>TO~aAMc!bBG&7>SvWJ1IeZ2nbCG%81Q1y9*{oUa2ISgA^ zjD%FTPdKNPP$X(j;ZVrvNzC91M3?B(_nK*A$!1$IIY3!ue_L}cy~k6$)0Xcfj-K`N za;QGWNXOJGH`+#Q@`lcP(gMqAbyu(vIjZA#uB&wH8x$eJN5P;>Zt z$sVN*RTf7JY2i{PFjsE)7#*9~{m9>v+7$#lvn-FkteeDrr)NhX z|9dN1Sd3w@dV1lBpuyI`(5`TVoRwS2jFqL zrW&Q9`1d6Hf314{tiO0m?16Y_=gC^rtF)sj?=A!}joZoxmgi!x5lL1COylTQt){;n z0@A099A=e}SvJg#XKRnD1H(Gp*`gDih~#mJJePOI8x<(Yo1oi+RUi6Xy_O_blZ5p5 z^@Zpc>Za`5PXmf!SKiOK&Hva)&dCxVxbhh%fuHH^N(c-x$MMd4EMx(wgLv@>IfstN zv#?3|mI_oGB}z9j!r(?W_Fh6EDE`qEX8%kX0R5y#Y7~@VzELyVl7y`-MGqfz)=c7g zpK$=okfhj-?&!H@(Kean(E}oRii(E}YF|E)8SnkRSQShuV>V9|m`XMF+VByPaSFg3 z%ti@XsS4IW(xL}5mo?E)|v*25*|MOzC zx@f?M3C#9z`Fm$Uny5wM+9KnSxa&+y=08XAy%fvrTc}eD7slQ)C?CRU;Bh=(a0KZ3qK1=iDse_R^N5-N>Mv*Ae>~QhJ(xhL5bB(+vvy0E{Y@(F2 z?YqX-0%^ov=z+>afmBp+MTNxrXC30q*m;_z0@{QAUqj1A^z|L-eWPM_STQ6wN~J62 z(07#Q;~c=m=S=_s3EqmfMMHv{exR^C2T|lqlh$2q&V>a@jBgWDRZiq@0e*Unlxp47 zSG+2{iBRi-pV%q3JLdf^ctyS0?o;Mg8^Zp8`rmJey*QOv?^%X0i=Xf| zri=yP`fv+0#jp`+DVRRHL$83uWkzbOJ>S0=3KC@KB8f2@hm8USZ`BLZIGMznbemOz z&TRJIy5){6mqELvy>h6`zQ>))3X_XNe4Iw(jT5%K7A<)@(1J4UU{$e zW}v5fzDuv2GkQAdpj=#Z=&E?vI<#D}b~^^NO2g@Byt={Z+$~wEzI@5ib-IY;7KBbt zRUg3aYLxzF zs#?FLD!%koi?>b}|5TX2`*|Q)iF2&Zv4IC0;xZYz z{I7I+vBGZBYyvji^ZB{bIbDJ33{M5@0H$l`mvYyTIBASS$!x&M& z5YeHr;QN7XlTxy~5w4N14bWaim-Zvp)Jsb$xI6I&pWbaM-I6d=Yh>JN_uIV}{;>7M z?~&kp=(=#`e7d4O53)EP3bHKP571K2-a%BQw*nfHRb-Nt3xQN$W0LYtt%OP>YzM!htrq}H_L@CUWM|wT~ww5t`N2Z6XF`$ zUJ|LNY$qCV`1&u3jBuZVDXjF%YKIxSAx!a4obuf|+ii6nQ)GR3UbSwJXrO8NOur0( z#p&#cVj4RSU-B=61WasNV8hEM|`= zVtowgtm!PwjTqBQcWhU$ok`pBuzw8n>oy8k^o3jvZpAe1*t0gl<+8r$@Xpc0 z>*y1gKmXOBrxx74X|jk9~5KM zE3a3>25I6T7VYQ6z4!`3EY30r>(jl%DnE|Ao)CRkLCl^a_9A8>=2}#9EEo2gcF4(M zJ7K{-k1%fmX2)2v*mV%8c#(CWSxnc*iIa1V{J%t38UVy_1M0Unq(xn-qUhS?3gYut zE*Te4JETb~W(Ip6(Dq;1g{4IUFc$Z);^v4U#j9Sz-nWJV?)mk8yvv>Gt@8P`Xb19r zUtNw>nO45qkbwS%0*~%AbAYTg+;y>dLPRI0s)`_2QHMq%$_;T>J_4ieRR zo^%^>@ClBvL^ns`8keSJ?Yw8Tu#7uf-_~iSiSkF{bLdc*1)12L?nktKtZBo$W)@pzq2QYAYI*!Qs2#S#nIx#`4*F+ZQ2us#F9#aUv6Vc@w!hGO83fPDapcQC-%}1 zC@<}p)4bQxCOjf^XyaaLsJ~+QoSG*iq#(nyJ-KZr7=vRG?1Vi}T-c179;;vw#FsqI zr=$VYs7}N1bPP!(8-@}p#U*s_Px<+MC0U5JD^Tr6b4IbG;XlmQ{T>wc*0GaHi@kK3 z!reBVUe0tNA!0rMbrMSKb$mbZP-as&P!*27UdM4iX-2cqIb(MFAX`L_m)RD0aji_p ztDkw=*2NN2@Gv(YP_yiVz*0$^8JR`Jit6B;I>puc@wwJ%zCbgHd@+k51;`*C*$^-t zOWIKk5>anZ6Bv(bM)K#WY_0Zd{<4wrOFmlqC$AXtug5Iwi10OeWQBhe1vmq~A###< zWQw;C%V`EqPXs%mrvGfUi^S|^`UxbEhA(vP{jh%y^$UctmL(ZMmM22Y;&VaY!>X2B zBz6z}JOkHw+!!*qO4Keo2)fIDb){(r?{X2%trkE#dW~vf5qMb|L`O@6>WP|ji?Z2i zJs@FMBYr+TI`F=OEf25?1-IW4UgtlwiT;Q*F*NyAQ2)!4zrUF!?VN!->UHH0+k=fR z3B0(OG(~JkkHo?XOyGhKYBEkopOO}Gy(0PvPG7q)cJ}}T?N#huT>E@Vn3MBwwPrbB$lqfu*%rCFld*;j(lyzZfHa=q+=YMspl zgq(~`xlJRiZ5#`x(d~_rAt|kkRm4F&D`;5RH79G&rY!%evDJ|h~im7kxA)+q=ocEF>$d14?Hh<2q1N!T|bnIRZ z7oej|vphx!C;#o&$Bu7Ay2EFEEXM-rkzmn%_W-KP2m;FUa%miH_Tt&WCzinb#f6_R z{dX}>HEXFLia#oWjp6dvy>uMr*sPeBD`t1m&$6G2Kf0)bF;k!Z5ZdCvxtcip8 zeJ!Rz<-8v>-0r01Dcc4r9<78?ajyP;5!GHYXcD3BVLqgH0mtMijuf=d2PKn2m%$7# zVpy=Tp~3w?cfsW}*Xk#pj>4So%lfd&Jz=uk&HqhbP1YB0WZIjli$4qKccy+2hBN0n+H;_k|(O>&!CfTqrqG>;2q+NYV8Z0KU zvn(dZ@U1VbK_ok5&4EE=H!0Fi9JW7Thw)>{kcKb}up7a?4}`#Fkda=0Sm3>dneuoj zTuZ7dSAoXTM0V<@t)^dv5Fy#p=l5|^C;Sip+f*Ob4!_IzqEQ3!-R5~LIe>~+I{xQ| zWw}wC#`NMt=GzEM|9D@`<eTXN#@-r{h7qyL8>64*PfloHQk5juO@WM=Sy`kKDkohdDf7OeCA<_M}Vst zM0UH0k(~ux+xQbdi7; zLx7s)A7yK49PGq`PhdOJ0z`@6%13X7{D9yfd7A# z@j<)n!LRIuT(}ot)0 z{I_4rW%$h)9$RAsVWR;OAAIyKfm%!gwoWX<%qqqC%mmfzt$569F31u}!;kZQTN@mL zPU)+6bis52sPKhp&??P9(1!Op{Anwzq6*v`jojj)EC6!m=EfltJ;Y{_j!BtNqyLH) zfz(8}&n*zp+$-+O(NCv&yp@&k9|)4J{cEP4PNmH8mabB`Hn+;ksmLmkMdze7>~7#T z_!ph|z8Pe*lmw(*^UZLIgbvjdpto^4o-B4mXBIOYhPP7t703$dh?(aMiwa&xmYxiN zPT`?(Q9Pb=JmXYhK7aymV^?NpAQz3Bv>5iMA>HsWV(HG@^Xx)YJ~*WiA!5ddK3x;0 zyM9t>vxb@Oc4_gnE+c;+IulZQ?Rd5oAK`XJgA9zZg4vvItL3l=pVS4fcKV7%xpsdu zyF^nArtcO^C8f6Z{}UAx5wtx-6^m5hFt7Y3*2rVB@KI$WKlBfhjl?bIn+i2GVle(M z%(Pw1oT-_%RcfD}CA)$QJTT%gxN2(Wnr5Cht0(mx`dROF9ehh~yks6_84x)rAhI-E zG-pYtKSNAXw=emS*hK0ktZr!NYeH=Y z3q)fRQ%Q50UOLU4^~L_4a-a z%C;mbKSAGbQurxaK>~vB#_rLsh zN?L}vCXxeK4$8@?la;k&joE6z5bsh^Ddyf8Q{(D{Lv|bMTOq7ek1c3ski$btVI}u8 ziPC7cop9FlPU_T=JHxPa)<0)dn+P@Hg4}d^w_o z{7ivj*|+5tsTXfx9I_O4Ts0}q`WY7nlAZOTg+gqP8E!u17l#Emw6_>!WlIrawdA95 zcI_m+5U!_e4ga^L_G(-iw@6#8*~Y^ig^8JOlO16{&EOSd<|WYjbvJundL@&3Ueh?x zcwq}#rMiIY{P*)~cU76H=_yDePtNo+;>=y5__$%VsZbk*?H$Y@C5L7JFQFs$NvHq>9)S(r&~nX4lOc3{rr2t)l!4kqaRLH2;d~{ zri1y#eY9j_*)xfoQS8gkkG@DRtJVc#yOek%E+3h*ka`3-TtS6-L%t`i9)BiY&Z=G^ zDx{eSQCBJy1O9Di_4U-)fU{llIO~7xxYMN@GxLdA3y#`Fn->b5_2m~5`G+ljOlI%J z9sYpDE>b9zs%()PsLeY;}^D60f+MXgIZTyLq+%GYdx!pyr_r}5(q=(nLou6 zwQHw!2)v1ObLkB-)0v|!_5`Ys@y3HpV+jP4lfu!Uy$)5!BqA(31kO@izW?^2{aSF} z3})36Qt;V8;GD(3QB0|5w|*&(F0~Q!)Oz^#$iQk{SnB~vch8c#Nc)czbOsM3wa4El zuUKzzdDO7;BYwI~qsDe>I`mGZlsj#~R~Y`krb0d+ST?@t$Q*yc`Kjp%FwZIV;!vOy zRReg#V~!^-I8Gk3zoV4OKnBE?*qqgfeBq!1TrS$IOyHw!mZ8e;qhAphtHXj7oj^V7 zW!R!?SN$;VwWnRYg@ygS1`RbrkV=<0i+?nI@EuyQy(366UymwOSyVjUsLk za`%meoPI!fmFAj11M8|;{QJ3Bs@syRWN63Z9EnLwVe*6o1Q)?FSZ&Y8n>iX2PU>h+ z^PA=E#PX`-dzmLfGOs75Uz->gIU9gLl?rlh)B1m&0b7luAhQKm%ehE;<7XvpK>?EbMTP=Xbf6rN9 zfex+5Q;d~Qc_Mclz$jP>zI4q|`DZ(gx?j8Qk?R&KtL6?{I5N8O16%pl?z5@Jgo>6gf^2IZkLSO~EE#()n z|Ma2HtBNK30Nk!qRbT-hp#ffrbh84g21Qi4v+X%4c3Hgw2+1qWBr=J^#i-<}*EVq4gHE-A?PobvGi1!!2$UUBCj zR@nzqkIAXLGO~(O{aLrRhQIH_W7^;MD}0U^wv6)0^_A;mYr#)K3w4wq{5B&U1buw* z6n%eoQ%)PQlxD$2rHSc-PjNnIzC|pSB}Uo0ms7!@)nb(hAfWGO&VBa45xZ<$aibR| zN+P}rYzh=HA`8$g#6CH8Qb=t(X0oAoI@2 zbW;jweG`P3u=ZR?yT66bgZ@INulhJ0aLcL{B4hH_SZN*r%Bga%j_!M(eCz*;a7TzB z+-%?9K#7Ga@uCm8$lnIQX`ALQWJxX@3GWtMLb_1}v)_a!HCFj`N8N9KCNpA4=R=SM z=zezt>Q|dB4cV@?TrPh6@6QY!hSKH2nHRkh&{g6&?HEWk*X2MVpK6DTC9$6WOUrV# zf)(IbNhselGYEfT8`EdQ*hO{-k2;~CXsKQIbYK9o^*p%4ZcVu*PnF}~X*$aQrxy^M>52rj|er$6)sSWV1W>7cwwGfjjX)4g+F*<H4&T_wo{Ex<`g2e@Gk%8k-mk$r~qpv6S6>4(^k6T0R54dS#-Vt14sb1!QU+c z60iw6r7Z^Tg&?Jal33amWcl*i_N*1@YlijVKUI`bKs3E+M25Zb8;){$5-Q9glMR+( z-){#^$#1Lvij5gc*#I(E4O?c&vX~1>izajCd{S8eZtch$zSWBZ1o8J@I_+~uRN_z+ z(!T`vT~6NS+=UC7QoLBE5h3)+4Tf~vF*s}xEq#OM%55MiMe?r_8rf9?%bAHQVkbJP z+3lPG&CG5RpxcdfrMT{=KezIMKR zQre8oRoPNXDs2^{a74BWu(RqoKjW54qwRNi2i*&XLla0>(2#wZ%{LY=>`C-q6wSWvEMBFiba!Yo~3<{w+_;uqlOLdP8 z1qbk^QbFdeLU4w(tu#B%whx4(h?Xh9gH-D$S_JvZG&Xt&;9W!02J@vhwz1u?Z;5o2 z0SwtVguwmW{opFj&%YdYW)HG`bc3)Wa_7RYD^1ycL#rr}j*$rX7!XtG^P;0I&;qda zz834NeWb}9wZ3xpPkf}}lEjA)okwD(T0~|~C;;bCAz(UR()%zT)_he#E|}-V(PyYW zA=FxdCU$n4MO&vlrhRQ1Opve3+MN?~O#a0km=ao#Lxsh<#O1kyLC!Bm6BWCmQ+o>l zrFi*Je%Y9)nzgaeKN-!;4ZLwJX~#0WQ|SEe(CZKufm+T^n)`aibriJ4TuuXb$-vV< z@8%&XFZSmSclJ#t8c=My7sg+o{-yt=+X!ORa>Y?!(&~2w%chiq=khPAP_XoGqG-hV z5cPes3k<5ht|`APqGfYh&fg zw6bc*A(Fv!T%3at5E9K~bh5;p;`y#xugr$Cua)^MgTKRK^7QsA!a-`O8N2gNvF#b` zcO}=j(9PHEtw&@}=aFA5Uk_q>QqGz0)T15|ZXkLb$stfBO~ zzPO6b*YPBYa9P77M3^VTutMGnQEDm(ho9gY8u4Lud0$_trC>Zo_v7(I@xNiLA3NO} z^^(#8yL;GXn7yz^7IKB}Ra9#mJ(w(K1ePc=#oUqw&1v<#xGiljPoio0X*O1U9o<+% zdqQi;#`NR@csiG+p8hW#7JLlV?+l4HJ3DHo3HibWtr>zvJ>ruPZ_TU%GR0PA9`6Wp zJ*vyZybPdxSnv08#pq+i$_?geChS7>UYJegKHnyBsO@P~+L$&M?=drz?>k zp^Vdh_cKvqg6h{>6>SF`qTzFsrv0UdCN~cp#>l(^Yt>h-rX)uEJr`;!`oTgLE)Y~$ zWx`$q6_KZ;r6KSqZK|i;j%agHeY=Gs`iNa?-=~$ZGfuaUY%<@}`V1G9V}Peja}0#4bU5YgD9 zM6fOqvX{=n@9CQNF8Hn1{qr0Ib%@%30__M2#9^9LuzaEsGUo3#0Vr}+!86_6jzhaE zizlAdgakC;w40kk(5=^kGP;_4%bLWKlFZSCaI8_}r$w8pd9zj={c;Ks|FFCl#LHF? zO;s(5K!p#~_mQnjqW?2}P zip4;h(G|Kh8V5s`;>U0x6CG?S>&bszGN?9IJlM1j8!ss4y$XHrwgCG3CpTK5Mik-f zxceHl+&vB@g2-N!UBlebis)mb=xBA}A|p?&#+muW)V;5LODBgBg?R~0f-1g4iz%{% zlBf#S&?JGd&wI3s@GHTrTi0K;*-%=5DE7|>Lm9}=VgPFM1d17hQ-exEf%wp_^Vz|T zZXX=MvH}c6au-1Mq$!kv1G4)hz{Ad;t(Y9vO!@!&k_QgpVd=Dw*F-r52Scg-Pc1h0 z{(F)#-}tx%_eN_@aKa_GAN*fxq4-wI6^G16tw6K_-z*@h@SLhGyrSg};ASz$Q>&$g z%9r4TXjWT9X}d=dh)MVRJYsX<%dVil@P>rIpo=Ti=JqdtN}jrW(NxUC76X0j59P1q zEjy!2KeOyZjXK3atAFnpenUB=jg5I5TIN-7H9Q+FRTxnDN;DI-O(x6jagL_#Bfj(L zkX`z&U+H`Q*$R=YSU$iY>z(NsK+{WnBUHoaYH%W5PNN<}>6$_xq!E6=QG9)xBX8?u zMsGFShZjb{D)hjm_ujZGIU*`0#-cEdA})j8|GpPHoP46PL&Mkcn^Y#GHo($bSc^rU z1fqmj2ANY@Hp_T^zR`n)?wFR<|I2rf4TvRB`8XyXTgB>-lxlIZ1gyUPmtyPosy%&8 ziOgt35(SKr!aDVO7@I{!RLy_vji(PT%+Z^%sD?Db?R5c_2U zU9WF_>}E29z8rlm#D7h>OjkfCQYXYj-!phM>^@q@pevZURA|58K!%76lGdc)+LyaF zhU~Ex_ECP$a7N_(`{s>Xx-rl;{ZyBhJQgBkgw=J7E; z=GU46&jlBJW1NI&5DDi)@^GK)#J*mO4?bjLpC3b+!<~VDy0_ZLcOWPP?73EKHW)mx zqOvAfUdzh(vX(3Hb))A42Lq)5lOxv;T|T>^q$Z(KR0-MDSnC$GDKSf(?)r?JL8PlxwIEdz!%JA&ce2l<$=_4^i9=hbYT zVqn%u`U_6KEjdCCXX^XJQD|0wzco}oF~7VR1q13_&UJceGGkA@!a2KTPb$U&f{?@tBQ!UV~ap| ziR};h`n7n!CKAM7&A)rHhiP97Iqs+P&pUL?KW>a077#UQwRzXeK z8q`i7#sOhzYdIl$IEDMdWpF$o0dG2alBshyRBNa8Y?U-HDorqUwi7I3@2bA*xBcmu zRo^WrxZ1IzS^DBQEy7!zF`>q9FAkZ5tvc15WGhc^0c6Nn)~i15X)$My{WLwRLzZWlea@`U}DZj zB^yKPLN(aRPn4_s2Vkl2MAejoLY-ivT7**NjWrNUB|0fy8Q|w`RJ{Ij?dWM=wp82e z@{rlGVQeYe%SRQ?B*zmR+I{4?n>u=Mr&H$b{2OQ*&TjF-*wHC-Vu_i2k1(qwgptOm zU3W}favybyomSv83O4>)h#Meaz&?|m-gsCPHyx}zNuhvyXj~F(2;*P3kT;FBd>%z6$fq3kIo;e>rwSYji0O{JJ2jBX8RuvT0vAl^;%_ zjeXoN%}2q{v*!{~O50992EK5CeV+jPXT(h-i9e_DL3_Nx6~4OOB}ts|`mXm1er75Y zq&4P7HmbGInz;C*#v00IN>^uZ4kFHb9Zc7l8t-2_B1>a!;0vy9c;w zk&{-$pnWD~A>OOEZR^j=jFR^RRTprjVP@rjfx;JU5Gtv4o8;T}`iNW=LjMm?#ncGS z%z-vDYz{mwXGz?iX~Epf?D5B!0C@jfJA!H{LokI*N;OBSO1{q9eE<f0~iNg2>OK#)vFe`@I{pD1(iX&Uma z(6cc_Quk-c zrn0UB0a@KK)BUZf)ai|`ZQ?#_UoSU%H+X=9Vr40mzTU~M5mU><6X2l?MT|AY`p6(M z%aG!aD!r_&X^^-r*V}8ee(<-MPTWjgY-2NRA)+~ki>|R;QhQ(KbG7Cf-6k=UW1lDc zRK!0lo$J!pD4zeoBM-U^l7Ej}{okCBLX!I}AX7d3)llo$*JE?&{4C)W(1)BA00W={ zYfS0s^RKh0rCQAqmQ9-$jc;L(30}EMC!f3kFL$@Gv7yM0NP9DDYdPNz15rWz!o$DP z&1(i{lP|CLxivy=wlYgxRhwzA1_;9P^r)_`ZFgei7k$oAqq+p=^gl)iS$lPk?XqXZ z?6c=)*OMeoO}GHVP;b!>J1F()=q`GS=wd!li=D5KA%rz4OFu$_mD61CCAGs@#}j^Rf)(E zTrf5kW}Zw{n^ObNNYdtmk|Y==wZpe4r^jEpbAdv+sYB&67mI}vUFY)68*VLrOE46o>aNnN;{;3EDk(i|}^eRyIKcqgTM79F{M9x!#VT2n+JU-fds^H4!U zWKW00>$t<+1t9J$CIzx2lOd!sC^OoH_a#4@>kZm$4OIV~JaJ$UX-p${m3U%(#NJ3; zOZQhGn}m;M(_1G1)Y9vk90I8H!uZdEXAskudXp4whgATlADg5w4eru!|7G3Q#6x|T=NZ%j zY(EDVV|Ns$gHXo1NIcyByRcakwnw=B3+O`}RN)#Ps+x2pFda#(a=)mgIu~Y2ol>XB zh3jtg19GP}q~39TWLHpnix+>?}|zao>!nj2#*o#uGrd11Gw{rx-N?QF1~g=+aTwG{^u zI)B4A;)ybt|z`I9WuU6mWh8#+>69_wlKrGF`4p#?@DzhS+3kn{y-0FS| ziGW~A2;Z{i9Rg=1#8fX020H3?o2s6Or)yO zH%BvW7lhMmajRBp@%Ru*uHm80F6#4w!wlXV&%oL<2_S&=r5t^zaP_dd350$ z%JE*yJEjq$hQ-sy&;q@pa-2`%{>%DU{+YWZdns{jaKd5X6@PLgog(2W_c!%-8qp5j zy?HbnZSgl8yJQ5T-n6n&HyxGXBRx;sSc-u#cf4<7fD|V@)UU--IGS z00v~pu<;A1#)3}y7S1zWuq?3X1M3M1GSW08dInH2s3_2WrGyaN{;pt8CYL1V*N~0+Ae<$aJO-Vn()xoU|^bC@iA}7s3=% znE)e2w9U+l6Ci+mYf zUs1;c3`_DVJFIZWCYU$*IPmIf!T*+9t@8ODY=M)+Jr9Nl&t4+*lc}nZ98x#wZpdav zmZ1qTmOdVvkVVS5?fGT>3$}E<^|z!-YqsE&1SZUCLP>b7O!%+KlF{QZaaH<&Fq|Kdqz zi~N%5#+5}k;8Yt}rv)(uiQ1a@5ob~#uvtSDv5d@3#{^jdxajqQPIumy*lBqWm7)-X zmd>OjD6r14g+`X!Ri6HOAJ}HXp~>8tDi9Uj-e^ID)x&!L2PbEsjEr-U$o)~+Hr0I# zxLSx}x-Fg&h+b3~mjz?W=+2Z>g`&qx(Omnv zqGLudm(a%DK|EO~y*B+Tu&SUa@C5VO8JRCU4aB7kiux3|cPy^S+9Bd+ zav-+yDk8-&Z92_8pA?Qzsy;Tka=UOuHpJTdpfP!quF80&C5*N?`B0^8$NpLuylPHw z)y4=nL6g;_UigyNhv&K-n?K5N+9#SHG1kEUjO%z}dqr7Wx7xqTSx*;sqlvCf6M=&Ah9W3Pue`CUWA62mR?>85aRnYuYmwQTIBDnD1Mz$b6rvG zKWN%C;Notj{eSb5;8+6&TYuPuK>b6d%)YWXnYVi~(vBV~Bnnz^+g8v+nQ3!DS*B?B z;+y!kDM)B&^yjzN!Vc4uXh}R=n2F80N{CsL63gy;2W@oy?J`_xG?hb~QQHYD4xOx& z`tA4Q{q*Q_l;pwIdXS5{(PZ#)O_$A?^TT|Aa%oEDUV``=V}}U#|4tq00F3+Y+me_0 z-~Gv^;XeqZ@@~X4e^Hw_A#~>M9qP8>&kw0XgUU2z4Q^}@XG8s#+cy?wrD^0)H+sJH z3TMmR5g`C8K-9l|A0u6HL)z-_f#sRt`K>_<(}bJvV;x#%Lw(Jc2Yh=Z8?$VigrE1c zL8_M`6W`GP+HWbU{@EE~=$Z!@McmDFc6z6r@KBsqhBYlh;tz$31*NOvWC#LNNT-Df zi$lbwst!ud1@|=H?R)2C;9oC-QljjMmp(^OO^a3sync`oBZF3@bS%D}VEc=$O+WHY z30&>DdX(BWo-e}H?9K~hG3QxvYmBcJXo0aj+1UAe`~y%TlNbGQZq)BYg86eO5GYyl zA&L};#Q}!bkf;n*EedLsl;nPk=Zm9gwxpb4q4jKBqxp>HS4yx8_xLawu!nZ2Av*pd zIeMt#rz+v!oYj8RvCtEVJXN{}ee`@zOZ~GSIG{a%V0CHfLvt~6U~8gj5x)%p%eg8W zJvd@}&rh>6%%gd{UU{bpVQ2JZZ-Rk4w-tsd(0Xgn;-n2!;iA)OLzVoaCVWhi zs#d)a>zE?PXhA6Sy+@m8Ermfqm&Zs5Tsq&Gq#swmdI65;LoPIyM9A+((h2Vp2gI6v}t4_yZojEw9rSW;+>rfquJoh~<{UwUYozFT)$z!)S_YXRhYp1GBSY%O(Ng}GI{bTa~`kcC!uqXJjhw@%>2|=;&WDm`I#_ml<6Y9b}427A6Vs{*Gz~Sj8Hmtkrx^=pPsD2^xG}wsNm%ix=?YCA6d?!4-p zF=6>bld2Z#1st~eOCe%Dej@ewDXFA;>sE3I#qnxwair&5@*&1qZ0 z-Y0dEg^`FYBF)+#l`BM#>e9_W6GUC*SI}uI--aEBf=f8f8!*uRonzpYIF7x2)W7?Jx$`0XS*uf?`29HU{~BK85f14#P~k zyo?X7aK+*qM@E#J7`{u{N zktub~yq)H#z2xvyYBc zqU3B?QH^q;(AxEUZ3-j5PSuKcqH_*thsmbe%-ZRtFTFrPbi;zv)Mbxe-h83;r55XRwP!>qyW<^MfgHI6@nxWwUCf}Z~S3|XoU3c zo2jn`X}!aQ{DW}b?G=1UIoW0YJrcz~B1lSrG+1{*9HV}P`JXa&S}%Q0l_pa<;X~gL zdo*GZJA*xp&zAyUJ6Ywz9G%^&cm%84mSI;0b(0nwjhv*Q#c+^Fx$KOd{G?DrY*NMM zxhH^URSNNsaqH`A3JUuB^P=YaE>i;Fz+mz71*RckrmG0%St;mvmvBh-UaZwMB^X z1rpz%>yFNH7$#KR$8J*_T|t54f4qbL;xud{RoVT)RZ;^FxuQR)BSFo0AYa?agFxs{ z@9Pn@SEK2cGM)ZnA5Ze@MCQYCH&q8sGGR4`0GYw$o5NEZ%9D@3taZPkz=CLXCJ8sI z(+!UPM%B87&4+a$t0>}cNCMmZ*=8M$B-I*^l=Dn$*!IfsXp3W;eyH6q>gd0#ceCk+ zq}V~3@e8bzq0w(e$$hf-2(w9Yj`HDh{J^?H3}_o+#0Ttynf zXV)$~+kF@DmbOriS4vlr?*Z&xYL9{CV{MGu3-G8Y-eV2D^mQ69ocryH%Bkp|bspne zE0}Ow2_?*T+HI4}Xwcf>rD%Js1GIHI1l@E03aF`lLK`?-S-E@U?|tGzdh@gFLmldY z<+&af0Av%i5~jWG|0V3|tA8P=P+T;ow+zupXCc}}6#R?FxU36zxc zCMD?D(GaB>Rk^GVqu`3x6KD{)gg%Er$~F5*6?BnC_Pr@)yJ;OxKq98v*W0PC=)v`^ zy;6&VM_$Lh!4OnmOItdm{~_#Hlhx-YaV8$oZyTLIFl_8o+gaZr;O$gx=mt9pu%dbR z;;m9mJaU7QkWE@;`#AlO<|BB;up^7h@A74h)p+UWYv!Utb0WhMkCJJ17)@;{^v6nh zX~l-PFIL`bQMmYMgHbzyRwz5YF{1wCy;QM;HAZ$wF-n%~p5s_w~nu1Kj=$9$q_{=64w?U+xT}))S-_ ztu)=OxJDgaj$wS59;tULt$U2^sF`B2&OTVH0{GOyVK@3hEd18sTAht!oWl%qdE!u) z^_Jv~&JMPaa&jXZx8}zQ<-j@nTI_mp7v})7gz1H7^&faEVB95biUydz5b!WE8@W}E zOvOWzW>lM9FVL2?s@x5X_eMFdn%D?l8&cLhCggI|FhRzWS_MUbXqj<5e3Xk;-*#SZUfuDEOO}b1uw;{B{_lF6+Y_(CT9^6+m!RI zN~ff>XmT{0S};Mc#{8^81Ff{HsFI&QsL)*4hnjFZ*<_vNu z_%oTn;iKtll(PV%)$d(IARn{B6#LSy(7!;hkON7FV;)8qsB>R9m_%P2+S$f5&}y9# zt_QaF3@ciqIfF{Vr^0%8d0>4L&;ji#Im=ohoI$`{WT*fD2|OSHDBvy!%*5* zii(XTq@HZD)6#MrkUmOGPI|=6#iPcgh^KXL;YFPCc3+wwsI!Bd5Fbi3H9AflZov5M zqwy2D%b7nHpn}{@nj97xe@Z-%bN0O~$M}Up08sr)dplfc5eJ5sFt-j&c-ezrV?D5A z#X#j_kq}XLx6K2Zn&_$q31EJTdqG!oV%2o==F~IH_F>xO@Y_HXUCcXFqI)1sNdfok zUCViQn77?+431gK{4e)kO`c-nkD^=Mj%8}pMyG$w*5(j_M4 zZ+rQCo+AA!L0nR6P7em_5Hr3He82jWFegyVe@eGC?1cJUoZJG*jgF`fQ)&;=8H9V%eOssAtwd0#{BYPGn%x|@(|I&j|HOD#4p3th6Txu zFt;KfhhJaZZw?N!cdpBqMEnQLJlh;V@BOCj;3c;*lQDjK5Ht5^8b8i_WbA@7Yt&ZX zS8RAiMX>Os*mqgZW|%rn4AA;;&(7wTUh_~AKVCDXmTgOfcp}NfkE~b5>?eMT;_?Ei zljdkPKtljz82PdxP$0$+XOT}FCTUyezN7*Xs5Q=eQ&6|zVjugWjn1g`e$o`NiA-v{ zj}O%=+xVRayn&`VIDx9z0$h3SNBZNse)_8*%6x3_` zHa^sGcCJ0(cqzV(k#2tyb#7BmN%2ykvx2V80=JN}22=r;EESgyV&<^k3W3&B073(G zz)$@!P79)UTlr@ypJHMVb(qqz&THAFEPrp=bJFh=V<2WtA=V)1#JPdRUhLbiphN6a z=Tzwz@=1rkIiV8-w3RdpwITutlNsL3wAduBY7_vMo1~^GaJ^jM!Df3DMv1L#az+3d zDJ(LRHMz~#xU)+tAL4pGSZ$Jb+>gS%w^oL@(x`cB6SJ*k^d}oN7m(6N**7S+LJ>nu zZ^N@|I5eZT~gVy!eGW=Vi#Ud@-H=O%y7A=ZvGUK3{|*AI?i2Kmg4Cy#$4B1J0v z{PD?&#&f=A*gd!5?)Pd3zPA}HhbHB*?rim;j*KghNYO+4JwAa4hEi5}23Mqn z-pF&|{=~EHIzLFeYBt{2;jXN)3V={H_;`lk6G@Pl6&diB`QXx^P2SHc5#eG;&!hLA zzGFyVMPRUU=IArem10Lb3P(}MDX+Y8MKn8vfD4>-i%t9yDtehrrLy#f>*XzrO7%fX zM{M!6al%RPnm|yV(eCI}#3~;5)-GTinc|E#?$7dqL9GF0=1qLSWKasiDJDd0!6SZ3 znStf0e$Iz6&WbFnC3w*qMjR%Hd%vA?a~$`Z5%$(`Ye7_YqiZ4P(jKN)A=O4=xS$ea z%*9Z{S)0OBw4e*9mHfUe1;JF$g%zY1<-+Jy{c3@gm|i??`wlWL0kygvI8+(ZS_jUA z!GYd<{)PP3`#%=w2uI9XR$I{7jMH0yEohC}Zlk2UoiNp97jk+)R?e0n$jD&zc|_zX z=2YW@^@GEgq^UhgsHBzMa$YrMSS`_f6UGfiJ_u_};BIVFeMInMul=Gbx;3Tmth=*9?$0daX+v)9f4( zi*Aljw|B*m@OCqQkAV8jj*;qAguZ$=+WH*bh`oM{%=m4q%Ib&+?jdw<=@3}xuWes1 zI1AFw{RZAqLr7RC2AjI-&Il?rJbkUo73b_71=Y>5gtm$z>(Q)}#`YVCzhpeeP-|SB zOU18WoT_qIM$EVqL#-Ua=CrM@Nj0wB%ktm=2yVns)US2?)_0Z32{005tw0txseWU# zpxV7M@{pyYH4&Z>?FKDGjjgcpY8r|<0)MwKO>!nD(>rPZLlDFO95wvNFe>?HDx`G6 zA$ZvF^zqzjePL}=bJy4hhR%x}1#Rw)PCka7M)ptTB4N@0YI4u*?m3`DC7+qwi3~AO zyU%9Xz@N^G@TG$R7evciGW=7qX$R)V;r=A2hvId-B}mz;eDpZ>5PE-FC)M zS!;|NBj2j$2~U)sltmI3fXwK{wi|b$(S)oLMzu}x3vr5JK?RIob)lu~Ek6c8^r_jK z31&R^yOha7K~Rd@5#0i%ZOoWl3_*-^J*7A}>6YoL9P9l477imeWi9vc-DE%&fM!7T znPy4l=14{KZN{z=Ug_GT953c|Q98un#2^#@{q>H@mk^Bh5m}1=eDELA1(4T==cke# zZE91V@7DO;S54T2Gdw-cK!J71cdwJnb-AOnBpw95OXi~c;{4wZ^856D8#YMZA`Wl_g~_^=UsH^s#*Q<#5)H17djh~m7IM&}B$(PJzS!8MRWFh&Y$ z44_8~xmYKyAlb?_z~FSI_tFM|ARl$|pr&-fMY)r@9`02TeX;J-|4%U}qr~FWY*K|XX3^lfYQctc6~(w|Db7Q&07hQ@Mrj+(_c19%s?@<)SIA4Avm z`bP^XZwrA!ltV%~=;8=PmT{!-z zI8;kW_U~AYJ}C^Dzu`8R^N)39jme|HBPr0kGV3U}p$|{wn!Q+qKUa{{fIIPQ1fV%3Q+uLy3 zC8{i5YEF+ZS+OGaOXnWDl7#*)!+{nG|G>K2{xWU4rpfMyk=?!XE!F16^d$a1pxZyg z8Dd5P4;Js$$1*6;2h!Eut=n+l#O-xVzJyb0v&{)V=)h^aJy!L_G~>(#(<^4@k|lTE zYX1An2@W#PDMd(5C-$m2q<|cg!kLveqqqE8+mgDR`4P;5AVxA9!|Qa=Ra-UDJsndX zz6}pj=413JJ6Q?wCG3{P23%$M9cE!z;VjLTdvO79wVINSL9-f*0n1Erejx~1FtbOX zfAXRp{bTHP?lPRRy=-X-oD2&s@Tb=z)2}+;isu}Z;*{l;1d(ke+(%U=t?HQ@A=Akn z3_-&^M~i0b1o$maU~lD#HK$>~jJ;a^jdgSr9Hv{SMcyqZQjOhx^^AAGB@gZQg3w%b zl*II=(Yda_;AIAAr%pv7R;?xPnOuVdMajSbUWSA5t8R1llL!h8G5WM=FrbR+dCIgY z`V}+%^!djUtjc?Mh~9O~yZQz{urB(?kX|#l3xf&*Wx?8aqUyWLtPJ28XoaqE;NQRF zOAq?h8cG9F3f&BKpVp*{+3;*HC{B#z}<}mvnq-8ERt+faaJ_;mEmysHCwTcMO@({v_!N z~|>)~oKBJAeO zQZ+3qaANCbK)OpPO=JuBw{@Orf@WA4@QgvEOgOOl+$G*EMVo6%MDK9i8+JROg^$Vf z_*dOo-;Pn5iAB~i4GBOO^ za{QKDzz~}rrEEQ;?^ubh#KUzINzZPkcFHgXt~1-2w}Q0F$MwJn4qfz=5##9Hvi`4vW2QmW>0uoiluru zwkp=CRtuWe7p$5^eMoBM10|Hop%3^AOgBD44GdzfultjlC^=-AS0sB4LWlepBQ2bU zUb(OvaxkJ{qe1R~^TTTT=D#a4Nb}%Ys@60jr0-u5&9~~N34t(rb2T8UeRDm8|8 zr>1*v*0WpeLx!nSBKP}^-?mjC7jUx&kKm7%Gv2&+fDmIXBPQ)AlsDs3cTB7|22ZTA zklkk65j4xiz8kO;BDisgn6<}aopZz}(>%X7egf1Rl;sjS2LZQI|GG{>Ch6U z83c}?UtDKOg&|m&jjx+#u8LlJ61QYeggbYYg}qFoAbJSGi_Si2L2zFZHu*%W=>siF zRnBfLU$TP*Qr*krliB>jl)PPRpOPjiQ7JDwRiIYps*V)>xa~h7C07({9DAl(*}^Y7 z-A$6?4C%&!exNBeZ=yItD-i#&FMENlxJ7WZv*Orv1&;NVbq|BzYqP&fcQWfYl&+e$ zevu>0&`hNA9eG6J4d1U5j9SN|q9wyj91<2qj0tsPfd%n2H4oOQBomo+ReIwi)K!b> zP$GTT{veNdCEfS9IzfY`GtX?hR2Ki6P>kFh_P0MSnA2epI*T)6%2qOdhHX`q%h%}W zg2L)NxWK~w-FWo_(;_pN@!B=4ou{UFwyL$xC~$-9-#jVy3F^TCqVgK56fN*@<<>VK zIHU)nru!Hlw87S!gkRJ)u-?HMSLOCR+i}GOnHP8D(7j{Sy)q>B-vSQ#Ve2#Wb~9&+^BACB*+((V8d)_IevEqeFOKI zP2iVu0kAvE4UM&u$%Gn~yT3ghGroNO-#|0umY$fDt3Hwz2(j zS}o*&t6=*7`Ch*=U%XPfLgBH8-oCKlsTutEOIwRzHtC{x@C#co@tO|D1txE*T&c@( z^sUnyr2~<3RWbz0tEVH@meTl@r{M(k1f3Z6mF+0G24{e1G7qy_OEl0+)ZM$0C`$;b z^D{9J%sVC|5#rkuUiqh-wr$$lBjr?w%t9pJJ>Bw=wjKs8xB+h&ucf1Nei>CxfQDS= z=ckARIWzgD^Rf({lAqf_5YdHVnKGz%Y||>k2r=6J{nbauU%wUEUiMmlJK)aU7hv07 zSl;RTrr93!o7naVXuLc`Q2(WO^$Bz1<|ZG5h=M*X(LXGb(n+e2%B(c-w|q8s?NgM+ zK5KiL$f191rqYo;HZzUCIjX88u!r({t~JizhMZ(Kn?KVL6?IFZ^*klR5YwX}U|3AH&mDo}<&DCpf2Ktnrjy2SIR=6*< z1a~YGl1vEnew+x^hQc+DM9>vEk-~&dMT4#VUl?xMrEU1Zy6#o!n8;tyYDY7;8^-Xl z5SY4RiN?b>P6(iwB|_23y1H(G5f@@LgN|Jf>CsDF)^<-QZ4=n84?XoC7Q%0ev7J2% z{&hGx1k}GhTOz@lx1?I_cWQeSQIdr5<&$0GGRFhuJafZ+NIW z+!$Bgo|r^q9&8!K2ZzW1r>k{pP^Ms!a7B3V=4cz`NJ=D^?PEi?Rlr@w{?<@!$NVQt zrByK4eX#^}^R_fc9LtW0qT*w(h+zg@%zZ=@0=x5|{%dHWp_sy9{3jfsn95S{#$~X* zzu;Ja$RBs`qAQ1`Ms=VTyu)~WzU#PQQP$q&xhsQe-fQT=Ll6ySez3_;fR|qB?Z*U5 zyHesQTHug?oV+vX!?lTdl@tDz-M^3UnXJUUQx>$Bw{K9c9Lp-6z6hGmunXZ>2kwDYf{5E})k%Yx3du3Qs}hok)8VA0R2Zb{Uk=Y(FGt0qn1o?mi54KnNId_pd# zz%-Gj(R8{ASyCzVIeHh+1?!cEsU5_=z%LG2?;=BcL|csMrUh^*0$fnFc}&W7vY(CD z2Lr^lNF}U@2JI#Bgy;-F=T2P`a)DS)d}6E9Z);r|soT?;q8@ZkPs*$Sp%&_SH zd?e2NG-<4N8|O57fGT6bRs?8%en(LG6fb`^v=5gQ3zVrP+7~>pi)yNc#v&`6prx@0)nr&&*jA05U-b=Y zC^LZm`Mr3o6r0viNVZ#f6!YV5WUW8XzzLYnLQc$oNB%V zH24^$==m7444p(-QELJvXx*zfZ_*CHgbz;lCnfg8^XpnutU6u@px-bc6?m)ThP>tV za{PmT&mlta@R=4b3kk$ZDna)`c{BQ}0LKolvYlfU(~jqaFm-N50e^L^k1fWTdVaVZ z*Hvx|HLq@%)e*$Z;6uQlWy`1y6HBfOTa;1|8E5(|_T9d6|$=zCQ(C z>!wS9`8gO8OvmnFr?O6*MM_U*l87&;`AdUrOLWT)Xau?d-n1cNemW%e_Mwbu& zQ`4dt>9m~{8cmxP=$pqHv)1mYc6nw~(412v)rv?=G%<vAL`E7#U@+f+Mol7` z>>x{&o!XG=qvL)+K{Qc6N78u=vI2~!vwPal*({@5oj@izj_zE;+%%;In{h++!81X` z$#N}~#ZHc)V$8LaJQ&#TxOJDioDu!@`hfh$4aU3gK!NBC1`W~RSFg5hiT&p08ie-a zQz-)e)VEL(7^OEr)DBT*kLa=fGU2#094ry!A;RlEN6sRU=4(*^@yk@8P)vDB#<+Gp zMjHKqE=O)oNi8BLQD{&4ILJ28^X9+%@2`np&sb{LFjZI2E%`Jp&?l}8rGz8k9|Gwt zkV;5V`&EvvKeAIMqf58kjwC)9{eFN8qgn5#&{_bBDokBDNF)duWTUMzzWn3VD_!nl zsRkAk-rA6@n$A=2T`n%Pd(-L==QG3h)*=ILxG6BQ!Ee7pcocG5g<@X^_wkZRtvU?; zk$`vE8!cO9oH+Kc7z-6xUf|n1=T53bBYHl3X^a%SXBTGcSAa${rwEzkikP*#BinmL zAbmO2eAMm0!0(vc?}lYnaa@U1Q+GMnSz|iADk6UxgQbsFh`s61R$Fo4)9*zgY{1)w zlbQH=tSbOoJGNRB=&MFQ#FDnZu3+GYV^Ew`58~r;aorIkc~jFF|AexzJhVoc_=`c5cyA;r%iI@VEnThm01GvS(zeJda0-(}=z09#zQ(W0ejekZhNrJXfxA+?vGi zL`@At9*T~NkN0VTFwMo!W3yM>Lrq5TXS03kR1L8>ujkPunSE~1QKr@X2a~9qa&5cC zGT>?9)&4CWFgBTy=k`=qcORp~_E0~>1FQG(vNY`BA?0e*q?}3jX^e(~4L^QICp}-3 z@4Llya97byEr;)Dr3VTW*gAW%fy#K2hw6pc8omXq+Oz#TGKx*j-DzqS;o*?8@kgpx$;9{+&ojL9dw6m!>g?t ztz{IO$XKK21cC`wTXzMypENT2E&vts zak&C^#ex0c{wb9n+m<$ZYMNs}0G^RSNgb&OboJ9l^mQaKKC^e3ZWz)?FOkf&)nPH%z zwNPU{@ zq(HlKCT%OLk6diAyhe4%aI4!0;5Ylhmb^dT3o?j=MRIzx0piP&yLTC~=K}JBMEz@1 zAqUqTtv_SH3nSz&?qPEussB=GoHIzIHSsgt61fgk!s0k(;m%F`76{i#_g>rGUG@M> zg8Yg4aSUBXG?D9zQF{M+lRqQEz}&}agKX!M?ULzwl0F}VSJ|wGZOfiLX5mQ*4_$K`U%XSQ8Rz_xftRK5F$`RE)aoIH{DL%FY zL?qwWste~!YqQl#M6DPdW8S!=$uOD0BUMK!e{({l^uE9Ve)qX>@oz4hT;b(Ao zE0Q#dVN}bUW7nAH?r#f*YzW!y?mQ^Oc`}qZcS08|UA;edm5~rz zPb`gDf#LsV{ksyCJe@ah!Aq$zAj743eOxYav6_O%{lq7%}IOr?||^81ndCt8W}VteCRMk!yu7nVaCtmgN(L_g^FOic{B@U zg#J(+k6>-AA@;D>dxXgfP~yE%El6OCsa=nteKCR99u1OIYOt_@aN7^mF`d=zcwsk0 zAE4Rw<==lYvS0-W;-n*upn#heD)Vh`!0>Fus3BCir|VQAx`uBMI&DrX*>*wKVI~%K zGxHF+?0!-Nlk!Y;M^b5T7^2Xrqrc-VmwBElAL~6N9l`e1SVzGu1wglZyLch}<6b1g zsBd3RI(p{1ya|Yi`An0q20fgMJcuMLDfpV}hU74FTwXUwJId4^;$Ir`fM%&dEj+uq z%S3-5W&BT7G_81uwZdqEWmB4AYzp`ETgrIaC;MHoF*8 zZ5d9MI%q`3DFh!` zV}~K22_I;21R*~6`K!@L9l_=eHWyrYv#|q3#LG1imrMMDrEV4gq}ER_=2!pd zshHUK+{*(-Eiik)7tqNT`5SE)0Yt}|Mt5~UnxdW#U*Ky6+PD<`6>ZmFd+Ua0U(d!s` z!y{{3FS*PO#3;0bYgz>Yd&Cemxx^i)x13w%td4_Hy28%uMD%i_q2lVW2iX9O3xww_ z;)oU@?na5TID{`-NhfW%P`q`8{+tWcEe{ofD;z?qW)DKrd`EZvHU(=*h^oiny?=xA zu8z&oK|EGtGu&HdFn=;)uiW)+Et1Z{IFlMEh0IBy2*kCB&G$ok@qK;1<1}?$OU}*G zS+o<3oAV>?ssUOYA6-VOmeNqaPCFgMH*X`W+V!_{UQ0ca9AL?+u0(NZrVlSlmku-xiT;=r%CLeV$Nc%NRT zGTFMqJlS)5y#y^Vp+C3gZy4l=F;C^v=b&WDQjthU?Zqk4J*($p)O~bPgQ33o@NFa& z3s8YVK+G9qp|PI+}#qPCgZeq<2f7&_)8j zvP|O7hT$5bJWE?dup}`)tprero@Bk663Q6`p!2hB8}OEHB?jS#UUNP=l?>H$^+>xG z@Eh0y4+jk??h8?w=5F`+JO&b!LROmKTBm=s@Ao8G+Et&ivZ*4)200d<<0e>cgu(~}we zIIPZdNBabRmEZqvcRa%~fhJ!weP^%KosY*K`n!GEItzYZkl#0Z=O+du)-07G@myt+ zgyPGj#s7Y!)#T*{GNf?|;EdCkHo@z`tBl$Jp%U}`uq+_QS@R~-hzbh~RZc5I?5Et# zr?8jb`16^|{)F2G>Ep*KF9rqgvhfs}I4445x!~vvJ*zi?1Z?Yb(esn&W7x^j@+tA= zB&2?jHW3W!cWwBZXUm-h)jd1aepqd1<0rK6qavudg2Wc(WY8J+i>9b`wQ z^Rsblb_btbZZ2gidW%RZYeF}oB4lHQ3Mr{ij((clIt$+BEO=N|`?3>89scplq@wPS z@I_}5qS)?wJD~XKaieai^NItrf3oHEJc9WDggD^-zOpVYhv|<}qwKxBwQW_yly-1BPDC4NcX7?hC=V4R!-W?2)*`97S-J#n=AZhS z0kRmcB$R2+;d~Hqb>tFF?Q>L-xS!`0{{EO8k&tqp!*y2!+iV2u7kz@Xaj{ zXr5P_j-6LQqgM~Dq}oTsATcY3unmc{I_+Xvc>xfsB3Va%xZ;y>m?@gYMseIPm zjfDB5nRJ4t++77tD-^C>YH1>83z3?Y<}t9)j0Tdj{7+11R#aKEmKIh!fm3+P;Xtyu z7_;^o!Mx{$>YIj@cz5TQ)}!PxPErCS@z^#d8n;s`<=6heD&ybsG^y{DQQ|1ldK}r7 zK{Z-|>_gmBH$u9bQXH`NZ^(2)Nws9SC=%Zb%8lxahI|4^F4E40dg;RR`^V$es!aDm z@_DK``yLm}COLtR2S%Yof|5|=O?~US0wloAP958{^#{%(NJpcEB+sutrx8i`mu*tG zpYT8t!Khi$5cpfgYZ>vbM`YxP9%*y{advkB;$wV@P^r?J7hH7q_@)~dEj|nh{k6|a9b&K&pejj1N=LG;~@WKsgz!qrN(Y&HQ#>NE$ z*k?%H2SnRxHRfGmyx)F4M`z42bh6dEk05<1m+uuaSy`AM3IeqBI$<9X<}*7H*bkD` z3=2T^fbK~At%Oya^W#O4jG~C_exI}|c|0*i*Ea(o=W|qO0YD*i7^66${<^%!dLD8y zx%eIi@cGeFwiJ@DrxxO$4b!Ntq~Odskd|Mi3A7iQt;#q})86YToO8y@x>2_bc%cO> zV30A_gWQ!Lf*m@5)RL{htTv{dRV_Yaqm$y<;Ol4x+o5RgG&Ri0|90Zzywru(H}0uQ zipsUYNfNmqW`IaC6hblz<+qUq_uGRn`GpKiQ|X z+}wabPFw5l4pK`#qQ=0j*pTY*`v_BRv%O5u``Uh^YW8;Kyw8v$?T#9t7RHFasKmJO zKYYBOIS70wMHj+!1s9@!vsURm=b#55YEv=Gb>Ry-wanB^mJ*B;T$NDL1oD0|BC0iz z)qun|l&5rTKf&xxBxtkuI9n*ldH~ulbi#5nJ51e#Mk4+jmsyQbANEwJ0gcA{!UWj8 zv*KYd#cJgt>1S8&+m)OKUeLJ3Bf@pvlN{=kRn-pw&5EKna#KQezcey6%8ZxW3v4z# z+uVzrj%nT|H1u|D=vRi@pdjM8LR*5#PWMD{Dn&k@xoT*6qS<$AUMTi60ktJv@$1w6 z_6ro8|H|90(iEIw)}6sU`i~`6S{o*P0SClWMODsyp1}FjDcKXRoEDQY9MXbsyMQOU zFURwbb1*^<3$AmmRGQdrH&=MfS(K%9!;Y5WpXbkCKt1Q$xGs!koblM0m5SKhsAPJXYm_LIF7DweR z=(!5Qn#0NpgQ;j|@;BE~LXaRM5j{7L#$vdHgEhnRP1k(9JOhh&nM zIKx3aw_o!dKxcDlz;>yF(Ot>vFCdb5m5jEYLv57*xicO9b4rMMX_`8n zP+5*f7R6vvdil^d=T@0#R$7=h)N|JlTQM35dsc;`U4wzHib2to?bOK9B?0|44U#$V z)OPy}Vv+1)so{&Apyf!^uemMn+Et@HqW#$a)1|@w7AVxt!gBDjd3^NDC!z7#_}uCv zHA|E>VLi~6dB$BVNR;ze9rt+r8B4aP%-GNQI*pkoOVgb`taA8BAtZ5Z%!*!KmPAz! z2v0W&OgSS>Qs_@Sa?5#WRz;dVBlYjhix|cY9?Cg)@jDqQgignoG^PMS0U23bTvcY8Yag4Jli7PD)=#*nx-Mg<|1zfjgYUB zT{y96D+-ZL z*A=y$(cAFiZlyYfI<}(aAPHKE>{>v3LPhty4ygBEXM; z{G(w-{=kY$D>r#x|J6c|n<)*?nXGAZeKabfFRpvSFIU`rXFXt^p~0eD zfG-g{r+nBm1=H@OjhP7(i%313CK(A|(hRheguluXoWE^x!3NhA3w%g|XUDu7-sxuY zqfCA5E6oqiAYmLM|5YF~c?dg}z|2j=)a>vi8&}LOBL{#6x_DJscKyCu(Bl-kdMF>Y zzH9*{Xn@*%XN{utkV{2-E>ahRl^w?NE^vixXnif0W#;aKOpulfxI+{}84edR^%cYM zhvZgSz)YdMcj{c z`#HiA4v@_)1}ks|RBUT~O`LxI>I6k_C}2&f(@a_ng@GYQRwmO3Y+tJEx0gAETCjD36uSTOUyZ87i5==Y3v!|Xku^YOy*^NLR!2NTHrKdv z4XS*h4UvMbUqTTdoOkY z*Vn=|8ba+ccH)5%Whp5oiN4m!%=Wl#B@<{Q3Ok>MV`mJ?A3EJ7jy3HzEiPPv|ur!i((W&<0RzrcN zcZTqD_~EqNV%b)C>Nk0MdIzQAc{Q=V8Uh!Z!}p9y2lB&?wZV4;|h2cOzw*6*^n zXrk)Xg1r^;R<{WnzPL5Q_qy}q!AiiispU=!6i+n5~CJNiZ`A}hwxTz0@7X4?ew|xh{MdZYiVPQ z7~|ff*SpS}%oVM%3VWT$9-s*%XrRS?e^=f=Ff{rmBb`$7wv3cymANRCc!TgQc7ESg zoWcE)eO;p*y%ww?ej7h4JO@$7f0yCZ{(IWEozQ;aJcf$2w$csaMiureyx-etyY&=h zDOzRDhOytSa+|)6G8zqg!g&G?QLc*06TwAWt_!k+>Fg7Uq%dGdf4G;%F&_A98DmV> zV+`|Lb|qQB+4-es0a29sc|OOl-_;Mf9$G2X4(`tV-e4kpoaC#o`v}ef1uXF-$&M)Gk$*3+x0`w-%=Oq9Xeze>*{7thH1iZf#I*BjoH{5d5=HFQ$sIn zFWpUW1pIm;{Jt{xJG&bJG<-sahXn&Ao77>4YOil?hR9`0rME2ZP$c7;YLm?HMk|SE z)q3DM$ljEj2qswT14#_RzMA?nYx_v`_tHYr8~fnO^n6aW)AK>4)eS+D*qozGU5rN4 z!6ov))c_Mv>56uH@itT>7cNtR=7C0Zl#vcIIpioOyq~=l|4RgZItsIg(55O-X)Yj% zq4iDl-a&i~^3uL?9is(rgT~?Uhp%!T&Bc<>IMps`jQ*{ONOf8~I9(u`zx2smm?%C0kfhg^AG8i%$ zX2JRs=mFrSQ6zjTqh;((TvL$qPR@`$h4k^%=3R0va}B)rKn9NwWBMH*0{JGLC8NWU zi-L12K8pTpH6b1B^*C@=9X<~!(>ZXkuDrH$Ts5a_c zoEsi?+0sh0jZ;Evak){FH$Ra&w({p@xK;yKcLE>0->0VHgf=T9YuuK%z`ss?*GD2< z!50(Aca0$J-zBhtQEnY!HI~76kamW;iwV~S-*O6b8LxF>b zzzyfQ@ngBP>j@zgKss*O@8E2tl!?yQHu58fY~oX3{DHj~`$bZv*Se}Vx`tO#(_nf; zRS+s<2W+9GqR%@XgCM8iy2m8-_>{#u-nR4FeZX2?gxFdqGdB#@-}`k4LIG$j9}~aH ztR5R^jIAqnToL#bG*aZnwirKD;@(IZv*dzso*^3Wqhm98N#k`2xEdh$p1-8_GOmf@ zGDptZZFipfmk9=J-j7bbo!>Vms zv6|9(HcLh%Hj#~Jy@EB8T|u#YWv`Jr zQWx%;^IfznBREsiG__$azQ&qW`UbG>ifwDTc#IWKvNmD76%z=ioFBCPI#WfpY8!}O zo+)$oLVy{Mb{Z93CT{XtuX>ug7hg@a@=<8OJ8X-!IUtvr9Qk%bb$T&9P7 z8?8Jc4r{W5>%{wivy+o${u_bazta#DH$nop#JWGu+)0UHp{c=H{pdCsOBN$%O3&x6_mQAWQZqlBp#RUBG zE0K%wCQ8z-XqC>Qx6OqA<$fLEyhq=Z-KEs<*;yR>jtxo6_Acy}fPi)<%k44X#==_N z9h~8O#`1hMulwfPHQ?mbm%?q7wf8L^oD-6Gxoa>$TYEd=BZ$<~YC&W*m(+ivUPV*| zKoUNqxXC@$R&?Le7FAM3y5XquoJyiB;8xy~d%9Rcy}7QzJtJ#nBXGw{+QWs*k- zl?oX;GM`be7nJ4br+In)S}2+M_|U*&=~c~&U%6W$_B=bWCy9R}CGx$Os@g$wJ#zNb*K6X0{n_5 z3BJzWOjX7k>EnVh0kSHPA4Z8q+!`-0vqmgxTsiXOVkct-vDChYz8h^W_gHk;dRsLy^62hq2vetT%DQCR}i#~E~%-W zfuaw-GtC`6LQWFAkm7LMR_AklG{7Yf)v3K4ZL*11dc=2)4iJv_<#wu%y9j)#?p|=; zNcQfd>-(TU<}?d7ADvNqTRC*$*1#ha&nqw?C*3=w4HsJH*M^v1SdONF`A*UcLKUsC zYhrBzoH2ROUOg3`gz=eoKah>h^QeXLXAs;Fo7P3cSTgBayLlPPQayv+80g_T6RH6w z&feh)Eg;?1e0yvI89U*`C{-KDCcri^V8j^az-*D*o#Qn^d&c;+j5u1q_yuBTlj&2} zl*Ybx?C`HRm~GZw_3Y&20B(EI%J_UHH|+icQVIl&@ep3mIct?t(yR;RE3r68!GL-9 zscGjt%^8^eP|%__w7mCH^Ii@#xWh*lgkDZ#^TpvzG?uGuAmll^M?E8KUern3cmHm~ zD`{TX(6{uMn7rmR9!5K~2BA{lFQOnc*mf(8vmdkoSeG@2?*Aa66J~zi^?tg{op{|X z1~am%KoNudnV(|zy!kuMpB2SiKyiXWg{dk6BY)3egBs5kl_I~dqDS{46CqbQY@F^x z?#9dk;=kI?g=fr#q>fFPYXu7+qi6tW^U-k;f*YZVt9#yrY?T%hj1h&%8QLbnt@oz| z3h{NaFZ{zrLq8#(naEUu?<9|GeogGPu05A;$RuD0eA1W?j>@3Q%^qLz=p#bIQ7 z6U^i|a`4HVt}3&q=e!YQnR3K*Jr?n6ch0+~mRgW&6t2j{uQaNi^4*5)oa00els_;f zPsk*%bb^FS3QZGBxBe#ZTuvqAGOnGF=AsuA-xb^R44|^=J;L!VN~}rNr+WMHK(G}x z_(hoMr%P(zRVgFBknR?OupY>^{u{c=uan%F>!0wei1X(;GJKd);l7>ww%=vIa~^iu zVXq^sOjc-$hwl z*hb8?Z}7}mQi1WAtlA8Azc%E_fPXuiUu}}b8n98IAOe(f{1wyzCn8ilA8={{AQxhO z8r(}VV<{N}lNy2oRsVjA$&V;V=D&I{P||1%85F{Nl!W@hIkn7XaF}H9e&eW|Rf$Rw za#CF$JXTl0!S2c9d_27KvB5>67Ww!%Z8X9jAi57#2l2d1_KDS<8(#L zhQdNIZ2G8}_!JJ>q@fVywkCk(4ME{2VkG9ZIzPwrsYUm#4j-11-(ZC%>Inq2Pi*i5 zj%$DD1qOv75v{(d&r$;usQc`{V;uvxza2Yz3YFo|Xh+{Zus?KwtH9f4V{+qG?!=O_ z_@8}tq%rFaKwNJs_nl~W^_h0I4VMF+`VY`PE>p#+j?lQew%M-m@B0gVEeB0Di=*a&mn?@G@MK`16G6USjTwn`OR? ziFsYrL7NoU9N*u(1tYSmDL;7dLz%O2zypKA`JpMIb(qqLoI2-kiHarhi@c`Xf)s27 z8kVHn?Y?#XZA2W&5G@uU_NY!V)Zl9>j@)ej63#UZ14TK(39vd`ueNN)q$w1|ySY$43vC zGqG?wXh>SYGK{kV2^L@yPib|G?($RT=Z3ifDkMyn%7WOIv|=k6cY>B43q&?5u)xWB z9N$HQj$S{A)~}1)$JwV!-X3>s(e6f+x&Q%>QxR@D==$33I!gxAo?Qn3HI-@WZ=9T! z^mVkIZZ_)GW9Ur?J&6w-8B1EF`{n<^Pm#CmMu7qIpB|cD51g_1dULo?;5D#^omudzyebZQ8ruz~gLEa5^2%T-@owA_9m^ z4M36gd`iy&LH~_UH##73a&Cdh`hNN1d)o+*PCC>PNLr0$wC5TTX-Mqo)3~q>VG;fh zS}X1}EHW_x&6=iLxs@Z1kWR4TKl^OVFexSM7p2C*)M0dmE`s6m3nm9#2hf%%!?|VI zfkenih>pJ2QB&qm?^z+&mcW8T=nRk04>!@9D!-0io~l9dKmyQqE=1y5Sbb95FFZEy z2Y+7cqU1j%OKTIV==83Mp1q?96aJ$Ob@rO2?V1~VZ1EP0f+?K}vozJ%6btig%I)uq zU!@0(TI5$eyS#yz9!=8G$KvPn&N5#NS9$lsf4*q^f{k-+%k;MbBCTOZ9&4CpCyXSCLXqf`HTm9PonWo@~s6fJJKa-3pe)OMRWr zQBZ-{z2wj3;l}ISJH5;wy8Ot|lWD@Z;E||{m-ZA*)L;_vwlWveOqpzH!aWm{F|_u6 z>zO~uVOQOLg;b@=S{d0N3v*hLAlwOTy@lpVDcS{bHwE^#x#f*t698LUrZNi0fcA$C zE-p`no(>|#Gqn$gQH$iZ?e3u6v-a(6!eyVvn5(8lB4+Yt%bfEOb2zM% zK?8(bvqXWXJ*_;yB@PlVd0ch(11Qa}5tTA62a>KGfWHwOBu?(06m*@rmQkaao=1Pb zJ&R0m7~q2BEmqQxU-3kxIcoT+Wi;G=j?~+-Se+gR%h+l_XmBF;#o5D;5_XjoP-Dxi zRXQ~vJ=1?0-fd48B37@P@InA>SWW_`78^2O7H>WHve7M;(m@tbQh5K9?cNdSt<&Mc z3ba!qiQ&Vh^NP2q^@vkltlr(`kA4z2SAlv!HNo8;Jy71nVrC)~S{~X~{tCdRg*LLq zwi?#wqH(_z0(6c-DI<1o*LS6D*46Ev_yXnRlU6Y_aRbY{*T7SzWZEG3p{6fvGp^Mo ziQ^RTS2Dkc2~)~)Qf8tkzUV_AW8D6{XkLA%`_+bg7M(kl<;2_0BS z|5NTqwx~j_QcM*>ux{UDy~O!>1-L=$<0$ZBH@{XAJhM%D1kQY&UJktA9lnSbbU$|7 zWVK*zwbI1p{vHH~oCq9NJCS*0?Z@>nM~qg8umtbI?NK)_<;S#i9;ybNkU)os>9Pgh z^j@uHaUyQA;?@zGJFVNvtekAW)Un4AjLFmvZ>bUb(aobE{~S%*#s?jE#hVgkykH)q z1O`YE0o=@4x1BDxDS6qZSqq*b-88{fnuk6dB8px{9-knEzn?!~(Mg{jd!SB7!W;WS ztzzLC@jjbk6)pGMH&T6w=umY9sw-Fg*zrLI;Indr`v^UDzMiR+0-BdZat`ND)MUV8 zqd^hK(_sX1x@Vux@ji0Nbw zJIG9c+~5=(Sz2(-kA9$7^jlZMTE_^UTduKL`uy?$tm9Y|D>T_tCcT`2%O zhs@Wul)HR(ZaO7%!AJTubFQk|^OaoFO3kzzSux5p z?KH6Jtnj?RVpN+rc-qCU?W{5naMp%ymW(5-7kLd$Kihdd^Xm_jk1jipP$ZaethCp< zfni1l2jVw`~zMFED=j-iGTtn*jcL)?{x?dlf&4i~0qY;?_LUPrE6*^a&Y0 z*6l=_kl}V9NS>2)pS|4&dN05bWYeuP-_wuAMSDUikvvI|&+TGYzsY)*gi27v4O4rZ z1ht3Q%qS1J#{aAgk4HwxO8=vkZ1A+tZ)UyU7sLcV+nvjlR%!DBz3oszbuG>GX|V<= z>1%bx2Qyjc`Lc@~@}U%c&uU_OMSDSdfQf+$U)Flw8&Ha|H%sDUrN&}==G<3T13Dya zX*H7}*g_$dM1x!=hFhpU`>w_-MXBqzsw1AWX49uZwV_|$}2=pOhFr`-6@I>u#z$YrKJ!8m1&+>&H7&ZN0%ExwP}F) ze2t!Pio^cNMl}F8F9`8OI6I>tIX<=>)WmQ56^NG|T{0tu)td19$|_bcHaFc?(?d8U zt#p2@d!Cs``iRs1?qlCQpsa?2+$MC!7K4yL7u4DCt{(?!xhOml$6+J}1oeHN=$08x zu3X?Vf}60qm)#;;+m4Y;eBXyZW$8^H*A7=iQ0st*Ey-Fi+KFB#L>g7CaEtAjy7IiJ zOrIzryhp?^i`53|O<$fxt@#+mAKODJrmgxf+!)aDtQ+f%$Me!usOPsHoh>Q*0r`<$ z!wxkY5D7^`ArUCz7Rf_c=M$6CC%M?zRajDqiyxhs=MQ47CY@n6R}8^|${NLK;Rf;^mP3r|%s4S=f2Z8r#I{ErHn$94 z%waPupWO0{A;y@Pal#85aY>2n=gDb9F}pebX-9V`xTLo6=oZYAyL&pOjT)10jzIcv z6XA3Y;BNHsmz14FjHP3>Bco?8At4am{DQKPbJJQw)HsJ6!IJj+&h+~1gw7WiANC`E zncoLd-Il#bbFXK}?RSY0(draR04HdxMKK26Z#rpHm_H$<$@mURkT>_d&T3ZjR=uNBv`zf*7?j{Eg z*IC+`BPzEO6T|cTb+pxMFa|Gchfn_Bl`Fa#4Fg$pU5vCxLyxB|jx9b%b&jJAT8pBW zun%@eZ3B;V{WU;EHML7d3BLrRxyDfHcclCL^Z!zNe0E?qc@Zc1KEayq_lrDt`7GmuWa5-vI|lT=SC z10y$=qwi}7Nfk4mB!GkM^~3@GP6sf@>84laiv_{qUT89@KwH%6hI>~5P_t2i&@y{v zV$OMnJ6GjpywC^BIb7FpITSdl_S{DRysM`yk{Xv`Hlu#3h~NMy9)e|nl-#xA1)?Hk z4vIX24~N`rmhnFf+yEM%f~4VL2LB2L_TB(+z)>u$DOsUF;JRN0T%<5<;4-m92s-!| zo^td81Ql+XV%vIbh#b!Y3wZwn(Sxc9EB4`-z2Xs1f`1PWNm0>bfJ^xpngS-hFZaE^ z(yrdObp+Ki%37tskqmnm2ls&=l)l&Rt3)s9AMULs3KaC?8@2tGh(?kjO82?vD@q z3S&pUXE(aHI2d`VRlbcKf_{^`cw6;rMU>tOkQo*$7D?8QZPoieL8I!U%_DsugiU(ix(l3CqTzX9#xBmMyTK@}x^4Reuv_F~H(;^#{iBW2x;8ZIKVXed(}c=Q2YTu(v7-{BU?*pk$S5WJ`}elL zTPf-R+;uzcaMI;0%*u4>i2JhBtO%(>2x)@U&J!*A;(fgrFAP25agp)gCQW zAzhe{fl>}u+Lbx2GNOZg_1dxwqM8^Rpsw%_THO+U4X|YmF@OuF)MH*;-?+`n&G$;} zSft8qe@P>VhjHSD*n%f&kVpL_0Zol=%g!7oAAYBau58L;S&2{NFXk207gYhOIDi>M z86J`C#4I>E_{pTh>JhWn6ysN?loQr~!N3ba+Z$_buof^bh^o~VWeyYVGMB|Pw3Y6}3P1>1xO>-Zy5+U7+c5Cc1ys@A7VUAW}OLC;OD@;*cv*8^3k zXa@qd7Nm`GGb)>1@-%B|HzUyJ8F;-}r5+xVQp7)9yB)(E2;Bl-hLQ;@rAtVWn#7aW zr{)9&oRh2~lZk}t(+q)uJ}O-k*S-QT*_4U*-`0$h;4vm(gaAUqi$zZKDV*$D(5VV5SAr3S()58R?470n@YeK1f=Or& zf8>OO&n@)(%}=TW-vA8EOy7s{^c0qUegsh&Iuyyv3H+Ejf?TVM475W(j^^zk^{0aD zPKgD3go!fLkMCq!@=If_oCSwHa8zj+)8eLc0!jkIz3cZ`R`#ph5lRVaZyC8}XVI{K z%SQZTd_Uw9o_@0ZCP;XLi0AzH++o`uLcK3E3F=F=gUyz==yuQlOe;#08<9T9xrRz! z<=#%~7aQP!Aj+VOn8Wl#i<{|v?-`>U@}i^=r2wtF&MU?{FpR2s7A0r^6_RTvJ}Lv* z)t+@LQ{-{S4NiZZnC8jb&M>*c^ zShEo*M%+49Dt_uGr{zs<=TCNmh@3Qk+#fbt(iHahYF4>2L4&wG14}?Ab-?b+$+<%p zirSPufqVg37POK&nk3%~ia!`~xf7IYz?p6>QzdwNIQFu4I)9O8d3S5xqa}$V&Lrd; zrq>8+Ei;>}mrctJ;}?@~ZQucGBrGs`@K^VYb12SGJHEL;=eLywu!$l$sVEozJsQA_ zn{Vc~)@W_uZwU``@@)+PzZ3{9FP;B@F<6gffyEv{qR?;w_(S($dqBArPzI{DLxg6#8iPkpkjSZ`qm zP*D>$Eev*+u(wnv2$d6Kw*P2!l(zAB?Qt4qakTJRC-w)Lf}oamj7c^zs`R{Cb#HM+ zXnroJxak?ie#4>Hvcl3&;cG5{1x#OZB~%xRh-_nXeenYF)w+P#TH5DSP!JaNI1t45 za9~()LMQK-R+P~WLW)(o-&sy;nvV++ zF0&9X_jUZP>+OaG*Qp1N;YA4cHq9$zlMEo-_S7{YAlODDI@>%6@0w$>$Gu_hDX^dM z(zd-<<5NeD_xcyKS@nk;c=!m&m#s?SbaNXrhBbzHq7&_j>WyaI!~lvtyN2N{NJW&s zhblZEr`ws(H>&FZjLMV;WD9N^nF@>+Rfi)`8^L5&=%DSx&+6IXA)H7#UP$g%erYTC z6dQH`;mJGgG75=G3EmtI&wsaBY~>;~f;ebXfkFUcy|^q(ixas*`gmQHZ8@N_)=H7j zFs$YJe2_YDg<1upRR^+!X9y<_ijli$&g6+ z%HYzRkpdsDX>USQa~kzri;fSdv%QN0QU7IBir^^OnoES}rv6~{${fWisNHFs)@t(9 zfHln`172$Sv*6ZInu0nCLL!uX>1lH4Cjd$M%CL{1Iz9gW^A@1Mr70s4I`5{dcd6FC z7<+B{ee{&e!H%pK-L%2AshJW4Qar)OK1FsWtV6_i0yA7Gn0U;* zo1p~ffh-F4n&@*UrF2hCqaNRO63OQ=r$@8L*o`Fn`r7Wc#++T`Iffo2c-h4(djB-0A9(l-?a z*xmp{dz`BDM=Ojy*6jW9)|oAv^EfbkEh-@}Q&r`w?sYp`-b;-9VW2YJ8IeK#J8^JO zuTVR4{Y2qX)R!F6o7`cch^`V-XI?{9qp7Q3!Cwc%DY3;q~VNq z_9b%1Q{sff4Pni>5Pd6xp18#o|^4#~c zZ+U+CetZ&}@*DG+2CbYWDGc#8i-G2qWTyE+4A_{l#~F+LjhAL6Q4P^>yMq?ot<(D} z==o{v)~{?A%0GDTF`poom~DbYzbaMIM8MmE^4im2I7Fk;EQiv4;OI=4p$BV=Ueb%) z0(-)!E#kO|$X(5v&U}>cjwniS`wl)Q5qV)O9Tv|yg=Od5@EMa2(41&T%`LBvf>lT% zDfDy&ATU;gF{}Mq=_%+f;d<@H#oA@iCk0CZ+mk!R}x|;serkmFv_BJ_hrn)dMz>mcs28V-?HXjKYq%dh4_a# z8#QclwlmaG?s-8Q>a<+RViQ(iB#VthwR}i6l+Dx!696b%$t4il{W8D>bIEMSxjYMy zQo*Tn-pMmkClfAa)f&mS;Rd3^X9)Vx8w8%Pz~wF0*!n%o z!TeV%`~>ZTd~*tzO~R8G8nPuq202wAv=x%^{yHX+ID@{B$D*g|MwFe=O3s@kL4$C9 zkAt0%v%Wm_I9q{@5adwKu>Sep%WDR+(pH{pdzm)Ic{gB?4EKfz8&03lR0IkmkBwQ{ zL+2iAQ5GYee-+Ld36JYwqCJ5g^8u_=qEd9Bxze3|=n(`2oMGl@)2!yWsreLwHc(q( zrP{z#RoDQn4E1%n>A3>8&gvmZF$$luKF9mcwz-;I8|?6#cVw~He|R37NU}$v%slhuIwY@(FXt7i+W@cFO+HoN=Vk8;dH=bl(B8O@hU=gJ(ifL2*1-#5!l#8pHNFi)^3znx-EU%MHwp*z~RB8rDD9ePt$cUm=CFTwq@%YUP7H z?*}Pf-xu^XJrA3FhqM?yIl#pYxkiwp+!kC{xGs08dmPOrTh;`lmY(Djcy{67^#@9h zzlZCCVbPgSI!=OvP{(c(;Eqg`Bmwdj*{#wH$0Of-2s>=S?3@KCTD{V1UemlScHX=4 z`QJhg1zqCwP7$I>6pk~SB2bm2;^8Ys@zV5!GB86LxYTH0ETqK zW0nyT$RrsPs9`*X4=i@zOE42SEQ$EHT2Z1tavrs&>s8ZAfqkxV#+0C5A_Nb1 z#yzECVTZ&`MusAXlK_5=n1I;jhgIX1$TYg8ESLc*%1b-_vduJV2^lNj0yQ!E4|st3DVdz!|6o{?DR>>@E8=VT!eacD&*Y_ehsYJR2Cz}$fHSu4se&bd_{b`s)bXOb3~<}q)3n# zW{9Xj12xVZRAo{V0K4>{r{N-7$+~54@dCA)t5pCZ^E57@N)3Tg=NuLLM==@!={I^S zwO5dF#9>&%PFfLLZ#NS1sw;C~zp9gnPJNS`#U5P3u1K|^&#;yqnYxN!+UL|O4ZSq^ zq21VLWlydujp^Mo3oc)1a>2v*)PfOK1fZ}HCwy%6wF5gztNKASP+oGF2nD$c-Jl$F zI`bu$DG>(OEA}PhccDW%o%iov$r#F%{6b!!p%`u$Gd)J0%QrZKog%2#yqBf0f&g*e zqORf&`3RygX#s#@y(KarLQkJjKCza8@3B$-H`MffFp3-otO79?9x;R=PiveGFFtd> z-s2%Dw#4mgT*eF1qbKH+*1)d~!Sj zk0**J%5!F-u0TIv$2T;700041naH4tP&P$lvVE5v1CdB*KL(AeeA!-{dr`%S5TjAhA7|jd(vuN&1U`zy1sxIVt6tokf zH=*cPb^#0;1UBm;gT4452d*#LF{)gn2bqrDK@C;W)>=UfUV%z1+rS7A$S9aVN$D(s z6TsL2003gHn6_5IEOFB--z4HwlB9A5r0Qt__?@jCg+;&|?JHu0y(%noj2Jb%|L49N zGj>ID=Fb&M(9e$P&!4wo2sU0==y#rQh_fo=&mjrRF8 zi}BQz0Z9g?9X}*eQI-*XlS;c7wFQhq89JyBrO9-_V*S{IrG5ocPADv$pCzY|x5!7q zJZdRDWO6_uCvi_EyX*h~(tJ^8WVbbacN1uBe{&SLDDp8Z7d{37Mjdu>!oFS zJaR}4L`;-L#diFzR-oJGn(GDLo^ z7a(ps*3%!nLT~&~*AWhsh&h2@PgDt30H8VEwe=t<@bJl^RVN&onmG=15U(ulJ4609 z@CCH0n6QN^%(lqy#rT}`^=ppV@7rXucmM!VHqbLd{(Dw*LvvkYcr}&bO3*5h(-b54 z{!qel2Eo&|L&^!UG$dAF&I1$k_#bfksoF&DR>HTAOE%wwy%|Nv(?${z<9`^_uQz*o z_klk+c>dzFFC*CYoN`(7pV4-)0bh$3??$GJ(#1BE$H#U}oR?IX$^!VJh{iDA7?@FZ&-}u4w86L6gE{xJoHtzwGK((J zq2_jPLSSggBD^k>ou%)ynS-PtpNE>G#k3Ox$!1<~IHmOmBvajQUg-s>2(GQ{zq7SJ zXG_eIlw;#;0JDyc>*q|sXJj^d1|ldT^ng>`z_SK$pWSswc!*CRCBw*2NmR?EqA6fd4@y4;$ln+doRTO9 zVYD3#FqPe(i z>e_{)@6_2$SI1e9V$yeM@vXi&Z8&7ZAFX7OK$*1%`gF}VF#y1 zMxkYIHDJX-3UTQba{IV}eItz}jR1zCiZQ2Hj&i2Dv)W|BYffv~0eInF5u1NOl;BR8 z=K(b-qrYx5Vj+`s%h#&xEBt7l)_Ug z0vMkYM|YBe-({&1=lFch`pe=7P@;YP#ZQ1 z2ZthuPXGV_(Jue+Y%q@j01i)~FMt@E5dLH>jT3-{Y)%B{x;Q$?zyd0W_8SmMX_vUx zdFMT0AVO^Df6s*;v9BPf#dPq%yQf7d1fG_2ZiCGk`&DKtUf(_CUsj)Xa=M*pbu2jf zyPY-#3xsN9{BtUrda~%WPP}u~*C#)M!mL87`$A2L;;Ze*%-DxCl%*4vF7fTG23C6rMQ%C5htOj^27b8^Ej{P+Ljza_taHf;G;`^HV5- zGB1W)3tK^+=3}IbkT%Y=p8}fu@CdbaJ8?n}fIH=&1q}%6MLh+~3kcX?jA#X8S3PP9 zK=lRv;wTng05xv&LZi7Dl@uYU6<{%_k+T$!VuUnNZEKAZ{0K+ zXWZX8`PMCg)(8rNAcUR{2)oD+*r8wW^}Of$Nc5e3a#R72&+JpX$-`bHCGtn#v*#$g zM9=Z4zN4??H}28Z8Qo05Vq%J=@nIjxTn+#q?Ozd~ zxAJ1CF#*}tPR>CEKYLLUzAN$cWjCP4^td+~y~SXXoC3TEM|QGNVS@NuGe}Z`pFUox zdgXP?Npn>^ZRTQ7KTwG+!32fQeOdI`YC*lnz~e8;E3nCmLiCaylh3GwxS0trim`yw z0JoQrIESEd`5N)cqp6H7=r56^7URxmuZ_6oH$HcoRM4&qk&m(#2r@;$+6<~k z+7b$_0MkF>Vy^aPi+sdsK@}z6Eif>6U<7hwl=mQ58F-2y@5|VDW~^O&9RTX4aKHd# zDPdkSfOZvF7m3$O<{#~>2il+C$I96!v~C%xTIFA9<8=In3z_;9;;r_4qz_%NcnUJ8 zHt{lW46Ig(plYuS^nCzL_A&U8JV>hL-`c@5qqt=O@vN9=m5(4f3a)mzO>R*IDLAOwO?o50&&Op)k(-3_6?j?|9aRmftU*J9Pi4_oBTT1qlYXFRdYKu9R;k^HCDRCP>yW(1tM$MGyj8mIS6 zcWjMgO1GN~)7t!SKpO+~u&cKRM|DYUA9)lnjNXWd=(rLWkItiM9X@aDivM-vz<>Oz zc=C0!_!}%Mz}17Q6GF+ImI$s!*o76Tt2Q-J@FKuL_J3AT3DV^Uz!sk?0H}M8>N1Q(RdSYT`LA8G|5XZsICN zmpk}n4b^u>BgtitNYbRqeEAAU!t#GzMT5Gv^#jXiE8|XI!VQtNP&}tVp{%%+ZbV^@ zFZbB=;^a8I!keW-*e1SexaSUcH|Ep);vt!_#^FU|?jh!UmiJQ0;yXr`*HkeLyy+l%H z98Y^wCXl1zEK&uQt{qK=$tIKsKV2Nxtr(M0UC)S?%j%<=u$9Nci2wi=58>cmc=9g* zfB-}n8Lez^dnb=(6}w56_7I3dg8`LJoZc0)2&rV18MGy4;=jO8C1W1(Y9N+FAtNDr z4N`ikoS25Q1I`)QVAYJUfB_}Mz{g4O(>88cKaz|K0t8 z_-XuFi~DZL``dT9`itJZHp4Z=4(@^y5Q@aGnF`(1jDo+8D*mWTr_6&&-hk6wwO`qs z+hr*SrK2qyQO>naEr4GFZf9fx5JOzTjI!p#)n10QktlAi+wHwbVWZ41FM1Q6fD_UO zJfW%@<6eo`^z+R1viMbxazUz6!Kp>409eHcLLxvUCU{SIWo0DYpc_}f=WS5hxSG!D zlvlkKP(L*{CZkbb&bT39k75nJH$|X0mbMIl8lPZo|0K6tewhs_$DQ1zQwu>+U)t)83GQu1YC4VMSkUw;_ zR!1pSbo^-FEc2$n!nU@8HLlw3Zy)do_yZ&|LmNU}WM|&C1l(^umm>48w?Dm=yDduH|m;MgT;jU@EBeq8>@93s68`rq^h-3Ycih4VRyQK1Jg>@AQDJBvhiB1s2> z^fu^E3c%&`6Zpm$1pH{NG&E$8NXxsyv`vkCKQt;^2xc*|4uP#~c^JyjY`lY8WVU_A^2m8 zm~&{kaD~oVWrXbwm?0?Qd4$|YE<297a;&GJqnrn3xM)6_D6erP?`nAAD+?0SV8Px0 zBRoR9j9bdS@k5a_I;}K@`|hhudQ&5=Lohka6=AI$FGN49Nnqp6xhv|P3@sQ?Z1IP{ z0HT5;reOZlY=+wLSgktFe_j|WF)9jad51{EDxVF!s%9eg>ERvX8|$K{jX~q57@>U& zCio69sPf?*mF+3D&Ry)`#~$WweFan;%hqlW?(VL^-95Mlx8Uv?+=9EiyCwvO;OW=iJOBfn$cdGF)7(>2{naWKo^50Io zV#E6`*-xgv&Omqe-MJ|YeSof3BD-wBcb-{at~)E#S!D-wCF~omY5FQ z62_V$+jz!Gna)@v*!AYCxQ)Ca)uo$1b$4~cSQPRhDOa`kg-U(R^wnf+EIE_EEiwJ*krOO%W6bW*UoL-*-~t}O>r=l20-^5CsK=q6?vmrPuUT!J+s>r=9%8s-Br z6dYa-v*i&xhwy|KRRqO-r#}jf6DY$)<4Z~|UBOtd$?2I(8VRu3h|`w#`9MEhS8XA^ zd^dB{d-CcAgB^*5VC&WlBWvEGOg}4!Q;2yg+L%6+@MMiFE2RPJE5J4?P*Rcp)^487 zH>6rJmmR0uhK{Yi>--aOjf^v1Mpy#>p$*57AF|M4%ei}MCnRp(Gtl5#*|eRe>HWjP z95n-Fr%v8^sjm!tVYt1+uzy1rAa*vW#oJ)bg-B1K2Um4EWgxaltV?0 z!bq+3L3wZ3X^nA%+d9*tfyFS1mFxf{DH|5_@j%A>IfrJ;BM`)22?uhFc(Q8RO%c+3 zbAC7CyW+XJ!}-NhE%$;ME+|IB($6tE;FCf2W5MY;KN{2A#*ma}NLbEd!t>Hn(=H-7 zQe%bpG^XDsya_Phyg)ai<3}do4EmhNiMuC(y*oqhG@<|SY*Sb16+!gLgCrLkj|;8W zFu{VaV@_>ZSH+7goUTtsTd|tJITDRi9*z}nj>FTNx1%ZNaVq-oevME#-8$8sL1o2L z4J^w8Oe5{$y(q*)K8=Hk?S#{`)$}4nsAygRP=?{^I`b!D%Q??q1V4PJVGE*46Dc&h zHB{T3&8nP*Nq3Wr=C)-VxpPuROU^B%e zC0H*ik*08h32+t|w7uz3dc8sdZ{>R~J+>D5(dRj@j^`0?_ZoD)_Ousu(zyO?F*7=n zL*}AR$5l7`Bxk7$oj?wQ%?H#c+IVKGGyo5ZHHg1PAMgWzb4xXPp=EP_@H zc0@LD2=tJbF$URatubs?%$_4D32H!oX-ShH%RU~$@_FtNO-~$reO-%MevqMAAF2~G zVuKa7M9p5A2++gAuf_`bh`D`0Z-K$wd>^*A`8fEY6^-o&5RWBfqQpidiWv|TsNXj} zdP^wmsxO)x-uK;G4QLoQWi7O-V?)ONVl0s?4;yHJ|Ff|yU$((^cP1z^K0#z)HUg)@ zhUgvi!jx}s`CwsJ?;>QHqorb!Q&eA7PFD-kM8k&zJ7VHuNT$FSrj#+ z^6W9y<4$`V-{-B!d+PqIuDeHHFRPg-&O6hYt2;HD0w0;8O5*HC1@l{;lJF7m`<}EQ zhTd0$aq#Tx#qp@RcyBr)lu$fpgeg~D z{B+ZSnJCN3pGlNV-nMGWml>1lb+f^bc?acs&kZo)fT?V0*wPDqwa(DeQZ@% zTN4j}_bJ%>y`0PCJ1KGYRgrt{jg((can@J1)$(r4Wa3()CNGV~3H72lh|A%~+(si> z)NUz8`=Nzdv+PP^;TMol*JPm|P$h)lz@EXm;RbpKhnbmnaA>^Hj}M*KzKYGo#f#(U zVjqWg(_)c`)%2{ymT@fZl1;W+>AR;*XyKV1)s3dR`Rw%#?t0ggk&bQSeZEF?a2fMy zn?j+^l)I-Y@;m3aP!Fp(ICI0fnJI3}7+0BBO+U(_gT7nb+#3~yE|B+GKaCrq?JHa+ zY9=4 z?p95#8ZhYX(rI|Sg1#9GG!;2U7aO_eP;zXsBa;??pM9JvASmw?b%o(X zq2o_dg@O4Xr5{8m#3chh`YmHDtkNl=BVOx~#L^Y&nO>AKMJ;Bzfm)ZdW*QvHx@#xv@rGd6hP*#0JbM!Y<^b77;OgmCD zVM*DH%TR{wXH`;BqkHX7(UFXTk7OSnkoQc$pC}cS09Q67MtM+3&EF(RQekN9)EhlG zqR{=eCuBx6vPbz3)7Bwok&%Y&;Z4ZjsIcgqmt}5Q4)dUxR=98IU}5g+vgL!ZEc2Xm zy!AQIDk5}B?J%pSgI|6gI`s5V#oHHF%9>^`_hnk%FMd8r)-0r}ld=0lD|@?-yRf^C z-9=eP*Iqv&iq@^DmoLNSZL`EF|s+q)8f<=y@||}m$ax0^J{~|9k08H9q#!P zl>9gkfydVh6QR0Uv|qdO*^n`relm)H1C#p?1iqF~RXN%UVIK=VFy!++hR+b`4I6ji zOkwx;&}3AuM1`x}jSOSHyiGBHzp+Ehr6ZoDJXVc;w#phA+;uRA{lj@qOEGJ;7G_&o z>a8|1>pP=GH$ZNL;7iV#oF`?i#W(l4>sMzxh+)-Qa~c?KlD(`dFkAUIgecO&>jvOn zS;!9Z4}x@xxZ$Tznv!R_n%Y6fE7nHkeU03+I3~7vK55%QL&9&mc^2aGmEy6v+|4WF zgiSJ@eNbEr?yT+arV|zZrW_yiW+m#<|KynhAQDI+HU7fC%v+l1PT;smN|7b@wm4Uf zS$I9snm_W{WNJ^~)SRatnR-OkCynLZ!339Y@Z>mf2zl4Cm4wKqDE?c0n>cK1VUo7- zfi~lWvTxxO_g%OzFf(@|1kJzX7wwBC2jAveZhvA^rDc@ltNe{7T_7 zZ$c#;7ki{h=#KLIsKO>~GO@o|Bn%0GZyboa8ecc8i>M?~Ml!)%^<@QSJ>rosjHAwo z#wQL`?XB?~e(K@8*uNWYkNY6%6z(Ry&9n;blur^XR;UBGY^`fBF$-ZZ%dj>kuu8^v z*|Fqnx2IQXpG;=Hmc@@gKW@2jwtTnkH84j_mf98`@5$FfrWb$h)f29@cAjKPEh0b~ zzwMn@bF;-T^CnJAwXpTFkHa@$j=L&}`dZ|ZSLEDle@fr#=U8uNaUunKKB6BU#%Jv4 z9pO@z7$!I?b;lJDtIjNMMi_@8g)P4%Lx5pK2rDTF*&igh!F6Nap+KdMd14J9JC(G~ z6*+F5_~^PpmELK}XR>Y9d4OgIcM>+HaCeB6>FFA?tV4X9%za`PRWb7+mpUEEaTL#1 zsmB#Pblv*_>wAROqdPkzS&~z0{VC3PPeD8(3zif3U{Gp4C-Ivh1C%z0YPmqEo$_0x z^89d*mM8o*B=r|gO-heh=sjNNBT0iA1tKg;+rYszaRt1a2$q&Lay#3D4cAv$JWeqQ zxd@Hbbp;{00NHDQ5{mca>co)3xIEH>z4Jsj2VmB5`@3=88F7MaCiqE)vWwThBbD@wdH{kQegv_%9B!X))2-mWx4p2#@>S&+wrcrC z{LHlKYxYE#`Y+Sy((Fj)0`5J%L@%Qvw7U+2v$4Yha?qVlj7%=mr1+16`m;$9IbjYx zmr@U8X2>Vq-I&51V{cr)zn>#|qVuC(>LHjyFRYs@7UP`Au&=4mZghx^>#ODS#KW3$ z_j-FKaNR#LCrz#x$cZ)>Qmp?1HIr3y=(C)k_6h3oE$b@_lz~@={m(OuYEK@xYuUO`+==_kv{V?cF>oisqxN1s z9E(kE!$Aqzizrqv*H&Kk9ClX@B$~w*Y1~AWmp{#)vO+W#43+zjZqqgMJ&-W$3N)WR z;fYK$MJ4)vha9@>d}~gDeIbUD2ptfk=rWum2RjoKsYMy6h^R@aLY`E6V#Gd$PV`0# z$BAAK9+n=4NZ0>!VIF=TDTb{2n~?FEFavsn8Ohb+GnnrP0q(i>m4@hzCCbDSZ7N?1 zr;E%9DTwSER3}xc;IMz6S&`*rcAK3^T-gg z`I_M*bNNzBxdweRPd_aR zKN>f-N4D$sM}*CxDzMY);v*rOeq0G%FvdDLP-m6IG0uF|9%(^1RQSr;xXRGyv{}0# zU-DEzy<$;O-*Bsg;|sZ#B09|&pNWnW`C5DkpNec7LMvU>jYco8mdkx=ca47x9a@vv zIN>U-9gOX)N{-!%8y0d;JugZ^_%lcX-?n;plbj|V(@SF7z?LYwcif+SY&0z)blL^F z@iH33#-@?jzb3Wf?wa!2G4Nm{28z6H5SEU2#<{!pBoC6jY|8|f3*OUq7Q*mYPzigW zj^<*`DwpMal%u)ZRW%G_FDLirxrtVo`~v;n&aoirICfgsL!W=>+?NG0YA@h zl5~3bS?BWf#evB2YoGt-dcMcH^ ziN(>MpV;xk(F`cn4lUM>FuS{-QNrnDy4?iR0$W!DwkC;7?UJmhJ$&7X6S_^iB&X*k zUrVYsrM^0xsp4SKRjrvL-8C4eJ!5pvZ(ZaWCf?3?t+K_9wT(^s0=K`?u|*3ne*nXC zf3thyAT{R%XM{Y3`y*1RdJL_hnid507OIUzFJCuinN9;QB*@l=nRe5jX8_B6>VU|) zF2_G?iucWCzJxX`%BG9Kb2N&jCMD)ERuw4b_3Iq;UdP$B8fzIi*owZ%4YQD=7c{WM zbpZ%sCMcem+5A|Zut%$0Dj1gj(wG#F5`>)Z+YX1zOzo?U5&Wfee+D6=&xa;3a>*>j z8~#YTu3r_^$Y6rwLSK_Ij+`8v9=+P2+f-RH+uCcgGQ$(o_StvR+7Jgo7Z>pey8dD%Tnn55<94n3jfu^`E-rAN-1oG%^`dX0Eb zG@>*Y$lA|q6PMv(`dIj}?e;C8mb@`9&)iCKZUb`qv-=w&pnP_Tvs9wPClk%8o&`NW zDIAV$Mww~9OsT`s$N^Ami65>5j1%aOK8RX>#vK!_-|I|E#oZ7}JmhI77%tQ(wPYrh z6*eq#M|friBWE_zZ*{VAay*GkT@Um6L>8LwlC|q+j|BLg=f&k%L|s->ssB#eG)*HX zKlq3ywT&^_h8f1|eb@pH#-n{YB?lraUxazm9}%R#98k2#2E{J7bqQk$-5Z>dtK>cI z2B0qHRh!RL7v2<)y2;romZ66Y%)P>~&K;Rj*?;wR!U$kGstl?8Wj{ZLlGNcInpQL* z>g5?VA0c?1UP>*1vPOk*!5|NtG%)0)|5dNbx-EXzf=&5RF`@A(qOG-j&~mQTR@Li( z2!oQm%FbQ8d_W^`7C~DLRv&jy&FOJ=c1)p{8-`7w=o|U$e5K7!*DJA2rXaazR1%vW z>>tyG8WOSS28tSt&57(sY0^q;&h;-oP+B4mjp-pZMnofBZV_+olyy8>T2cP&*J`w> zucFh5I43=Xd8`=!T!cOohYve9mVv8+o03FfyP?FU;>W)5mGN}niNP~tBHv=Kym5Qc z^oGGE&g~<|CEhkMcgiVqdOYG!*ZLQkgC#FTIVjA7kmtV3-s;ZU!<~vR9MgYIztUIX z0>7lT+NYZtC~b@QV*N~8JXE&?pJyr2V4EDP7ocleK>r&2fh248g&5RRyJYr(KpZ=8 zGFnxK5>dSg?U+Y^;}$XFXlK+!59O>wFKUm9im7nQRvh!3PE8v*nHgH-l-fY@Xe|Ty z*meyZQxL4q-%3@K-HbqGbCc>co#RF!R87iTEGsuy6L}&B_#62LUqxPCtraD6m6zx# zCeePgGuWttpEI9`2vU{5BFHK)TV__G*2AYJrpto9E&X+-Vrjt|XL5S0>P_RSUNX6+ z(zNwamFu+4$F?NmN8aI=l(7WsURP&It-$SwHTf94pNI=OYrJ2VUS0~DwdlQ~y6JO` zUkHxhWx$i%nlTlrjDvCx?>UYt8r^z3lk?-4n6S+m2J}~StLUDY4>oZPq4$W>%2-r=b1XzVS2Z6$R7(5@LtY!?#x4XLLCr>J_IAm7Oo~O2# z6z&@${IrqUol7S_54_f z8Qy<-6xlh7uDPyxV^I8IKVC^#^DC=!*?VNm3rKKK&H`0wt2k0|pW^&1(|y?Jlgx&o zEvf{;rkZXs`uma9T|%Lc*(n%{1YEUKL&Wi^in+omIr{8^0cuuPVg=o$A%qsY0w&giZ!R0W2lCRw)4?lj)SmNr5M#y3%Oa`f% zPmH}Bvd|YzZc!#J#e&zwhN~{tPE_FwIQScH&INkyA!c!Q=?fGaKOo~t+;!=D zUMX4PI5AX-#*?oWma|gIUQ}7R(6feT46r|rqP`)ToE{C6@ckJ#xz6(-n=nAd!u!kU z#F2FZ(Oth4*L=O`4VOReFWOwuR}QD`?a8e#Wq%ya|A;#g5uK3_avyf=F(%X!GL-vN zN-4}j_0dydmt9LYD@+}3iRwiAHj5$PEbP+Yg_~L)|2tV|`XK$=Ih8FV--0pGZn;j^ zPvy5Any|^-@LWuC_;^#jORS4~F}Wh};%}P9=1LEy4m^-3mXH}))z|swy)=}{If*_` z?SB{ysG%>KB~i9~j7i>Zk)Rnujil>aL320pe47WHop7Mrq>$O%rB;F z;Gg%31m$uh#>2=fRCN6yh<@af+O#f8IEQztAIDY_##FpG>jd{n&F205X)5-JQ8aAT zMBs9yK?}{M$nry&|0;Sxo2NsEXNKNRzcU*5*AZ>z0`tP9A0|cDstOk`(08kv+m!W$ z4i{AgE0WL(*sF@XVAkoEK4vDyvz55Cob438z7$$qChop9i)X;n5J*Zi$oH_`$P39YBDi<k;r5hdwwTk^>;?WPN7&icXeFi+(~2%R35z}<7S02saofE^$*>)nuwo7tte!~cb8ytdGWONuFUPW zXxj4#UVU_3y`@3rFS6YUEf5Sal83~Ikm+DL?oxO1=8jBU>(IY$TlB_3DKI`m!_-Xt zBBXBw&oc#FJ2O!>&v6OXvNvj_`T6U}v+Nb~N!85E?9g4jgiGU7OUjaTL)H}kq|G#j zIfYNpIc%w0XLDZbll$wQ!GCs>rsbqq(0%v;Y_Umd^cLI4p z5OW)$jr{wh>Yg*E&~V1D3C1I+jG_e=!^Pe+^XO}nPP?_K*6dYLf}GhL3(J_Z_{<&6 zxFucY19-T^6IHgZ_iKii%;v)ngYUdZ_0?f!lI`4UII-sA$L!UX^1rE%R<(ds`p9? zkL`l4DU7k4@UR%xM@u$br+2hWADIF9uevKW;ErMzA| z=3e7cXLo*l+^ggqa5JS^8Pl0)Y)#08w83mGb!rwsz7D8a!9J^~HOkrg(jk-E=K1j_ zw;jhyvFH%iqM-X^KxeTY9N1kG@}U%BzegX2N($8`UKjxLvc3W_|cv#AR&9XpwA(MxF}W z5c4;NGG{7iNVweerD>KPapD=(HEot6BVq4z6)_qHg+m=38948k%{At0Sf$nm>a9%} zim>%&h_DPxcVza~2HD+_&O>4C$%=%_9<5%rEJ$+J`Ib>p=a^{5 z5d25aSkG7Tgo-Z?9qYoN{K%b_$W0L}QECVFqdyxBJEiXA9E-o!eEBh`0Ta!U+5IUg z%BG?DvWriPHK{_GqWJ3>ZReg2Pq6IEYyd$n<`<*_b6sdU{9;bK=aeRi(3EQxbP*zCHSP{Hv z!aT3cDSh^VRscqnM3(e)PN$FE`-Nej=|oGW+HoSTFpl~5JoWo#rlYpCYVo`FyRk(I z%C^eVTa}NqIK{I+v9J$I+7ehdag26{DQJ&c2?=`@%{xt}XO9%&nMbr`(cX`mk_OVr z$KA-I%40$m zXdwvl$WEH6!x4YGJ(NDN-mdqAXN$2kth7qz-z4=WEn4$*MKXqVk|T9R<1FYj4^6hB z^=?aMjv~*8F5~;lFMD2Uq$fUcm|;<5>y^vOnBt4Y%TXamV%NDY)KcF=yEqxrMn2(u zg#NB_PR9uS(z#5<%xY7&#l4M0OK`|1CQWe1WvEb_a3fe*dj&;-M1|{Yc0#0I~<+iCKYf?WmOPtnt zLMio3Bw?qDar%Q4UK9)gXNTDN>0+>PVX#J)Q}GL=;GtEhXm*0d^;hr3r|Lfv`g(@= z;(YT%s#W|lR~tUJtNakCkxm~n{@p$ac5>(I_SkBOJO9NL-VN1Hg^o|lMAUe<7z+fL z@#;4L)`pZHgGUjhJI%dqJ)UxI>bCNj5bp|+K`F>LOK#tkj3 zFP|St-~<9+e=TfoR>6bhUoANyvL6Z z`b%yDAEFsqHBVAF!YErt%b`MFDw?@`-t)UA+36Ir`Bi?wMvwU{lAn=|PI(85HSdxL z+reJJx5C+R4?R~LL;dtc~7Y{ZOFrEr!hM8MP192ECKfHAV2k5KXI<_U4+n6j-8dI%l#DqaN{)lVt75|ThirM&n!_uRKH8W*N z-W*>bOUera3a@P^{amqbU(>mlE{6!C!DVdJ>NdE1Y;B02xjlO7caeVTR?aiV|4NXk zoV3B_GP;5J1+nZi&Th7aNw5OrFrMheopOo&4~yW6a>rL_E-`(QvbM;&XXVRxN;mxV|mM>>MX8J2D*e)Ew z!X>!OYe(Rl$pJ6bB8yeN)VJ1E?H*u6MBJ^$idF2{TrSy?$pnWEZ-~kAlt8;3`i0wV zte`?`ibM<;P`yuWBZldTMAU54${V`Y)^nUeD0XlE?t`+I#K7*|(6evc`zqAwP0&)- zp0ZGoyf9{?eTBnk@%4-2Oz-rV6NI|R7vFDO19L{UeniW(4a)U%&>a$j%Y>pfFtZ>BsAsJ>lJ-5-l|PN8&59#&h_WvhIZw;Q5^t!2yE|L=`BfG6N_t*xNvgON2J`kKm4Dfc(5=zf>xfdj{X}y)| zdCVCzw6;-~uaYDPWh-k1PX*|zY1!|K@%Y~w#|>dK72l;?;UuDmVi24cgp=fouWv4` z+2z&A9r^m1Q?!pNvcR+;8XasdMCKA0+JKN;<%ge7+R_#Zhxck1669_PuU zWfZYM8eesh%e6pL!z{j++k1pZd4$P-bT3Cncuf`Cfi-;L%8l@{ME!ZwwAeHF{5MP} zy1H;u5%K2F4-719mg!li`P1Z-(mR-+bPc>tKRqw0|N|5w!cSKE>C?7jK`wFG^Cb5 zw79}PY1Y^)lWwkdP$^(SGuxgWP>S5^jBC!@?GAwY+2?u^HO_o|Gg7j2#mNI_6PghC2|s~>@clq4j5Fk_gSkT|eQK);a|50TH{@et*oevo$731B$Kok%9^25>$($jsWFOiUL` zYRMyUiR}(9wUdv>;ZAURm=|wbG9Yz}7LMxKl^mj~SDbYEEqvDaROTZ(DN6MKO^C{c zBs%CT?LT2&VZ$keGKf)wrEreE@3@#%;}P=h(k*MTI7R@9d%gTxvp)?d?yi-6#G~G~ ztjB_4Qagq3+j=jn8J%|FT!be4Or_6~W0(JzguF7TjOo&@Pt0v<3ZX%(Gtu$*z zX?i4)qEsNM4b%8146W_g_aUIhJ~<*fVn!De`33W>Hf7qMsYo}sOMY&K@JQw*t$QQUf~3KwhQGYsrIWqo6{ z=t1B1=gP-Y*IQ)%m-(C=m%Tene%DFIct+mOf*ZVc)_lA@^9Zy{acv{vGQYAt{}kpw zD+?hK#E30h^)hC6jdQ4wNBjmSoZ;!x@vbF=L2tlQjQ2|z%pLVLpI>0vFRl4*_qFz} zSOi@O0`fBZrMsjTh?(v#FWFE|_wON2+;57F-qB$;UVP8fpAV_DR%`fntD<5+75Iy_ z3{9}$L};7B2aQ-i!yyrijJijI1Cg3G16c9GV#q{JS{t-nRm^3SLbVZEm?WBp*PMH2 zRG4t76(q*+Ek8CCx$1*fy93qgNn(uVWWPl>TOwAhU##K~E0fE+$Df9bF<18ANE2*T>^_7vEyAQP<`x2HqiyG7KnTxoHC{og7*4^j*3jS1uCwH5out6njKb#XIQ%SIA#)RtE!K8rWrnuJZm%plX2q&m`lU?U}rhbu}%a{roHcpY*^M#2+;EAo0 zKD2yhRdN)x)}uAXmSOdHb2y+;I%%*<=u^IBB9SEKZP za7)w7uq`WBYv>JPPO>KwtD2eZY$ZrZzj|77->o*7dfh;7V6xyK%pl*LP4sd!lxOee zqgqx%ep`CfZ8Xu{qCw}-%5ks^@>+ahP5Hp6(;Jo)J>Jf`h90IJuba;^%GDws9pq&r z`C{4%Oyn{U*iw7vo+Au)AOWgk{8LYNxhu|sm;S2bUli99J zay;Vt+ktP}5_dgl(%{=tIbA!Y+;oXSNp*PzxmGSpD?8_%6Jq?9EE79Cm!%rJyKNO~ z!NlnP!Z~)O(*7504q4Ro+E0uz6I(O33#y{>Zf_%-ll=pddY7jsp3O+37YF#9AX37k zuci$XYnTi_TFz7m=W?l&kSo31Fk*&8V9|^}h`_C)x2j?-dAgi+wKo;yWBU7l8i(Ds zd*add9No!#T+qGVzI3$QAf#k*)Uh>qiHJMQ6s0p5lj+?wyH{l|WsfYHyf8p+$UT?5 zx3&u9ty(H6QQl*Z`23w_V+^}CdiFyeTU^|v?;zVV_uH-b=%QHJXEGn%vao*M!swS@ zvkeGFO2X`rnm1LyS9EXT7i1EW%nMJ^ANKJ->hj>Ns3(Ho6l9<$M-L7uxHHiE zDkY@L_)=JD;!ef1JiH-Znk3Xf0=MBJ)U5=wJtb6*q1T(E5}~<@Q;y%{iGeljOw=n2 zs?*a0C85GV!6h=XM0mTree=00X~wH|5e3N*$HiUVLZ<3)lWYUPsw?5%UADoOV&7co zxyFi_mokEnTY_*+^4l!Ecq1S!HoO+y(DlG0#RwH;wyr#+!!E?zMKHWDq1MPZ6q9p< zpdv3uY{?y;xNW`AMu5V;V|xflbV6)b!D@tDw-_hz5U=2I*)mGgG>w0B7Ic$Z3qH1F=> zVrzR_cd&cst(!x@PqZA0iXmz{1?B4(Eq~&YJhP3k%b5O z8X=s2Fb;@2Ai{rj&P3V*F#qUTjiUV*BT9fYK-|T}!4j}lwQ+W`q~PHEO_Bo(X#GDm z2OldhD+d5@vU73^a@=|bc3-WLYa`6AJ6lF-xzy3klh2;OmucD~_>uVIy^AG(uew&2#7dNIrfZuTg{e|jC zf%^VA|FH$;tQ7L6?~va?E`$1q{u@L8 z4~G2*6M=NjKfZzfAe@zP{jm#<8$^sU?mw6r#CT;U|J4tw`hEOXPYD(Tu)zNR^7sFv zF|l(Bva}P}`So=TY zio#Y!18f6FJu}FG_zxc%==JYBf`3BMfL?Rq`)R2f6>n z5U^*za}QoGFmV9N9}FsmDFaad@=yb4e=!Vz@fSmY|BNSEkiQwg`AbIu@IkIW{ef8n z2>+#1KmkO590ubKvjvdP1IrAs{L6zL2(bQ(!3eVb#i{`NUs*MP>t8yUIPQNj7(t%D7zW_|i@}?G z|HUwX;QwHuzZd|7|6&+G{4WLog})dIc=6YVmw@u0JobS7jLocyTjsrkJs{@ljI@AKB9g+g-HwBEq5M%vm#RiB0B?vTx2|@^E2>AkfrwzW$0SQp< zHwPY=>_Uh?WEH@JlmfPZJs=HAdx7C01e1*gTBilHAS|FyQ-CMn0u+Kgwty?xFCqXP zY{vonQUDnTxkdpq-~$j3=>c19K^>%^JSM1x4OoP<1G=Dx+CU5N37j-BAxD5Wm{dlP zhYoDt1?VA?KoKAW33O83b4%S-==D0&xKffI85} z-@PLNWB@H_1;`Yz415HzAl#67C~!LyPzu_|{U^df5I0C7pa|;Vg3v>rL)!sqpa;R= z@FoCXxPY09gRPr8JNqI83K|9$4jw_v%E8pyP0Q2N!Nc;UyRD<8o4KijrIw|Ov$+ih z1RH>Nx}rdIQO6R>nE-=?fQe5^$HK-h@_Q_Sm+YT01%lu6!~Y&)0Dw*iz;R7HJ+(Ff zfVSDwFNHk-8pjA^`T&+7uz=Su@SIDMlY>`ULV$&zOG=W3TY^WNMO=bghDCr|K!!(J zhFgk*LjvRj00~tJz?F}O-3j24J8iiKO8lbc0?PePo9 zms^~di-(two&S##sA2#%R1g5liNVQ+{NLcs{|=rShZ-jaqy!de9*iQQ1}7^ASU9Pl z%Ol|ifu^XRf3J8B)&SUyj6(ez{XVFl{}Va{RCG*iJYsTcW*$Mw|Fr#$ChC9w{(DyX z*D#oX|HJxk0{-O%Cqsg%VF3N<0i^s{9l-j}Y6R9OV1fNV?>;EZOwH{nEIdpdD7i^L6j^G8}kK zf76jc{TARV@mv3ITQ0xF!2_HT|M>Ac10WqO2&^ssq5bv`T5m2cOKxX u|0hbS0I2GKw=B{DJ8b@M{ohp`{V+W81cETN^tYTXXY!p8I~@`_HZURM)pp zovN8W(_MAcN>bwD=y^bZx|pznngXZBHvj-Y`Bi7&06jTLYg_x@EGjUAj^001!BFRbA1;_x5#{=(=^Uq9*# z$Nh)R{}&hjhmHOhxBd^0ijv3|&*T>-G`27_`N9`pnAYh3LpT5bU|Sp4|GxLX^52!h zo7$-=f3@ge^#?!{Ur|CtWr>j-XU1_0ca000P@007$T*BEVQGZyCm z=?8-s1^^)cf{K$8L>kSRf*0O;z&!Ts6q!+u@<;Y%q0y!~FFpK{)MmOnv$^N&5Z zv2%X=pEDoFAkcFU>-NjX&A)~{ftQb`NBK8_*RKIbps7nQ5YksS&!S%)2=r;+d^OSo z`n-A@^gAx>db{tuQ@?tusQG*&crO9XnAmUY>veGol+EsfKqd0se!g9u;hT!;7OE>| zbrCe&Wfx4COUyJvAk_*E+Dj6oQ2D)}&ya;_2gKuEY>%kU17!u}_#Fm^S&pb7WAYrm z?^N5p6t8=3J^jU&a@seDJA==sEp%2&wZTd~OF!-%;V%18W z?by_>`SH9$q-VuP)fo>y;a0^*GYhO;zCHRiE9dt##uM~Y=J2GW?obpXvMQTvuVyJ< z^oQ4v|7Cb&y+$M2MAIy5VySZ|bHeMhYH_4mT|>J8R7+_^LkF;mY>k-KC+G3+^CD%v z=|XmxFzQ#Ew9IEhvjuZCSf;o4it4d|@7(H{rVs9jE=a26;ISz?n?J^=Z0<-#Gs*)i z)J<)%sz*!nJ0d08ywnwlCiwb7U}+!q!jY}S=#OikjGcqb&q`|l-%FLPaXkc1nvcmc z{g|qva4h^!0F|#Qk81Tc*u`gbDF?jjH^nmS^Q(ma9)hoR$+%dh{M}OMND@84<^E;s zZkusYhwkwrq1O`C#($e_zwoHfPK3moUyZ$?(O34=%&yFtBrX*W;n$?3)Yrz2&FcrhVmBo6Yh=LZHs6e~0SwLW1h^)jD)^6wkVG zyH~^g6oY;(7Tac+_uCw7`Q@(8hRcJX>qM3(YD`i-y!@Xh=?3$g+6pf@4=OF6f7 ziHJp6nwwvk3(LD*T+ab?h97B|AKEnh2889{sHuNNsd+1ONjvo>FBXCRR0X?2aN3?@ z@NyVjvPyH5%59yCN)!b>0C|Bf1zfIse@qvd~BOER{cb>~RbJXxN8@(R#s*wWp!7(Y|VFM!@T2@H$ zy<^>mY>=J~Ru6ZKQmV4Do2dhS0D6^}B+|u2;RQOR4d@Efz-KQFf$c+MrF);Pv#Ad4G-Hhl>C-Ed#JA~-Cg_X3zYl1iqsM<`lq>#C0v4nSc ziS(;1u2W`Qkk&;wnE!RrN$O!)>iq3O(z|y_cJ1OiWV`e87OyY%{j@xbbmd>eLcuLJ`TwyVt%I3echxs?~pRuYa<68{u9eG6=Y5f@+D=Sh^9Jzmum~{RG`Df6s z^GC}<3W8sH1abjcjy_43aE5uDD+(0*Qq4ZyE_roK{nylLDdm9KMXuSf$$eV~zxy(` z6w;f1K9KB|6=z36snJ$}=rP}WF5%yS|=tZ6??6CWj=FB5Z9Bq}9s2<*?R z|EF%G{YbW#>BT5CJB5WMPFpd&z;O`SiKroG%>+k?=ZPw zc|}t~yss>Ugr^j_0?SO}Z28H~3>pFlq~xUBc7}-(Fq-oD(XoMEx=+4m40%6o`F*UH zV?87v&)myg)JmD+I+GguaHFr^dBd#DlrcUI`|^^8$t$3QbrzB}3pee_7M0XXcPo24 z?9?w73H%wgo6^7^Q&v(i^3KTMU~imq_WbbgFdU9KsL>1IR)1asBi8&$mKRJN))9y7 zw%b`6%OHD{pEuaTsQ-*X(0`O!5SLCU7*V;Rh02SWw2|P!sXDu$VZivC(XE;E>&f`J zE*>1CNwmAy@D@dNs=o8b`3J*Df5U^ayWz@ZO0`5gXyZrdpT5%-Dn>^h`x7WJ>Pd^qDA$Y&3fVd4CS{WDOpjGjlS}nZ|qA7bKpqyS^Jv-SX zqo*ORrXnDqXJN)i0K+b8D9c(Bykl+EIS^)3Z3CUh(?ALYyP*rx2z~QYH_QZoX}9W& zXapl!jOVs04KhDX*Ef)gd-Sz4|90^!i|~(aAzaIM2Y-ReR~Zwi_L&&DnpiI330Y#! zXF&qmTJP~ad+P2^OP8Nb06vEF1a=Gq!%2Ny@}O_XpekN?6MfGvQZv^ zqA_D^lJKWTqTZ^=^XVI)KdVSn@NkVSXz{_F4tF9`CA2#<^|0sH@0hp(Bj>@jW9}TW zQ$ft3&8!l5vWq%pov;+G1-7Xbc$Od=8uHnL8?#{($$_t(XEknHugC#Pp~`D@p;s2_ z{Pm-agocVWR~tGO%z}&;TzwX_T|)v7vXwjR&Ab&7PJie@MFIY>PK3S+O$`6UQ|lLx zgL>E538mXtgU%2G5OmZ2!Ea^K4y$#`@uvTJY}ePpis7=t9E?VU_HSALEN&TeDCZ!t z8o(Ph{%8VP2ssJ;`$oK&wzdbhHxv!KhxU)Z^DMAMo{A zXm&}St)Ud#*D#0`<2cMBi_*#9ybpgUDvX+I) zQhk)k@1~Dk2@seiawkz!rC6luaf_aR8~|gg-|VMPWWMw)?wF};uo}*J((rPnb135U zO5k@8(C0<4d;HxbRG-e^O__3LU^x@@Ybhv5@43*78+Z9a>6E*rloWG>mlTYAeA`RJ zmIvW?DzEFsyPni4r(y<;4q4xRLZX;(hP;Q(cYsvx#t*Y>>MZ=#(-BD;VN)n)s)%!A z*rBsW9TV@-o_<`&gf_(8BWJq)(fb@a8!|krA@l@v3<&&7kya*t9&PWnSMQeWwku3N z@(#n$*KZp5x!~7fVWO*4aGkHBMKKv=z3V*vwYs^h)$|t;zo%dF9)lx3d{@Y^+{y{A zh-=Y1i;lq#P@Z0@eB4C-DZ|(5>(|tgEcNpecRMVt;bwWOga>67N!q$rN-Qatqkk>U z${6Kd{diMStbn?RM&yDOZ~&&3=S)OMPU2!#klnl>=ZzU9j%!_DsD{KXEhmV^--|@8 zNfje1DHQY9;H>@JH{qcJ)1FaSx$;Uv#XJX_ew3Zd%cWx_oNH2~kSoz4&`VB}e<;TF z1qlxAY&;H^5bg~D&8uJI$x&>|+v4{WZry}dd3^H5P8(nMuWeWt2D|iOaMX>aUcli; zNDG+`BD1=xxZ*Kblg*2hxtgP^k94@Ua=`|p$Qu&X#N{~=i=EhAFey3RQ>^(ARgTy? zUr}J&?6Hr^G;NZcxKg6+s*+}dbL^uNRGiw3rYkIKhTDmhYZ3|CC@)pDl{+z1wM2RN zZicbK)&-?CRKN39wL}F@fW^k71?OZb_i={}>aAQZRqpo@f;Ci9^^+7Cq*-kR#cQ;< zrz_3Oewju_{3^NK(vF3cDhV)%1Nm4LR^JG}4vQE3(FgWJ9F69Fte4hcluCpPqUcJ= zj~zk3BAv}{I zV)kmJw3Za6F(sYUw^TF?<#kwntx)2gB>e%U{~`?$@de7Y%J{tNcz4jRKA3S0^4mfxnWYzZl&2Dcd9JmspW zSP_OF;Hr5;D7Vr}>h%WaGb&KsMFsH~QHj8b_EyPH`6;7=xcC3?M?1Q{qa9KRn%ip> z=ThjE#60U()&zf6d@p%Q02x1xB@?b>m&$_S%1FtFjeL@~gH-B1R`6!(hj}`z^61Lb zKFRSgsHbwpSo@srsVgn{vl#^50@z1^1M?KkmG~xB7+4TJt>yRT(Xi8kOubC~xx*$0 z>v7AY@zzn(2Y3GbiQlgz9rne0*QvNGI*$bFS`+%+WS{&plDql$23kQnjG@}IHTh(I zfX#JpUT(dfKyQ~NMZY43z+|XNM3dr_nhU)Z=gqdyZ&R&NUFKJ2y7WYsIT zo9gdMI6l<(BB;c-<2r7EpG5Fy&z&U~pS+?Yi7Pq_oX(y^j816!%p_^Y~{C-PoKY_@x2fETgw^bn6;$Kqgn7mpe49=QZfqdnrx{= zdrbjLOUY#x50>W(>EmdXLKVj=!D1aQUx(9$cr>C=GtQdjf@-6A+@oeLP00*{PlWEF z6Pu;k`tWScGjwUn~lVxIx}-3oPJ1s%-Yr>HhR4 z)kEGjzIvqubTJu^zsKlQ!Cf{Z$}@aWMN;lh5El8(ShI&2L!xLA+rS z|6_bw58|NW^&@wSU+=mKOw#Wrv4}jqpo>0{$LF840Hp$ud15_;zLPL+gp8&<0OVdpJ`+Q1Ed#PeMGAw44lQAV2!zB^CQfaV`-=*-E(!*pQ{1F4O&By)q@O#q??u2vSfpjpUbK$iSD=F zA1nmc`|eH&PU+W1=${5UUt@tOt8KmK8D}u7V?BGWD6_I5?jDB6Bp6by!`fM-k zH$~FbcQNT;eZPx2iKTvN z+Qz=0SL6n22ZiOA9K3w(#-1u~@#WN#f^G7or?q7~&TMCw;DY;I+#{dByX_`MKTh8w zOzwRU@-q zKQBaX{nl;{tC>Ik+_D{9;sFEK(Hx5WFQrQB`M{0iQSL6W+4Q%)8gN9i&dMmO62}aT zs(5nZ?x|7ngTF}dMqbi3ENd_D(!V-`TnuolA^Z8Uf5sOqBmX0TTP;|_>*S4hg*%V; z*JICst5kgh0Tx$(fOaIuY(zO`9gX@+?+kE5TZmxh->u$UwSVU0Go*9$I+e^FOvdNI z>{b!4T3h?I11-LSC!|Ga&C^q1MHOxpe`8WgL-*wbwD+6T&4Q}_I+R(uI*P*v`EKL~ z`*q47A!_%B>Z7G5qKT*YY6>+$*ej`;giwCvhSf@SC*xqkw7a*gsv&k@x)lolg{y8- zAbctQzsj2OJdiO5ms%rb4vO|60t+lkL5W5#Ztn47QUHS98_q*sE+sJuIUhXrK?Sr}L!tIq@Y`TUB+zLNX~pAFfvfj#%^D zjV;)tLs#R^K2`foX*T79H))R3@?6=RT8wOGr}FUt><@0WU#vzJI9Y zzb~KwGd>G&Sal$Ye+rF+VsKk{YCdT^b~m7%L2O{z3SIe=kW**R{m47! zsQhmw%o&2{NJnTA_%l2SFGZjE9ZCU)BXk@b_2#L_PBN(W?sT_`0u+15t%2JDs#ca8HhDCsf5SN53@X*C=FepIF31{(EUCC5adCRF7q z(jq}b(1d>KZ$EG@vhB=SU_={FKw`VcY1NpYh%P&ryQzCd>9HzSk|smgr8j8NQot=FAG3POq=s?E7Yx zT`^Z`P46svlQ;!zx4Qcqu^6!z(h!-J{5~_O5QQI=03qtdzU-kMFm*&*ycyz%{A;Nr zRc7DpX!~P|5B%pMvMmtIA0N||ZlY_DG~#vWZ~WZCf~~U4hqH0sisWvZB5SHPaC6Az z_yRr;wEG0&pO??*Fm>)M%tfYTp5=0WKvKmp_z(xJyXYMvKE3mFD=8n3L3$TgmE)4I zcnQ5r4KEN(Cz7cykNUz3$7A@HQyL&%{sqJCXqj##-f+KHnc_ex&{Dt%+w+& zra0q>IZN*VzWK5!US=vHq_AAD*YEu?;j6aMci9_@X3a+*iVLJCi}A7@6%bQ7Rj%6~ zKjTACcMJiZ1ZCq^{_3P#^`?^ z|JK7^cH1YcBYS1e(XKG#i#cfI#0}Gy<9s@}c;Wg*s@d?X6z}8*!ZZBKd|-GHI4^rf zGkm9XMWz*7nt*i;$>E)*KiJd>BCQZD|65#1o+M@$_IDg-%8TupW=_Z6D7s!yU%l2_ z_;UzQ_RVY|7r#xjvOZYBKJ|v8K^S%~sbk!)#OWTIZuQ?*FJ%Kxjlzv2>^rH5B>nqT zg5W$+|CJFjn$5jgbyY>+!)69GgZaX%gUtZv&2pm)Vs@yAHrLbm*vtcdNmhEMwQo#R zs5@-mCMvGbOBXRS%<7D{%@0nCCvPbT>^~1+z9)j5O>+1L9Wy>1GTx@AD03DGXSb`N zQwnowBr#C3UzBnz^OtFZUp9OY5C66#m82b4lT1?zPLwsWLgc?K@ea=~aOWsx5#&COvgB1OMj zkAu^}F}rK$^o*|lUON=j74o#*+pR#lrKPN%$&W5yyat*Cuz}FdLAU>IfQC)sH_|ca zQDCwguO^vLnels5Y|BcDW6&$-Pf)VL6rT-`6WEA(~z_pa!QyKYo9=m>mLk&kFo|D*g)&tF7V} zCx`(dr+o>#4;ry6ZDCp0Wa6eg<#CtbIak8&vTIBfF)#|Pl``}@`5rlz)hc9Ap*Q7| z5e(=$x4QTt;L(XMsd$e4I1c6enl^EY>y9uXn~o;=uwL90R`jTRh8|Q-Ank0|)YaYZ zz*-+1K=XqR=(TfU>*u{)J54`4Nn|{t%Ec`qzxM5Eoey(0{_mGA%s?oN>q|!R-cfrw zMcDFe$>(zR83b_5_|K(eLxMvXG5RkfV}hg z#1)5AV~0Ubuy50Xyyxhzu+N!ED>74BFLS-i5sizNgDn?$uA8198zbpc#HGW)?*eov zrBX9^+BA)IA4`h1qzIb8d+g!sh<9ZwR92zJoTe@KTG0=c%_qs6&HJ{;20;zB9d_q) zjJ2Nu*6ru~GJClG`kU@k`-(iTV;Y1pL_+m<;b!MGa9!r?Z@f_&8VPDOFmxaT>b)jJJ_KQ@3N+aLbf*wj&72t zht%(q4IG@8=yA#@NdZSMId$(otHs08@zED2x6i-q&j|BHSN>cfUxvLD>#aPe`DuG_ zX{|xh&4~OL=!lh;|D9ge)`(o#btl$~!O5ezrD0HLUg5YdFV*tpP^Nv)DZs%sJS)^Q zm{V3r06xDx?G#Cht$O(1>(asM@Ua9|nSUv&enpGA<_=>EAPLW1%HPen0zI$lea8PVxRl?|{xUI*o6wB=i zC?CYRcQKQP#r?=h2cHq#Eu?Iur6+ZsHM8x!*VngD+(lqvr;oeW_mx5O%8(BWtE#}} z;L=DL7Lg%2u- zfupjq;kKgo!(5M-NP#eL5U}=i=C|^6XHFLHDoy~LG*7jl8$VX5VgzHbNcKUwUi z7^Q6gZSjpUxcxC3VeX)S(YuaTlI=CFJB-yh6Zb2Y;bm-yNMv)@Hl6MAd_Xt_mFJOk z50$>g*LYEGu)d~1>fxJDT|J;Nf|-DM_3SJ7DN_Fm&>dh`GH*F~?Q%zK>}iC&7*T0$KGS0G%rLEvP37 zm+;G|UrQW3$j7J`SPwp2-}F2$AQ$rOddc;|=3tX9L`*Eh76nJi@CH@x9-{Xpbqcjg zFjjMhJF2%7tq^S<|1>oqAB)|TU4)jMnmph;VpJR=7OlNN>;cLlsSvU1YV!Veb4A;i zZ2Tq;So+(vM&|-*Hth%A`FfKEU|HBr=muLk~x-h1oJ=Ej2wdsb|fAX zk7ND+K}g269_e1o1e#||NbZwMtpKT~*R{QJ&UMEFdr|v-B7x8u>GeWX;U=PDDDiER z0~!Q1_t}>bSY$lBKWtwc9Bh|rb$$0-&T1^BioiF_U%ysB0~)n`0TcI@9B~^y>e;;Y zDOaYlPHv^RDp30KzMAF@H%yf+w5y;X@=nAesb80|IJ^n2pgB`6E8em;Bf{8dSdlwY zTg7P<)qGvGJE7h6{hd1V3>A(9LQJ!57y0!Q0?57 z6fQfgR4_PY$HPe&u9#|BJ>%(rWzUErrO*;pCO08~sPZt@@Gyh&RZi7*UW&UAHWD)dK=G z`lcAA;8WtRuRNxkd%o!pBtW*q^~?Qv+?^*y`O^h+5Yg>MxxbZ+`PBL#iNpXbRizz; z`ydXc5%xzdJJi(PCFvZ0z{h#<2#Ndmh5gcWm~SnH6}c-gihpMcche&G9d?&@7UY@l z?vcxe!@6*kTF1=yNjcGTS15|PCJ%l=aico=^(5Rtd#h4mvCjwSvYYAm1vrcger*CY za*>ykHXD#mz20(N2;qd>0?J*+f0L@1lhluYhDd5(i}2Z&SB(dJ6uzeB!C?`enRNH{ zoM%AROEilVB+kgusCgd#Es{49wVF+#@e5eHkRou~3O;orZcbSWszni|?;hb=9;aUq zQE(z)%sLz^b!B%}PNio0FAw6ka}F?Z=C^k-v>T1zi=IJ@ z@%F)BfoSh3+72y~xkrAI@A-=@n3dZ{*T8PJHt$ z8}tulLZP(inwLfRf4nf7@_pM0?pQ)8z0sO%;*yuxcw%OzJk>1_5AH)WO6vmR$|?Xf zWrI=J*=GRYj5x!KVEAVU!349 zd??Zm^!o~Hn^3M&^ZC3%B=~fBxW!YS#*9%$89qvMWr)F7o7Hp-y}Gl46cE!LSr&Z= zuSu@-0XM&+QHBUV2)lmdJ!|}RuW~*q0{m%5vviHY#hD~)Q&i0O~24Q z`FuKgaUHKl|4p6!SN|uvi+XH-r1IEMw;lE<#!|dpp2%H7WeuE=W7MzHQoR7Oj6J1k zQfDU~JPwo-;-B*h9BDR>-L%3@6UyRf_3;!1&pDleD{2+p*^FQtXxbe2BrLL7a@>Hm zii*p`Vi*WjMZzDXKdlZZMt+8a+(@a&MOwxHm;U>5&k^^t;P*|X>ZjLXe|uuVA57?# zAeV=(wjxoWUpU%c5pjS0JqPC|JV>awp);D^(hbs9=aP68E50ru0)|LBHtKS)q;JpH zFTI&HJQ8N6heVm(Ay2eDOicnBX0{Nmbj?+m%*M8cw5E4#jS@ZAW|r9=wOB`ZbB&i; zN3eSy)dIZL2)nrP!Rmf(o18rH#a-tL!Y!Rt)@6ZfXVT)?x_EjtAK>LksWo|m_N7oR z?tYOO2o+Dq8(mA4tv;eB`1c3X?%hS1jBfH$(EjRnb6*4x9Lqgp9CzYngK;YrhGUtS z>doed&(B(t*9Xu{f#i*Mz=J6Q1nb&+=RDpQDtzDd(s9&r634l(H3J>sGqC+WxhAM_ zgIb;6+BuYQdtq6);6mu{=Bu1bO}B3aI`U9e559XG>5WXqb%<_eFg-Sk>kmg5o**Q8 zacSb_X6?EB_=~PXzbh~i2pnTEkMOuJR7_%#IeJl-a&%B}KG!d(5d@JplsD~YyMV`? z`YHZk9sXXcMy|-Aw7UVMsKL@n>RK>cqYG27JHmLHI`jRl2!>e1(q$Eet?jBw*wD{V zvvPB4j%_yRGdDp1=XNZ^N05-xEB`Bkp$8nvI%Hl4@KGNh#D+Vo3F5Vx?EO4AaAN=b zyi{y54DE&2K}N#s{sAwXIyWj(=d*s+JYF@;SfU#pP)8H8i>(hE5X@NPljIps95!zE zoc(9$N&I{8-ieMoyE$vMG`%Eih~$@c!(_dy&)!o(dVx5mBR@hqN4KVHBqyVP1k}V& zQtc()2a#`vql*_6>n)p#a8)O&k$+3sNtw*haCOi=Gmba+$ODDY9_Jahe@lz}ce7%@ zfak(MXOC7ra=xU@VdYB{*qk9FnLu&~EQk4El?`y*JF!U5Ym>NbJ_j{YL3d4PkvEVg z?iZK$BwLk?J^qL6lvvbCGGkkr{JB{5_mXu!>8h2Xf7AH$9p4mKz|g5w$X>@L3rW5}jcrgUOU+Fm2|E}QWb?@IzU zI}IncB`v}svHKf};TLgCC8c!vnZOA+Zn6Jr-ydCeK&oO9&B-h=1;I&XM_K-CHMd^S zQzdTyb^o7_a1%{f>l*ow7E5B1?Yy|(T-Mf-P;U>)G&EPAF@`X6n8_QJX9($e>)-NM z){k?R@2uVVX{`ch5r3S@J*7@#A)Dg`)bB~JyweX-wne(`1>6R}mKg*&QNT3U;n>FLQ!yah~hO`}gfvN`{5ZzB&cs8isE+pb$`k7rizW;2jC=e(Jc zKmIuL-zB|!mt7S|D*KER^p5BAcclNtESbgb*2Ku{Kad9{Dn(}z>HM?H)luRg^V7Xa zSE-*LYVDzVwcPwz{;zz32t-*VguzL1oh)WcEdla9Q9P9^_rGOEyU!;?%f?RqL9k#0 z#oP{@rcO*OV{-*aWR@SMhB^0Js zhhJ;cT(@B`X$HoO_e{5hGTmXC-MK9JH*CF*JNy!!07lGPyzxG8A?~69XN|LEzn`$^ z;L1ds*rW(DIWL0EzlNbP}`eu7gDNG<-hs7Cxa|Ovzx|)m#KU*cQxF%TY(wCn#Z+Dyw?2 z+JUjGU852`OMo#{7fE|B8fvnb%c5)oqpE9l)vwegCwoW z^UeIs4{nRob(Zf4luL|HYI6P#yWWzyinCAOkPqG}Mb8FE2LQMLFt4XKPbM~=bB^QE z&$-%=fTE006= zm;Xf*tclDt1Q{-*CBZT2(eVY@P1v`h{D82pvB`5MKJXea_L)d0MboL@^2mt?w&d(E zdIAq~W4Q^`4u_F9_>=jX&^`wjcDHa8w$2}(^3%TSs{G0)e*zV_E7287DVfaGYB_KQme={;|DqAAN%u%%AeDt_c!u~ph;eg zvpkKR#~O) zUxs6+*U2H>h7FE#d@?*%-LUlHIHKiHWrgcuXNaI$E5jd*<-h;UV@rZE&f*p3a4wVA z!xt*>P%9L14^tBB=$l@)Yl`k%CtA!mtR<{0Yf^YC@`J{J=MuU;hw|@-llS_15&3K~ z+Z=p>+K8m*OgQP35VX1M&ziD{!-I^V1BPJZoWyFNf(m~v%H5lm5{8&WT333mqZ=4= znHT{&q~o7JbaF2H&6m5k;h3w&xmykLoIznIaU^<7G)%NpBel{$(IL3xI{EqJTRW~o zq~~fsu=V@aX9#n8csE$ipXY_`>HB%D^X%;rWCbqeJP#^^)OI^0)hzX^p4e8uJNU}k zEFd;`YN>*rKC_+~Ez|<}0C~jJM=*SDkuGH2c6*yVeq{?cJjv`)E-@W{1EIN`uj;ve zjaz;=~BdU2F{m!O&e6%d2$|Ksu%EAA=)#%f!NWDrPJ%1~;(jP=WiN=1fO3-K$ z^2-WJ=Ln)XTi6T8IEmske3^#lhM8vFM*;OioQwJo2ZJ4+XY}@KYmG5_%G%;&P@0oF zCtrIar2%KST=2zKF1b;|dOUK)QV0vzvhKoJx?|mzl#qBVX>&aicha2m0H&~u#*Oz& z(T|^N3jKRgewk(9LNeLj&h`=qk;;6gx)GlmV`@)v(uAK!UWIvWec5d5mT$d4ob%-T z$01qUm$vY5d<_wu;Q?D3^wED?0{{BJ<<~geT8FH|m~pyhi7hJer7`=ob_0dMcnUWN z7YNCEpl*TCJ`drZWW%2=-%*(8@dr*ObW_4Z(41bUs8gA7LI`>(WOWDgc({}tGaw-9 zH z!w9Rs4Q$bP?Iw7O1)o_ z7w{U-K4C=8zxoC`jay0pRnivGdPU-Hp?MqpLVaB;od|7GnvlV1!bhrP@AVzpjiu}6 zexz_0x#s_?u%8?2oJFxkNiJ3|1|ej&n(`A?wCfzvVAQ~L;VVH;8;;gre;{jz$#ZIV(!#-0D%}z= z_IJ#d{M(GKo=#7r*C5MYqnp~QRN4yYgen6Oa&p`J=Jf1mI3GBCS&A?ulvZCe$Zfn{0deM7e$ zN5=(Y*)uRY^>P4KGW?nUCpai90cO1lZ#up7E2~*0haGo~PmIA~Xv>EMpUCwle*9@& z7xDAcQWH{>e3(uZB8lavXT%`~51*k7jA7$FpR{}8Ld$~74Z$DT5AEAbOdPCsO1`** zPQ@Lg+-TT=QLd(M;8a_nvY5)L+e{}$tm}E6HGzJ%!Jxzv>jiS6t&y=PpQA`&_n&KC zoGG8(1tZ(l`JW2V7#2q19$IUd1nXLRL`a#k$%~Qn&@`xrENjHzI-rZ{p|?zo-wD13 zrNo&Tl2yUi`CzZpSMxhc#cr+n=GdWxt+@kRzLgpllm3huoe##ptef2w7Z51*PJ+BMoVA6JFP#vcoSD(w!{zS!UD zNbTGbC|Fx`vGDTTTFkR}zH?i-@)jRkU_Z=6g=r_!mgSZ)g0;_>wzxe@VZD5-yriQ)~5!1atmM zwHSrhW&;P@({E$d+PU@M60eael8fv8j%-+v_wf}mO15+>Pm&sjzQCBmVt(x^`?n$q zuWf4aY~5}yiBfaTupPXd|Mof6_S(DJa@nf~mdb6Jci24>$bENP@|F{u=8j(H%WwGo z`Z#0rU#Ru+j4>Hh@V?CE=ezWuT$d#?x#>oCvOWFygSuI!GuX{5i)pdT_8`x2M%IT> zVZXS-G^2&YPfP?LW&cw4qTYl?4|y*ME-)qgm>8v#ec?z1u}8l)^DBH@!9~S}8(meq z&R3$(0V!AJsmZvsrjf6YVLB2x_yN7-U#fsW-zv>e)BB`2s?#5);V)=n3pP;6CVYyH zHdRy>@03-vBMiXNlL2jArR>)mBh}`{1Cw*I!Wg)9F{A{?)F11SY4$_ERtWRTK)#43?k z&Jz2#Dfgh^Qh_f@+5X5ULjOAmg;&y6wkCABOS?#`)PGALofhrIIm5ff9z~JybSa^l z)KfoJdq!FVyeABs!Uo!ZwPT}Ay00o%jQzK912Z+{aOwVQ8e{`cWXN_ z3?>b1rwk)QvcNY>p};EVr0rvP&jcbUnpK>?UMHFg^{!z%SB82v4kb~ph4if7166GN z! z!e7)tTx(`-UiqbGCOc&u*Q9AlQqYG;C*!&+7$)S)^rA!6;QF4D4~pa3{$cpvDmnMp zjlm1G#%?YSsdtO-l7fk;qnqrun^@n|eYIzFLK^t#2oNvfR!jz0VotYl_J^u#*+}>P9M^ICSrotjb!pD>`rTC|RuyCj4-X{AEYV^>nBCrJRfqUs zM4T#vOmKi>QQj{u+tu5Ac8&TZgabh(nOj-2`KOlyMRp2_yAZymGT ziY8I^9o0imIsJYYZlWmh{~$^{uyZ)2cxm1YtI5SY>Z0tJDM@5sxF5Y&eJTCQv46KH z;-)Y@aho1)e?G>hr7*U#+vy+<6DyO4UVG+6CSoP=FL8)W9>#IF-W-xra|1on57ay5 zGQFOaDT0p!{mF#`&QA@7<{<(O>cQDM07f`HiE^*WBbr?!Ges(NNmbR_0+YJhnCg~p zOn5XFMwzI-ZI1-$Ey``;yr19{>xXUrQ6iC6NY?VHMAa13tM=J{C8rrW>ygM%bNFFT zM!W**L$u1eNXvh}`nu`MC-i*Q{tPuAk6=pV@>M()EosuRdL!~f(=OuG+V|pcvuiZ( zh`Y+MG;ZwfF+7Qdrk~6m!tkf~h3~iAdx(^>GrkYv8~62$Jon3B?XAexRgMLQ2q_PX zE5oGF(5t9*bb$v`+2AQ2HnRK0aawjLTVTu=^6)ewN!(n}e6HVhIyW`O8d_G-as z>k|vB+mRd#BJ%oUPLfy#%?vyt(f2_wuS0`}`jB}LCrIWCrLY8Y_E(A59fULVyg0^@ zG-w_Y@^U8IU~!(dcGZo z6}oN?9VW^4qCQE8B|h&kgrdi!+X+;#Hypu_kbdLhzWi)I6SUi+2Jk7t;3znNz=n&$ z0viF?c!BV zuEFG7In#%*xRQY2fw&x2vz9}dg0=LE#%_kdv)a5lj}J6;dAVtoNkLvVPOLbxCjro9 zPrB)ilL-U1=aR*GQ{<$*7|MXkBM>FjGS#C95AIf@6uZm{=rBn+ZQ!ar6+>2wh`3xf zu|By<2R@yRlQiAuu5MJMs@!M;ZeXE&3QeEyXbz=Rt1D)&V@E;(HE!rTBFIji3RkB+ zrYiSt`BA8PK&7LJV6!VrGQT6^-)&gJT`_nk1@1Y}~%IToFfV=F=?(mkQPF-Kh&3`zE z$93=vB+kPtZdAYO-RR~H?1%9Z92ZT0@JL^is&&9O<^0s3!2X_Q*QkEayW?+tccyTz z=Y1aV=^?Sp`usV)p3>E!_+=a2DM&})ip^caXFoAJ8~wrlrtXq}1M6uRU5+wueq-L5 zNuoh6ehKCyF{5h?sMUTpY^hmqOQDQ3d)c4A5=`Q35O6v(@Bz3X%9afBcF?8UK1in+ zbv_dij@u!#{G>ieja-0+TR6PBN3_s~6bq#c!4iuA%BtXq{Hm9z*igq7VamCL_CkIPRgiyo@ySLHy$a2e{T!FkuPA{TT}Ip!tLU*5?r?Z- z)YoWx7if+XnqFhbNpk#A5ZCv>F7?i*)qzV3xEvpR?~>w(*sjRMNQs0jP;2{R_+-5j zRP0)3d&H#k?!{>%GXzX-6tl(6TQP_eUj0LC`OgE#(=!s$0D$#ncV=5Xx}i|Bc< zg>|_x@W9&ojPDWQf8{Hq9c9=8+L}$@dLWg$YBkok4Ind+Mm6zYc3Bm6V?XlTDp6hI&M+s}7 zdurJ-Qbms8J%Ao}c1PL7X!2dmw>^FvdGOWS<&}%AXll9cT6ABv-xu`A7RJ4r3>BUY zALrX}M7innQ%!O@{mEWgt^J63{{{Bp1#4leF1NeK!U?4F5vT}2 z_4)RPv8L3c;mmcga#rKEh8%y^4*jX{{{fCbalcr-@!8j)So27R0!lg`AJ%%7L%I7qe4}Wk9>RVsw z2n1zvd}pFxMgBj2{dir-1Ep=0kO-fBCk)Lpa(tWhjoeNE{2d-I9W;=QYbcHbXoguW-Q4RY z_p^7O16U7mX3mmRC2`D@Z-`i#Sm(;)s}8^AK9-w%l+Duufp^G=-|lPVp;aAg8TZzJZ5+y16uY7I_N*(oW`NkDrU5-R zLL%+c_tOSlHMPdp?8j{OXMIA%=_+D|7C{tMplCMjrEVTk1gi|Jnt| zEm;mgvXLf0ejD{l!C=nUU$EM&onlT>&Y-F5(cVs3WwyHAx4y-l+rN<}1{XMH0H;Bf5_m=i?vMI=dghWHpP(X1CbY}6gOMd+!voYOJ7!L zHxlvGe_*;nr9pLRBc=lkA`GaAXWM?0xux3ZrcY3nQx(90g`Ik_Y-9?Z%q$2G$Zz)XX zX7<6fI4cmLYlIL~km=*rV`YSp;POKgPw^ToO-K}kXcdaW&xZ&&;DYxr9C?B|R+Bh! zn?F%$53w#s&MmL*znVGZJ&ol+d{@16f_!cvYLwF8(Ti5H37!*hB54ljgjY3X0-#Ix z03;(XDjA^n|Dy!ACbGGtE}m+2&H^#*R5)ZFRQh5h(@<`lO#QOG>-!ii|1a-}-D#x` zb%pcA?Wq48*#)!dSz?G2I`RQX>qJL|;g7*R&qAnybV2hg?Ts#SITV*&o7lcYLCl9x zB3#n>O4umKgI_~pcSGKVM0cvD8h{5%dO>PQ#Niw&aUY}gu9vTig2*chBU-o7O2hC^PppDuXaJ_liajOhC@5+`%{bEoeZI*Fz3{NLkI&#c3xD z>U8-4*OKQU`Eqz3c@`3aar+s@GUIxn(#5hy_;Jm=+#d&St$FKy73V82L21I=ua8nr zNkUJB4O|m5G0!Tsp$$wgV)vR|ItgQ5WSW~cEmJsCAH~ov)*avIG~;5)8EvHAN^*C0 zf0kRJ|K-G3fjC0juQa3dw7rQ914={*VH!M?7_rkN-1NPuYNwjyJAg@jkaG`=xpQ5g zeE9;E#^l2Cwc~vI*rDs{p$N4`HD8Y|=gRtMaxPP!p5ypW}V~ z;|ysnA=Fpe?&*OYLrbF?l;rf(ywMoDd}*UI6ao_2F5maV_7T@KXep_6k7cwAAI5;S zv&WVURWl#g4{cpVTu_)~t!Y!fnk1OPf=daA-zh2Ho>R*S@<9{jy1ntY%MN%>SuqF@ zG)H3&qs@M)Ju1nG7dneRE=>BzfI_Po=ABf%ism%TtRg{LMo-@XnIE1Q?BTTXPIa&Ff?xqmZk{WIpDWwrFExpd zfo^poGS_6OPR5k&vnhjb71v#QOaEL|c zh&D{?Qb4B-f2OPtq!j_MJa!2C(iE38SYniVo>NVUKj4EG;!9p7{os&DU#>-P0Hg50 z#HUDVz)?0CgvU@<1RVCjV6jX&d&nA`$JMaE@J0U3U6es+UPRr$H2Cnzfe#MVZ5j0b zuMUFi?56*gj4{#)(WRcOG4~ELk@nYD;EA+`+){X9e$z}9C+n-{+sS|h=C^S@_Blyt zOp+)zYq#hCj2*uG#Cp%}|7B!fsa!7GSa{{M@{*oHdM}>WSNT5dR$i>#kgcO`gf5wO z*`KMy*xRf>nqLJ`sdWhTtPB`N7cH_lq~K)9hhxFsxkAs!t8!TY5Yd#oj|vgOR&VLv zrtSikKIN{x9QXGTf+IknX`5GFuSXdQd2iyJ83Wn7XC@m^I`v_J?K@^F;9o~j8b>y_ z^98~7!?MSxFD)?=v{)<<%6Aepp`E0YYNtAL;3F;Bm;t@lS_rm6wz4dx^5@r>tNQ&~ z^)(c0KH#96i70O}Is94bsm#l(32|1c%)wa4J>Z|eaab%bV_86^>|PcqnoNfaloYF~ zylE6=Os92@tgWA}B3F7L`IgMk)PoL49;{e)Ml?cxpls)gY@1DdATF$ph|ojc*Asb( zgA!K5v=h0jn{vmBt=a$k@T(`XAJxh+dba3)zP2QcE9~v{%&n{~Bg!yet2B?iLs1sM zvvE{^y1bb!gB#8}M7#xT-OtE@ugZj3sPG^9J6ef-xluUJorIMhtdU3@6H64x+->Dc zyJ;`Peln0r0JpTACJW96j`oIVaj?KpCc(9f=b8R5_~P2Q%fhOZ6<(;%IqWaM7bj@@ z?b!JjImx-xdjo6}ZYbBEfB)Urf4EB^qvJ{XoWtQCDCBQmR66$d8vou;f7G z|MpPx6P9V!$whXt2aB>{>!>N{d^p6*pOy)IHUUZS?hI^f(j4s+fm;*K5hHaBs!-kS zT{I{&7j(-oSh#;spxR@G-`uyGHw*$cZi(&BuyP`z{o#dWEEqlTI@(OF!5C5crC!7Z~ir7nQS?fXQ=c%r1*fRz|NvFp=UfV^%wOI1DR2%SaY}!Z< zvu)_3u*b=DB@K4~J0NTb+*b|d>pD&%f3%5uFkFj(3FiKu`?_HWqfDos{P{|oF}|Vy zD*f6J2W5cPACUThtbndGQQo`_1$RWKR#rEa?g#m0%x)1JMSU+DY|{;#k-*SPfp6Bcub786to8^P8*Vn!REhXbb@zh1w9sj*1F?lagutYqkf zp2S$^)lmk|(>#k8JQ$O!XX#x&I%=lo&(km9SM$+%y20#xO0{J@x};&1W_Ntv*fh@5 z?eSEpu1F&QqFMDHZik{s!$2qvMqJw}11kYMq9k%WJtkHu+O^dG6f85%y!EGNPpMw! zzd%l6Osuw=%TsQLy!@V@{Ez#J{KtGjJUz6= zu$=VA8(qXY0l5q9rjLUASouWX>GlDgZ2kpxxivEHQe7zD6VB#KW^)Xuj|%;^N!=o8 zeGXY;B^^pp@R{LyYQX2>x_m$}@1dL&1v&(z1Wndyw-n3(M)bd%hthH1vP7l<*wAgt zDj5KxE@oS%Fv9(MX-N|NN#>iqvO2L1ed*=TK4jl13%-2H=}uCSt7IJqQOay3m>F>rONtq0)4hyq*S}&)1d1Ykn*yOn7hT zUh!Agb-%&_MpX6lljCChg4#SyJLQSMsrT@ zUA!gOVr&4g6MjN(Ts%iui0ul?X`9-tD};iNG+I9Dlu)3QMVBG!&Y%H@u z7UUzZdr?MdKi$4#&Yi{N(IwQba;gX54~kK|GD#p8S4BdA1r&RPZl2b9NixRbQa$z^ zqz*t^faaA>4a?9s+=5hk+s4KV;9jLqJqtrF7 z#zFU|X)NetCR`5pI{MLx%9S0JOJhweQ9iTEgYIzQA=Wzq3XBEkR5yGo&aI;)*+$9O ziKZcGB8=4(Bme(Ot45rfAmyBdNdl|9T4MpCiR)R8yWP`5{C>B;Gu^q5eFC6$gbgzW zC&x`+(4QSP0ZV?G*&`F|J5~x7CeQb3K$I%;t?Kd#F+R4p>gHnCENTxY@$A*@v1O?! zZEbaS(-8Pg(Nt{vB5L7na`+r6?oC@p13FV!vJ*QO-(RA5nf$|>=f?;Pmy3s0{sHD` zv#FsW<<;d4Hmpv1HQr`Z9|6#)d&c4p)WaX9YG10(=-?FyFm|Ca*he^g?Yu187~pkq zYnslX(ki2hdRdhC9y!W0)l=LnyYlEVn1G+4IVF}i;N$+oq-R-JM>gr1$B7%zSA(Rk z60DVVEt5-*n}#wu=(4ZkKe=atIaa|}LxMRiM=ee1W-tS+>QXv6v7(`xP~6IYSrsc! zA1F6|b_>Z$b}%Hz@NYy2YR0?wf-il^mKEL1`#5O7`wMi(+7vh1F7w;(p_W#PaFG#) zpyl#em}dI@e+2mSb<#|SaAJIQ6G@Qn3{Q`_zEIM9lC_bk$W4irM{ijz?7ZxmBA1Ew z)hQCQ-s^d}RID<%3Dd+RXYW|IpK&ycw#Bee5)-=+cx@H|>ANbVLE-gD74d>6(%$=- z{JjYVviyLbbn4YlZAAF#s)1D4hzfD#5;->mE4Kh<_#v^lgKp`kreDNREf?tw6s%f* zOaE~|pdNFWDiG_r043I};C2zwB|pr!CKC&pT-~U(Jf*NH{PzU82HAN@u9#6_g*!A| z%)YR|OdOX$)&k+hEj0cr-PS$*nw`+${Pz;`Ld*a{bwj+nqOjd(CguQP4i z7$=r`a7^jLlp~&EL4Z7?$W`%5y~$pcKmV?j#c1p(_-n`$P$`5_)cVZC?DujV!HtcY zUcX1PHvjqh=vWBg5J>e%mbkNvg~U%q0dY7|Z!!FnFxr0A7BX@Pt8tq&A$1aBvS%MZ zOt@o7v|4s@`PwDImyL*65fYTIm*Qq(sq!*0v9R>8exz$xH|<>ncBsQuW5J=Y8z@$x zma$j#eHrdzb%36?GdNk`a`P94E7`)&a($pfb!abv5f^?KYO;_4 zbx}ZGfk^e?)=>n(6fKr2DTJdD_w$y0!TMY?s$%#5=yqj)+u@@n$0v(Cp1WWEC`QwL^~N7uEZW>n zR`cppBL5G;aj8PuqE@;r-4N0!3Iw&3%mSd4|6OUTeD$BQL%-Irt$M#ecY-s43=$J^ z7+gyHvA8Sv`zfjh$0P37aZv#k*WAk-g&GaNgoXWtr9XWizQc0a`56yUaHjuV-uE<5 zLeGq}63qJE;>66XL!f?)ZewGS==oMujm=>_!8GC8=QGa@471--R|sVKm{~DO1$SHN z0`YfOSb`j?dAW4RtzIiPHlN|e>@hw%YPN!8J&#HrKpSs|E_YiTt{dvojW4FU^b|R! zfodUW-=c#;1v-Nde+`9!H$#cn11+Ak_H7j)g4+{b(+pkqXbujbym6;w!#A8<_5CfW02t`mn#L~Rz0*x>`%0EmOl9F7AHX8Z>B z2ie&7%_rVONSJMnqB;Hiv%GU|=#%Ndx_P398-P%hyXYPpU+H2VV~a1{rGTFuHB)nE>84Rc zmURO*kth#S|5ib9oHbx2X@8z^pZb=hhzR#Fh$993{uHuUOaFoW`Ks>RQ6V=wnm*i1kD3s zN})xl()}!UZt`yIhAG>k$}1Har0PAHUpiNF^%}(2aM$5gR~a;&GCm5U6nkXpEk{{) zzYDMb;M)IIVGC);hbL*pnwy7(s^mg_jJuw@36aT*~SZe&jc*2NlMc?04fBD{fjwjp7T&|32K$VteqH>~8HjNOu zc_J#V`zY>0&(%+1iW|Lt!g73d6G@Qs3qFIWlXpMk{OMwrz7WiAA&&c1=0n?y`R638 zTN*N`ua_G(C)VtlTCM6E0n|$J(^JNXE>9}gYI&Ha3`eN)dA1zUqfj%T$XMc`6*Gv6Ibm9rJHh`&|ZD+4^Reu_2(Ld-J==_QbVeHsgA7*cgtA?%vwg@X%HX&ILc_ ztOA+N`r*_#CgZ@aju^Qn+QT}9XHpL@SB6?R0m!D+fEDRd`XsxIknmO@x|UZGRl7I{ zFCE)d)wR+jm_cZg;y$vnZ8a@you~r2V9hg*YxdF(Noh*BrN!D#Q9-DcC@9}afDF?_ z)sIlixR;>!FAUR_+sdBs*-w)+AsnXLc9GcLt7T#nL}p5B1fHTqB)R zkOeBtu0|!7bY?j;o;Bu0D4?YG8sERM6G2Pl{>7AkY_gFnsJ$x-kF8V`*V#-mx26&E zLEARG1jrtjwa#FS{en`#6mMfe7snDs64|<1MBLVzwZ>8qRxgZ7d3gKq!F;(7j}_`q zA4v>>YghWywH)7V@KAk06O>0K(}=}&G|y}lq+;!R0QkQ^Pw?*L^04I!hI%Q%FuN)X02eA=aW`a77Ye&x1<2c0$9f8%C%~ zI61HX49#W2rAT1o15lByz5hv+8ad)3VKBblf&4@tx3#u&;L^u_op{!efeEtbc8K}z zYj(*#IokozddeZnvtC8g?UrcOQ)C?PmG&neYp*Y>aQfxsk&mu3s&PcM^HM2QDOVOZ>|{=kv={&vb#qYwNQSHR!Qg4*d-JTU7TPQoI7&J$z+jGepVv z$+@2N|mTpn+s>6L@$` z>JvbO{{FHcauT%P8i$p8uA81O=)5iYwMYN@(w+w(f&7*KPw(ws$_CZjGOwY*ykejo z#`(k65C}+sUB~1~MnC#%o(CRhwi>TL4{()fy1O|#;RMZI$NGQMjftMP_^B~%n&mvh zy8JqgmGtyh2#H#^$d;zjQC4rz8v`!2vhz_-)C0oSxa$n$r>^Bq`>XOxm;^&oThrEsFZgp3dx{7Sfp(!k+8pT9s7|EVR(4VA7f(fVwf}E37hvF zM}>fwDvor^l6L&q;PfWsev?U_A#^Tsan=}SjjlcnM#Yl@=|8+q*sd?QrqUk?UeGv2 zyD&8sMk*a%Q*-hhX+}1f#!w@h1$+t${DH7cF8|~K;h%5)1;(Uj zc{sdo$SKoIA*z9s8PR9{aX`K-d0tIqcS%pGby!8fmUqhWIDC1i{0tHDFu~rf{MSaZ z*+*24-6c>qdnLBja9=OWzGHsW(5YC_i}`Vc;kqJLbJvqtCjQ^mskX@704mMWh2gXn z4hzAkGeog)dBveXqd6v_pJ(LnGvZ_gO5jti*TWk6&X%)JmC1KmH8ETX7s?r;QLInR zQ*@`dp3(t)X{IS5S315uPM84Ta`ly#Uo`=SYl%Pid>S0qA-}u&s_Jde@LgiTKOdv} z*bn+-vIVnavGbY<6^)IWF|hh$7_2=ghoyA<4~deSt`}*j&m!u$e=H3bz!U@r*zy-; zqQcZh^P<81=o1o?ub_uV!!U^S7?2VM>IBI>g6U(;UJ#l2-d&zr%J-4H=VQk6Et{wE zuu-*qefSjR0Rctz-1@J=wR@e+DCnHq{Jk^2GK(|0G(gC((JM7U^?KUhJeWQ*U07dM zA2vxBAc|2*^mW75${!7QJ=#3{Hovn7nt@x&dQ#zgW-$Xk+BZo3QE`UzOPWvjAszpd z|3=~k4|L_7O1mP~jnLQ{RUeZz1~?(4pXuWCrhY%C{(D z=UA5&_SNZoUwk$D-4RP^I@hXbsy3Rn$ae-O{MbEo&+yu^TmS1U$cW1}%;`nuMA}}m zH<^0qK&I+zws3FF6|TLlP3R49vBweua!az3HmXA%Ab5;or*zly=1l%RKh5qPVdA&k zQ{Wp@T9Tmy#Bg=%zqGJ3&T>0zZ_a0he0z@~O1olja*j^X?w{d=wOwjK8%^6njoAy8pMgW{-g<9WO5z(OjNfjQ>%^OVbfeY;xnGD$ zJkw2JVM+)=eR~*y_xVk92sLH7eu``Oys5-^y?*->azwpAbUqu=lUmB1SFMMOj2b&L zKy$HWIF!i#29NQo?2D(;P1)*u&ySYA5Du>+25Kqk?`i*h8FZ;3->CnB|1&c6~Wvh!%`&FY)qjF1$|u%^XF;dN6KXG;6#5TGx3%)B7ge6oFKai>*Nl6jj+C2 zZp}922_g7&K>kFPWie?oPI}%n*yXP0aSGT0BnJ@H`%_4w-Cp0}UdNgUJg5e!o!C#9 zG#Wvm4IVGkRtKmGhYkl&FyzjRL@9;6mlp=4JDb?mhRSvD(BC5e+06Y%5}nmSeEb$c zUZ4PELJQLbiw07;V$=PQd2QE?x>3efz$#nN{CavmUgt^gcXh$Gm2=o|Cvl#8U6wOmT_#$`3j*R`+u5$ zWcv*u6j&qJfA$tMc4CLx2?JK-092LG{$Mm$fu@x8UAaFje&zvw=^s4`mR@sHX zS^Uey3ADLS=fNl&@p3JrJTViuY5}X8OA@IE<&mcM=4J=7>UihF&>Ax4LpaYzn;8TD z^2FJ`mA$d`_5?EswjdtW8yoereS()jS?n? zbq-z*{2-%aZsgw!FDZ#$sz49Y62rN318A0>A>$$N*pxa9(&r-c(i;rB(|qy($Fh7u zy?=4S*bv~G6vHLY1RK-ZXjZA6iaWS% zTLBhwCGMMw;Xjqy6G`RU2%sn*idf> zK2OykEuK_zLFPv%y+-2At*Vs-YgsVZqh_n`D<1-az2*B$le>`<${;>iBM38*j{45@ z)Y8XWelkO>FsMGjs3?JQslBlDwKhtdBmS4lD*NOPPq-1{ukvlpuo5*F={WazGy5)m zTb=<$dZP*MVtt2f3J_G>J8tPi0yD)DD)6h#_t4C_Cc`yBkEL`H^0S;b`ZXT;xI_|? ze=BwF=5jf>?IVh#$XpNs?NwcU{yP2Q~9kAVf`5&B050b z7sG=X?vG}kecY@?5j=I@_beqro<&}z;b4r9RsfgN*=hDhX1u-fhj}VXW0Z3rU)9}+U6QqLG2gf8AAiZm-BWrSt=2;M^5NE!uVDQc2>ZUn zRy;F+lQ-2Rn~9F!_@9gV>{9(rm&on{sV>ZMNchUGeT{Vf>5y3*g}+ll+CFs9{8FX&C&8-E_Z^zI2Oo zQFpa4jX;x%3X-U%s0~8O6*s$R*`%ABK>%yEG~&w@0!Mc|?1swvxsDlFcg@7fn!5>* ze~0W-gLWEzTjelJ2WFH$yIVFeOkU(M_qPLL+&q&S5fGbNXt^u@Rs{4&KW={RJz;VP zSDPxc!Me}qD*%YdoUi?mcb~XbwOkd@m)XyY=dMOpi(WtT@BW)3s$C9eWfyz5RbVco zyXm31YNxUpV1Hkuc9bQydeiwfLZslCbN&A1cs8t1V<-{&htuyH*)#gFLwujVy!4LA z%Vj8yWFP-7#~aCGCiA0lh;p@K1O|ULk|I$^k&zUDm$bmuzogsRMJzhj8!K3?=>Wg;g#|UASg+%xOEYG84 zI$P+wB{|OqO78*#S`DpzmQtlQ`YUlg{-t%N(?dGhdT8JW5 z2XP{(o15U3W=D}LuZlsji&XgJ!~L`W0<-3vZQ{P^zrCoF5h#R1O#+Y@fpOW?KuKsU zP#Ec7_ZF9(kHKay93SU^6eNKf0U^+I4iCn6mTZbfk0hrChC0T`Nk9E-qO7n}57_u>qLEeQJ}#Nf zI%+?f>T@SuNgw_G@U7dm?f7w^f4Tw$aHYt^zBROczNGNZl8*|jB0nb-W4KaGFJ;{@ z!-0u(UZv$@>OZ{F`-bUrSSb+Lrn~Em7!&v4zxd{#Y%-T&h(tU!dvwGPhEtt<)=HeKii}lOOU5GM72xK{| z#In9}Ox=vDb?>nfm0uS3cy>wav@+6PD94MxT1OdTJT63n*^_uxGX3z37{=T@LzgOk z_^wpxt0o`w8c zlc3Y-0=&> zeYcR-9BH?KI~EtyJvVCgGK;5Vd{E4pb>HY3P}5V!0FJ5Q?sEe8Xg6^4$WYpcX8?FF z*ABX!7dIVOMLlbfyh7WpX?)R>IfXMk9>9myHaYR3CbwO@Cac!|I4e3A@1qUr zBrliVW;)xR9S^r~&8amY<-1I_=U1ihi)aC%GQ-Vq=dVLy99`Vh}~qM>33U$h_>Y&5oVU8V>w@#$R)u z3@o&#q@NuwV_Q(C09YXDldNs6p*&~`GarK!_EX1`~DHo?X4iN zi1RvZpQtm_;SYgs33gc{Fj;dKTwte{sLIIx07rjW;upM-!?jG^|EXs}@#@K|c3v9h zp)TXErDQO;%ME|Qc!tdqz1F^EpOPcuBmZPqK?*RI5=}gZ#G2?VPhn1dH z5zBV`-j09#fRs~4qJKc!Z51(l1%vWPQ3sgaeUhgz^~uQI=QkWXA<5YlZv7G!4ae62 zzb&MM%Gy@cPhaqDwL^nM7&kebvkebtCF0VX(sXC|Pv@J1*tk-NpODl%D&Dh3o8Q>j zgr}fe616fSr}I~Yf^cCJKrZ52CwaW2nGrWcu7rpjqyTw(^}+%8xS~)mK-~;chYlW7 z&GbHnVo0)TT?TpxXk;^Jt!6G0sx0Q&k1|q2U%ppZF&;J4k5WHEkVi;Sg9U&5^zX6$ z%1*xOUA+}utRBL>e3|Jx{U39~;OM}LTu3kSB$sZgWf#sV5Wc(=ajIr!PirV~qyIRj zBXTJzGXtGB9z7hkD5bNXnUMn!R9|2QbF@%iA>6Z{Hbu6@>D-bcA^%hH)$25`($gbO zpdLYe_FRim)2@Z-Pa(l&Op`-bYCdBePkBVUpsYQaY_Bd{%{1-$Y7ku=gh&nz;fDp? ze5!+%h%2fY?E;UnHQyEgl#V{MKT9Hl{^dH`AnmYa9xgp=V0nW7w-1>N$`*KheZ$vZOMU>tC&y5{@Af1xD(7cYCWOaFpfp$$ zq`xEO|NGFn!>OqhD*#3m0NLqn{?K=$M%zQk+JFeM#23WO?Eo`9;u8+i)BL{}rUC=+ zDl;j9bo02XNtb{P8p)(lTEB6kiq7&@Wbtt&Y1v-9`&7<-z!Hj*1?LXg3WO7?$Ltsj ztQktLrVFifJuM3gCG6i9f8tjMhMNg7f<+GwT~MTjOT5H zz{O4hLgU?ZQ*D-tbb+j8cnI6~;%sd-KFuF_Z7zMiPA1+iWEaTuss1`@q62M3=#U7> zfWG!F!1%$sgU>(%Hse^`>U1xD?fwEt!_R}so8?E)(;P->;!NGW#rx&cedJbs%Lc~D zJ0jqFBUz3Ms?hAkF2q7xvA+zon18Fxh!Af|@&1?jNFnd+7_-H4=?=aSu1XxSwUPR% zk5DSlND`CH<6&9`_j#PiAjuJ%{anVA@OT4cJrY!tD~r# zu@^;)%O5PopW@h1_>&q^%Q(B;kwOv9#>YZrigq)ruecK-oSnYztazV+o+Z_^bu0?BtFF0jV^G_Ck@4w#c6+!&uu_MwdU$zcyd zWvb7ZMiISM2m4raH$Qt(RBgk*eC-+-9Fa6$nRz=vNwWo%*VGoP|AHWG3NvRpFPE=#7UAKF<|pEToX$$03RoQ1kB{+PAz-ew z5^{YBfzu{S6K(OStwB>dmPMP$VH>02r@Ms&EbFdyoMhkl9LwzQ*W$0F3v2($R?*+|=bcK$ES+8b8 zq++KoMx2YjI#iEo>N_<5NwUL-vg}pOZ6|Oi&8k#QPj(K~5bpei>?4wXL^co=jBDY1 zl-^7wy0Z zq1BTR)9k>lZuB$WB+8xxx4x}hpbm-CQ_srUI%;B3U zr{0EzmRyU<_M3HFH~DtYYKPGhOKPSgDm#NN+r37RD${+yDptRkEt`GU93boNZb82A z8Iiorr3R#v>$ezuwRu*w*p!EjfNGw?W37y`4>T$varj&dE3q4qj36RBqeEj>qSfmr zD$#o~FZjIe!M?z<$Ry&;I)-B`?&~C#8mfw<8MTQViEbaXtgGH&gb{_M7m>fmPU8DK zd%dn*lAWk`m%o!qfj3&8J(c)PHqz@z=QQe~Q9F$V!ZLi!d*rwcC2`#yEO5Z|i311E zAEO0uD0DFJLCqr=Q4Cc>;#Q7RG1)~SfsaG%;>ccNFZCp3RfVE+c#ISvUSB5`8ch8W z0}bm#hC~38u8{o+G+{+bfyBneO5lb*^EFlWaG9aI956t%hb4TZ1U@HKA4H#zV7Y`( z%?-}3w_muzne&^r{z(8Jwc7sFJ`n09RR)oMp~}_`GXQC+s>%(rtO~{6tC{5mNDy7v zKN)_q*@%uNV3G{nYR*c6V*~tb|LKU2Df^QU12Uqtj_;ZAsJjLA(uGV18Y5WEck_#k zqz4rROn)_~V20wXvf!wK9sXpsTUL!gj|ZPWD0^)0;8{}ABCD`Uq5JX$WzK)7j*8ldbrdD^xOnUt31I!OL_bOfexo z5nW*!=X%j%a3<*KUYMS+8@#s6`ZU?x*|^-gFI?65o)qUPSX)}V_+B4majqHvK> z|Hqgeulw9Fb2K@if{v-~sjB|j^#vw^((y#IY}pC}E_6<(iG9XkO!NKQ)Z8T@KeXVa zAcquwlmjffcAOvcCVXdQ>s~qB&WCkSD$5YA?s}6_o_tiP!^qJ3yY&f0!eL~T$yL>y zFpE`u^CJtoF=clV24BiU9wpXqJ~nM5LPK9e-|_>wj%I?_R9l4H%l$NJ$19s(fvPA* zghF|&cAk_C=~rRC!uX8f?R5zzqC^!z?I73tPP`QK~y*Z}pO`LNUHyU4vp{i^T z{c}(Gru*5twqt=1if<4#KY-IY0#DZ_u3Z|N{g9kW zRJLzGLbuDxCg3zm)1V01)lXs}Me$`;L-~oKz-HA1>H}o7{C$;_oLxB6GE~Ehyp=-7 zKB{k<0d~D*SCP^Zm;u3dDw^(5r;IPJjTLTwqsSsqc?2Nh^4#_-v9&8?f7%uU+$RFX z^avb5Yu!dsvkjTb)39X>eXPfKn%W^oqJ!?Yc`$)P$pQjUfS?nFFY5MnO~W zy8voE6o!e$%ACC9kY6kPYx#`Q`vOdlOWu@74PhUn>)k-9ZRAX4(x64yEW*$d*dkw% z;XVkNt2u}s^m~+1oYtwqa5@hdtIkMFu-t1WlDmK-mE;L;0&NE=(C znP?D&5I?a9Dudfve5~K-23M-agnbXDs%ez5e{Pfz`&80cLCK70g> zLsq7{#ZRhaQ(ueO?j55Vwf<#z%=2%xwIk(5qBA8=s|Q-aG=&Sk`uL+I8^r)wA+(?% zLcf=#!&e)qGsr9w%JMHsY^D{cX`rlh3~qUTgFxWG_rL>)4_Kv5U)7f5wRT)Lkp{|S zq%33EEDsEQI7LAJ@A>~`({Z8@Q9T1i>#iE)JAQ$FlJ+e0gcbx9GH)!!XS={yns5E@ zmnpc@^>nGO*u((lM`aeSmjiRz_jxaY;dKT1?w2g^)vDH@@Gy0X*&VYIp6DkXbI4 z-X5g+E23G=I`#8%mpbuPov@_iMcEMopAl@@RP%a0riNr5E%kR7z_Ny#^r#9jK+i&D zM;gbfAx*VAN$)$gUR($i+D@Q8V;hI0#(z+Y^V4$AfPlTs@cQv#9stgEb&xl5m#p=? zxmEc#$m^z;c~*?EFi6kfp!2RiC;a>BcyK(Ozz4F9bS-(Wjwh%G^qEpHbNgGIrRH)) zm1*AeAEQ61CvVBBkr)WPqU&?YWq1pn&L;aSdZW2nQg5*yueIUKIctT6p|LY%iXH(J z+0MOINbFUctb{%kG#xNH*AJE##r{}eP=ItSRof7MgM(5Mne8*D(W^mWhjNl<^OS&N z_bO^cSK|Ww8wW*w%I(cVw7RX11Qp0csBfV2;4~i84UXNfm?%(rB?S&!W;lUhlD1}cvZI&h>}d1Ii;Qk<&c+aXt{P^NpBpRJ+d-vj&S>a!E}txq8_L~wRS*Kkq1 z$XF=ztLOAAlS^4LF9Ku>vCRgorR1hkP*=@d&oD;}LROT2<&e2iaW|sn5_40=)8YKx ztjNJph6zP7P{9YU7t6N$IQUxvbk?Gg*)2xix*;1;#hY_hD`mnb~x5x|_AuC&7ue3;oA z+jnG0Dx8yGCEBF`VTLac!CO>kP~Q@b8uOn%V8d?x4=;~n($BwDH%lQ2!EPI!13J!3 zw%GT;fnK%Q`4YOs*iWGg9`dJU0VC5-UNz0XL1bdm^=@Rl6<7NOU@qh2jWERZWo=h? zh27QM+4$-ZKN|zLIPQ0>ImFYNIsGnZUjHyU1m#+(X8Qo2WA>eW^Mg+o zRJCppXSPYk`8~qVB?NtZl=<#j1VUJm<|A0kSCLrgZ6qVQ@c;g3#%W|Bu1(;fS_%va zrR&^6n-VLOtIH*9)HQdlH=y&3_q&B>)bmx0*P?*$t`Z84_t0$G3%m$y>JP~X%Gbg= zp>BB+t>X2Vd4b7RFHV9s6^!rQ0Qf)$ze2lQXa#>GffY`_!F%)z1h{?9QtZbySn#v3%ft=mVk;$hqtlAET4;6A_$!`3Hj2Ucz5xRtJWF!34TiV3{5i6PI|42Ko=vG-LYYd?J9ENl~euPWp+d>W`8g=zAuQ zme12Py?(xoTWIhE^{CoM%IjW&i?Ph>uF6h-4AUl3h)SHfFSE0N%ju!W*u33JD5na- zpSe4!s^6{~Q(GUXR)$zDT%`BSY4OD=aBu;vY?w4?WIk;)?yDL=E}sEb^JLlI3!IFR z!DVgx_K;XZR1DqF@&6Dd$<2P|uJ3s~wv)Q4>;%3m z&2homF=$ZzGNhzw4G5X00%)`i{s`ds-_$x^Nl%czpV$QYxt)aT-+%g5!gt=JT(!Ln zACbozSpbjb=uv-8J<{-ijzWKa;vnZSHChg-PCL~GF~~>p0eIv6?BcTtHr++rn?EWs z-?`L&;a58`R3e-986aPMBA}0W+L2nK`-!8L*3el$xrBP2Lrrfo zY8wasr+;(vc%Z@elcC76M$4<$ge4MWNc<5b4BAGN49Y=!a;d)57BN6^q!tB^YA5>? zm(Df8ZGRqNzG)ayc97*ITa~6bG${_1W1)SNVk^ba#2G7Bk6c;QPUFb%@wERjhW8h% z#pz1#DnaprlJv7wiRoGTWlPk`i!uCF&~@!|Ubp!UNbTktSk*5W%~7^c0IRbEbyQqG zXllUoXX&)73sYIOb5Z^zW-LnM^#((bp~%Lr)mQ(+Led#O1YK%%YGw-)oS zBlK%BbRG>W{Q$$NM%h?tz_4FX(mw(WXL5P|KaklgjnA+<|6eAX<^;jAK14`P&GDL+ zpY27PlCNp!9zu+8h8tH?*SPik=$$#_^{oucfkod9;opjclJy=MEcVJxXtY~qrC+Vd zF*(@bTHvw@1*ot6vx!hncrEE3=m8R?AmQaVCtmeQhoB1N^QpLIaSNfN4fe&QmKpbxPd@K9 z#O35WeE}?Br<$omP^m>?rh*27gkbCS^vvoES(xbQvgn*(=8n2vzhAjgyEj!mfH-R= zzY53K#*0C1@sZ0=wWUw%6aV}p9x8%5J6velzL^<>6F5*o_5n2*8)f3j(W~}HWToyf z<7{JjX?HN(k`we#42IwBWT^|B%)^fBtn#gZB^Lpcm`uSW3BCZCvzb!cm_;ciHyss6 zal|MP3B3o(>*@8GjRy!renCxy5~lC-BpUl-m(46;J6!HIi7c7|@<7nzK~HTv^W=}y z^K7{;%Cy%>^R0>-1T3n|w{YorywBo&0Cn*EM4|k+3y3HBFBodphEFX3Ze>yOoms&_ znu#(Uf+cghH_@Ep=49R_|NO2!^a|qSfs{qTM*`@hjEv&QTZBPnCHN#rV%$SsIP|I2hVO6*!>5$d>+u% zkp`kPx;K>q1OFiuKcJj4SmeJ`g}eH(y^p%7Qj@L!Hf(@e4@4cp4Ln{hKTrQ(fZihD ze2v#I8zQLvG}+)c)6k!wM%eDT!$}hW5^?P?82J zbu!^|)%UKOxo8KlH;rn|gJ_^};u=N&Lq=yJz8;)tj0uOSx*Zjo-Qw$;pn<9MKC3&x zK+@+PyGbD?BvDS&(@wWXra~=w_6L=hH)OOe zBFq(I(R_dDbAWo|`*?Y>bnlut3YdPa$Nc>D0^%J7V1;JB!>?Sr`&x@j-wDe^oVN>oo-Z!>v3yC7 z^)trU^6|K4aS|QTtONX7m(8oOQ|<=NW8hfyk>y=^U@RP=_;nATGp@EXzW&P5ldUA% zW}X8HZpx0#eiH(NW{q)pMdCgKvQK3pIes%=SxF#_OGe{KN#F?cBNo!lLJ=u>(P;ZV zE4@Rs&uLH03_*>6!S2E5eSmbq`aa}32X#^Uy)kAe=aE`|_K3U~p1*MkTK`V(FZ|76 zuM#cJ1lRv!5o;S^=FlQxCdKbTi6)A@BDJvr&S{-pDqm4=SZGH+79%s>#|3njG73_` z6R1@3Lrg%+|3VEI9k$(>?D&naL{6x;>!km6v;EyfTqg@hOm)&HjnV40%-&#e3e|jb z8U>J4kV>j}*V%|IsjS>=j%IHlQTx_vJeEbXz(CEOH74~U=ctGm|J$^4zFJ_pk1VxH z+zdDLw~N2|Q*%*DX>kpjTetooG`Wwdro%rnw4HQPSJssRz9$lfOc&mwIw?D<%_gA8Mxo6=HLKM7^>S5Ek(e40Dy2&bLWh+qyj-?p zNU3LN2K&O1li}Kve_Hh{{b8CR7TKA9&(OWLXDXv*e2zN1{n-#zYxVx9h|iFce3nG5 zJ~@GE%%qBblv`={!vD;o(YVE?bJxm;Ou#|_l)k5%R=u|Grz0UOQ1XUuf^0##cCkbC zS58H(vsCy`s*ekfcLmq7(u@YlX!kJtUFm>VFe9<r2;j#!9C1 z`CfqTL}~#ey|Ae5^Jy~21S}+4!(UshJ}slBs&Wp(25y)sG{0*I_d!1s_}!^Yq|K_c znYGYnd`$bbqhT*y#fbC&X|&y<&YCnbvN3a}aHe$h*<>*fLT12)yAZ76=~80Ajn56| zyNf809&AC^pLB4Sj|X#Q}V&vpk zzLay`ERpljV3{^|v5gwDZnU8PM?mNgVOnt~eA(lj5)V(5pNF@zYf`KWu;)&otvzN3vj@M#4^L zCut_1zO*2}wZz{eXWS@M>h;Kh*j-{h3(s>{JM}B62B%Q=oq7pZzvf>({oegw_L<{Y z5J%;+N_wp);QVSCn-chKPVyILH2RIAX)HjvB6mESQ>HGg+dE)C`!KeOC{;vZaz;*d^~@*m$3VsG{|__|RYi?GJ8dj4LiYCNqh#$QPeyq)T{)a^_OqM|9rC=tX$I zooG#ZMW|qB2z>p`=|v_r4ct9-{3n`&aD%Tc>JLzA&*$9mLWk+FV*U8&W#sCTd6kNS$3{>Z2WqAuA3ULQnb)#}C;6=Z zWzD&mcUD&Q;ZQWpAxvU!Z2dD#p{yCE&ZJrtW1oA&@_{Jw*!$8M-n8Gp^d+60gnEe@ zDktUM;Ui|A$%tb1vM|-1BIB!efnD#TP%4sDFdfICL1xNc<|9+f96|u%co?agF27%| z)BA0ajU>p|E6c3?GgVXivb7i(^!GZU_u=q_E4|`ZFy?v+_w4G zy6Yt)O*i z(s9k4NrC4x>E6YZ<`1a9jG$R z>ldz(BRs?xL_#AdgOoEz*!BPyeLg-g`0V%JlYjML{K~K$VWI*a3&C};E%Jj|@6jDZ z>i++ff`xdXWxGsPU&ul)90>VklGw4%ei&GRR(%r#4cO3b!C53Xv&v@Eu*Ly z0ZzUgHPZ6cM5D3;-Qbsn*TOCqU2mwPlG>Jij9wyLzgjWy8vlv&|63_&-7 z7}(jPA_;5$a~^C}_^aN7UoL{85AeqYYeSz9@!9@F0@Ow%Z>8#(W-q8Qe%yy77sQW`uaQvl_j&x|UJp>X!T%R`U|;W5bD(KlRgNgA?p*w>fWwXrF4GB_rt7 zf}edo__ER<0i;T7O_($19PRT$)jpmqRWMj>mh_8@VMl1IyA+P+>ChmZ~G0Phe^>Grd(Q}+% zbfrHem>yaszko(-o96%Dd_x;V!ok1S667;7{l{}wxv@L>m)5FbhY&hl97nn*9Ifml z+{ZJrJ+a1JJF7W$IhKV+KYbvJt*Mt=)yFZyW{$<1fIqx}KoHv?jz+K~*)sP8IPfj| z!OkO2A)YlZ#|VFMY#&fIZ@{`my%GPrvS5M^Td&%>Ns!hGlN1tnk>oT{ns(5g5QO{5 z;~?$eP$xTcxWHvO?lx#_)%-AoIP=Anux&&M0gTL$NH~Qxgf@_;jg&evN)xqdNJCXO zH>7_x*37%-GVr>=v(k25lIXrIS6ptj_}yE8;>ow5-(i(Gg(oIJ~W_rc~8j(r_m#o|OP8;M$g>1~lQT5HNcojck(OK3?bPiUB@yt6DMJ~lPZTbvmofYHYmSj&%KPD0({v%ONWk*f+?PAhIT zkyKwe0uJOp%nag1A+MUa6%-kJ9$*d1#CAsMWc*;9rARf9O3`Yjh9Z_1opu<>HZcYj zSTR|p8=Cr-s2_LkN`>jhWhkczaj|m}rH51$+7txORCOSVt}&KpPS~dDeXg%0KF-;n zoz>Rqj;j4u6m`-ZghwnKj#SCd$ysrMVa>RhK_LPEvv!_%Sd87IAj=$NxC{_go=>RY z1IA)^UxXC&DfUTE5o=!xBo8kzQFJ4XQsS6wv9hb&5=7~d8c@G-C(oZt7bT=BaoD`b zR3tFOJA9A0(s@}#;q`xe`9RD%0g6{BR_N@BBq-#;QV`4(Gw$?5FRT(%%s7m{NA`WG zl=?5OmU|07y@3MjaCLix+5XQZ_fA!O*9DfHWWh$0(?^hMP9Vlx*&F5%=u}NdtAGpi zo)_Is%0tp!u!BhS=I1c`B(z5ETia}q5bf?`_fh%t9^(<7;`Wrwjnvtx-R!T>qPMUS zt{Vghvt_WrS$PmAJEBeiH!4Y@lsFfvGai2u?+WS|Tnqn(N(ZW9?kYrfCJFoLRUZ@K zWvb@QaSRZ~YT3eq0;cBRzh}+H`1F;0XtNujjy;pz5=`+!iQg6?NK2pT_|Hg{7((5Xx6 zBQcyfUY)t9*`_sukqFuwx%D`-faWfk>>mI(##%=PwJa*WTWTkPS?4YLB-=@?8viy< zWZ%^~7CfXV@a)grINTSRbiG+@4A}{$Ni+yO=$w#PCf`x9rHBY}Xl3Vbp5az-D=5+T zGVGFBCOy2>7*oCTy#bt}f|8CUe=f81%`acC*wfxuA?$iW(D%Fn9SWR^0Q6SPmBV21 z@=t2tFd%+FUeu7L;|v%-RdTQT=%a;Ra{Ny{vpRYen8vVci|vPl3lAFtdOg6=wwkb5 z#9Sg1Awl!E+w_F(4DaSa_hV^|C((}xx)?>R%*T)&DloNf;@*Y`V5vQ zY~?nl-M{MTewy0@h|P{q7G+2hXxKXF+GdXR*QuSg6LoknoQ?`I>O`b!7Ab@j2I>nH zR%(pe=v8km(8N}wKmxH9GlKqaBfCzvToFPk?8^^{)D>NenYTajh*+krLp9UJ`$DIR zT|`ynIr`I}WDJ=|pzA*rbBN_OYg-aZ9ru{X{wB@N^R=!b(S}|D6gu+z8oj<_2C!Az9mILkvJbG5ewIrbo@|*HV1!b7Hx%e zI;Xa~G*{OaoM?(oalaWM;8LQ_?$ey}7~*c6`MMrYg)Fr%$t4rKXtTh~Dq&>^g@#~nFz z$BD!r5ZboET}c4fmEY%7Hvsri)kcqL*HmQe~dtVJ@ zaw4~AXpO!vsylnOVA^#qZ9xbu0N&4bL|grI83E%uPR`;}q8tY~yGG)w(S%j!X^?sr zCLWOn#ad^kuE(Y}Icr2NEFQM4M^Ms~b5RPNR}Uwd?~zb~32x7QFQBSyL!KHMj-6d? z?>B=FTl6p^#uixO>ZsltUg+ZMON`!XLuCY0OA01ZO@o}$bgv~YzUb#nfB0MZp+c^H zOn$9L{~_dX@EogCC|N(6?Hx;4kMW-eUT*1f-9^Rf-2=x>vB~-J8{kp?HL@!<`#0Dd z`AVtmF|o58DB9D{+DLV|;r`@nuu?Ag5tu8mG(Tf4 zQ5yGxT*X+Ctd|X#-xbJ@XF@x+8$XxG7Vr;TVVw2d^)5DK4IB(?mtA^KkmTIbWZ^Rc zFBoi9Zw2_*m?~H<#Jn$Dzz`&*>zdd-=+5j^V{sT!z|=hwA{^wS0gHbCh(G*uRD4C8 zjLj0lWNxHEH-=i~iIC{P>vuUD(zI42742L)I3MQ*Q0_af4gM}l`waXKxh?b!C&B)` zZ5tJrs@Z~|K*o>S=HGji64cxg2NsnR_!JYQ3?FI^PS}MbWb#cQj7tPVQ-cYe%sWo8 zBAF7CPu5RPEu}(M-Z_HTdg`=9cbE_lcE15z&Rl@yp@a>*#wUg1Y0}~U-iBJ{-E%=| ze=9RGciR2j2m*TPeyV#6PmZE#O$GJ(_<`CzDfM_?UaD?v{WD9{HMuNKb}AQt!i8}h zOGIRSxhjrt5>U4lO8}8TvBoLfv8>6&#Z!FLSL&8X|8b35yS_!J1b|~8imJ8WJNerk z5-{0S%fd(pnBB>mWL$RD^~%%h62tE{Y})0KBPPw#>7lxcjUOfXxg{;AxMa;gAGA%j z2VgFv`|h*C#?XeXqp)xvpaBd)yzGe+#81rUhA*Mev6LP^thLa=mtdMRZN(apyA~zR zKqAG?ZwbP>dY1+J_Uerjq-es2f}}g_4Km z3(#aM6QhR)5&;zV5nu@e9ux85NRSW9n|1e!sln?+n+qU`Jo${BrA`l|mAtvf4>jC& z5uWk)LXwho63_XkFGKKs*X#BA{enhscyy z+j8_;JYOBCE`2kdW3^*y83KtvG>XR}D4P@QWa;IMzO&v_qPOH?inOEhdwi+C8p^-1~oog>(vMvD~jWb!|D5{=NkVUIztUR2PCjckJn zJsu1o1wS<7gcEDR?%CM*12lRu@&fL~n;|Lg>Qc*Yx&zVgf5n=;MJo>CJ17icK80fW zNwa(s8hIN)@b0&Qdha^jb-*Xk{p zA~I>uGzL{8KwbRdh9au^J0Mj+x>X)%ua=%yn*Fd6*SF*;6>X=r|LC9eEMcWn*c#w^-(83p4? z3AA+%$K$nyI(OYMqw>Z{9I4SCWX>_)fajg8509A)4*W@k_X`4{lVUSmkbqTSPwA`X zZ1T2-)3l;?k0NO#!tT6E;xf3j`<95R@^a>n)T9OlcFsyzLK?^n)Bc;{f%)=(`3lI8 zF7jfkf5PJ*eu5D5YfBJ}gRA>lRb9c)5KUtAkk;(`j`juXUD%L@(OArRuxk5PUE0jL zhdCQi3IqqPw)pN=_BI(|>?8(`Rbr^b-1k~`$J#2eKqMN^5!#q*aue8;8FKMbpMCN= zBc$X4=6SBg7L=mPP;r`}sE| z)8ZQ!rzgivRNU2V%drGy|EA5LnF~kZWXhgM$BMrzRdJGG*o-_~on1}m)Ij*v7GfX) z<`-fF`~~W-xTdvnJW%I(d$8fgeretC*R_#bq44+*B%G9JK9L}Shz8i2Jk;T8lT
    z*|7^VL{!cQ5}vN+S*(J_t(vmsk zji@E8;?5YN=p*{%7LB;DLpH)%PrXrL0nVje0?x7=B{w{8$XoPviwg`pE}TS?(nA;4 zVHI##ieoI>^ur)C&@d#%n7M?v+47Ufm-CFce-h?(c|1IYnUQgktR2YoDYm*c$w)w` zFD`5QTn5G`aLVsGeX{B9GHlYAvkEj$kp+5;CF7UA52hEYZgSe{<%;!VdhiOZ8L^)Fa#-oJ1s0f}g`Kobaq z?i~2@%s|%eqbqbxx`hs|#Bu4Hs6nvvjB%oxA~j;=1r$f+^kh$i6T-N1MnhFk)*Vs{ zS|Eqx!x;xb`)Hb8r}2fB%d}m0IHv;_;a1S_K zU8QL|JeCu$FIE0*3?H*orbCleDyJafnWgLX`w7YM(^$FaMrN0<*X#KrMn^Zpq_ZmU zm2Uh5t7VJ^pOl9}qGvA>n_{ZY0^B3mkn!{N~wmLj}v!VVICmEljM+4a|^2aad~kq3Uk z-KMDq?1?RKZ651?I~yFVK<^`t;!e||yY>v0fuE;(x1L8x=(%IT5lsLUoE&=y>_GKw zDeG~k_tWeII5@!2$PaA=`Ctz$+V>My2a`bctY}O<&>ad23tV(gW-B6f8f8b**;2X* zkr-+fbqP{s>eQWoEC)^3+9HoX{5Yc5z7KzTSx@Az9F@38S{c9RgSAQDTucz{$H}kd z^Cw$Mj3?kI`Om21|F()zhBt`xenhy@}g6g&fe*g;%Eq1As^yTCG69h z#&DcGQ3_PhUT&m>ZLSPo9UzY844V))kSA@RGMZ@Vn%sw(MI;2W@!Lbk$AL!!t}n zTn0L7wt{3<^fNTQe%0r$L%24p%@2h~eSk0;6$DD~UV;ZHA8u*P0(lUV{0U7gYKP|5 zCLMWM^TL&gZng&h@0AM&j%fRh)XZ+krbVBM0bZ~hk@!uCawWOR@T2N1Z^dChx!169 zBNey0L(3EDh`7Q!gnxVk=UuZT2I@v(pVj0?kVOZ)V>Fd68YzseUXL-mQLXD&stw)0 zpZ8>UJG27-sk2qy=(7cb?YfzX4qc*&SFQ1!i!O!s(o1jwTUADq11oA=c-A zu4Y+2)0*OYP+k7HOl&0Ll*vv^qddxvF4hRvwY@oWcs3+$;8i81cI8w|IEiY;i{sc2 zhj+LBr{_-n$P$Kv8XXZ(u$lN!+LHv3n}{E%pB*(*bg<0Q_4@sOzhOB+7$YSFk=?97 zRb2lU4)b%B6^YH?jba-sP;RU(`#M;zHUwSK0RL@!zK!C;C=~Gn`h;2tp9j7*G1${# zue8GN%)3 z_M9saDh(ceWsX;{^Lr4+XKo3uR&=_n!=`-Xgq+0rXh8=CtOOhj=uz())2*XGn%D4$ za1QaCatKez0$r37oY`cCyk%XOhl-?XxM!3(Bo6Ummol_fWRt4YB~%1|T~`CLRD-k> z`b)6-Ys59*dU+-5t^q#9;aMLEmjb1qI`t}x04d7K8W0xN*gZ9!I!K=YFba7uFSucL zyz8edJGvm*xo8u3erB~qk|#gww6YGxKh;qjb5s-K;hFu*%@==ZD!1qMQH*K6Sr zfdM)oF6M|+EQ6{Z$_ugS_tMr*1F~HRG;nVHd9fAg%X?kP=H%q98B$&tMM23Zq7F%| z^dk(a_K+eZ*9z@9eqTC=65NQkJl=ojlrCN5YQegOLLYVAsKddK?_#%;%VVQ-yqOiH) z1*dN@7XT$b43BXN$GS+HdUC3dUb*IHL4wU`){njCw{i=BFQ;s`;#g*`sMRyxTO4fx zX@Iqfq=O`ndsw~tw~)?~U2}(Ev4LMih5~|G8|Y_l!?Rqcd*`Uo`~t)ij}CBllX^vf zP6&s}=H%S4_Rp~I^s%TlBI4STFxC*oa@{Yd4y@P3&VBWiB1LA#x%`42d^{${kWz5$ zTO*BLbd5?zPxjZh{P$eo@s~W_qi4%TD6h0$z>6{K3`l=K-6n|=0F@X?sa8k555iDD zgYuv}+`>e%x4b}ySw_d|Cdq}Bt1p#QWlVko@!yL!LT+w8(rIa5htqB;h|$4b-ynQj&+zxF0LF;2 zJ%MKInceRyLpidewMN3TK0gOX1hSwRa$9Wj?&{>MEj%Jk`Z7%|d8@dl`f9BjV{$an z)E(5tF+MtKrsmJnHPhp!z$qqa?ri-tOV{=Un8>SmZ|R)_hz^xzgv{-If?5z8h`S*e znpn{{#_!PIH>Ga?qQPj%Vxro2`x8FK{RBatV16$ zRnj$sedZWy; z9hDJ1F{%C$RGML4Mr1rzcx1hj3fHNw`P$dVaCWetR?BSaj)dN{?gJ@VBbg4x>3PhJ z8U6E-q7ZQdaCh9k;koEbJKe7r+1hsSzd+=ap-AjJLWY+-cy{5++V+8#o%@{PaO0A2 z^VBA_3(qeEtWGiD#GSa){^4Rmcxg}g`4H~mH68`slHEURZkp?ojyRg_u*c$kX$E~% z+}ZkOm#^3B_4@t^@!Cn(P%}%{>-GBmLtBebtRW7i*ymc4`4Jr8PX0+D@XK1c)J zPP924Sfn^pfN9tD@+yE40(oD;C`?TZW1)N6JyWRnjFRu}Me1-gHa#4tN1y)zV?U*J z-Y@@^R=}tH-hSUq;9iOr~NA8zSXwY^!bnH!Td#awp z6XT|;ZfyNCOW00qZRdl~qJ%%U56gw78p&S`tNP=OVi*+-@$X^-yl=xue*AOp@ z!kG{}RKI_XX;?%+;0hRTwZ7;a8G6~^6tv;@-tjpcx`GAp@FwZ?91>%!mK(C_f(@T1 zRU+uUkgOc>i&)rPG`&8p?CC4X-R^fN=OX2%BwwfeH8|RNwGI#M#QtY&fq%nkR+RvE zd%F6|)$@g9f{h-nP#O$9Pzy$$*C@g108cQzDjmm_@9}smNz7Uu7!l)!5}CrM>$LAt z`Q#&9=amT~Pn`(-gYjaVV|YTw+v-D%m);R%LpkcHoh*H4XruV!68u`B$GOXs6x z@{@7K@G?2yS50#3psi0%lM(V-%%!?GekP^LfCn;NoUIyQQMHEO6|iNXVA}lKT@fD( za%xno8$J2#l*ALDj!k*quJt+s@f&28F>WnJ4KWvMqjkB=&&V$+DrQ0#V1bJomS*o~ zB3?I6r5tv1c6Z)swEsaU86a@l?asSJ%dCuM?+s0n$&7nyI<7^vy3{uh;AK`;{74W@&o;Gs21MZ$L0}-x6jB zpmn^;li(Ukeg8+dC6jMyhU+qcbl&~gyHO7BzR9v9PJMcbaFtNwRa~55PIA@2()L#c zlNCf;K?xEd<*QPGVP9la6j4GjX`+k=;x$TBMDlKvY%@9+9dWN@KU)1DD+<~w(}8H@ z>Br+}T^r7Y7t8h=bMo9jhS<+Mc82)$Mg=e@tOpeW-I7#Y+1i_KBJay1E*&B;(Efd7 zeqyOMK?2X$3kTB-Y-wR;w~0*m?iu%&P?8b(0#H^!%cb8aG*_c8G~IXqDdK8WO#x-Y zRUHZwNd{A`oenR$V)xK$^U|U!v&!qt3Gm41>Nw3hbjc~tNgneh1U%F6igw`ZT@+A8 z^z>bNmq;Mq*6(q#-H;uTGwD>@J}2KnXOI(oCIxHdaS}zUWpRJh$Bo62jMOD(v;BTd z-bwp4-B9)#7yltM>Qh(pHdSB=@Q$ph>!G4tgxWv;58q!?c$7lkxNJf~V_vK~Wz%4i zVtkth7RjJmEgx*$7sqTaom5=CQDH|BP`2JTs6%`@U$58e_52g(U)_Gy z-$Jj=avh*9!|VP-6UKI^V^msVGk~jhV!@Jzd#@T1?icdk^<`~uAek>0iBr%UW@_7#Y#9r!g)6pTQL;H&4D+w-Fp6@tsE>x_l5ye z;Ed0dLu$a&h^vfmo3G*|C{|UY#aGN|^>HSracU5V{2@pSh#IV=w@4vK%JN^ReTQ(?oqJvjF=GlO}~ezL0Lmpx%S=;h0KGSifQ4 zpql;jT0Ab{iI!qTb%;TA0MWqq$r&$FPuPoOW~%XC-z4R$eZc}$9jtSc-lCyT*I*$d zSjy7Y{%kMNf=LPEu?Py`1M~oLVkLWfj^rG~8ZGB9NmR>IuG9as^%t3H;ey$54$m1_ zN+SnwV#hwJZfyNCOq`z`N3g~wlOfyYL6$wk7x);b9Lnc+866t>;7);&56N8-N=3gu zTn@6Few=DM2qYdlcRqF4I|EbG94Swd;P_6(*;EzInHz$jO$>%(1W)@!MjaHCqw;}h z;B2HYZ}0$556?Sa^)!FC{v>_LBQ!#)K8+V-Pv%)cM8@G}j_S>8Z%GUdv3pq4ZGtNg z8^gf01mCz*k!lfxxIS_-cU-i`p#{^qPsuuPGXEFG)r7cmPmrfds{)Va$QIqbZGnn| zPnnC8rr+Dt1rxj##qPi-sAP^VA!EBabv#vT4pds<%DPPvPv0Eisz;@=xx5`Onb+1C zi;#zagzt(s!Uow!f6?u!;I5uQ5<>0#7cX2w;ik4I+A9CTV7OyQE+G1+pHT(*5lIdO z5S`{W?JVgx9p6W}hC(v;k_igWNv(_Xhc8Mf8!L|a*cw>9Gwnuhi<((aUbSkX#pA0e zjEL1`nhxfG$zvcE>ftyrED9BBDw_J!7*K%F??yz-PC-7xutNSGsVWcRfEisAGzKIO z$1DGgfD@B*rw!7pAH-1U1JdRjkf8m;b^Ru(u|mV#?fN^j(E1_&j(2Pk_udKd(^WS% zewn4~_cWPVL5dr_d^EL(-(Qvf>|m0{N68r-jYiTl0}4_yW@9Yowq*@lE?ULi4JJNB z&t2A#olu>$?U^Ll&j}GFoR7|5npNt%wOAe8DcF zY9$69{f2pWghEeW9N+Bhs3I5Cu)Kimp|a|O>jpY^7JXC;jctX77gSAJRUt{Fv}s%` zfyZyinm$lTQm!1}bw#go0!N0HQA%@9zxe6<{}h7Cx0v^MZ-~k=wz4$f_(hn3p-Eww zBPoizGfpqqdB4L2cBhfq@mvQ2DUvoBtlohimX4=@mDf($6>RbG(b@y7=(^9t%ZM&G zi<*3zB8DzPQc%RW1rVrO+TE=Rs1oF*=)v@jRn9p&53sr}E_c#GBg%ZPFJQb!zJV85 zO7$6q6N#qvc}$w&%v497h(knQyKM+NABA3_?EFPy4^M5?X*LYH3bcA~Sr+{A*Y00qpi zU0@iD4l`#O}phEbC3BI>g#Cpccc~={oh7 zl}V}!ObbV{Jh3NL)XJlre5PudlX>;$;tIQhOH>c+rxvbJ-TEmCg)A7=TnK!mC$GPF zLuz2zA<87;(HW1lBV+TB+p9DIkP3|dd}5mLo);|FVM;e?9R6l$2ow5rNB#pxF2Ud0 z7vVMGa07LhME7x$Fj0|!ol10o-KW|Gvr5XgQydVMzjl;spXR*4h~A_vVzl-cpOtqyM!dvNbf!&B>T%?LKIv74(zy*(Nv@B#cdPL z=tXJv4VLZ^3s1hep))wF~m&%p*KrWr@S_L2C!2$=U z!PF55-Nz*r_i~uiSRed@Qj3UBSiDNKhYdYrZ=kqhh0rRw4I40^F2(K zNm&JOV{mPB*=MnpQ@h6na1neJb5u^R@J11ol!07pT@dEzZfab`xm5gemU20 zLGrpp8{%A^%YH$hf`&+pco8)#FMfeaT?xn~vzHcQb-khM;48qE4NdXIW*9dB+wkam zr4lVuv@VJHHY>HQ3zg*p(p~gb#MIcFU~F?`Z|TI|#gp^PM8cq!Y#BiW2-EI1wLQ5w zaOQw&dk}I4392Cc-F#i1aXHsddtZOie>%8@MWgAHa>ORNy|69}`jUMv*uSgoxnE0D z=l|Id%{)7;)m(5=e%>;opTi>(tLaw?e00}(S907!XN5#+qp~<{B)X{K%GNL6&W8W~ zE(MF3Aa8!nfwvFcK}4ZZ14dN<{-#g2(NQBLaI{s6*kk>Mx?|SOV*}yLI)3Qt^e*;L z5}O4SDWJoPF^bNI`bSut7fXqmy1s0`MfPL+=zHME)S41MiZ&wkWf56L&p=4zF!r_H zQqq3%lirB=66Mow0SpAQX|{6FoilETR`vnF>`y#3$W1Bw<*3wMI}zY6dlg3dltz}n z>1v`K_c%&Rn8mZtS%3z*hcp(wuB@2FO37ncqYHlwrM`4gb-18asJ-_O?rvTb63~+5 z!V^lyKxShGC@6{vWck7luh zUeq!b>C{njMN;`!wvb6tvICeJvmy7^EuK9kUIMcDV}XeqyaeHX_oIHuPq4z^)t)YA zm};zZ2TM5wI>NxEbR$`7_05Pf+<4UQXuh4ao#pE8D49ayz!^h}^Y?y92zs?3Mj^+c zmd9{OCVwf4f`66=ATn@l7LA73@al5Rjg*G4|W z;E4>O;2zn?E1_yn#uJuH@ zj&rHtBJ|H5o%ESTG=7pSs;EOg*Sj^#sB>^x^H<~wmEHIPKg1u495O}t6b$B qk z<_LueboIfsoKoTr*V%U|Q505(+x=h#^)h!|a`3277n-W@nG*n)$?AGS6L--HHNjlU z-*DDXEm9N=&Zskc`TS%6G}V~HjMv!rIaaEB3{Q@lskyWOrt^WUvM(NY%t}Rr76wM= zv>XwJ%zR6ri=#nt;6P1PGJ>Zd2ST@p0cdE@UnN(g-DkEC{|(6tkwzIznSaR6RVUv( z@6y{Z)v3VpQM7@iWKh(C#{gJBr@t?R=vZR5X3`*OYy=ihYi_^-9}4vm$Py?GZPNnu zpCVR4O)(tuM;~b}b*-jYV!bjQZ0{>KFu#0MU~FS9Ms_aV=BeK~h|35$yJ)-zv&jdG zbn3Dd7_F&AB9yeyJl`y+j*Ql2fa-@H-c5S*La?g%8;& zfwB@gkyLl)DZ)Ttc}zRHh+f9@q^JMPAyef1 z`v<#5^**2@0>|T%pOawQ-B#xsKfnghXt82lG%XjdJ#P9!fP-#HBhdadZ39t2f>11B zZkj`B|F$W5Q`nC>Q5~Cq>v`j*@!c6G`BL1meZ-0Jiof4F9CtKK6ULrsh%3>^1fURy zxsv^WAE8IcIhp*U*>T`^|0U}or^$B#o*qXsKmhM0$04)3_^6r78mtG{?rquk?}|6b zmNlc$JR+vIPn~~t`u%>tU$58d5zo5EWD*}RPgMP#!O9m+4CV`-QG0><=3)kg%Y$WE zQ<@W-Y6nee#au@=Dm~H+@W~H=V#M*zSF$@Izt&axWrmcF)DH+jU?~d$0Vsx4xdozq z5D`0v;qT9;`EM7SsX$VCXpy4V*-SLg zTQKpu6>?sUcoISH(Bkh*Ls{^E*!u@&m)1yrL~suC--V+gK54!JNm0NX6^|E6D(S$l zujyn8E^u%ZWvY^=&$sNEuEGx+i@B8=ayQfy(C%>}6oU-T&n(tW^I<-$&PsoH$eNMC|D!o?v+wwxqd_@? z`MczD>(gYDUcDmU^*q2RS4f4Cb=TN!%pmxLk8P_qkH2^NR^B^7DS0Aw03b|fT;aT5 zkP#!`v-r6bTE3*|&s($^J@<@%p#QSIHH-~)Y8wiZ5yE1B@YshP%EfLKtf>A3N{hG# zRzZF5fspW`Zyw~Q;;(OUKyTPE-e<@7nso=tHM%2x0M&0;1Ln~Z9&W{c{C1P~| znC70G_Y|)7+B#~c=PK1tVTmvlwf_iFMbQ|YG(V@^?A{N7I#(``wPW$0@Rq7M$qe-( zW;#z*E|#@4;}V6Kvo_$dOGnvy3auq(W$aqCSDQ1s5=Ovn-9)YsE_?PFVP(AhOTB1? za{j=Rl<@K}azy!++&bbQ?>ymuI%j|x@BXTbJX{xZWpUg1m-cJ4_UmrHB?jjf28~=v z(*QrWD4<7*y8;&RTK|JKK;l0qUl*Q#@j>63-F7cPO#(Q)Ai{jx$FDgN+{!Sr%8r=B zbwI{EmNfWU&gGxDtd35U77OBx({`86V4E5bB-rRnLtwrCp(u=5E_!2?u0B?^uf+nX zcDkiJ>B%49T=kN(;AIz^jjLn5FFn~J12ojmqdOq@W^ouGvKXHExBHzwQcy zqDXWW^R$uaa_#&w7)3~1TXGiB(;C*K)%=oi12nefYb5=rg0}WjTVHDB?;}hI+}`|6 zlSE(ePF_x#j2+})w|{}<;TZsdQeK8f>8T|Gw0sf=e!3e3#4xrTl(`4L9?;~@T!1Z@ zEDy*sC2L-jn^eGeX}}>1uruv^hfv09OEZ!K!-rVC%)hqDDEin!mvND;tU=1+S zvQo3;wMX$^JEhK2v=~=m-HF{qpy#-(ya~s$p?_H~wG6;E8&UJ9VXgFvR$?&;%@T6}RE52xH-lu#S1tUb4+1_$NZKArMP{ec(KsQIL89nGMl zzbg%U5jFP^YR`HpLvD(U>UP0iRtL%o*I}T4ni_HesPG2QM(}6*>qILW(-m}AwzA-x z?V?_^QSwEyuYKmPOoKEgK0g-0VVQm&mosMYyWfyMCuH>`Lgk*jiQCNzaUAYPqyC8W zPK{6x7Gegz(wi-&qpLEcy{N4u%9;tEN!kU4h(_m`HW2c4pHn_0mCjvr0>8@+))fKE`BIXEWh&wRWdH0}y&Vw#?Bf=tJR z+|_x>8Ty_Jl+>@s0UoGdqYbg|Y8#jT;69On$dc;rjrH|uoY^`p(s@6S z#P}gQ746Z@d`V&r{3z}Zk)iTJ8!dd-;HVrj3E2OKBC+=$w?#X8V(lr4%P}hRg+yM${}*t9HaoWP)z+UP;`$l~7ISBVJ`SnDHx>s3 zJIv&f=!YturhF)q{uljyjnHbrD&MP^@;!Yrg3r@5OH}4t=VniUipuPn)W1R#c(>7C zV;uipttCltpMk#WAuGFFA(S_5AU29t_W4&J#raC^`1sqx2KpN zK2yj50VpZAiJd@xFzbJAY=Xw>Vh`kz11}jZnO!vq`rB4ZX~4mg-AuiftFI256@i^H z5=8Ss!S*os)mt-ang?2ki?8m#U#I0B;(AqaImX0f!?0(8NreqF^mQ{>COUNwuF#&S zb%)&Moq#mDJrVEti^LyBn90He;NPUvdLNxU+)&rTdIfXL$r_$U6@u{C4|W+SPc4*4 zL}FySQ|Y<-Ts<+sM5#{ol;F=x6C%U4do?tiq(_J@f|8M%f)(-Wgqp#6L&1Y)qi&f1 zv5V9_oS?`*LJ5dHSO5X;fp15Npb z<&5XB1RU?sNUs%NiwgTAlL>j2?b7s3BMQ4kO8i)PXA4S`cv$#tdBzfPD8F^xCzLzOV*xQc9*{8`kWAlqEuX7ds#LGrk)SGIz5U3$9OX z+W(m?sTNK`^!A%mIZmk~9Bxw@gZ@lVxhmW&LH*B+%1{0(+ZY5rBe8^_-pH-vR2c}1#?}%qyRXmckb!^L8;FKw8EODz z$U+etMnZ8F1%+b3EhDH6O_gW^IBV=he!v)4;EC0f_%8X&xM6RrZ5XNSnJ2)31}u5~ z#`gHRFsGWbm)8LK8bHFq{od^D!ZU0bu~9z|L3H@|#dm$!I|(f6<6m`z#gS2GP`M@xTB z@7bF}0Rp{)$s()Rvd1ynyx}v5yp~y=0L)+koObm1>8L|VOse)*E$B^#QO~Wy2TCV0 z5Dt6t+0rJzA8Tg*Ta#0Kw}H`cg9b!A${2!Ruy}g~faQLTP%ILZNlb^=!bF8+1Lo3* zG}2CLp{I^EEJr_us&`ydEQ}aya?h2QZX+RM>1+c&w`5v!p)@}%h)Xlu(MP5t| zD$A@MTYY4?V7h*hb7QW&+4EIuTEc6{suCeyQ8=pc8qauBcKHtjPOwT0dNspz`2t5+ zLj{u@pajlLN;A3|y5<0Mm}pldnz;!85`_Y<&U=8+&V5ZCYrj9<@(AV-emXx2Mz`ef zuw(14X8K?fd0ZK!xAEM;PW1Aoy1hiusF2(Le| zz^>|{Y!G$W#S&F$^q%?Ocg+5n3*XdyeDsin$F>w3n4FyJ16r5xxM}&+WDc_>f-7I= zR?C=+T-I7RKU`)K(v205>EN}sqQV?Nfwi-GfR&;U_5CYCY4+F*C!K)ityMvK_7y$C zTZN;%LI%P-Dct(n@xXCbrM(G{xY%@3g)V>{z+pBJ{ItFU4iS*S&>ueu{q8d(h+YNnATScb+sFsmHCX59f2AfRm{3G`bi^q{V09b z!tEN%`RDGluBqO#^d14CM*0X_Oz25>x%J6Ip%61#3;{DTS&ntFJ--!=CjfmffLuZ# zmWMd&FuE1y5FL@@mO*5IWK__z9bQr_9%FCj^NmI1; z&z97|Ctwo|TH*9Kp5yb$a(kAfXV1HWi7DcBa=Lic8L(2U3eU^40VZR(JX##{nps)TYK#4*tKC~K{d4{GbM>$bL z2-<~2NHU>fSn_lkJ?lcWq; zd|a1Q3KD9&-l>L$w%FtV&gedon?rahNP4g~VIqJM*@xRKWArql9!aBgA*#Bmde=zj zurK#tITrP0e%)grIDEW?O=Zm__0? z*Uay{m9)`GLfl~TxxaR$6dPxo{X6o18Gz?&r4J%ZIag#dpURD&i|v%;TgpRG;CXSR zszSSJ;CZCpzOMQr05_erA@fB_tfm1t0Wg4$lT-%S%s~Nq+w`Pl;BmLP>YjoIW(t`j zP9T0>)s7(7JHmNhlV!8DsH>K@Lx%F3-Tnp0sw5-?li?Deq>FeYhfW{g+@sdh9DoE2 zGS$a?MNwLnXv3|bM5sn4+LNCWygT_{JV+nIjdN`IO}3eWCorNTAk+|IYP=;WU{+ZD zOk^nGz9T-ErE#VA+cZA9Dy3RLMu0A*6T+F!RdWw%jcIIv?U7g?>CU_HQm_T>Ay zd1=Grao0SaVt8?ji_xMCllWuT8wN%|H=EW1@xTTEwv@eLF&&h!XKg7O z1Lcr-=2;@%VTT{IP#%uXyH;^C|JpKQGx*Y3_l0pP*ebSwPr}`hqR1_`f@~O2_3V-m zp7iY*ohyzI?_(4i3f^;O!k#q&J52|o96{Cvfc8|9ny1fwVDNHp86?3s2858VdaX_X zY#NfW>X1xHA9z;WFY>DELh3w^(2!KU&7W+^5H|i9KUCGK&tCuiphHHqYIVPbb5po znFUqGRS^J_)b5P)>;~u8ai+Y9cc=gTEp=*9rrPyC)@*v#8L>1qR1TkmCREQ5LExc~ zbDL9hqm%LLm8qbvQnY55x|o2L>ABQqpfwGUn_x-aing%cGWL5rbg4A^-nq{nHtv&D zkG6!gDJ{_M$$qb#0>w6SMUXJu*j_O}7D%6bMxZ)s=&~9KDfz#HF38_@6~lXRR2bv`6w2!>%Hph7Z3jlqx@v<5b5Tyv)z=@K z2rEhSsrY9}ag{thwavRKcKXLEOe;&+LXRT%_9PeUz972$&k5VXAWEI*bHRZJ8OR8+bzoTYT0BOou?U~$RA72JzVb9_XTd*f+^S_Ayh6TR)nE-Dh zZIdwkWRT9zjE@vb)v(~8-9eYeFRW-5)77!SQw+-Jln;&9xHZ+a|6E`=4I8o1T_<^t zE!Wq1-=)&EUe*HC1q!F4&_pbA2EO8EVHF5I7-SYz5xO>l`MycGdxklg4K||ZOPHQB z;X5wBVDfPa%ZrsTy_Z(#2vv4b|r`8%;zAakjh5< z=!4)$Wuw}0ZtpSkhq;G@9pRyyBAunFSvNKoV}b&yD|v~`^sZvGh2r{Ob7CXIP0EYNmX4%x z+n*KaLQ?WGDv^2;LK@FPvwM5>v=@_$kG0Bm9|}9wbYA@xrF9fLdm2w69qVmBc@ev$ zugG+q?Zgp7#<%Ig*$cEOTnRk~4N0mF4Aj8+96vav)zdL$ftm45<$(aE2EMY5);x3X z5OD)9g?xF>(4uq|$9V}T$!aT#AK5+vLvG3~rCQ(*qxu`)*Lq7^4S+gi^)(n^Lt_PL z9|YOj_&Y*q5F9!&e;z9OTdmF)PI>olRGNEA-CA&&{Y7!%sDhb(EFSXL!h`3xUXo$d z@;TT}m*zsaIk+GtKITGPv0S;E7g@U}z;R(651;;$1T%T}YnhMO}DUNIO z&3dljfYxulOOay4v|tH>W2T7gqsp)v4hp5A*D+1md`=@ck#}Mfa2l?#REdi`E6llJ zi_LeNr!8~#2A^4B4=UqYc@X*u#SOIwi85q`P&(_5isv5e#`p>DR({r7a*O z>bX!vft9Z^J;7^_vRmIEm?Kk>9h6YDn(-HqHT}5%%u)K;jS9^$BjCoDO7uZTC$gZ| zeTgt*T_93ogkBr6K1w-rF3U-lP^w->R0&U!wn!E!pH~wARZ~cG+m7EkA_F!zJGYE0 zK^9X`U%n9UWZtL+v;inZ2%i2}e(s0EE;l50QH4z8J~=Nkn$4n=L?_@AXz5KU#*N-x z5@@TE(rz%UC>li{ehMTAS4(~09-`!`3_+lUiY4K&vpfqja{9%i*WgDjh5ED~;dU(B zS=zkqcTu~U4j1G{3!}Xo@$)6B^C&ln6^pU;xTD68&i8DDjI&j;&B1NsD_L_pC4&kH zAl7JUPkK=Rpu81c&H<|URGkfLy$YvxdoEbJ0~7(a!4|+P5m;5lr63C0k6HHiFR~Y2 ziZ13zPVq66!j?Q%#%sQd&<+PxzMjEG-(4FGX#b=sbFRKsF7*^)TX!>E9kxt)Fmb1x zDhxG$mpAxj@sh3oEKBd&bU10KiUn9E>v4Zymg~bITS(^za(Ri5pgF~g!M0yv(hPDb zGnXmntRYJ1yN)nCBJ_P%hklyKmGmemC$_G3{+jg?zsm5$w7gH#MB;h%b-?oO*%NW(~Dvx04I}laAvJJsdOU z$;t3#b>42o++rl9!-R4#bDDGUi(m(;o9xCDTsU6Zj$h3ZwD4l8w_$g0u;#oPo6pJw z?BOZFTt5)2&0P21cX`9$oB+-nj409fMBqvLq8&Y2mNLksCkf^jn0G8=U3Gt$y=P_Y zc_Ri-l9HJjIX2ZcuJO+;ARgZVW`sGXDlL+iUjW1qyXCVdYs})PzuDJ z#nAG)%7yWLcktV~mII%HoQHGsZ{8*hH$aC(9W35GBQ3@HuDyH9~&B=y(2sK5^P)J^LgvCj~kl!?38lb+aIjwc2B+#CJ!sNnX5ZKr0UWKS>&IGVEMvI5QNM z(5DO7In{Bi>O?XSDUrH#B3ScA2Tf50doJMUJinPsYF;3kWO%@)@{Us#j6kZl$T%<& z$)8eqJC`h!WDI!6?0a>0*t=%l1OzplNn!ZlWgDf1JZSr=4eIHHOjLc%iQ%cLXKUR=Rmx8G@UdoYVNxjJ)8h!V7y$* znuxuiG{Tyepb2eYtaG@KUm6;8jk^KBkgaw>q^8r@ylz~c>h(tTP87p(0#SR7C&x`# z9yG@NOdIaAqU*0+r~G274D^!lNDGCFvYfp7<*jVfiatkkbOZ`SNp)U2_7L01^Bj79 z154d&JcumBr?B-~5#o5Uq|ngK;W*{1 zr!Y-%gqANm6>ogBvE>XAQx>k+Er&PC2!HFMsrg#edDN?!J+cTNN@}FCQr#NT6F}o0 zs2Alwwd%g*72*kx4&e;A)hzM?oYiDeC53g039_a*k#}gtpf~1=&I_gBI)Yns#F4<6 z(y53jGbTPRxtTPBT#mK|$E6OpP5V%0VC`TN8)*I0=V&$SJdJ>Fzm&Pqs9h!k+d&gX zlZU<_X-rOPZdkV@DCPAI*uv7>GcAb|0TiQag)J_?FNxDs_V$q4lfUD4@wmPQx7v$g zlP!RHxx>K(cO+M|r?j^Bfl{iSLFc?j&+3$D`Y;$0qkSzEhJ=jlWSH}7I~Wv37kgkU zEmUC3L8^aRhvMR3Bf5;@s&5{vbT`#jo_MYFS-l13ex4`lQppirUNI1 zwJYP0J_p#uh91SWJpvllhO}R5x$WMCO%s}oaY)enhJLL^r}QYFR?0@5Pf9g?=x_xV zQoJx6Zo4E1STd^fNGddxcsU5gPNj%0WN~$2XO+s4Ks?ZHgVKloGWhf2-qR2}+x-3u zsZ&5jbbdt6L1Q6NqH_=X{WBo>%CaZBv|VTu9}R!5sN*n_GiGxW>rXAZ-7(KRuq4Wj ziE6j$Lnj||IARR>)06I`+AE!N5b0l=&>fvqH1hMg)Ar4Pz*GFOk{9C-h&K^38?m2Tq( zC!hA=N2yO%`6cs|l>&te=tRykuwFq|bU4@dUiyv0y6nV*776AA(n`lk4D#NOl$K3e z4q(SQYX~R6dWn$c0dLJ>0&V{$#3sZdK>#A58AFv_8F{;HZ(y~C8)@jr^3qM8&WSwK z8jdMFcBbaNJ7W}eJYFlV`KxI~5f=5uL((zg-PtWJXYvfAc(2X%5V-$(H(4Q{3Ee1b zIPO+6q&h9jNV`ir4X%zH{08eRhXZ1CeN<14#sq*ay7Xqb3)|>(A8ejLRiAhY!_XxUiO?S313@AtM_cgT~^kJ)yrVX{1w5bt zwmte-&4a5?47!%jJEFX>u6&0K$G2MyWwzJ_E{0MnheWL}8_bga6x~^v_LWoon)}2M zh*mWdH=+lRJTDZMuXLTGW+-CJ5V3vd1W6`YBd0x);G(;@sxDoNeET<%8lUM-qoGZi z$|;3EnK%O&(@KFHLmdku%s79p4L`tBv;kTo%+n^0g?DU7`V7gWbmM_pc1#v~hFpVu z&ecX94YkrdIkI8Fw80og^@Oc~CLgv)T#}U|vq8T<(ya+i#1`Q`U%-Q2h?21Pw`L(pcRt6>Og}pI4Q-L>FV*%W-fS$l9LUvmW$ulVEarX z9rxyO9O`D2COo*tn!?f2=+n@Fv#rvjhwViZN?}#sligAETWc zB*vzUC90@k2BhLJ0V6VNGh_@`zYjkwOmgq!jT~_vj-n}|xeWcd-ORoxtc4Kfalv3j0NbsWZa`hRB(#y~pC}<&tR33J`-u!oUFD zdkHzrkD@g*0jPU1uLT08U_c7%>dP0WKt$ z-rW>xc{9Ea>oajFIg>9i_1#lbOb{A*iDf$lk4BLGlyGQ3V+=Zz&7;ukVD+|=9QBH} zW7xC8p`p_7bOE@)KKbcP$&OaSlkmADg@6Si@b_ zlNtI}p4=T$Jg9ksF%XgNwDT+FRV*1L&$f;%;_Dv0?q1N}?`S4OQY)C?uhFCEewDHU zd9|-DbIh9h7Gdw@0Cl)*Y=$U)@posYWf&WO>^?Hja(6DW89Y`GT-S5Hiy+6mytF4~ z8w)S3C=-%cDOzBAS{NPzD>5-e@A}WB7qli5fVV zo>E`JN6%>P=MjtbIxKKm_Lm%C0NhWciy~;RqZV{}R;8a+{l;?Y-WBu{9qxIwpz}a@ z@BR=JE_FZ$9{oVCE_jIvUa@y5P}POKU=lW*r%jsM z6p*fZslN`_j{sr-G%O;L498)@dCaPI8cHet^`-1mdS)S1dJ-#lkYydWk5bYg%;1+P zM?5{#*Z7>NBml!e8BWNRrfdIVdx+)Af5wgyAf~>`fdUo@p2`wXWr$A zK{{o%gklund-|ps8_Fpydvs=7AqN%#35cQ1IVf`L!bRUHMaN8!LhLw}%enQ_BgpXO z0R=pDeEY8HhB?-#2QOA1^^Li9_apOD`9!7>zCUoHyaJ)8$;c?`o*p+P7IJbeV_X#* z`_%DQjUt>P(SrB*Gm?KeIQ&2FjUG|uw?bomgP_^beEQ)?S61~{`T!gzrW&`U1SFMZ zO{qWag5y@fQg0w^-mPffrmIusVzuUXwseQvWbk?Z(1QMDrR@g3z+b)J8({-LfaIPeZ~v$iJ+hB3|@LKzBNi0 z_P*V+^{apPbAXW2#p@$M;g0_#ihLY3ai8#zOYpW8cVym;TYsmXMSFbii2sNdyq%!~ zY{<`yc!&}rm>Prr;lXJBTOd)}nV`Q4dyRaQ|&~eWdu5z*_Em4_H;r z@K2|EM*2GnnkgVN-+jQj^j8?jg(VOAYyzU*bz?N)HC{ns5Pl3?BDciZx%Q6L#o`j7c*U z20Gfkd~*LV`hX8fLk%h+aiTKglX$CvMpLt2oIy1nb_oK?|d9dJIYq^L2K}p3P9Qs0iccva6=4V+YGmgiLR|%7R7e1SCafdHX1%4Lzp=_@gPo zbFWq9`h~|lQ)7pj%%`Ez)|mcs5Z*u1L;)B+awCfiC(3j5NyheqFRJ~T{#Jl6bKPX= zOy?C;&%N`O4mi7jFq56TcU23qxQwFQ{NcQy8eYQ#N%7D|$0s*g+I@`Tw&LUxuyWnv zx6*|;ajqT-{ERljE;h*bo`|n9+w<@ke0x(?t}tq7=}so3z_U#G2Cip#N{R`bFO@x{ zn)orD9~`swAwc3^O&QbJ%^}0!fn+o#CK{Dy`_ijRIh_a>v`?7sc0aym zcdCmPI&p}QO1IwBxsJJDX~H@uwHdwCmH2$@8xT+!^?SxG!#44}kwmOP<{m)sX`Grt z<>;pAZqJ(Ld8$NIV1p~ZVWmgHL~q3IC8T!VZe~pG#z`;jmZ7Aard;kx0eV#KNVbjo zEd1>r25)$1Jq&aM26)X7tv0E|oX(^{%m2MR%J9eupa-t=WDKP62$+GR8qDCfWMfVM z&GU)IwFUqbFysGKTs(=vY?grVz;0nB5(`K{L(HOf+Nd!|&-$?KX|*)`!k;6~F<7`$ zV|4T~enBeozn?QZKL*^qDPYQ#d?C0Q3wT|7f&irV>}I!UK4^pL3JR+)rSZ%G2Xzr= z4vlgvV_X6F`eQbcbRDze#hQJYI^@m6vqL+A_a(sL6Mi^#!>_&2FEia7h5T=|2&2l#d9Bek@1qNZ(Q#V!}X{nXo6Mp#?0aG=?3 zm{&x7a%LX4F!HsHqB9k&s0v3rD3h$sO`G#trCbiY$tC6)#9ET}o8PBm6vI7vqs8bG zd_4;n%l-sR-m8_Wo(}#KaG^LmL}Sl3EI}|!ZeCcLX#rq*HKsYrx>j);*-J9!>mFyk z1Pr<6IeSsy$O=N2{8Ie1%cbYX&qh$QFPj{jxujqg(lYE-g)+cCXMJhc#gLz+qnTbB zE_+t;;&f|l2-^Z%;SH zcSZLGK(ljsYM89CS}+ z<%$SuwKI;&JeUdk36ZD8SNve&8c$>b> z@rM#)fN&6G3p=b5S$+aJHZ>Q2^c6W}rVH#=E>ii~M9ns^MKO&XQLag+@F2o%(OrtF zDw?>(?YK+Im;CHX{Cpr&7MQ@lL?Kp#o6x8g1r)|=RjNi-MsL1G9I%~2X53=Y2l$7l zGB40=69LU1eSBp(Jet~JZ8EY>I8O&V1y;sPI2gI1Qz)acVAD$>&E)34Hwa)jM)1uB zn$XBzr3Z^ZZgIDJshkd6@HcU6+7>f*z}4SlOeij_}D07RD}>2=9FZ06T)x)E}CAT3dOf$ zFQsEv2?s5+vtYD@IC=?$WR$avy!C^z`!-E7CAvHFAM&OzEme~Zgxs)Yc+$s9_mD-& zWjVBDPUkoZo3`&_+gG~Rkw0Bd?0XmVGbj?QP3gt(@oIpGe3n8l4UU_CcQ$p~b9sOr zJ_MYPFCv7r-?EXGj12nl5_;yn|u)_31y7Wt{?&54n8n;(# z7gl4Mw%|D6T5qjF%h}{_Pg`)f#GGO^n5SeNcsIC1_kLDE=m;$I@(z|I*oTsp8%rv! zac$q1Yt8vCvR7>+>f>H-b2TxvBRWCxF9;v<&j5G#=G3`wdlfT0w8 z5l}`aq|KKNuaRO+0@voQwosN zf@?pry{?R6A?n}w;_g2z5E`~L6jx{zU$Sy=qHR)KaEP%f6twEwZz?+O*haDCePN!=4IJQa19um zu>iUkE7SZMO;Fl9$e6kQ3eHvu+2ukCAO89Hl{4tD<^G3x&4G5k9rrxDQ5OL0r#OeN z_<*bv-I=21H7R_%*bGEmD?TogvahJ>TUS?1|8DZ#J z5C`50O+rnJ21!)5sB_6qJqC!yJN2I|@{RP|X@^@$&%aqwd7AKJXSF^g^X{FNA7I`D z_Z)U_g08$e2aFJhou^E8TfXGmwL^Daasq#V%p)rQJJZ2uP+N{NjQ%v;oj85=p5P%A z<>EUuMTZ?#1`+_h3gtAR&=n+J$vooy75)JV`NJbWjbfmT%o36lk#p*)tFPXrX`Mum zewDQ+G)SZ4E73MeL=P#cYsSR22b;+GaUZ7}KlS^irXjp?nq|=;Rf9&6;>-N6hH z0KA;-NWzrUl>4eOw19xiwX|lAXh|!^>KX&tDwGJg*tLkax-+J#dIge4vPq~+r^b~A zIWlj_5_)Uebe8xZgjwg$gj;j| zRIZ$M`ERn3KUf;g8+|V*^Nn(kG4l82kpg&6N{YI=4T#(la;SRpg(<-jJ%oqtVCMzt zsS^HsC$qQXi%pu`SQU&U)z+1Llz?PVw03k?*#+0-g$JTbKgBr8*%-tG&nj%9XA2=m z#W`|r>>pO)u4U6b$+^f=97dzd3J<&22>Gh6vfWd0nmBLI$d=lF+HHbqpV>sKHJwgU z66q-s&4^4?)kK5wjS9R#i1!8{%3-n_USTfkJy~q|iLu5$F<(}W7~9Yyc5@=Id3D%( z9(6|;bbIkv!awB*=n#f zo+MpkJA+;kHIBm%B2k&IxiU3tiP>6)JEMCUr5n;?0eVkgU$5Yw9PwmJrCzT)$wsdT zXB1}@8Bj-51w8Jju8^2Y<@iv~DQalQj1RIG{Z(K#A?Fn~U}FQH0B$XsAVb%y#$$HK z+WIE#V{Su*l_X&VdN+sn?ePjZ7~4!W2iX#k|BybQ{Jv1sp`5x6#vczQ%+)&#yHaI_ zIUtPjgarL2jH=&hn@Eb-zvRA_Qs7{aZ8VUUV4~E3{;a>FL}u_0wdxf*ID&#s$#LKd z8RA||Ae<5r%`LEG!paBVlAlwrXD*MHoXsemS%zGHbB9MY)J$a8! z6!4s1#>P3Cgo-B27j5B0EmywAcVaU?aL(X7AM)k?&+L6anC6TmKxIJS@+)Iuf z_ptpvH7@<*GEvKt_i|g@^%xPbictrpBC^fI8s=mG(rCOL)~Z4`DzI&A8xcKob^dRc z5jfC5$cCpPsKv%~J*rp+#%Rlw2AP(>@0&g~Asrp4GxH1>Q?HN$bQyrbb*3!PWtU~( z$661sl#-qn%?2PgvP%em13U4N;hm%z4QxH4M}J*BD|o=TXn<|ZcrPItyPA@1qKUik zhz=4#wyffX|G_RG-;8zreYx3ZyLi;05@XO3U`a(jmKrB<*K5!i)mj4L-~!x%J`tNS ztMAL)`vXQ^18?H*^I2n7cxkdtKQaSQdrJ!E|KkvVVpd!v4oJNUBa@UWvgO_?j+Tg@ zWu0+gma%1EaIvA_u*qC<5;?GuS2@Fcu@e*iCin2X%p{7X_4YM`lP{LrR62S0|Gm%J zFB7fpr_W3Fs~c3S*z)!lW#>LtNyGc|xMt0o!4Pl_WsqU+D{Sc&OHO3a2-_G#2pO#c4 zCC)9&3@agI)3z~DwaptkMp48&|HyC=b{C$I@y``Q8cyw@70^~|Z#B1qdm9+X+P)$& zj$oM;IRn*X*9d;%vVF#C&RYq~fLak?n!$^d19C2yK!ZlV0{dzbhZQ@JQ4v;(0Bn%~ zO#~^u+V&gSaYE=H^tPk+lmkd{V{xJ(I5sg5`zH2B!qCL}TK9fo zyqOr1YQ<-+^1pyizhO5T;MrUfb!w9AdePF6Zf$m?Vi^#N!)lu4U7D%Th-BWubZK``je$E5BkpcM%DsG{p%93tW*;yJJCr-3v$_oJ!&{b z`BHd(9*LT%O;#gQm;m@ie zUrqLsCd7x63_%%nYOgGI2`FoQU*JGrewo)MDVeCc-zNWN51};mwmD-09X#mqdTy4`{)fhgw8nrusp-KEMKZK+krQj?3o-XwZfBSYm{#&JX*UPkeVCZxqJun z#dEqYXA~&64ozOErp;UgD?>@jQM=v;qJjRkk}_yW-S_=}vCo+)>RvL>BPe&Rjt0$k5c}#jm+WV3(PB%}f6dH!JSA z^PMaTAQ*|>t>J1%DVM6Z*2 z!vSq+7SYLce0p&OdY$JR?kq7LKd+E6TkA1qg!z)%I(<|DS?a|dU;VW?pJ z_#PPe8u=3)qs4{=V-}F&Y3!oEi!#zz*9GfU`Hw-dN6MKWOAyE9v@i%~dZ5;rgG zHd#VSj*DQ(cs&R4t7B4wV>3}&+nh}P!ffJt z`}a7vkZ>^ZQ7(Vzaz>5Zc^wkh>%x_muU-dBz4oSqioe7`Yi{_hkb#w)g=WcYObfBJ z#2SNj$%wWw)|r@Lmn_4QScaR(yw-u3hw*!!J|LrxM=)iU5Fj-c6oN$ig_;4sa z%gh`&QJ)O>f=-1z%kpE=NFn1Y1)(8un(ht)0N9P4JQg+y)LgeagcUnWMOA$_sA1n9 zz3lZ;WZMXCQ7QmYK(4>-Ddvr7r#wvYiVif*xweLO7#-M7Mqcn*r9qbaZ^alWQeG5~ z8164oC-*l{XDZFN5If}iEj(O&BlE+J3zh0lQ8vX==ACkZbYKWPT~<1=Xj*MgBVMV= zoToSM{_|tqEK{Pe#}lFcg!GX7xHjz;`X7?Gs%7$F4Iip7#{Wf_17aIaKgh>T$;D@L zg)7}z=lL+fD?Ks}w;SNuAo0t4J*_hW6$W#2&hzvpkB^?FX=lR35Mr4ui0nN@u^E~cz0DHbuYYRDV4>^+^`Q!pCjMl?0#9f7yF^708151=7$`(bk3p2Zy~Gf0 ziu}lm4&cfb42$i{HfpWxX9vpNTYRD?prKoahvCU1?(fHx_D}=(w*#q;&oRz@DuZi-*E(D6bYF|YNOx2WWgH84F(soZeC9uE^tHfr z$k|ddH3Y>2s>UDGku#p-b5x;(-5P+63w{kX3@pXgR^eJ4tiT!wAsL5G6LyNBc%G4t z>Lv*O>k#s8A{}p)w3JFjk$yYw>y)0U9^~Mww9t&l%a~XfJSO2&%Ra{eOQz|);UuV3 zdfvuOZF}@a+ke{W2}Ygv`lifK?2Q8WDrp>e4!U%z_z3)VXC$-tcU6NoZ%|{)A#F6z z!P_^bB>I|M|D>;eyDHw(XiyQ)`vl#NJ3@QVS+=L@WyyIvnM;~`!hR!AaLTdG^7F)z z9rAmmMuwl^aE*;NgN681TO*9*qx*HM!$z;bV^eOMdCz(JqQTe0e&Ct}&Ac&>Z~ z2vpdu^?fwXajU|)8W6p-f;Yjb{Dis+n(1zv{ltW7X?ysjah8T;eq1=Y2n$2Q1rfC> zt-!=84daorvDR8JBV`bJQY;bX+fl}gJ1=$&X|VquA+%IiR?3ohCw*hOd(6!eB6fa~ zAV8||qFay!8JLK=D(=mRjM5MR&j0q5Wp`FHq}nhLK<0%mjM(17?J`#+G89iv?x)cT zy3O6O!rt@AH}#!I1RH*J(?(5arzgiQEXng4c(8qOQ9H^;M6;=K_z};+p=d?)fPcNT zvIwlbwbp<)IB;-p1)c0k3Ay>x5g?XRbzxAop+HVI)ZVqUSR?p;&~(8X_3c7d{V0<9 z7hLPBHjkqPe0Wz!$?5p?qW4j#vH1sz#=jeVXf)k7suEzTlOC$m12(~GK5%GYWnb$U z?0f3!zDeFFXt9K187@Pw{v@F=XC5n5eCG^xf<#8%!OjUJ3sk;Vh)v6|+9$`56dLui zJqgj#`*R_TF((Kwt|;zLX=JnV*#*+vU;#(yZMF-;vJ$}kqi0&!q%5$_G3SMq%^PoF zd(e&+QkY5;m-HZtr6b(>N4}0!9_Cw^jLEDeuoh`3Khql0f9bzhB0NGM;h{~!r)3ST z3eR{+(19R6U3>x^_-bpvl=q4*s~dzooadY(;y32{^79#@-y6MU*0Av&y(uEb>-h;aYZK3uJ)tsmzSqf`?P2iFMTz6e}j>q03iCr7#f&17GtHjSzfKv8h5wfj@3`F~6 zx~~J`KuW3K=- z47a0MIVr7O9yd0&544P7;mE|6(`3i85FC$Xh&ADou~p^!Qg~REhQaYdm*4dBoCvUv zm?Ti+d|Gn8@>2kVOKNsA6+ucXVoxK|jKN1uuwDR|f)VvtV9W;5lEw3zZLEhUHDaUg zeZB`1fLZTN4jA)ZQPowomlMtaUnJa+;AX*k4Tz;#)|ql@$7`QW?`@h;E(N=L{cd@x zhGLmrs!$A#-7ioL(oD-Ewv(b3!D*=S^?t;`B! zz`}=5jey9W2|B{g?VL1?sz&XMgV zdRUMBp>qHbPGMy2W%|y307?DFwbefjw?p1EZjNyawMD1uyUPRZtS`Hm@c;4yM#!AIfg zLy5j|=R{Gkewzo|=tauBhJ*hXEgLh6{KR4EJo~(x(sB4*S?XIRvP8P^w(@RQ4B{mD zCv&Fp=Yt-@AkRRgEFAW89_P10u@^ZUd&V}$RxHLJJvXiPXmTb@lsK@x!L=w)H49us z;J%>ur&xZJy?&p+IC)}%$Y%m-e=`(s)s?gR&YKo#9Su8Lgj#&-B>W@d6#GADr(-H& zhjxGDphJ?(y!gzU0CN%L=vguXNxSzsvvjxcHa_0BRgFpGT3ah9X8>R?{bQzCm@i2= z5(XW+7X**Z(QP$j^T}{~@o{X=aB-o51*M`LNLzwfyOJ~XE?4WVR7J1XOn-V)9+xuo zj8&_+cv8WDzoRD6Mue{)+?*Qe!`E2KNN4OsJB{S_K$TR5Y{aMSuQP#RqiShEG`5vZ zM@`{url$ZN>Bysk3M%DWO%U3iW?{e2!L?T&+UuQOH}dcGPTUP*YJJcwOYvmX65#HA z$iiy6zo9;1MUl#8#IQ$$PoiBqhue&?>bCT%d_%+j_=2sEsu;945^z~4aMlBt`O2?d zB{WRk_<-}V9(Rez;sS|viTi~RVS5oncMsW`{wH|p7{~=>&U41%wDIsKr#%#TiWI3#C1DB}z+@Jk$RD>T}ivhHV6qta#4hCpxxKaaGRyekWwxnZ2N4$|Hq6ufv>H6l8rMsE}B; zFbBiSf5X%sByoD&yWTRO@FUWMr<|OL${}|G9k$-zO-luAA1E8$O+QuWceveMUA}0r z-~OgCD>asXs4~;zrmAT@0wzoY6U=_fyzmjigjVt5p0|E9fwux1oe@W6+L5zmu!! z=y7%S0yIz+MtN8vA9o_+3~&Eyb57j--3w6K|pQmx_0#V%2C z`WB~w+d=6UVc^gm2FIF#3mc5ri^mE01sO^SCf(l&iW!-`s+LPu^6IGl59OGaU#dZr zrX29N!|(GJW!w_P&PS1(8tPW`{vpKFOAgD>kUY$)e}}$Q0G8q$?cuy$AALDss0cMz z78i<*<$dxaLk-}9FfV23Xk9!RkSe8Ekh$vIy0Q7LgU3n;-F4wfL}_hyHoMKC~T z?fux}t5IaL8IZswMrJErM+6I}u?3)G-PqagL{PYJPLzv`$>b&+1}KzH-vak4&+MI* zMC$sZwb0#Y`cIjl)->NvX(LdjS700(hbUNsU`E4U)QGDQV%5?&Yk(iCM)rf@8pi#_hD2 zY4o;5P5E>p56@j>hu0Q=vcu08yD;O-gV*3>Cbk;!_I`-c8AT4B_DHOJww`lw5}Zen zPK9GsRRYuI%)RB@b{iDR(Rvu?U)rixxC{xqVz=AX^8b2=B zL3DZ&J)9xHK$H;zvO{%Bjj{FGgz$8|!uEBKYkTtUJ*mSmSn<4=wbVh7px(YBAfNo@*AnIEWd zjvUv{t8P7{+V)sGh)wKltFrKA`zF-P-RDjPbgb}hyx^b*P61lve;WLE;VQ4v(t_MJ zlpZs~Z}!iniaeB(t9ELR>s{|;M`kFX6k3JSca!nxvgd-gL z9$19zu5fOWIsPTmkLoHl+FSrOFZ&sL4ZXb1^;kl+KNy`fKT^)gX@KBYF&V}H;9t4W z6w3vvc)8>3=D3G1BN4Fm#4YLklyu9BXvF7R2#L@fUVTe35CtFX${^0-)sQ+zAyscb6B`G+uX}YbcrWFI`ZEQRBy?)&F#n7;$faWTd=KTe5L9 zaK~ow&Y$^ZJMlKvW^%y5(qno;0(}&mK6$%02=5om2U+-fy$ct3xGB`s8z_scO;$){ zFO`2f+sK_Rqn?i&eg^2j1;%D{mxUN>m%G=r^~4ps=I^Vg&g$e$f@mZDM+Db< zqsHZYeflK11>ySl?i;*W>3W(}Uxtfu-L{a!_QgIoEVfNsRuA5y>;^L1S9`Rl;1eZ1 zpXUU40`zSW{B9mjzhN#BoA}IjD<~-}0TOqnah&(-1Y|*Bi2E`8c5KrB0 z{o{-lgd1SekrX>Zg?UCXi_Di)oKL~y$wS1F`<5YT`&uJZJmiESHICP=X~ZO^kIlm6 zJ+Pu}T~2%lCaX}eKBF2n3D!xs_YV_AtfChi!2+MlsB4ttY;FW@ujlJZP560ZBJ9{z z6JNLwGW%x8l$@%sW*jYB}Bp+oW0 z$nWB+du>3-6?ZofR(`F{Xk+H0$XZT?r?cFxH7#zob~ogW%<5&ojf*XvQ6B#IP-4z4 zo+_BiXobZaC$rEQGUaxAK7)ZPf@ngbZ}5A+6PX{@X^@jz`M=T+m`L8SNvb;u|0^hT z1%jIcM>Bc~!B?n(0s7pYG}NZrZrji$!pTmwjBK_-J^Ma_P$RQDiMpOk9mPAw=P?&z z!;&9}))f=e`jFZZ&d}zP-v9ZgV$>*O%C`zM>sr7zMPA_wEuE+I4KAjyVzU6Zf~mWG z7W|p1Y6hm84^C|jk~j#q*K{ey>KQ;X9kUuz{N}59Xc4Us%KB#JUu<+|)r|jp+}u(J zh$&QWvJ6hh@=MyJ1gMqwGsExksb>K{nYp6>JqEN0BzHq63Z-)8gvw(X>M~+VYRe=P zBESVY`5xz`2lauVag~PsY?1RzC`O8>)=)(_j#TRca+=Q5{XFW3&0_B~SV1?4b2n-N zOn`1wOPVb9t%e%NF)N1PMk=?x)MDu%0PUgy4rs^qpnu%hqZAL`xW&haVl0XbCrLZg zuh-a+9sF+UmctQ%R}e|WA?*#ASX$tmXyR!h!ox%|UgZ0%OnCf`Ag2vwMxJDf7AWmi zA^AWgHpdIt(OPia5WGrl{$dRr|8QhP;6-S$v}BjZ4>r*6)`I6H7=DLq{vKVw99yEU zNxTZ2x4Wo5eVjZAKitTfly4#&bw5ldXN^eM*E;voMF&P{!ZHq9jRR7*4V^32-K_3} zk)jTsp1mtJ0sav;V+teubzQZDl#vY`DY_c7wx^1+CII2mk6Vc`Z^4gLdI}9o`Anlj zdUHGW&46I_ZbS4hGwFPxf1vQTSPcW%p!!XiQy_;5Hf&ZGs|U>eKE}>RNw_osVNY~S zZboAX&t9KuF>-!99GR>czX>PcY37cX`=WDM>>f_b*%&i$L|uGU-L#CNptE#k1S;@z zFHMpK*>1{g_KuS$kEQFMgMm&4#*ks*3D&2#aFz9nvv-FPW&%-CAC&7|()*BV91Sl> zOaHJfMWTn@8|&(bI}`iZ1sMXx0?{c+zang@_p*fI=FK2zmLMH30=@eG8?6_JSQBxoHch}FFa-)cWWsT zNV-8m53!RqcAzo&u0qhoHY@*_gHfvXdPRQ|4c)vt)wqGCUt{T-RG1dxZdVHE-q=XQ z3)urpVv#kfTS}yqktsT0MUxRHHYbj(o|Nwlz#X!v_QZ%%zb!mZr&|tb?dpSpuw27QTKf`+wtAHQ636_ zv4PTOq<@WfcKCV?*{q?Nk}4YE+{a8eP*3QI;i&sweq^TZu>tYJ`&8IhEEXM37Hcr` zYm1fOcpSM*qbr4xEu{;oKUAf1&oD}3xt3E!6#`ez>qfneEs5m;qiqIM;( zO2z0Mj+&BIVh;WYPz1>1_LT}To}evwzRlR*%|@pk+m<;JzJ^{G;+! zE$K-K@OV1~iFo@WM7;Ol6pHhEB{1wV|-x2K*>w=w96j^wRdj#Dtr9adc>8Y*_G`Qpwp%HZ*I%s;Fq&6fTwm>1lXrJo^4ou7#+J1Lt%f1h=U6+xmNA;<8@J*9! z@irtysJ|Klu{|+))KAnQt{sPGmA0?}2Vzlo^oQjyp+(_#jtAywry*Vn&(MBAFQ9p- zG`H(9Z=gvHa72Lm!er2GIx#a>W^}Y-p=w>TjaVDC+2jLs1Ny_6BkmO2;7fAk%t{iS zER?WS1}WRm%*$u19rC^UMz^b_Gx+dCYjO3W(M@4i)1^a3w152aC9P@VQ&cv=1esU> zhU%l=PEcF|qTSsYrt>?5j;B<&R9qTgB%hJ6f^wOCe)qLu2F&?{n}$K+=jqpX0SBv(P0Jr-FTGx6vBgze=Q#b}h~^+xd*TySm7Y&9`< z26{h6>f0yzF9JWNa)=J38bd+B++m)KkqLkPI;r%^p2HL4rmB85Gi5OdF$|eumj03c z#Z%cbHA5-tbSrNWjJjBkg%zP+g#>>Xj7JdvLRc4^fySNi*J{!^i^-_%_kxOQL@BJW zXLuYzA!ls`-nbs?N%HY}6p3sF^E`c8sige?1k|`18e92WeJvLiRz-G{kWleXCpc*h zFEXgBLWluE5oqcrlQnb`A|X@KfnaWOJ7O?bgx5nZ z%v3s#+bxi|(($;%m(k#F6pc&!huip{b>OAuNrfkc2<&D#eAN%%Na)&~f-}Gjz9-ra zNIbhgHYhzK!#)9GjCRQ5KA_7;EtJ7|TSO?nYj@+`=H6_5q-Mn6wnoGaS(1);%=l*G zZlGLAoG=X%lvlOvt<53Gz&Qp-8`cswzR9 z&zQwR_Jk$;5fTM0PWusOPlhS9v%R3Je##FmlRoJ#v46sTnLd4$Enl$27@@pqv9o-d zwAT(?Q(99`0yz20rpXv>#QEGzz$t;3pO8lA$F%8hr$aqUn>#K9D2^}J>?bxhYq;NO z5@Tf56L2cNoM`EAbgGwyOV-c>6;^*S~M^wQ7K%=vRIdIp2x6YfOu}xHyCM zVleYGHkztuG`M>F-ScJK1hf%<8_SFHjZDDotLQ?BFG>T7zp$8Hbyj+Z46|@U*v^;Tg*$#f$ zpdGg6Y2NjAVAwk#+215#9r@zZJY4Zk>r&nV z;wQrJS!sGsKEv4Vmp5CaozySkti#lz=AejeKZ-+)Mfp)u*mB-M&i5Ay){>kFyjQ5Q-qNf;TU+DFH;P5B2AU|)e2$5-nU z9%cAw8KX8TgqlrpYr-rfo#IBIr^=BH+`0`M)C|wTKL|A>GxiQlH**?}B2V1GVD&%t zNE{v`_tQ$2zZOWwNvf-PXqwLd$4k>YaO`rqzk z?-#;RmX@4Ac*;ZAj`>QP>vL%epMxXQ;2Z|D%q=9Ds(WWZ;|kv0`gl-P&1lNnf``=z z5~3##S3bu>0QrOkwX}o5v!eEyjX&BvWNhaUmlwZME9OQ!+VqZnL|ObCuGY*Zrfh@i(;b{kci5zyYaBI#NwdK%kVct zMn-C&MY~$NC<9k?UNKVy`2F$h5S^w+#eQ?rS&;E9;~GlB5fTm|e1o|r1cqlA!Mk~9 zIY3-Z?|=cH3C7CxIp`Sxh`+9TD0zv*?C}k@Fah%gyKcM^IKjz$$t8dNYHNd0fZv>- zKn^EcFxoT?yftNy8r%`7KW*C8Q^p(mMV%@QRtl|oP{cwB=l%{BN=rem^_3sjZ{Wa9 zaOe92fC{2?*+pHWBGvZ{*cLik9Z9)>)Q<(#a|hULve#xFo;re7WdUlC?K~081W{OY zQSeGJxvhF)2uoC~2lU8o`6lvi^9I#5Rg!aGKT(;t=%&Q>i=}C@MpsRaSg7Cn^U%%c zk9q)MHO1a-bOQ@l@K$LqKvN+Zp;12Z=%{*hAo3IM?^HN*7sOi|FUxRYcpSNBnjBbA z#Wxumjd<6bmdrQ}cT<)T!L^tc=~TJb^(|L#6lAtX5%}iWD}v@#0Hv<`^&b0g66qQ% z>W@{^1{#JTABGbee8NqyNTjb|PoWg2|Fzf-oJu9{H3P`Fxa0!m|67jGU2j@G%8&LqBR&0fo1cp;W>3ppKl+m=fl)?4)S6fI#qplHk zIAK`DteNG40uKGv)}dl~8t-T5K8cI2@RjVLrH~c9>6I94-`Uf}$=qq6-gw!jv^i~+ zeQ_;BeaLA!fMMlk4u9wf2%N%;xHo$ZbFG74N$H<`aC2oYuNd-@|>8P1_6@j^k#>!f=k))`vCep`(5 zkTH3+6ah6!be=fSa)nRaNeT&!TA(Gr=fI*Z>&0Ru2^nv8s}}29QTJcquZzlT91H0y z%_4ats4jN|Rg!DjodpN9@@#ryGHR=#nuAsXenFyZF~~mU|Df*l$Kha@++H=wvBm~} zjM;BR(f;}l&3PoPznBiA4B7?3By}^&H{-6zdt=*kGIUBF`6rbmi`{*dHDqr*vkBYB z>Ds%f6X?QZxvHpH+2!ufd;OwWBzNdSs%hg0tLi&tC0Ysk){WOqm?JOfD4eZJifpuV5HRi&5)es@3(^88+8%i}#K}qQ+ zwc*Ahfn3psm$7P2Sc;EGb(o42Ie6$)y??4zEoM_;kot z=BZqSO-XYsQ=^$D(?M>^a58q8@fOJfq0=5P&@9~sM8W6jLP-buPFBY0t15yM=;{Bq zV(^&_ESMC-#6=jVq2$$}!&NPqeG@JGLa$lV-w9ecoJxu9LU4?)Ox#6g)Q2{# zJ(NLln`rO_9I{!-vP*Abdy>5P5T&F0!gv?RH8Fg3yxI$?X5IIR(iaAY6=u+?Q z?`}ylJp1Rn@2%uOtU7dEwJpNidz4NTd%kFTn(13VcELy6RqZ#$rKCk(1i?bzcp4+R zf6f_^`eif<9iwfEJ2d&VVPdI4fQ)v3V%9m?qs>Lj&9biL@ix~3-u4W;PXlbysl=5E zJy4zgS3ou*1*fGTkWn?)lHNgm%pa7VP@c3ySa zM;3Z^&d;Ui`Q;WSPKFl*o4Vj3^r>Hwf=;@Iqc$)Qp9Cg#m(!*GMg{o}f4^Wp^x=%p zMoF_SAq9|e+6>X=y=844#Q^cNAA}|>F*ku%I9ttUlheoEBTRc9bny-S*7Z1vtbB23 zOZ$6 zj4XlKC`hMDiM|6|km=bc53*U&{Pf}$8z(c?uxlg3Fzo{>5*M2e(N9Qm&QBY>C8Ovu z?po1L$uwi@VG9IXZ@l-G>pgvL#2+(vU!I1HVbxh?mER+?=^H7cpfRM{J0jJ>`?_!8 zLpgMboeJn)Rry^_FbkrDy$dRjnReY$+8w?PmJrBjxjL{X<(`O-DyJPX%wjFnGGXy;=40mAzwbgNE zTNWD-rXvVRl{14rfFS%WHKv~IyKXd|a8ZA!_S@X_Z&_;-@V@^4Y%66%;edmYfhMf!{` z%Yb#wiR-F(-Ere&Cm=AscAy-Evs0D}|to+6&lPw89mnI{32 z(olF$Diqb~$2~%X&!U9O{Q<2t6{zD*1V`-Fa5Ly!PDmoL@BG3Qu&(ctO3?ax)>6Br zY+rtK@+~W!I6iT@IodK!ptPEy|CeB+Gu8T&VL9O3P#bl!ezsC?5uv}-<))}-h8ugb9=epF!nl|RdTeI_3=Sd?723nwq0KVN%? ze!VxX7`pASf8YWTwB)$K=^DY;o}_k1gzXUW&j@k(O-gKj8+WE98e0ooC}Weq-RGb9 zjX(Ps+AE}_$G)K^xNSg=8~O|0mQN_!*$Qj#zXw}x%&H>eiG>E^-aek7aCk8t6qNQ7#iW|3 zkv^5~lN7mW2lcF2t%#c>O*P1m@QDHbb6WfvPd&%Ty>?m{38*-R?eAkF9(}efOJLSC z7wnvFU6siK_yV0brUj85`L6}qAL2MP-#*auJcUIo#78Yz@IS;A$Bke1Jn3Om~96 z(Ki~;902WuB~1sZxE#IVifbv0_pae-38uJZGHa6oR}@A?!Fa)a?kqkvXyL^;v}#Dw ztZuT8z=?jDfF=&Bft{cFuDUqa!CdC^_G`voLp3-rYv0?NBJZ@}H+g)++XW=gCdXG- zw*(7xz%ZlGE^u-0Qgou1C1Rdz9s7PQgg=Lwa}j?ARd%=yAwD4!jHK>$r(wX<7B8gx|KQQrCMfXNtAW3!X*%r-O@}_7eIT2? zraLlD?buryXvkVEAuv(~I0OQ`aTUOxGLZc5lVJ9+#38r6JWRaER)|1R+M8lRQL8XwXY*R% zm&jqlfn?^iIxGiA!S=J-e1(a=r=*^?igz|jqnr?`qMhFNQI8ZWI*I@i0LFcr%gW!V1HI6sf3 z{7V2W($njqwSxtbBy>tycz-Xq*CN) zt%PPmfjm};+=YR9qDD(6TVy))E5r!gANj`qzPf@eei(TxUNzFP@W#bHuCLu5l}7Ru z6w7`mffQUAJp-|uF4!qWqS$%g>vcO|!~rs}7piqj-c3A+5IB$}d6^TFaRu$m^Sr#{jKBtXxS22*L z0DSw;%UF-HH&g

    5v@ZOdlWq^=dqJfm9A$xgb{I1S`X&Es)-2igJe6+UFHO26Pq_ zNwShC=u;rOuPn8ev&*EB`0hQ6RmHGI%c>##U zjhXogLEC@ETB6|T3y8b^W!7_fzzIBfBua1kq}YKmn?5Pd_;H@SVoNmuQ78E9?gh%; zWF2I86kXM~e>Dx-OLy3$&Q3{Y0SXn+5=+Zj)n4!{1W2%`#J9PvqiRo|KHOarOK{(j z*?$KL&H6!)Eh`0*HlRO@;J27=8IeR?qP99PK*} zUFCVB&+-Pwi4&cpfmcdhLHTSr#hgVex(5g2)(jBc)}U<(aUW;4!O!RId4&Ii?Q=rj zMZ^fI7(})X8^>VO>}dAv2kpujq0G!3#-NIrsiJX9p#^dj<=-9g{W`raCEf+0Xe#lK zh>$*nHnxf+qJ+gZKF<9@{G|_UhQ^d}Sk+ndKA3aVxNeS@P0SR?5r@SbIBQKMNo z0s9jKSx1!cE?g|vOV{i5`u#s3JjOW8=uNS;x+oBN#{Z09i9cP#qse{JMUusl2%hz? zm_?;5PXrLVJ@tlN!w}z*$3S!!l$2cqFE4sbvdqSHkp znF71mv{?;eUL=7h;pa}qU!2mcD8fp~(hPP|nn`VjTaZE{iC_H&FrI{f(E@sm6B$Sw za5i-XlUh98ygt2I}L})=~ z2T|_5Kc%%f!jEH=GI>B%(z{+CsiuI2e}MZs!`yv>C~XHWnjr?0j;4stI|mC6#g&PDG5i>|esS<7pt z6BgTKrU!%88{C@_di~%cI!oaT8I^3qRPDYFO!(^jpZJ`jCz-0+Y9qdaZD)$yjDgX$ zrfHZl|D8226zpW5eaLG?>Qn5%9xqRQ4Z37qRfTW4AUC z=l*x%Ng)M`Iy47cFEwxRJa_|P$Ar#{UBNjC282=m7naq?3;e}(um(;mb*lUQgmes- z3O1;|9zue}E|FvshFjZ|U~Ql_AzzacwpsD-&frYSco*m0ubJx+G=DK?m4Y4$D>PV& z9_Ym??;;$MOgvltwSyqSwV#cX4iJe<9)+NOb+j<7;m?Lo_dk9aj_+uzzJ5ttyedmLx_{=l zu;~RE<6%-G-7T_7X3C)>S8}O21%m&sh4dYET}81h2>@PB(N!x$_G4qo(qz>{8Mv&3a(S(25LN&R)lV_rr_w)o%gf&|= z5Ic$B*3jq(CYM!rq0m)eX_twsha=}kFl1JKN07Kh%15UGWOR5F+V12P0=LCk(QgxY$R}@>mDb4fN!!EcnU% zdXK;ebdLJlM6MoOm zC=vHHO;D6a*Egp^mxPB+xgsQinnR|g;89$)N7%1L?m-ZLG7N|EVDHiyjEp*V*5yJZ zHiwmkbT!}^s1fwu*aE8fh>c-?EN+;FzKSt@B^{DN_!rLC2QAUX1SL^f1+WmcQ{_p}z7e*1i^%Lj zfiG9tlveVliXRGVLA>r5N4yxI&?%)v7XYO8p-9N&dX7VpCmSSvx^`n5YRbn1cO#v| zUQHq5{(|l;(IEDrub{-!O)!GGO7j}Z5yK%DlkE$?3y*(sfWy)k)1Soh3*(A~WSJwq zM^B?xhk0r-iTN>`K0NQs>;WqZ)Av$-YrTAVS4PC& z#eER@CEw0Y<{%&tY=-Wxg$f1JRn>`VD;Ah&*o%qi$y^7+xCKuvTMdK+=&@5sy5RQ> zn-YKoc5Mxlv?f}wNNVJ|Ydsj3i5O_9>H%_@b&h1szcYfj^G9qM8N@eKiHO7kbNf6K z2O8Mh{3bV+X;((CPRD5V~ z(u(JJ8AuSW`wNKq&wywwwTetxteg6X0QlGnnrU*!_t&Po1}$njGOs39D1BD58e~q& zEVXCy9}y~Gt^wmP2xrWhFqkQ+%prxaSkezeD`R6?utbp5SYec`CON2NWNhR;x6sGc za@1;J{e)FZ)$~rCXcmNZeg*(&U4w-0#F2#(`bG@z)Jt0Mtn0&VWR|8=iL8v6ntLa0 zY%DII&jgt{jTRxjVZiTqM-i&HIJ>XTS-PH*GyH`+GSgy1mp-U2BLea`pKGc+o-xVN zc-DcE#cBEZQzN9;@Pu7y4f#gE^TsgVF!ZN`Kom*`IFsg|Pf}3^&;o-O?Eab$?4_6A z1T$qWgwL_6A-8prDYcCb<>QfRE)$OouwU|;A4UxM#1WLvsr#C2M=OlQF|Z~C0jFOM z;(6i@C%$ad4SiDNq|k4oL{UlgdYepirQAvqK*`HuUiczb9gve4Fl_w^`}Vjubq(jj zwIW`d#z6F;`o2?bXy&XHz7dpebeggC7Cq*h9uz@5qajV>uZs#ELa4q` zdtyuCQYs$}fI1}RI?7>qH%UYU#@B9LMwuiK*no@(Zlz`joo@>~{vAq{^gWcOG~B^S zzOP3RaYyYd`g9k4vdM@*T5}VsksDpdW~7d7>pCa(j>>YvU;QzfnhGV&$-@EOt+=g2PB{C+>hwg|fM{UwsUe6? zNXmpEe=RyD5unsb=pY-Dc`L4G6&hf52y8-?-l=#<%7GomW|UyADJDlIW*I57YJ(ic zjW$$Gi0aEkrbXwn3QnVAR@L(Kx5Lydtk}fa8ly6Za(PzN-A<>qvHO|Sn}9DL6E*`< z>w!|=Wj5ru!W5onj^v|GBfA8|VC1a07j?%0CEl9sE9xwuT>HT|cw|Jx0Tk$OYt zRp^qj@cb!ZLJ-m;3m;D|G2(A#IWekP!WLm_CYzi_B$pczN_?nPvry>?8nU>F5Z)b3 zUjh7iR9or;ZvWP^O>{Wk`=zK<-@fpL(1FbQ z!f7%c!I?ji-z@4kR}+J(r5D-T8j!%-hzB|htvCFrHk~V8+*HHTRTaugeUT3LL9sCj zR@CrQGq2s#3r1yfZhFPd@6X@n_)5+Cj-XG46#cb0LR6v>T z7F`ij&xe`T8B$(;jfip=b94Z6(9^lCYPzKG3X1zJXyAxQE1w^+F~8{cjS4qo%`FHy z5vigWD7)?u&pse|M7yAfJ7{Z$)+KBRdEbH;Lm9Dz zoNWqn({q#U68zsDvaX3U6U?iDP{g1Jd|pi!pfAc!X@h-_&qwvD-eVVi3H)%J08T)$ zzYS+Xg;t{a#)A*4Gfcsdusl#IsGx;Isi%P&kHnm?l{I6_e~y|$`G9y}E#8dIfhmh% z6oL;mW(E*j=4?Uxa1P~?W+}S89xDeox9e2Tlm%xCTKC0V3OKgY?$o^t0DC=kFJQj`nvpRa+_u5tRdYnbc`wm966_a<){3EfRrVRQz7TIWIl>BP^NN;1ZX(QP0dk?$ul%0T`?Iny+LSns!`v(iX`KQ4rER3R6$5|qe6T{1c# z;n$Kh#9gj&w4a?XLu!EE97e@0E=lo4j^sVo%0^kIPiCiYdfBF`Ie6+cT^(l44uwSd z%4(mE;1S{!gduBL`ig)T@bszpG}R5fLBB4AF14`)fr!NBbY{g%AzJLcM@@~TO9tdo zcjYD{=0f#EwwH|1<1JT9oL3WE0Ee!JxNq6i5GNkhRLo3}Nrw!PK))um7 z^NBXn2w&a^suwm}J#Qi5e$~1%4UfH{MT$>YVfKIbtadKrYo+V@rFw`BIa!O2z)OFzy@i677KAnm88Wi}8Y6PInqaOP;{cu9l5k*-rm^ zIpeF4#<43HvP;zC=?>^uLGUHp_;xoYIJ>jcA018n*!=Z=&|b#`ClyTjW%WYgBYx1x z#PsT-P_-QLS#LxTvZc`*89o|ofh23jss!x?WE1}~(s*oZ0LOVMnY{j3cZM~B*r!Mw z)@|vXZ)o8h=ysxsyF}N0@^g>wH!|A@SQ`$|;1@bu@=jMF!f^t$@hjJA_gM%7w?3BW z?wI4wP2xmB7wvI~rr5}yE6T!-MKd_IcI)nZ>ksVZk)EuSCZOUz%kGN{ML+DQ>BvEn zxX}h-g*Nbsdc*8Gdt0v?WF6-*1>(58eg@Xdgxgw0e-i670JuGrMenZ|zm?O@YGKUjyFBQ!we%QU<8 z;S}YNzZr0>moYP|q9Y;5;O8=ZGC1~33u3!EHrtR#Q2KKRYb}B<#%8-yJ3|}?F;W42Gh+Bm047p^Hl;q`>-VWm=6<=3+LQkDDy2mz4DPlma=p4dS^PbvZ+6q(!75 z+^&zR%9_?Jj_JC){6k0h z51gc%g#?ep>Pd&hqGrRD{A$x2zi@Qg#BGu5E}clBo;bAQDPN1J-iGoAjlx$F<}R1! zzP(kHE8aAfVppU$z*POak(#ctcs`;kFOErn#N2WsVT+(9#A2b!Wd=4jX%9sgJQtu` z0ZmF8#;FoPus=6DK-8gm>^bsJ4c4o~qg&{78XXdoC=AA)fY>`o6}mmK<0ncANcJGK zSVJiTpRc1aN5~TV&Sh*_y#paGfg{q*MKLGu0H%6`LlqD;I%yYCM@%O<(- z#h8u3ZsQVgDzB#lK3(9bCIv4OQGJHuA-=vpzTP*^daBeCg$0|y*ring&OA6YM^eSN z42oxrj;6h-$p+RT#Bzy|+*(IB9W(9sdXI0#2$~y5Z4&Jrg){daSqD0s@g1m~LBk{4 z@XU~J4|(qWBR&{00tSFBFyRty@K{eklgnwAUKX7ob?|IC{k{-1coDz{;K}P{4(yCn zsq6?lYe~U};#>0FHBl{dtH=p%Y$Q70*`G|!BNSduCdYL%`tS{b-aa{iO>e-4uB zVs?hHm3ynIs`*I}8}d)`uV4;WiK|?!g&z{*UGGoV@O&jqYzubdSWv#U8Mul_dpr== z?#ePauDg!QGN=ld90u8ZrO!I9{7qt>5+R%IgO3MO1N8Fi6KLD=f)mvm&?rrj#^Z}> z^LALv{!;9dir((uNd9hZJ2NWUrN|j9TPMRKFKLzB?Vx9e59E?De~f=R4W{Sp??;UN zpiPw3J%y&3^V_q)O{F{86w`l_bn_NkXl9aAh8dSE9FS_P5uR{#3-6ButM~koUR~-E7v)-{LW5Uv1uC( zS;s@d8%N7>@!p96QF3VKXT)dt${m$&7T#&&OJ$Bv+a02@%28i~#J=V|$loc9Eqe&3 zKOz8dNNjnU9#;XpBDLK%kYv0}alpl72S-BzUPP8t>qfFF7?h`FTn@`I6+b{*B^^-R z;Q3W`(T@lMsGPSKx95%sef#91*36{Y*U(X(sMf&n-tkt&9#5z>-)4`g>AHWq2ju(4&pWAk(($t#@@w`F zH?bc%lZF4py*qOrRjLcO$3dk|3iWyF!fBcO9F%rjbgcPKfEEUGxrcSXxHO)|r0q#f z>w#_u{>E~p4r*Y1w%859+L`%iPI8Kv`Hy8@-@dYIQbQS`=XyXe=t;;{WT3nWP6 z-5qqsG5MmtvPC-tDfjW1nZI0Q%)XBj4GmgOnlA=Rv@GUTw1^r&PT2NGso|~}B7mNx zN6sCjsk@v(c>vrE`_QH7+#$E?#Oo(G6A}{rP*95d9KF$p&-#a`VoWjR>qPWJ7!rB! ztSqb;-5Re=KfG-{iXC!;?!2!(Ad_{^WM{CRMzmNZ7`v|c?R)`vy109mH;;ortjaNB zKj?~exs$0NN~Mu(MfETmRSYv8-z=Ta+vb?=DBX=hMPNHKgBvs?^iadmV9}o|nGstg ze+_N6KOuaPc|KyRzc z0Y2J^-Wf{BHKP4l*K$q_Sm)JE&7cH;3WO4Y-*cwTMf7C!(}T)(bIf4Ta`*q`VLmE*-4wzdRuioB#Z55 zYBGkiCD%DFQ8e#JXNYZ~p6uVanhvIYsCHoBkc#@BSBd4x1};XY$_*?^cM;FE<&ej|dV&Q~S+7z=aK&sg z=vKZ6r;M!Dr(Nb0=Xu%W9n12s`NI&Qzrg)0_Sl`j)`Ty17>S~ z=IT3L$0mx%_`kY7>49yTFoI^T+IXo^#pbZ8*a{iBw9C&c^z;aK2WeJ<)%~C;v#BT8 z8Pr?Pr6MqJ)ji7^P_?VxGuz1lN)7cm81y!q)EOt}=t`Kb>yqgpEwjzC1&Q~P2WPT6 zz|g7y`A_Zh(m1#q4eCoRI;H03Z-eeV*%QpM`pRLFejPwH#ZPaF!az0<}hS}?KvT(tNr^<=cRI=iPyKV zXmf~ftFR;J?VvkzLtq>0kk`8-s+*fXU?2z+&^_xM%{E8_thu_%S4K%jti9{*Qx+wN zBLVUG@7?;VQUC!AG!E%qV%EbNELixF8BF~tx@Pbqwa`vkk`Y1<8!VaTErKE>1!tD;V$$Da8v zNUVQ@Vo*=(3sy>@#<{^{%C6V;A=e!%`}r^*IsIA4Z410r^EO5S?9l`fy(G0l6Q2(pgmj*NvD7j7|n1PIxF zK_1@0gP^6_Kp;}cUxKGObkr5%fM^?fRbbFbHqAJ2uq+{S1afb4%Z*qKyQ`{tP?Yi2 zc$oo@t$_7vLec|P$inQ?$lfZ)ej>YYVu8`VR0t#l+vCNhKhMmxKOAK8G{`Wj>C4nqg&$d%&&0Y7u0M^ z9PXmmjjry;mlZUvO^PT<)FdiNQr4^vuj?|nb6Drqa;NV_==+fF4$_UZp(-idRwr|q zOVDz*r;SH6$Bze|mz}Ss+Kn)|s_@nY2m2W8jU+3-=Hr+&rHxeQPRr#G+uz*pj*9gQ z@4%9cE-_V%-jTP23I8Ko2#n!Vv{1=z3EC2eX@*fLdN!8+MT|1Ay)&@DBwjaX%rw1X z6Bcd3!_`(G&ehyP-twFm_R8F__V^H%VzH1e8FFWaZ3*+`aJ=BaWXJX_HBmuDUFgqYdHx!SgNsHT_o7M&#&ZRM zJ({`Smm2ZzBYA%B#_d)^+((r2e$i444#aI<-%~~GEGq*}RNDPj8_;L$#yLQ6BZE6! zl(->ueX&yMl%0&tFKc}7RW=%?ux0=~3GwDMotDH0>DTjzokoEetR%pZ? zR;Yh+v2T|`e7{54jDYT^m>ybF9ML15nR#6k=qWhxi17}IPVP5?)oS2ma%vc0VP+n^Z(dK38+PBsG`x!#GAj{Kt%)>3^PM z!E~o`hjJzD`_rE*2Bt#Y>_C{VSf4pR^v9)5#*hlQ$`lKo;f8t)23>@s9OYMtYlhp( zk6Cg3xneA_&&+7<^+YEJbwkXEGzs@BL0wd7=f|B$fL2pW*XpTMDE_(5DXcIvZW;5(9AOg=Ugil zmxdGWoa^e+n_H>1P(wqn_}8M+m2V4-9j=%|9eJgu%9-juZ@eyEJi-8~h)5&%_1^~k zYUvV4Y2u7 z!!1ga9+aPmQc3AbxiqgUCF!V{8!|f4DDzkrQM-dNoD?P}=ErR12rR()ns_AvpZLeDX8R6b0E~tqJ~cF1z1x|?DuL^ z2;6~pCU}PgVfOQRq7Ce%GQKMEz)wde`f3+w$N^-yqYx268dbQ8)u9$$yx?~lT}+{H z69jGJ(&zd+-|D~C(^#d?ySPmmFy-GxfPK=VC7}*z(LV|8f4ZdefccjDCYE>2dc1h= z*nC%qAoK#Jf8q<4lny-MXbyoK-7tMIIj5}R*SB5rtht6K$4yk+s20)FRkTo$?HCIp zcQ%0{>9ycd2jTJ39Yr;`pk{OK^oRF?VQdDb8S%F6GW-r5+&7!q9K#d3BG>$m{qQeM zhKSOirBq<=93{n912hmb4P1qbHZtb!Z7-#QVuJ?1h=J-MK*}{{fjj#LkLSI-e46t5 ziHz39`yaRucs^xBL1*{y9_5%bcqk=;p!5dYnG@q+fV_v;+=lhjQGKa_kp|ED4d&|G z1QO>n`zjPrz_v`Iv9wTxWh&nwpST21!E_~pbr7oDr#EwhEes2Cr~zyXgl#ABQA>@8 z=P_8Pw4*E#G%3#^-hhF-MY6oi#B`fR6R`|Eh3qxZZJA#}68;4|Zy?sY?O} zwnEp!F27LPGZSfXqfhD=`(?i0;E|5fZXt;TnPsvh7En{?uv1GXA2FFTDeBv3Z~;Kr z)rjOr^pf5tboMFIBXxZ@@n#Nm?o7??Y?cC(9TnW2_k;;QJ24rR*5fT?d#ou+8BfQ8 ztO9_4`2Ng*X==muK?6ahJ^x5mernbDpt>81bG>O8fD@R)GT4YD zh7BzwtfHRh*OxMo{KuVRFk3nO4s&^%Av+&{xu_8PwqM3T_9&AQeF8qzBI9vtHY}(4@&e^C4s{JO@gvOZI`!gDm1i z^VKD)t?>yPCT5@@9u%NSa#ZvnE44pQNYptZk>Wwa$mg#((ZW&Poj;|>lSWW{0LHxH zHs<`N9APk3PR2}}wGHielh*%88`aNQgUOJ6jA8xZ0Q$MObgVYpMi^)IQ)-`z7(=0V z6k{J1VSw`;_)n_Olye?E@RnVyP1fZcB==uo2Lo5#y&|$v8*j0Hbz6CG6c*waX<5mh^fL=cq^+o zToVV39|>3^U%?(KG$qhPKDwYZVY$*B@l7!XnnziAJk}X6SOG?tg;&}+N0H;35?JM( z`^#oI(qT?}u>6f^0d|V8u)#8r6v95E6%F=#@IMcI1LtvQ09V!E?&GHoaQO$xKdrpc z6KEIW$UnGEe$(TpmukRvU}JSa`9HQUG zyF}(yWeU2a&!O;Irik=S{?CxQX6uu=c6m>{CaqR`!H#OqLj6Q=Kxc)fWDPS54C?) z1vBpqI{VJ@8)2)m&`_0fX5oDOKT)0sYVXbvI=;2_=Cf*r2~Ha`29=f}utEKJ=dR)p z+T{P}1j)NWUCgUkvO=3l!GiGrO$G%dy?xvdIutZ2yc^21G>;rm_hUt?S{4@un=^{|I=>|ztMKRlabab z`&vOzn8qrx(sk%YpSYm%fPc<78inkViUV}eBKIY`bmF;(V=601VVbl_&dM=Cl$tyl z8nJ(a39z3sV1B`|L~w#hgZqn7vGV~~lmIdfdC4Lg=okdpnoZP>8H{#ug@TQC)oh0> z`^xz(?~+hZ_ofV~nS)&$GP4+Tys+y$=i*Fgjq|fML%UKi&zz^<9-PttvjZobZfe{X12zJ<%u@pI z;XcSJW?46&2#sP#+E{R<6KMc%z7zwLFv~ps>M_D$vaK~R-ph=wY(VNMx$hM}0n~y7 zg8~iPFWjdZYpSu!l{ZL= zPz2+6@WOp}Ll>X0u5L^1e(tnz000Lzd-eLgN~Fi?qmTcM@rqMf-J$zH9lL|RtZ0O# zKUqm11!+R0FsOXCdSz4&a%hfZ%RNXg$RCB0~Sb+mKSsky)Q>~RC~kFe@RxKQZpAK6$9IUY8~!%`hiC)F!cec0ki*5 zyBV8$#yt2sT1OUgH@Gk=Sk~Ns#E+CnB24AO6)4+Mu+^atC)d@Bx!3RdFOWNR8tanF zpO)atLmduDG1p0DoVR4>S@s+1UbthLYf;`ifE-Y9dUQMS0Bu%qGRl8*B^F!Y0q7#~80eI~0PGUC`XI7a2wzVIdj46B z$9yt~V-dv#XWI;4aL(kOt-)Zilrk+?w&8Fxt$i?&7Bu*(_czH*jql8|Nz16)V?+Xy zq(76uIO?^iKUSNP>skA#nPN-)HKjAtEf+J(RdumFrwshsN@BZYEo$j7)kX*BR#)}8 zkJha&4E=;=W}EPT2#A=(j2|VS#WcO*cxNeL;GEq4TEQZv`Jg_g%+Lgf>P+*4>q(&# znk}B!hK)SjN9BEnc%R-TX_7$~P$EPCppPR!3{cGhyTpfzidm=-dPr(19eli0%v&ds z!zaeLU|b*8_yy;Sd);+__iBO`vb0(`_VfgOdMY<%%}MLxKPYMAjBjsb1$mQDc>`0} z#*EvQ06{V4?WF_&kvY@#nc;1+Zo82we;FaJkpB-<_4ll@e!q5OofaZSx5Y?pWBVe_ zu?}j+UumSyatwFCn7rzqRbH&IyfbTcf3By%L*yC{N?f zr_r}Y01K_F?8F`+RvUWy!mIcl^w0WSm8dvHA4Vz^a_M{u#=!M0qXHP=r4OoCI zdDDy-C439x;o$ny`hc*hW)|WN#UYlr(?I^f+>%*yz-wOL+G>eGnDkB7ak$uduc!QJ zqEkPh3ILPnGQ$amH!!v_x-e|ddRKSI8BLa0;uB^lCaRqn=^9(&_Zqp2&dWT~FD86% zy}2+lpOgRq5~9U(WUXrS=ER}^@n-?TNjL@=MXu?sw&{%Cz$+(*%C~_fTJu0)f90)5 z8U{^V(u?^W%Ge5QR~($Sz*RAN80ahZ7*a&Bg8xT;1aYI%=mFC`#@Y!(T+^wqc;T`y z3bh&#bXOlECXl#cOHFx2k++8rC0>Dkn~gf!rsAGsibas51p});iy|ND%Xs)0qowTT zDZx8sSHfv#S4cdH^(7QD_TmIB@0~rNzYFppE}A(^Lfqk7OV8uj&o32|!NR71Gu>U{ z@VBTu{`LHs%iU)=pvoSwyYLY*Sy>F-(tw(ZOGA>6rwg56e%QwQi4bNpA1t=I!om0` z%_J$WOSqw~ad@_!5rr0Gt$_b`l;84z6fFRs#`dJvdD+fhW@6qN4J`x^E*!$NaazS> zFZL5QZ!{y#v;(FUs9F1Hl=sfd;;Mtr0006dL9{8i-EV~OU08tj5YjE33~Y)%NNHM! zvS2gAxpIg4CRbH@2j^9O%ZJWGfo!ms4XH5W=FNH%w(%4fi7 zh{;j2Qv=L^Xx0*Z^qGJXJJMR^*vxJ*ORu+&tje~#N3M4Hsxz$ma!Pexmiohko$AiEur*N zk+@Exmt&OsPCB;28K8cK$`%BVA@!I5vn;@XY$Zi*4Y%5ob$yXjuZ%?#OW7*a!=Z$i z%bR?^&S+P~l-1e+93mCGCE7Z$W1V(aJ*s-*aBd{3^9<~4#%qF@>1Tbq z;^2<_SwG4IMlI}TSZ}7_zWCq{yfTiQ7Nv?Qen(|HaO|Kk}E zJV>{0FN4OYB`2xw)^~s~?f?K0X2EkjNdHO*l+hLgG_`pjBcd2To2*y%>6h*wD{nH( zh1ZRwFv7$1Xh^8^LROY%Sd8E)M&OI5_@@I^=BO#pQxpvP3@!UmHLLmCO4y+Gs7YX) z60x`jB5$}U43R!U|4!A=Yynhqkn3x`Mrv6XXVnu<0R$)tpbu?^?O9W~npO#3F}KTL z<@*W`(5@!4E4_x-hWivFU7&~mnWMr0r~V+S;%f)-PLmHSBfPHpb7)~B$CuSEg&$a7 z)UkrzZh%hCD5W9Gmp3`pn#!h#z-qVMuhMmH_a74uii1n$%v((!j!I|ZFIXbP_D^Kn zV}1%`*Z(Usfqa7cHn1eM!{}_GU4RliDO@P&zs=%hvE}dQ^DifMQ<`eVS#r8qZW0v0 z52AF^pX8tb2DiWsxSVzDydO(2F_;Q8MVYqfwwj+I0*%&vh&??F-S3>oLA7nCvz8xxoX~ht`#ci(y1yXqZmc=E# zoz|WIeLtuyx0Q}}s%`)rF~^6%G@78Er5Gd;DR(NpAm5flh87My*TwrQ0o1_($}wdW_j#wOtQR`i{e~KJ*?fR1iLFt74+2X zKnNZzBGxhqgrw+oJzr4md89Gf_YQQ|n&En&s`_s1sr0a_xln>>aqGiJi&*umOI5C2 zUvHX460Xw!VSTQBvT$B*rg@mcoo_w^;Q)EWA#Nt}I((vEJKIF|4qylyP>2OQ0znYT z-Y-|VkY!1W9>H&+f0KthurtTy<%U^Paj}XE7b+6ZYt{xfC^^<1mx)hBONgyj& zcuMim{VI3tjMFxsY`DBer|(svp133CoO%cdfLr(I_GNmc$rp%_(Zj0ZfdpwbSB#bX zxTjIx`~SnMlF3o&)tP8l(5bQn+<$)tD1BEYIWAHJPRN8|V*_+66|Xw&A;Aa&KN3<1 zEAYpiiMU-tMDhjsg58R8gUv;3NQ7$esM`BvyM8{(nMK9|y$=UvA@61rMucQ(?@?`1 zU7dkgjQ{`}2%+#&*lt1}RpLcnxFX_qLx;_L#e>OV7-~@S)sp~j~bWV<@ z0CJc!QjhZqxqoe%IpgHHk~bHhRGSal!BKgo1dw=k17}yIMK`5oHl2yaGThtiRyR1j zjJZ3I0VluwxsjtwQ99K_ITf@gSU(|tM1x#n$LO9H^s?ICkN7!2%Cd{LLFoo;8k1J} z9F`DUa{BINNVgaQ+J+y83LN9g!x|>WJU&P9Kqjzby&2e9_Gl#VB+@>pxp&-*^mL0a z0GMf6MK4;MW=fMm`Y_^8t>yvEUmkBeVj=E(X7P12;Pq>b)g8ZV`UGMF&IOb!8k^R7 zbQL`$z0;^tKwJF+gpR0=sltL@UjV{RJ43n3K?OHD7mRr2EZ_vX$PP(Jtp3#vrVDT` z&;zjj`|e|Gaj6qw$Pu~g7VEJYRZc++_dJEtI%J2X-`*Y4iqT|dWaTDe607iN2*J!WK zaaiUUD(iMFT9%givX3CSW;8eg99%Gi!_s6OtJLX8c`{u_NZS)cr zYdt8~y#6@vkR-v1(|V}&28}-cm**9A%#HA3G9_h=MK=HxM(Fu@C1CQ1En2mH`%Rx` z{P-yrfFCNI7tuY{mgO+*rKhqq7+mCehe_ovm&tAr{|MDXioB%V3kc2$NE=5nP8l9yo)~a~q=VL>F(@x& zzU-Hi#nI8^&!?UbBd|!U|DuGz@<>CgHMAO|P-t0LJ00<9=Y6>1ph!`sliB#@=-mLz;pq5ZSqLpaa&#Od4l}rU;x?3m6 z#6Ug9bV@o&ARdhe3&$kWAOQ0d6iEO_wd&YW3ViZM9$VbKGlFSE(x&*3@HPcweG&}{X|mbaL(jj)MGt0TbAey=lH@VnoZ?2JqjaqXY8+}jTX*pUZP5E?;I z$fpjxlgXEU)>Nrs$koodXyCh{KYwZ!%%`nEYKSk1OIyq+|5huzx%yA}w*G-{V`i3T za+m*J#)&ptRJm9fsmZVfJDwpq-98d1#fAU^6vX%d*%I(3CLK&la|~W15*C+>se{C3 z=FR_DZd|tylOi=G0`*#lFqTzQ@kI*+d1mM=)ZDf%vuRB^Sa0eeZ55|h4;4_>Ql&CE z+@SPacd64R2A?WScmQ31IKSd7!sodD8e9*@d1Z-%yob+Wk4{GBir&#J)HzRFl-%7T z6t@8wUTzMs&<|c>!;n+*q)vUs%UuJn%<}eek!+3y(aGzM5)jTFsCByiN&XBOzMsax zr-~MNv>CBHhO?QbsHDj%*7C23uglWYMytJ{neOB}w>Xo>ggcjR3hoA^KLRXz?~@-2 z3vNn1ZxAXcZ{ye8PkX`(3=yNV&%;CyfTD?M^4<@(ft%^SnWofT$_so`I-J{F9|`e; z1flZ;{NeMze0&?REZDY8Vc2>a1YhHVGEpnaJq-)GYQ=*YNMxoAC zYA~z6t`xd`w{oAAIp+lnxKzoLx4~?0dZ5#UhLCL^j?7Q3hGkU(1&DQl;&W|M>Tn9R zH+pgzXaR?*Nfj_R+&sF}tGXh5OI$KL_m41@pafJOGvx>!Z3N8kQvSy{QCTfkvMHYY z7D>k%ai>aQ4}i+*1-Qp7jzNKtWAWe~1c3k6=>#hZfxUJ}Tvy{p8sG&+MQH6m>YxL7 zqJJlDw6Va!ty6``UgIFYf9~v!nLt#pik4hF)m1UjbR2UXFN=jX5yEz1nVkUKZv9J7 zZg~Rvv|-RIZ%zuc6kLy^6|O1#wkp63`ZP5|Md{LRe@|D?<5JD_6bW`~fCi!oRC$#} zVMwUVD~*vlufu>pYX5B*Mqkq}>p@RVjszWMu?6m?P#G zp6-b?WbdyYjUi{vQ9yC*vV#oG!Xl6!iRb|V*AnRN$L7Bu7)V-$1|hlJ1k@md)bSnr zHu+Ed1MHwwodoO`jqx^d!(oKcI=_$PczxYeSAn?EKJ?+QiP4f2TWR7z)~&~S8(l>I zBfY^@vp{z=tS-AKAFvMTgBuYbh-UM29>bp4l$yJ~Cp=4OJpjrgyA7urLF;0z%tOr` z^n8nwmAcS7`}u0vS{JF)nP!nauPx7J7UUG5 zA?=?)i%bF3?ZJ*$`@Q~|KXwCOX>=OMzwO~pr!p~@W(B;9oyR>*EiZt=b#EulQ#fw9 zn|ZN92GEl6yUaxI;s=^V%ePbw+LQm%yCW|8?yoD?v+bNbbrf)PrzpT+cW3uM)9r%? z*wsR_IesU;2Tj&BYA0hUSb-J#=V=+^tF&7|#HD92{_pOAS0u1hWXIV@`D214*76rV zwB?{RM6OuMrY;9nru4mLD3=iO1!$EJznDg<{#!U=bO74|sDxI=?tG_~@u89F5G9+? z-iv^J2XVx{(X=-%{c1Z}uE6`_uaYd)c$Hg6?>`Xlh(MY<_xKv-odkv}o#oGeo z8pwPITKl^WFtLNW1=6{b2yL=kFCMEv=p`>L&Rn@WIMV?-oeL*_MqX_d5CJ!|?Wn2^ zfT16s^FB`4$PoGa*EFogh~9agLc6i5-U`*ETwsSO!D%2|)m;sCEoJHLsle`KV!2ai ze25Xm9AsE;Eln-SSVhh<-wU-ZcG)F&D1;mX{4x=Ww6PJ~U(44@s{sNb-JrQ_Kj8&@ z013Pf2q2d(lGw7u5=k4cQeJ3ML~Dv3c{SSA=q=A30tfZ1APpSQvA_U`i*U`7(YJ`k zl71kwb#xe`gqD{d>WWMrZxwq?O7#FeYCA~Q-zcoisyU230u+{pIXD=oq3+l_`Kni| z4QTb5gu?8p4j#A-#$ki$GSGZ}3Ii!vOv;tEbAR@VdyAc@@SH7(3;Rvl%F4Yn)`EE2Q)6De>km$C(7keCSht+K8mld zV}_oiy6|E)N92(~j^Ao64PrSj`;+Am;Di*XqzbC%=5DT%(N3eQKvw!KA-qxKP8ni_ zq{_CO^5}H?)H|w5fi{o6)`0{!y%N>s6_ubKQ8FG#Q(HAc3$C4>H`z@budGrE8{M8D zG@0_a2a;n{FyTuzvZkrVt9%UL!j{e(-^X`2GmH7OO?SihE+iAUvPwyo*^p9ISRzGv zv~>yzCH_zEigAePYMzdC=B?&ReHQVSR>p5Plbj1(AFNi&F4-HY!sVh~*(_l?ARiqmaGg zbhOMW?HK1!shTA9X(V!Hio42@lSZ}FDpa*4m7IqP?K?wf2lLGAYbk$>+;;@PmIago zaYOqN;>RpAX+_F7IugI4;$%Ni2c9q`pHY-v7ac>G%9+HTJxDbGo^v4i8&x(x2b)DN zTa2-vQ=riK;ZYxlK#(_Yj64A!jlo5u6}<#f2(aiq{P)gUA%gi*->Hj>I@41=zaN*u zR#$6amm}1BUi+kh& z*hXJR_Y%I}_)cqEw{#tO#q1~Drq+&VDxT|t41#ZUh%eC&drE|_{n@`8<2v;l({j8~ z{#tpTqJiw5b$qk4a;8}(j&YoI-YYiQIa)qrB9>ZdZGuTf>4sE%CYX9GZlbTc{4=T8}cLnJE@Pka_qc??r3#62Zv25whpY1tlNybxxEjR&2nvGPp%V+#i0hO;Gyp*kf)hep7EMdWDR6o$_M$4IoZPPLXC?<4kY1 z3*E1`ZOIRJCJ*@}<{?AmcI9AIbalckGg*{EpMsMGw4HHIy0#pj;nlKCLzagpW72cc ztT+m+^EQ?PDP#XGOE>;}00n6;YF9w5mMkd3WWIZh$saqKA=JpOQ7HYM1%I+{+R=Rg zHle@*BlJPUH~>VnMCO8d$Xtqf93_k$@7Tz7Gv|pRPPe2j`b+Ny4q1!b+2aj3(3_6XRJ zoo0b1zYTTOa$5^!nR|~dcQdiu<&7Xf20iM4QlJjd$ zr?feGI=mvWC>~J`k{CON_i_iLPk{8t64XR(JP97VvyV&R!NBm>WLllV)C^#gK?Nm= zOxe`kX=9TtbRs1cttepK1SgNFcXsE-+X(ynkmL}fse3kWbQmvg05nUqNHWxQCXny= zLoUF4=I+fx)$Pahd|)}m_yDAOR~Le}Zf>}!IV=R*nEyHUy8+G?zdbE^L7#^~Bm@_x z6$sdzz2hQr$%2o?x4>N0_E5WH_hl<&q2`mCY5mO7myV@_<)S9<^#zdm;ZPAqaz+F0 z>WP*&JwJd?1gMcta10=X0W8ZnKkj_Gs}@gLNXYFDXjSl5!$JOB<-e#LxU3OSv0Y6L zXBc=3zfpY?%EVWLM-Qb^ zI?g?VU2Do49T%WNjOrkZK+@) zJ9t*_W~$tEd{sOCiO^&u%sGsX^PrfiZzamiJdiCj>PjY7iEq9(@)8xwuW=21(4*Z& zlz;#@D(bHzMUOS06fx5&ksaxt&-VhR77wDy5F6eD#LXtBqd5>*to)0xZ?Qp$h&|0W zg7T&XZpJaLUjHb-?nwgGY?*@pRz4C;48== zQEOjWmTFTqd70`y7k8@s1DW~U&KqwJ$waPhfUGYmZw75@K$m@IawfA~-L*%Y%&Nov zxHHZG2NQIG5In=lnSjTgpaYFoG;4N1WGz0n>(QVvGvXYBN=oAcLeq&tfjaBi)1 ze6w||nyNtG{kPtu!j1c>=Cs%iC0>Sfcv#2=zg?k(-xxm8e&kSZWb!hXQ=CXsg_rmb zFaWszSL(&=x20`ik){2eh!Fc?_eO*_OUm^)cOcaOOF*>06urJyL{5VTW_R&DnpA0+ z4ah`k=DwFmQXu(g`c6iZc5d!b4PT309gB4Wy{*qHS&EfzEp*$}&jsQF~ zfio)XPWM0oDN`^UO{`FRmW(ONlvcDL_^#vut za=ot^_87LxJp~N`Lp)Q)nYv7~lrEgXK_^M&^hk1(RY*QKR&g@=m}k|Z?~#P#8%7E0NP@rCq!g@X&4Z&*=FDWle(1B+zH2ulPI+k73Yox z`a9F~Wnm7bT7^*&(v?v7q0yLQajgxR(hz)I3TetxUOnNTpr}Fd971CQ!f5%K0dByJ z@Y@TRH=QL=oS7d%DyWSqMbynzO%@Ots$nmDVn^Acm?;a(F-{vNy_&U%h#&9;uvxCi`42k-`ZI zz@S7q*gS_C7CI@s&7ZWB%-`a%2(TJ90IJPwt-}>tx_1%)02DWX8D9%pcU5t9YV|!l zd1#wOd4|{>klO4tcB}tOT?~b@aYqZYqLZKUTY!EdPr<>~`~U)C%qo0RNdqtm<%hM-lO}ePSK7W79!SLcXjjY?IqGfkgBEPR9AFr?zvX8EB4sS18|iP# zQ%g!zEr6@pWO3{Z1kdlUZKeG31->*`wW4rw+jZi*mv4Msb{hxNvl(@=f=0`m@^Wp!C0pJyIF`DSGx5X0xcL^{qi4zSp^q*ii6Q$MR z9{D)S{{~BC`&zen;u#j4^6diES5?; z{uB)KVWk{UeOB~nbgj426*e-|h8@67q zf0RJ!-4Pu*Yd|574y@PR@N}9LB_mU9Sbe2Sv{NL>@G5g_K;SlxEPWDyBof{LtR96@ zBpfCk6OH|DoAeNv48^GU7oU{CkKSCbGhTCQ@E^>yLrFhun^mj3$M)Sq}%ZPzO({UY2kC)t54uU=>i|xjD*3B!mIfh@w{CB z+Vtr$VGVt&(V(%$9#3%!=+upD=Q?$|>NLVoX#TZ6jE;zPg12+Jf2;=~%#wur=@a!# zIMw$)KDgFw1*r*CEsfp|R&3+e=jaVmdY;U(y;j0aG-lYFRsS$dqzdF@Jz#iYiez0C z8HtP?=UQCysJcnNGR>I7wzB^c1M32rQ0~Ff4`9oWa2Kn;zzFF`c5@bod_c2zZd+ZB z*32;^0_1MQ_aFH!2mrGB>qlt40~cT#Hs6n{&Bwh+KUnWHsR>PE%}@Xq*NV>vgRw6S z>CE$;uafiu-&3M6-CKh8nrS=VwZ~UuXdmsmU~@+jI)iYMGKz_b@YdTK+rR-$03Uqc z)%DvS>8Z^o_4^_9HImr2eWGfTd;{LDMec~I$B0TJJG;0v$GAD2RbH#X@ghkLr*!hr zou`D#lT$5c=HuRH56r)^Nqs}WY`Q}T-O$XXV9KQpQgS*hbviUsecAH^6<{p*_D{6? zIS%0-y)6kk3TN@5ysyQ6?MW{T^=kkDAOmM_;R{$f00(5nDX(M}`yN7wE8Tjob|uw? z1m_6YQ}f%-K%ltYB3WzS%kx{3DYbNU4&&CaY9?t@jK#7ZFUq5=MdFkAJ~38~_du(H zX}7eRAfLEF&;u6i1*1hV{RzN1x$_`zu!Jyq0IZDshtK!fTlrO<5V(b7BE*mOqB@e& zS*=ECte(~bfq*gjFP#jfU|DvYo^0|3hyh=2L>8NmKEf@FRu#tO(gLJ1NV>K*8|B%R^VyUTRd6zx(*KB@x$yvfmkyKi~9QE!V>6s37 z1u5X*sQRvCf_8q%)ax7?eu!aZp~?$3Aj{IR;9ou>p;kFZ9>w@rZI?s0H#tMnhmhnjFqq$0NC_a z98}bY9aE1J8b=!qr8WeFUp)Pqrs$ehSf>0M(mlld!Mf!R9jZ0Pi58L=6#2c=c_hH* zdghC(9bibWfpD&zPj>I~(xrH7JjIX+sWU_i%MZosa9&&w`;8^)rE&kKf#y9G`5}c) z?a5kD%%W3B9SLP+@mndBrG4NzP)wNqYMnAT?(i(sga-o`5IF|LFm=LD)}Zoo+v=|A7bZ zGI)!*ach7pA#&+!jl1h^A6>Gpo2KQ-h2Kj)rh@!p&+;{=0Ys1w-2Xd+<&^jSi0atn zF9}Gv4BmaoheM?^X3I8OKG&#mBMrxs*lXTX9Jt?C`dGKawmR9ROzNwCv;5m9O=O(o zgU@B7QimtDo;|f#o#~MPRx+z892wLf|Na*R%e52wZ)5rn;MdM#a;j3KQ=L!-aLwRP zLV-E6uZ=E?QDRi3=vyvS%7CTonMk^SXLP6b_4wK?ADb5D3}eT9;#d|~?v5zvRX-C2 zD}wVkFz%KDecu97)XPC2{r)mdYE|@SEZmDF2Xhm1=0ilryWmK z`b>&EW%+3ZYb_B~sHMsiIf3&Ss_YcEcKFMSbxA_rW3w4O`c=ZEihP>b6795Mc@vwx$G(`xF_R*3ZJU(DrEC%P*o#2xfBlw#u-$d>r$>8}d+aUF5WIWVpF9czEYCs2-x9fPK?(#J7`< z&@AhRjhX8L33x;*D~bOidwqBx84 zRG%4a8(b^GJT8Z}gVSj~ow81~{SW)9xAD71PPjcd^QY;rM3MkXf(ji1yjqY6NX8s&@&nV)+i23(XqRPfQ?=vv62ql2}MXwlRk;Mkp5M)I7|0MNtgG zWi(v$iA(#2UV&0C1rs11%qLs0x&Jy;p2ccA*l})z4W`6b3V)?P1HTDZ7?>SP8CZwn z8m zMLOyRxC0~cEXn*kp6qTyjj}*AA|XpNIENVRm=re%?g0axTTO|ZV*cj5)+%F#MFO}5 zb4ZoQq^f4Hg2s7}bC6o{sh1z_d=B-e0eg;u_)pRIjE=8NuMQbsZxV>( z7k)K)zwf&Y^OI3klTd$JGQU>9nXVG<9TKyV!GUWXux4&rt-zRJ_o8u_oMV@|!bgev z0TBweJXCgb1ej++dHRlLzUuDO0X5e}(~_Q4t)Zz@9Ea_T&@?IV8OMo$a7Yrvjy}#e$=f z&}(=EKm|6Vpgk8F8tmDC#M36Xq69~Y?SgFDCl4OFMN)Q0Q9*(R4$;?~Brt)v*8)%S z>~9^_r~m+)_~dvg%{rJe_25)v(t=9bMgj2QNrXo1)1uMyOthp)vHt|)bQi>OlUbj8 z26mPwAN}UZKog-_Rkc#u`tVs=W`vtOs(dD86`A8^e=W(l6a4tGt0HwoTAcTs0ltk7t=+uke>stY%HH-cGQABwpCE42qJrion3 z7bVfKkiS|LBJRCi(_XhITa>nZ^DB8-2?JJkdh%eTDC!7Rnp}w$a%A)4V*V$k$YJ8l z)zg5Q0z-C%oP|{QSyq+l5R@1RS%95f2=h5C$k(c@G`sj_e>A`_ddU2P#o={H4!Xps z55(BBEt}|0yE0UZ&t7ap1uz=p4K(s|E$J*_Kh&v~)=!3)rhUjJ7s0^PDVdC(RY#GC zXOosv=!?UubX1|$I0H1tXldjC1OawlA#esSDRy9&%zulunRH=S!S0+laZ0+iS{s&R zJ0cn4*jJzsrO7JroL)gd_Bm?Bhwm#$e7z%w?c~v^$)1XCf7E+aZf5;xUtMbi!nYK~ z6%um5X-*4SoIqvHtY-9z{39QXwR4%j5`uoPD>mPKQ!! z!0YPbY|`}SJ#ik6tYth)x=8X8l)+^m%HiiIA4+ax!igTx4`?>cou%MN%s|55WX_8D zr3HJ(kpA&OKPYf4MyFhAd$7=D-8c?kGA62RfYu*;hg59E$LPL6CM?PIpNOe>+I#~k zm2SbpB*(U>VQ^7>tsn^z89&6*LIR?e4x_&*i(3z((ReAS0Cy)pXi0tzAafnOfPh;S zyo8S2^OY^BwTtcKiT4h>zDJq(Rz|3#fn53YqY5!c<4*+zl3t1|)&uL>?hsLr%D7`yCNv!5$#cbQ;WtBI37CTyr8c$ghLH= zlEv(R>EZm0H_5yiWu;^W(aC+gUmIT93DhPem@C@cmUE1C*?S{pYgJPCLaXkE2_O7Q?J^2vVb{4xm{z*n@UkXB7J_y~@eg3VTu z2!d&>(o26uV8hXkM}PVu;U9p@DqFPK{1^!ocG=hAac8tfw(dX+1+u{aK7Ik0W7;#~9 zV0hVYXh@;M|L*y@f|4I8h6IEKnF~qzNL4zjTppjQP7(avS}PbAR4mI#h6PU)2v(p7_lbo8V*uZLsKf~p zY>O$Ux@DTxFc|oion6O6yUgYH#^EH!W z64Q~&_FWHC(sgcM7(RAWDku6bsC;#G*o-K6$u)cX|0B&rrm%I5U}&`>Ur?orF@OMT z+W-1LLtp-P&?*nc4o>RQ4Y)UO2^kIxtQQ<`N)1St3P@lTCX$A`gwfx$ihlV`8mYa& zI=8ZWERxk$fw!StdX@iVp@`NE0WV%s;ajsRzNx(G!<|TJZ^N>DWw);h>sk$QywJ-;38^C9XtbppimWe%Lt8&dcg$ z{;k2Lcmex&yiRzJ7}2XxXkd!GNu~pnv{h_<=r(6FK?lL83p#w+xh)a z*iYH#*9iy3)dErpPkf@pH5<4M!0Emni)>|kyfI0>Q4TG=5fI?##rkzkvHhX1;Df+m?KY$*4Cb0kyEX@s;k|lZ zE-E4_y+FRfic5}LbubL|%v&Tt0?SIPpEMnFP$tR&VPdy)q|?-PmyTzNYyZP%4rd5P zn?)}ga*45Qvj%q5q*j+pwK#SSM6eHTx4Kqzx>KT;Hrdret-&H%eJ*dLl!pZo@F3)3 z&K1~fAX5H+TK|Mo59T|#KY723@Rw@FH^6xRV_SloxiVmGVLO!G_wdhTTX-y(fBi~Ke{;GsJjDf03*d4#NECT4 z0oF^@TQGn}zHWr3p?+JRG5rC_l@vZs?_Sy2A%A zg>*1X7c~B!=&zP!hk|Ko;_EKAo@WK|8D2eM1u11wrJ79aPa?u|C(H@Nky+@lVF{E> z`3-5y5@vEw$&+dY5GX!w+UZZVr9WCt25w6SI1{mFd9Y$K4I@?YqeVkjq|fLId3Q*M zEr>l}2IHc<>PUh>A+U`g`KMGNwPWCCm)7}%a0RllEGrcYEQ^5p&*kJ}SU7J@E9cB- zI2uY#wz8YIH)z24cB+)x3VkhzkeQwF}g+~z&#SDh=5jq-meIk!&k^5Np- z2+K5KaZQ`K1dvfMoo=e~swWC~4*ngMinun>?$Tx+`VvtS?J>tl|F$90qwea@Hn{{e zh`m#yQ`=;l36!_5>m&>F4c+M>0~xLMoEG!?2Z$k!J>V9ifQyh6FdyUqevSYucxws5 zmAnhSrMcd+ow1g7do0+U8H`N!$rjmp=`tt`5=}ax^I!UOO4ckbQ9AAs=!ifsws)uF zj7XT13>=vMY2o9gkF`{T_j z>B_!X{$^MV9k~UCmkTs%0nrD_rbAo&2x+{(IEPX6$uq93sBKaj0pC0000L zP&BBY7-Y*en{3?!8R^3?s*qt7+l8E3BnV}yI%;e*cfaG{F>rs4Zv(nSKp4vUYg&pP zrYjeAOjs{+yTA2D1N-Y3X z4o!oihi=B|?LD*DRlHe%XwQKmE?x$zD^rqyGcJ*a4>!)cPcE<7SJj(8tZLaB;uhV5lnKY zdMw~cU0y71K-3)&Sy-@KD}>mrOJROg8rsWivlu)2mrx(wu`ci|2CPJ?J}klg$16w` zp}+$*Q^C-XBF<%}zA>SI7}={#>X)(*H=+RD7Q-M5#X80rG2MI*LX}s1xxUG-N>^g6 zTnnXn+(LYcD0In}L~vqT0;N=A7q%P@6k<47fI-*=f;D^~gM>Q<^{D{2ss=1|}zOtUCI%z(m z;7bFL^D(l4H@FaDT@%Wv$fQEO4EAA;M0;$6II;WuGS!>$tNTtJzRZ?d+Y`*Ebh4FC zL#r4@xW>licYlWn_W)>j3P$arRDpshkca@lZ%=8_%wTwl$w0%gPp+rSKmZQRG0W1= zC55QaFJ-K@f8YZK5cq7#mGVvGQA=4dQA+9nsV@g<${Fo3h`XqHA0^FtT(WOaEBi zf9L5-32(9`g|9{H=}ig95;{PPftX~Xw8IW+;j(Da6F&kjK+s*oPkXv;!z~ov*_)s` z{S}t*K9;xE7ocuNCG%RSpI66&JhdELT88`2o|DWHLlNYMT6-6xb5WG8)&);wU{ZiP zX4r!NWPS@6OaTi3tofIKrh$b)_m<^!g-{&L=&UoVK=)tnEHH6Kyz~8$>Ioe_W3DNv z4~!SK;+Mr-`2M(e$YhP#=D<+;KC}Q4%Fcxj8L=uh-T{gNqRLkU_PojS;F4oG;LLPi zf!Xms<5UdbdJ-13qrptUnw1efE?sb{|4S?xD+VF}jmRiKHswre73dUV?E_c24PVfOOxruEEm}TVNhYXj(AAV=jpuzLv*bci~nHU1AIX?gCJJ!>jsKr1~(Op zKZtNg1!tjPi7dP7yk{(InZE~_b0?uHVWb(p=Y_mXk@Ba2Uv>N#-z?u?RF%g=&b3QA zJgt|JZ$JL3|0{22YDeK(T>Sms!e+O>Ssw{wjm#})6#?%y$dBcC$-Ze47Ci@%y zv*92h6S@JUNUzg=ysR>vvQ5ktuNau9orlZNGBugWaa^bbD>`sxkjtuuo_CDse7W7= zoJACX$9=2ZKj+-%6vNX8~4Sy-y!5vg{ z2Ip;lTmT8H;6M!%c3*#N^J?Ewb#{N~J?0KY@Q;G7Qn~vS0(de~Neq~3v))KgSsfUd zRfr&zlBew3H;uypBN!k+<7LnS13+j78F}pxNT{FUkm-6a6*7r;zyV><^W&Z#a~CNO zCtGR0ES8P(ZED3JOD^cuy$hht9u{?V2ISF10km*{Wcth+#jbWDboXqIuRyh$;lXa1 znJV^Nl90_J4Z^|Hiq=kfaZ7ML)%|@SYgZ;rIqdm*8PUZnVmvhcVjm(AO){9f!`32a zVqV%9i_S27vUfuwQQwAF3_rn3Alm&3wy72DUQ@-qy$Iv?lqo`miKsc6EhW^G}IjxS?^8u35r2~ouktU=> zC4?1{Z3j^4=w|$i;`5owTl=#Uw@dLS(ii{&T;9J1;>Fz?!9|f4Ojx>rn>x+iy13 zf@CTzd{F$qf+N7vv#%Qj9~LjSJurzaF#iF4+)Wj@@lQ#C^brnn58i-Kz<@tto%pKC z22lEUI>&1Adp|NTcKRG{~{3WcA>ADW+OSJgSBdLq|$Jww8r+EW--$#YchVZP!<*!Q)$sS((re) zsS7fwGIP|^Yf9R_D#XZKSS3y)3`K2mN@u6%;pS_2eW}UH1Z++1=9)?VX-*Gz`1}B? ziKZFx2fg*?X+f3ks~Os~igCszPI2XNtBY#Zksy@Ah9c8)C(d)>o&z*X;RezyG@~4Ow$G9oG1sLEa zicCro2o9%_xt+=gcTzimp?KA%#lyo60bMyo~SmF+h{z1b)C8~-MpN5K?oU`t@dJu-i~-62T}1qL-h z2#4j?bkc*A4(Ts#q}4{UdcVz0xX6Sp9>m?R%Jfwf+97xr6)kzSIw7C9b5Q^9r~#HLR~Bu0-@bO1o|TdUGC7M+lbT#^0K4FM!Lh8_)}YF;_t2(F?o+> zImJ2IwoNJI=W<=kNm($M1k_WkUtM@+>X-~$c?ezj&x}W=*3(KMZrBZD7vxa6lGYD& z#C#PrJaBLXRxL@78I4I@X%Hd0lh1i=?0Nq0Fq<*JYf_74C%JaKBW%9(j>p`qfhBC!!m;O!8B1lBke@(A7jVRjAbhgJR z4qcx45Gh(H(G9rYlG%(w8ZWvqaf?i?T*sJLK$ z!3#ijzd?Y~?l3I%0KH$FC;JeO|HXY?@lpvem|pH0ClR``2=$dK!`y&c!76|VjB5kn2EYpM^`HQE3bvoC&#p5NY*3_JuW^0K6y&+ zk8f={Awuhr($v2q@g^K6tkz_)8Vs^|LIzs+NxII;^UI&#$aG{PW$EPJQ$&|cUMvqz zThl!PU(Cxa!MAVLS-D62xT_jM_PLf@V6YR!N!kJCHEI`lI3l0aNj|p)VdJX(-kZDj z-&ICTZ*?i&;Y!ax#1aH+`Ym>?fS@q-kSrYk9Y5tpMST88u`861S(}jC_VL!1(A&+v z=RrpyS^m@Oxm$o`#~mNHl?0RcRV=>AgEbu;+CW(UBsEXIMsv&j)6Ru^R5rx?tG{`G z*t^nEOQgTxGybNb69+HF;S6W<^lkwlMq<_sH}i1kQ>LC;^Gt;HVTDjuzY#33HHW3? z8NFbZ8|NgIg$()ez(?z93hF6KYgfgvHvFQN+8uo!VrW}U z<$ga)SqcM?q#?7-FM6-IGN!70D8vm$fe8xAae`gJB6>>V@4+-sTFdU8nPFtIt(E=I zkUYS^;_=d8ckn=XoHe-LB)a4*zVuypsu7AHt0+M8UJocySZ;mff!el^b6V%hU>Ji6hY9+>qbdOZ zkiYO6q$z6G!>hLKjDSVi?A>0}LmwvJx`+jUSAv(K4*J(us1XS^-2i3ly9CZz<{_3y z)j}x;V9?q?j!>4@KA6KDjsoXn>w9}F0fwEO>&3rQJ$NpJnYg^0iN%i&@StZ8jJA-> z5f8V_LQ=Hg>z!aQf4>x?tgHi;7z=RZ=;l1EM$vC5#lurmUegAXkXdGx0{$nyUnOIW zFrBL)Ez;cy68M%Y#sD_CfIEU32v#Ih|gSZQaF z&QVnS<1v))f+&=j2oKkgf08@4O5gTGl}t_GEDT}^Nq#Mhxb~=J@#?^SbOvsCgawM} z=mb@O14>d&7}HOVu2P46;}jBhQ4|GguLfeSgr#1P1c(4FWJX7p*^IJc5ColFL$5Ze z9MDoBa3qXr71PDGK*z%(UfMW{hh4hVIyntTe`D-@dc z$BGKr-#2O#*?>p;B>CT*N8cBrPr(0vKJNojZ&F=Ys|0a=p4Q*D%A*@(T6c20uFd3G zRwL#+m?(J(^fTNv^JFJ3M(9Xd83IuvR55pe0kXs_#x8+-WdiyM^1Az8V#c<69ZqQj zh=Hg(cs}KbdTtcm3GVHODrUNkj>8Bo5n0mQmcbcrLB`gW@CY#B!^z*lgvu%cnkA?> z!u_o|jDCT|aD^7-;2JBY#fSN*9sLbOPYWZKByl@ZR0PT#6i-yV6rXZnYG?7XsPR@;vd|nii=5;AfijA6~K;76luQjGu@#A^N z_E@Z6JSR!q{1Es_wiMNKcP)6h8&_Haq7P|%vK^E>P{y4xX^V&wmXT?**sx-d)FXDp z{z$JF&QQ;^L0Q>E_{evEIcK8qDs`&LQ;0B+=ba7)JY8#xkE@|j!jo=nKIx0su!3FR z75S4~6)-mDibH6UFav4QQB=UlXCAI)r+s8YC7V+tuK)n5fg#0)7G{OyrdAucd@vrh zC12Cvxa}#bzFqzhJk5wC9$Dn1L{$={y}x$?=m|#praem#*C=wIT`D7r7T7Zf{ihbt zSfFGWJ#n#M`KvB|SpX`%H>GTw)!Zk2&qc5Qj=acF=5Dm;AUT}DM#s&FA;|To<7S!E z+@25E^gjrOcD@$k#5a>1lg-bWJJxy@La^P2FhZi=Y&g%S@Ba4 z$CitNFSeKT?HMvEufKY7PD5=#SN6FuXzzVn_)X$2Oipr#?n|>zD!?B~%d@KIX2YDV zIf&w>mGB4rt*ucXN_PqUn7?0 zpD|`JmawUAnN-YTR_U^jD}6pf3X)hyqz16AK2Q}g)k&BcOaCN6BGzet6qd#9(_>Y{ zkP>ff0Q`$Wrn&*d&Tsb3w_O8dml%nb+1-=%%C%_sxazj7G*w|Vry6~xv^Riy%5nvv z;lEvG@8(I76p|1t1#RlPJtS6>8bN}dUF$Lc>3CmC#l~Ic1qioHvCP%$oi@vj*s7@g z&&5!k?g@0lPCZwBjkKNkT|h3YlCq>A@YzQ8+ z`R{^G4$V!UfeV^<<#*i~;RZ!m##C-%sK(pKBGLsgLy*C%<-AShO+gO6;JzNQIyWZu z6NC9SO=+tj(!Mi_GhJ%RRu%+05;}e9tPVD;jF-QyDfb?1)Q^y~9IIOc+HNtf3?NP6 zu1J7pRYs{?46Re>HGlw;@2$mix=Ue<+5Q7thZeo3J5Sl2mLyROwJGXG#F=n2&H9+8 zrz35&V(azy3mTG`;uxBFX7R3tEjExYugr(^mwmhT)gN39dTzfy7mR_rAXKXRu5}t( zmY;{jpH#B0VhX~iKdLQAFExhdsQ1-p6FVW;d+LL89^`p2?{=hF2h;N}gcj^N+x5tx zhl^8x>{Cpozf-U;Ms#L1lpp8N38+fzy1tRiTJV#h!N(5aacQj;QE@b&$R&nmsa4n{J34(rvE5ym-O4}D!kQOfP zrerx6$6m(#33s!e4SKM}wS`?Z(z)WUdHe+hCu&VD5ubTjRYq$7xLad7u~9TDJvNAl zsU^8NOMX1X71Iy3l*FlXbN8iOu8-F%f-z9)xgd*44vehFftBm@gDJlC00<57yRQ|b zh~w%Avgqt8i(C#>3qslC_---gDkcQ#04av@d~+euP6ytXFmgv`(<6iSi8`2HsqGZA zj`XbXyW-QA#aw8dU@2^dw&3rXLTZ&B&^b<7z8UFOEEkA)5aDbKhAx}{Tt?v)^#;TGzIqx?}~xB@sAl z=G(rxw<1UCEfnjd{BY#$K{OW2Qx(C|dk|rm6ha~TVpRn3cS7C^@7^`uN#N+qjDv{V z!$HOdu#fo${v~u3(lP z@;hS=DW5qcGq9hr{4WSSm+$(w9w1>mG6k>ioo3d)ueQ|V>5f@j61&Lqn$GF;Yihk> z``ChH=JFurH{avM~|GdLUDD) zc`}xg)iH{Wd(M^vkJFDC$r^&?T$t^u%S!_A;b*QNyiVnjt4CXmWOWGcHs~Ja?lD67 zH=1JkYpl&(P~W_nWR=KlAi@ovh`ZGQZF)a};$&E7LVLvk#;%{+&-y2Cu}JWlMn$c^ zaSoyr_f%Ix*zSD0L9AxoVtc`@l%6=}5$(Y811X2w*!ww4ic0g z=Ho639I29-GL5Yb^m~FW{Y^O2uq?=h2!+>)QOH$fod%B|>s-~V>S10tfOV71+=4hb zV$;eDh`;!bPcY9(>z}r-#3#dIgU>^%B5~(x&J5J?%`Ry>6zx-U^e-ebD`-%#{7DYQ zs30T&*i{SEGAkW+6mrcbysxcMFF9Ot<^i@xv~m$9EMX4L0W8_OSRe18M}^-MyT*$K zDw#sf+dfo*k$zB|vlMa{qu|b?_tkzBpN?o*Z&PRf$V$k5uo}3XcFw?`3n$_1f=lm|eJ*N+ z#O+X7J{Ew@=AAml`VOt!3Y`-kh}P&;&RyciSo#1WK!B*?dFMyT5o2gpq<=NJ7JEf5 z)n&haG2ZDDz=8@A&3=TJ1V&1GK~hw)mc@e)8Jo3(KP3kX5`$O|{bY?idf0}vNG2c4 zD3clGd5x|W+_+;uI;-6=Hy8xXpak0j72xzh2t%{a4pn$uq(GIx6h(NT_2M zzBT-NBeOCI+$#eO`DVH}Lo-=DIzx;gCBdiDt$N@2=f= zATdCK?t^Z%f=A7$sK}%byT~w04;P{I#}rcYvWF+bfk=jr*nZF06>J%LI0l0xM8LDvk} zYnpNWG{O__PcBN`!fE5Z!qu+Z6gcG6rC7BSsSc1yI#eUM(+1rs7B$y6JAA&mp`Z{pjEP!Dh$n5m9&`!Z_OWOY$;$QuL(Q@;9%I=?crXi z_$_2ErClJ#Q6K?`01MOvGbZwn%MiKvCV43F)PP6(bFDhBBW~XwS^hS>9KHQ;W^uE& z@1!rW`B%SCX4Vye`n<7$vv-F##mb3WNax1m^A+P!tVm@{GRqsm0D-Y&E$QysfiV#2 zDvg7V$B43`5!9J~_^R?y6Ks?N*~1!Hw3Xg|;9?+L z26a%G%&*E~ilJG|l!j7KHe_VU={HjsD;whiIMIoVZZuIM1S(j0IuU=g@|IuCGWF+m z2P!bor94+ZZqWsD4ffO>YCQ}(`8(2#ORWw1; zQfUXPaL)l|*~GH(-~MLSiUmR?tE!j+31Pub z$ywvu=b&s?E~Ax`-?}uNYemiK#)BH|3;z$&RxEqV()cr&HI;G0LSK?m+w)VQ(|6LJ z)-I>l)=3{jt9FSvTkH8wf!>}kDm6=|b)7R8IOe6#%F#=*NJE*O2L6r*9k~F%A9d5@xqYz5?#aGx`EFz7tQ~tWgU5< zfO0FDEkBVAz`ApKaD!^*66O@jsx8E^fHRr!1w5bjkx}3>o#o;^L^o~;h%8vxOd2*> z3ST(&%w!(WzgPy;E0Lt*Kh?R1)xdanEKogt2{o>Z5>CN6ic;6AKmgxaih)i+tj43# zjF_pQt)OcZ{1S6Y-9gj({!PB*KDPdiHu#{%;FdLo=@-=iwdkpg`?g)P&RQY2siW}0 z(z;;P%}D211j?qOBUNWIW=|Yu{`fiRYTjRYMem?eVR0T=?#`HSLshF|P42H9c zD0?7*Cj`q$+E$z3zi2|oBh|HQ&QElCCau+{A}ebLZG-zig!-{W{HJ21(I4F}Q+Dw% zeoNBRsc$``1?EcWl{$S15Dhi}XVCqt!bJWQ(0ZHxQceQTR92PX6?{^E{;*-8WI6{; zY^0>T2XLn4kZ-Qs=w%aRgtyg5Hk&!`hTJ@Gks8!cX?a->G*HQYSiY^_6DR;t%A>ed zFjvL}M@!i%Ecp5r+f~@8t`d2`v&$gns>c_|l%qQA;-+$TGRQhC5C9v`04hLhNXuE~ zjAcc_-hSRQr}TNV+-{PV9gXwL{mT>@f*OBV=ixq?3lP`b`|7jeBVr@|#x+H>Z*G2A zy(BmwC)^|Z$e?lgc75hgTNnec9xxDc)Y+P`h^v3ql$)XOa^lSD-aT=g9nhsqD0rV{ zNhBeW`zvH&2RzTR7vuIMXO028;2)^=6Q?iXlN z2Ja8&lPMnk6i)jjW5!+1=+zclnstWzGG-tv)$kd~;>_B~ko z-X4@pxA)=MX8_=miNHMl5As@@>r{_out-WUovYmr+#N}srUYptNsF^ zl;z8Qk@WgMw9-4Qgz)fygMO)26gKr5;O3A@8<@Iz5+^ z(Y065oeJ+{{dksWq4NW4QbY43=Wpa?jHjSlpw8VSwOy>AgMa!Ma8SH&xkyPqoanAi z4UOAhFN3eC*YMega9a7f9)Yxu0&=dVc?zLGe^iU9`44u-u$9xad45wkbyaCSo)+i;2YkOK zw}$dch17C%tk`ZVsO)5jq%S#C$*Q^nbt}nNMxO_~z#~7xl%%2kmyNZ00q~;T&p6lp zcVV3S@j>Ia-!LY-b3$R$r69M+^R9XURlv?i@g;F3qayOuXL7*^ zZ(WWbg&wK*9JvADa4yw5V}A&tnvIj4kQLv6|C%<_0L49qS}VTDc&C5xu30@+eNXU6 z;Q$jL1Rmr7K`405rAc#)kMBgq&*Sp=R2x8c#Tk4+3`1Yk+!vJ(f&A5xXmlsZ;jnF@ zdWxyw%*gmwdE;4@UIQcKAHSv*^da@KctyG1r&`X6?Dz^EyN692)*QOEvi zG>>z`+&OBR%#|2CvnJA=xGdFE227KN0XyLMcmPwxhNi;9YMKf)Qd@3rqOX^tdGI_E1N>r1MgQ9RoH>W4P@xH;|EF`gqVs`;hUy0XK-S{BXW% zZyxr{M6#f41{~Ykt+5%-b1}qMl6alUKeNe(h)m;5?lBb|6mA=P(j2y~H6OngG&VIy zqy4Hrb1y@?isQIL{8!l;LP5^5z9EkAGM7jhFTOJEda@a$j?8P(fpkS*m`paD7`GDw zLuIOQQw$&(+2d)0^Mn$rMVt3D=f~u#xC!Cz|0b+l+T*W{acY+1< z&W>6hfFEeyxp5xRx|iUQxqSC&f2lc;d=G)cQ#Pg`C@?l#?B8dcOEaH#WbKKySV2}mebi(t+o4}(+mpWXluttrCi{ei9 zAT3m)o@A@6-KBimDPUFy-2O)5-tA5+eW!C+9i+9)3iREmKOBr`QA^~cX)R#+?Uk$y zE4%ws>sDPZgGKhWtqcCWFEZ3C3t)e_Ywd=;m?;%%5q%LKT9!+fs^fTIu^Pr0V6!Cw zA6*rNTdQ^SmKdA{&$0Ir(Gze+IwxN}NCSht!_}k@BCh;hpfVe^QgEn=;zL?R;T+B& zmy%-U#d@BY$Z>P}z^3M7v+eMNXlMY==D{N4OIsPtTB{C1>YI|_l0?I<{sE0&{1%eA z_El&pGF)51)3--1^IOUEm!>3;NIxdFs4e5e3k`@mx>3Ti+weg#MWVr>VuRh8vpe+} z34TvyAj&?$=}#u}EW%Xexo>_=31U^*{B*>CejSXkn4>eZQG69h1Z`K?UdK>@P>rWT z>5xyTDi&}DuY~c|tlbPE@c;{=UNaf3$g0Egm}|W$NXc&!Cq3Bw39SB0`Mn|h6B0}q zC%1kOD*M%2Yzvc*mXRKi{R)YtZE*XOWN)if959yn+pl&d@vgfys3-NX{b!Vyt;zN63k3 zHdc=wLqP=WMsBxEja17egJrSp&i@tJNh5MFJB`I6sZr#4MF|l3nhcU zY9hSG@rXHblA-6JV*P#Ca%h)e7yVx`u)8Q5D1p}|A`}<9fEg2!QpbNg(M9b4A&U`6z{>VA2cLQnLz~nKhFFph$qKk8xswIef z3l0!kl00hfAbnCbGENml@&YN1m+x+8iS#a26%KF--YSn~@>c)+#32hdL`o`0@T`7@ zXB{&C7^Ilg4L&Jfa9zv~#%7?~xT$qS9D!8}@_+yeI1vRM|!f+8Wo{_v|aF=Z}dDqRwZJw6B}J#7HD8ph~ZAQzKD*=*!@ z8Q>yFJ%OW9l$RitI-}68&S~Ahcw6mkvp*t_>c#mEZDpqJOZH6?0MPU|#1_y-R~Ksi zA<+=gM;~@@I`U2iQXJq3tm6lBD{b?t)0@<-86OF;lXFuU`ijxHM5I$gqU#I9HuE8+U58E2*%je6}Z#rzgI-;|RtD;qm6cGS$ z@bo)qgA^R`vS(-+U;{s9SI2-Q82-%^(glb z;#zAWr67v4fApnEfoWcab^pN$oj0Y7#oz;YR!LWWUIY$yz%C+NroIfG6yka{(2bwcKK7hI0$nRbO!E)EPVIE~JCYn8c3+Fdn{Qc*V{? zT%|GD(}mf#&f_0;=Bl~%)KnNJP7N{@Qm?!w-U*K}H}9ptUD|=*=HJ+rh<+S`s;#?@ zt$Ze2(EkRE4;Ik4-xABhb3Evrf$$8X+fahd1D|fusvIO!M1J{Q133;QS9`>^;!Ptv zCgmaz3IYUPyi}sHItkMYb!B3AE8YB@l78Yt@gWq6-}DCkN)*yhQ=fOd3O3`d@-;KW zl8DFjgb>3Rwl!Q1qqrDzkg{IHWSL%!FDkdI55)act(%na$Ylz_q;r?z(F&S}TP#xe zMBO(5<()q1f|q^DtSE&6<17HDwq~sQeCl%$Bcg1*M>NYIfc<*x>#9~fG^HgJt1KD| zTLaBl1J7$(WJwU|QLdE>FmM0^e1CVFz$#pjzb*qJU3QPL2iwkcL(8`xph%4woc2d$ zNg>eNqe?6J;|9=bdbXJ(kQL}W6o~Q{AV(NWN-Zzd0(xk(9UPb_~*_n@c z7plna_{u4{?4BJx-$^dn%U|yCaatPm z74=ge0f;Ia24aAI)9Wq@k!WxsHA#7|JSbk-yi$X~|AAP8WAe!u>P4sL>w8(P{;J5! zM5+M-3F>jcQOI}w3$}LgcEn(+#5v-a4?IreP8TwEH{)dU!8HwxKhtU$q?T{EGys%-x9gY66U4{hUc}ZSXEfg^XUj2R36G% zI+>t(`!`$z;%%3MKmV-;?toazSW7syw`5Y|A+R@wGH}887tdzeG0|+{dIrsV;B(9C zMqpQkobOAWETaUH5UJPXxSkRdq|u3PW2Y?{GYlZPz)o{XNZb@deJJ#l-pT5x$b=&T z-oF(1MOuU?F=(|JEH}ywK~tq?nAIEXYxU2bKOZOj7)1)r1m+rrYw{}wBr;puyEAe= z_$Jte^RvSFKVr-bJA4Li?Jw~5tRMA&HWF;`LNTgLc1^8W@LnYmF~6dQExlQ8QGYp1 z3@TAH;ssnm&+0H-O-SO>>hFf;IdMnm%+__t8@%Xd`Glq4-@L<(H_0?9&z|Q|B6`6T zU7iUwY^Orv`P3trG2>Btcl(kgL ztt(D`SiUskhB2+R01yYH19RGlPTPTGC~J`8vKQ_|1U9GM%X;+wZ0Gr-s5O{`M#RD? zPu%=2vK68ee%wO$Y~ER!ukN8~dcIBKNRd`w={9W)%%r_JQl)Gu_?%jE)u*e5I*iyr z`<@qjK-yM+V(cUi>tJ_GqWUh`j zQdLWIzY{Xf<$OEw0b>h-{`1~*H``z^>L|DMjJ7*h#tQUG<1vDw7-7@x01@`JDjejr z+;F|G9YyfH%4FKJ*I5!}x=ihECG0gFuoIcl89jO{)x_cXcM*yJ3aqTk!9zMHY|D}S z>^_o62g;*6seCrUGUS+of}u;<8r6v>pPVZ)dmMIJkmKs}IcFwNEj6$WioFrs=alf0@MUa}#1o=Pih9s?`B9m8E`6Dd~Y*W0&CEW`YE7e-ilq<)8m z1-6G$_W+rH5kbv7@!Rb^2yaoQQnIQXjLl($GFxre_W|`|FVZ8;KIp;h&cXu>*;zxJ zOgIB_f!&HYz{~)Sku?BZlU1fasXSV@m66ONK;4(8O52av$2ma=(y+nmM_D6|c4W)v zT5@^4TAUB3l^xG;iZCylZ#j~=fJb~6N+qmyx_ zLD)eH@%MpeDj%PVl5Mz$o!5DI>eIW1-eUMe1yU>|1KO}RZEg9%o#}yG$<5)N7<$JX zAqr9T0!>ZdP@Rd%_e{=p+{Cwp>{ocWL5}C6Gofog5b=wyBd~*gSM(GB|zKG5i;B&Bi>v(VpHQ^>2KF* zFt0KW;(|{oRo63FTjsEeldiG$HnNs^_Qd`tCyKIYd*-eeN*B;k9khxh@A~y^iZLU2 zR&_{vJOL@a)!fz^1ePQZ+rdcB3b?0T9Eg=O;h@ zMydDMz=QnipjrkE$8Gj&o5hV?F}M8_to?;QcJDiy(1a1?wVT1Rdqa-WGks5M(tNgy z5L(izRyyk0XgZe^6lu9nF$K+bESW$owu0g6_<|q?Jb3N?U)=XU-U4n?>uQ3s=mKN# z9Z{$iCOgj(6jg;QsoBr+>0&xqfwr@!IrRC@(cfhViT|NIf06_Q^j%B!?(b-+3FCbz zi!%lW8it&=gNm0OPVOXC&Z$L!lF)r?NVpsh26lz26vmbHIEW3P1McaeM%h5`b)LUo z+pQ8hJ=URgQ6Bd9JJh5XV$MUH1NXdT0g`MOh*wagV1wMZQcgiO2Fy9Mv=)Fo;!qE5 z005zaKVBepNbup$K-stpGz22g#PJ<1n~L09fn;4+UMy_>`)DQ+n~!xz4jX;2auyIw z46QdZLl&9PX&N;T8pr1^XzwD+2BCp{Cm~)Ktsvsuoyw7S(fp$)?+##PeCr+I=5G@t zrQe^_A{(k1Fnp|7){$(3t-&*C9ztJFAg@<07E&|+4t60Xaj>$fCZs%PBJCdNj}3yTp$+7 zyM>GKhMvT*l_~c%H+tZZ0Vu-M9|7M}u>wx(LkTbn4+jv|7PRErqi5JC|%wZ5j+quK}`l--K-;*wAYZ2 zhPMPGZpfc4vm!;;lbeSkVrC09&we3tGn5Bn-~7MZmPbR*2wbpF7WFn)V5PT!CVE%2 zti(mY-OI0|3<4UFXVBT#JO#L8pvx$d(!;bPpNypQu0mK5eeNQJsy`e*G${3B!A;kD zZ|V)UL06WxM897geLw&|gTsnQ1%}O~V*uJfKn0FSefLI+F+wnO z;%CLWJ*+ZB69hrw$yKjMdSBvB#!F9iIR-(99!7WXEzfjr?JEVf+4SPD-%R!@1z7;C zfJ%aOxf*WS&4lke(|jmC-_nbs(?MN?)xpv#Lj0w}#<0_4Tr%E6Sui!-fpXALw%axQPl2&%pBhZg|pqGz_@S`ndB_y zhVchnw}`OrE6dWXwA?|5bfif8DzflnVPo``>JmJakE|KiIu1svrYQdXPm{FTqu^}U z5W(jn37gxrk89IGt$%2U`ArWT04EP()a&?9vQlASA0f>shq1CviRnps;OA5LtU|r8 zKy8{-@NPKv%^Tc_4{vW5dEKBz9(U&y)^!h+GK2Vw%RFat$5W*?U-DBfb=j8bv%k+x zgu?5Ke>uIAUX38syrp>5Oe&T<`4VK82=R273G;p_^g}@}-bTk^pk69_efI16e$BKJ zpCg7ij0+QkdNIMMd{eM5;ge$cU0ANVf3*ksKV{b1v_AgweM<;D0dT9ryC40GN|Cl6 zVfg#d<;K&ekMtW3PKTB-2SdV)-pv!Tr z5^p)d9|Cp{#Xo^D)nDjtALgv{Ff6bX(RAWi22XXUY;nosRw9Y^4iTSly%pmtwhIbD zGDSz19+C^@Vt{``ab9}JITT0LVKDV@b==DFyc^-BCd#5F*&C0K^wz*h6W>to2&Bv< zIb+_K9G(PIl@?4~4f*y!Ov?8H0B3mEi*MC51%g!8H_3igAzE`1G!p_Qe)-vKA6Od> z+?6z{D2h=Wa0F@3vdXK6E=~NBMW_p|Y%Ihg4GR_1Umpeq?QL-v(U3K>vkMZ@`y`eE zrnW-yP@qu&E~502z{gGb%6)(5!O!BD01K%_UI8~3zua*ydOqOeglEgVr%RE&5R{0G zrmWy7N+BbJK@m2P15Yy4eWuDu+7TTs)QaMywj+nKQ~to2R~lo2Lc=;+LTXS>uB57! z)2wXMIjNVt1^dHmc`2K2hOVyeDwFtuO$@=N{I^npV{?5~f=*_t7Ue2_pXV=Rml3^L zMm*bU@9_E+clmHNY{_eBAHdoXj)3?DAvqrS&T6zTmhS4b&QE=yLo;KQn7rCnftc6f zI*%T{CnGZ7x!DKz4C^6-EAS~u9|GY#>)uf~nOwkvbX_D4I~8|VD^wN9s&L#4m$_A( zIZ38xS>1_ZFcAa%Djy!2knC2v0n?j7@b0 zDAp>bpS1H?Xl$&`;EoG|&|@SRI0OVh5_qXhYUJR<+iFV_g^DqIiV`&39D*Ry;v~GJ zSO-qXzADI(Yjv?Af=AT54UIn(Xv1@o>49##^lc!H*0HJ%QJj zni#Q*^%TGZ=_-@?(GW#({F-WQT$SxlW({YFDPC1}X|b@prr+~Gk zVp`Df@Wjd_h!5EZVx*>#?JEl|SVCb?&!@@eBEpnUpO_3`T z*>EEruybB&y7W(0_x}q;j685@R^g18kP>}C)YxXR`i>j5+(?02bItU2xh|zD;{Sin z9^&77>Eb)1?xqd#sh`i4SpO3Wtf}DXX{)Ubh4-c2i)wMQl^id~-ZvVl9PFBq*xDq= zhRpoOO_yvhTtmW#d?&W*kITl*vw*Yg-V@%pleUgRS6T1@s%+TM+Wxo-;?&!y(_)Zs z_wx%jIJk^+C`?d>&LIB}#tlyTYiE=<=f$+KHdTOBcIV4IvqCA{dIDh9w18nl6!8c{ zi-=eNUs{zd7&@D;zGgbO^4P?gz+`d&XZiaiHlZ~F19M#kiM@(MvCOTOFbD@n0#Ql5 z%gA!silytnYPK~x%K{hm`wRJ8hG0X_3Co2Xnn6q3@q1_a8e*_k^P}cZSbx+0hB^{dMhXvo*~GDF%r!tefxg;F{s}9i!apvM z5aM>8u@ATQhEHGFxP@-^9?r5ZM#gbmAA?nF!ab)qR`HNj%O@?nnls~7j(_gca+210o#aMqU|Z1IkYgyd+rKbYq}_@5vWJp7M9qB6<)wRJ@UtUP~qV9u1Wo~cX$$L z1QTo)M|oOaAQ%u*B9WuK7dX2UWqv40CH+!P!@nThY|7%NTT&yI7XM=YdTud-Kp*V9 zMt>D7FHb` z@1o~XMhm_t1OSw=fnP2YAD0TmnXw7uvY5R--xg4ewxa(7nW6+|$8voIpmYs;AE2~V zR&~|u;HJV!*1N!`kn!{JMT?c%Y4i(xC`?;G``b4Ak0lBE{Im1lW$q1EAvJp{iI;aEadE`;>Pl$2Gu=GrLeM+&sD$ zbP-<3;fRyz0-!zV`a@Hzq$-easo>uorC+B&>ZG}URTs#jm*Ke&Kif;P-cL}F*^^iI zvy=yj(h^t4NX)7*Z@1c%Xpcy)~h~B+qdp&A*he8SB*R-^H>9KID&N4Imu7GmS63yE5Jrn z=7uIriv0cSL?6?3kKUPem6KN`xw|}%kz1V8dt~wt)uHA+u}uKWiv>%GYXhQx2^fGp z9WzVh!OHZO1&i&#;1UOv`hFwzG~IgQWRbUS_(Md$kcfhIuwbo{wN^nT#8d3>$e{lz zz~!S+ErTPZLST&%7}YmWPjxiVadS6O`H&Zc^$6ZCP}3xVZJJ)H2L4}W4-Pm!1A}ey zga4&M4qH{y=Ik_kRz$1l>h_CMz4Vb2F_08HUp~Ytz`+u5V2ckm8h8Fs4 zeBmL_DBOEe7&9NeCmyxm?*rJp!Oy!Y~Ku z67(;#x|43_k_lUXO&U$Fu1CQ8{xJ(C29+M7r2b8C@OyKSU!JuuSKT7^Dux(!?TMvg zO5*H*aID?vI2@42DxhN|2(+$26ipqWA1yCiNl5@V@Gs_D><#n{i|PTPj9>>^XWi2E zr9&+9r{yimTADksPyo<5pe^yE*WBUU<9umOjr#;Ws{z(p_fpilo|^C4pX@i z2AW~?*GXNDgrF_)T#N;hRVE^ZHFAT6d_)pz9=5JXY3}O_AA7^*HkH4scD}pj1ajc4 z2cb*f9piF8@+5tMau`89&#s#Jz)3cBRCofeXpv0+2u{qfHp&V(_mz}2r?Qxq zDTS4%Ohya*-sMsJBHNzKmOl;!aG;&jk(BmnKfm2&7C#NJB<d%e)X2+RTrtL! zH+oc|CaAY-pUWbORHMq69>Ynz5Q!z=A&j(8OyTr4K^W1;mx5;R2V_i$^g#pf!-iwI zypRF>ZJ2En$28aJv?S~vc9&A+SHyePc?{F(bDe@+`+Vu2zj=|YG1T3TG^wmi;brWZ z{rVo4gh+)Dal;N{9t!W)8VT??K}s}C_=lAhltkR6|?`{?vyoCBk0 z?#nTKaMwZXEGT^c*?xxE1lBPeJ_(j0i$1%Z*7Vp)TwD+&wQ z_jPZel2gD)WC89QP(rK7!7b{*JK{>=QaxWpYu|i8*Nxv$&I!Du4&+hj_euobV+kqW z*|d`}PMNK-bf$n07S!y6b9I~2Qy-HFO2ky)0^?Z43yA=!Y^O1)cCnI9jp%YP6|AYi z&Eq@rRbV&L%R$HAuuyRZJ_hJIC=V1!U|6{Hixg*h56uhnWe)d(7yt*JWO9$oE)~70 zzruAY?io@btCYQnr7`=$YVVXB;*NYDH1+XJ=1cn~QYs`K?D9Ms!y2BA`1Pwzf^XJb z0QaI(Pg1|9o5QkSrRdR6GU=t(iLJ=CED;!%#G1^bOVj9=wV?#&hBP4!gd-q|{zypu z_y^tVwZes? z8AbIg%S?jAmsz#-J%LAhI9!&Q9>-ZGA(^)`0b^Yr*M{Plh>I(mQ9q z8Tg7Wq7cJF6q+H#X0nYj=Gw7bf+d`7MlqjU26m0p`>@{Tb=_}t1QCvObUQ-&H#(qk zCXKidml2=|LmQJq6BXC)F~f<7VIU1a7Sv9EM!h`Wbd_4z3B`65%T1R+m$iTp3M4&_x964xcZ z$$(?rB*Or$oCJmJS3{y_b-h4|GbIMaeuuJZ{L@1Fz#u=+_bt~6N`pxI16OCH3me2m z^X?e4w}wo^^A=pr^?tR(L;6j~!;GyWO2{74B&mbW+6}gVNrVvp-OZq2wMEyB#)toH z&QQq5#J?bzw}ARajVf|j1sQS*m-13;E2`i60LDrO+Oe0FtAk$+$e)jV-)Z7)8GITas?h%Y@-H_Hd6~|3mBs*6<5~g72%Dj z_s@~^B`#=&+c<$sVb=>gYN62BpNcb^(;RCbML&t9ar8eI)sxrg@Y}2k)I=B-T^465 z9S900FYYkziL7fUFnr#)MUUxa8uNvfX== zXnaP--J@{JL6?o`sTHGwEh&GMe>^$S2wF~B3W!D5wc^gku4aD<3Nw}~sGH)$!#f;T z@Uj;9OOE>;yQW~N4$M_y=4^bA;`RMq($K1dDNO_UsMy8wv;qF64&$xj67S0%1ETr^ zJkX&}+A5{XH1<}%Jm*3+30)_m@VNOJ$kf8bfUM)>kxS`*rUh;Dmme|W8xhsdL_xh@ zJ~$7dz?P9OBw7}JDu+t26VH}!2Gpj;HLd1U$nD-n3vT_AVF(}nWO*~vY{X9@<^F$s zYy)>@o*YwjJ8gNN1RXs68Y7F@bDIS38MMdipLI2K@s+2gG@e7`!CRZnAB>7wBzE_M zZD$bJ4LKa9?hm7^PJ&05PG{~sVJP!P1<&7k9}wk3_c?kPBo`m&o{-;>fYksOpj5L`;0?r9!$?rs=p%N~{kD@qEdReYmj z2Nm5#e4&P1B$PBTH`s(l&S-GSw=RUaH{%x&)C1WT2jEc;s+1Gd9AfB?juK%c+dMl{ z0u z$g|KaL;qoZK^YVK)FJz9ZxF3;)^BcCPc^Ap>co0IO0+CgDi2km#?rM3=)9`6jgii% zfCS%lIP`=b8xzx>nh{C=yu;a@HIfI*r2Za0N)f+Y_x9Hju>^7(Mu_A{qy##2$Uzty z3d^OGAG&>C)2j^&nEnJSs;0=61n~ofuglAbz=#e7bd+h&zDuhX?+}0 zy7c9ZodE1ScgX%M!T9qAswQQLuaTEKroT3ipyLj6WDNEM&vmwsH|ET4f*pbCU z@nRJJ>bW;t;|~ryX)mJ@T_Y{fBn7CEUI9B>eR6z?RuY>?xMi#*D!<;|$#OeoAv034 z35G^jgVm>StfGSzsA}e#$2&05yhQ@4m!ASvpytey1?+1Bc9l_8Evf5TiMgPPLxsHo zN>#&_(w4&CoDUQ6pdjuS3gR&T%burvXvnxJ*bB5fgJxLBg8Dv;y_QkAMDI~Yz~&GO ziNn=3`^OgsXr>U#bW<(vBPvc~<}dupUNP`YO*ap6fLHk%fY7;ox#cyKyw%jkRz%WU zX6OWR0Z~&YFbQdCuI0O^A}b27!3xDe`v7XYze!CQwvO051~Lf3b{lu)UBW}&G4U0_ z1l0)wn4NT>eP&lk|AizW&Wg~y3oe?0xYeQ@tM|MjBBkCMu16kGsMAi!e z{LDOuU2PV)l|T?kv-9n=p}wBED(~U+@8;elJjhcpt?5=K_+>>knGK zTUa>86TdTKq(w>h=dE7A9_`%Uy!q*fh`G7+h>&BN*bTo4dt=cc)4}a4!|?mbO#dNv zptCO55tFVjJ2QbHG{D;anQ+b#@MlE#Kus0;_olfP@t_T zZE*(5$2R6QNLvyt*gV(hcnf7v@|&!+7S&^T%W}ceN6B2#4wEJP?C^BYQhv9WM_%OY3M_b;OJD#ej}C#Of7ck z@*HFY%61qIR*;pQP_e_FUg}Tbl&54c0H~du z?YiN#SmhEj76BREm~|1TaaY&X;B9SlI9c_Jcf?41DJ^fC3P$bUbq zbQKR{CW9*Yw`-S9{j5S2Hmn${i9a)Y@w#z?jqaz;`TcEv_1w2RU*Pt{A7}abn_6)< z)U}nFhf1+?ftE#@BbtHw-m{60tK5|>P*{+ir+{$%VwRSmG;^dOZX}%%>bDL6Mg|Sd z*kS7*M~mjvt{x@hSeU6UcVp?+3d`d70I|>N3Nq>uqMjWdTUEZ11J%_);%F5_&P-Rf z*BBjCX;u=9Nt0@vWG8C|Y_!Mxd$%mx=@74gUCn2pEC|=M0s)9x+U$*q2$sCP`vl3` z;K94OIqbvjiQ~>4INSEK^VNR;VhLh-L~#g8YUu;ZFt?^asc%U5(lYBwh}g@ig(SCD zeo@#-;qxhEC>*g<~b=i8?L8(nA)TAKLi-C3axk6AJT{(-|#&9C6f zV(HUP1;PfkI1ZhIBU&Py@NLpdQ+JK~i{>pZ-Ua8+lRScQWrHXfF3Fhk4+0=5U#|F5 ziASo!Z6JNi9;8Q^MvV*iDdy*Jwb^f1b=uIs{ zooO{h|NNx2{Z8O2M_&XmM&_h^gUI7h_mr~}J?Np^gvcJ5zU0f)Ke`s-TAdAwwk#5A7*kt= z%-f8vMU5fhd_y8{PD2Sd*)7*4#fQ>3`6XKk`0I|&74a*vh7vwHXmq;j2 zPh7Xp-SB%v3L_6rB#>+>-V*#p%Q{mpudv-oE0(uHE@Hl8JDG;b1`!llk$|(ap(urI zxVn3q#b||!&@khVRG{;oU7V&)lX`edl0ULI*d`;XgEH&K7CO~QRZym>AYM%8E1~)AwlhYX6(0l zns%2ZehBRvBFy@+M`ScT_FIs##o(Sd={pnT@LWgj3CU`&gW+Pu&C!)!Am2N85MwEN z_SUMVhkN}R)cz1I6i?cMRibrh(`V6twK}!`%Y&DOVd~B^1>&JfgR?0XV3!&WTGlDk zItn}<+Yk0gx+1qfQkAFx_iX#?ItU|8zv)anYQhlRC54G?D8(H5y-IsdFKa^Mb6jUPvSCSvyPF8*y><^k!4|liO|Hf*DUE0w#Q8K zGrw3Co!RX@{Cj#-ER{upga41_8Fu-UWwmdg>56Fq3BT#Ka*~%kFF45jSL;C=8I7q# zdj~s>y+L=!LeKPxhBj9yW~b6C|8@ugsnjVFkO9=JkANc& zm@5Yahs3pT`D?&(kU+t#v48HfrUhBEOJs@kXaB-kPuZNLDg|4CiGDgHuV z1Kh7$r^*wxbrUTsl9Q0uIyu9V8PcMUw*8WR$w8glbV}H@AQ2VHzap;t!Rt^aQs>2Y z+0{cS;bV)8?__N69vZ~ML6AQ55LoIc*>rb_pH9w}^O!)YMPTyr9c>I(4r%*C+(u=R zj@UP+sB6b3yNBL7nNk{#F%$|!TmrOJ6QOXyMFhYBA%H@X<`HoJHYFSu(Yhy9`B$+X z3P~2ZbJywjQ0VKPPR4@DFqQX&hK%IF+hi>$c4A3!mP2pHLm9Z$Dm|m+-z;N`zn+GW1(@ zp)Ae`Ktf~DRhdzOmxF3h79k`d|E`1*5!}KIY!YB{(f_3|enxTrmAp+N?@>X0LMx2i zq{o|v9j@^*aMw!H(?gi*{8~!IC`?XYR}!}3M6LVu{~jGk0VBnScrxM7dD6}FC-!UP zCYxlzrmzF|J->=9YxC>B9vM?y^!P=Qp<{o1Oeo9MQ|{G~75wmpY{THhVLagsK}q|* zZk_iUp&Ie7MSf_@b1SbckK{}g2e+HTur|DZULf_UrzoC6k5i^MB?Y4UYCXccyF45$ zBlWm^5zCbbKe?D|&#rTm4A)o{;^4;elBS7!KR}FWY$fI{8DY(Dm2*JQE49_F0Hmuu z9aIN9?QG^)ZI|!ClS*Fd<^0$rfp1?f7=~5f9o)~JK zSlnu8a|q!jOAk#Y1zkT}NI82@IO5Y)jZvsZE;%To>@AOHh4E+cQ2 zc!PVoafbkHZ=kBRG7Z7dr+1dkqxDis@o8BVMG&J?EEsI=J6fY$T1NQfblDa@_}~Sa zY3rb=4*1?=ULS5_eQf-ggemf}GaJOBI_?;!-VeUPJEfKL`S5l9#A&Lq@)!uIJmoLA zfXCczGQ*Zx&Zv+-Ja;xSj-jP0z|alDNJ|d0+jILiUES0S1Ob*Z%%JQ{YlWK zLcnQbkX|YK7zQ=%j7XXyruvTcRt9PA=zfU<%s~d^+nr}%pl#1f&MP!PmH5*2$qOUj zj_xp*rgB^fi*XG9)p4`5gNtc~#$L`#M<~sFpA2T&`1~}!YyZ2OwJ6jRx05v( zv8J;NM_?UBVHe5e849y}D-)Hl0@z%4<}N~B%O?`cekhx*_Js5YMR`xWAV!a)M@oyS zvrLl{n=)$o;drT&cBfb3{;4k0Hz8ZUdF3NJL#^EFV!*Dx^K(FQ1|c9Bg%o|j(#6#Y zR}2tTF-0UP&H;_Pq$MfWD)S>Le8Z z2-qUy|E}ok@U6)=Mvlv#ziL)`3^ULn1>PW7R+&ogvJ$!MCl}pF*5B2hRvhtu5{!Fp znh(0Y;F1VfrQyUn7uJ z>ysV2T8qw|ol>>mu7=wbR%B|Fnnx(0_XiZ^&Ppv%ooelTXteVuw*8W~t}6mLJHLc}gQ z7XEw>On%vvyE%&mk;bh#Rg3$%MovN{EqrmLvVdRb1>y8w-sbAfYyB9&qonEL(_2>^ zivZ1bR~*g5u-4K(-z*p&zU!;mG}V*kHdKmix9xTWe!dRvTPa3SB`!84H4NMRp>3IAZjQ^R_o9mziLMyP=qgKJA=77u-=}E(0D3;laBN zvJiu&|bp1D53gme16mzSx^ z4yoh(w+Stc$Da0TyK+Wj_9?5u1)W?Sr#&yyw>n?x>cVQC zYFXS-=4+CA!38{PKlsH92TC?^9vt#fj@btpvE89azyfRw$Q7=%?rBoMQDv?BgeBv~ z1I@N`j}Kg6s!--G93aNJE1%}@8aLu%c;`ihllH`gNIBxl>_V0PD5F_5-0npd@cs}t z4vLZoSEg?wIYthZm@RoDxrW(6#}O{dB#h9CUfPn!F;hV3tt(-h=M((eaS;8k1oGu% zQKS1<%=)!D#2jj2GaDEHvwd6>N6{9OYzAs;2d-K=S)_sF8=d*BtBlRDF*Y_lBn&pU zXHq^~E!|Rg7uF=sT;h@vm;h6vc05P&@#<}|$Qv=U{ zlA;sK8R?;Eo4%svKps$C_uXkRWg2asVsDzUilVTw`8D)kAxutWBEbilD3P!`9X#VY zJIpZ@QHhs3zHk9u97N*jdBH})Y>=b2^NrjU*mtmxp{E#N`D5>gvz$tG$*BLK-sw1^qpQvy1P(|)}5u~Z;j##M@q0G6BK+bb}Pf_yR zN&Lz1C%XH8k9wC<%8x{WEd70=JMezp0N8l*x9c0)kii!QrHqDm{U&gK_v!P`mE__b zXqMA9@w4j$0HwyMP{lt+0Wx8CgfZQb@6p@~K_Xgq?_yP0^s+VV6l$e>p(eye*$Uag zdhu{n`;sQJqj;1_5?nCO+6~sU7!mk%yH#x*Y&=Huea!cej(w&ZuSuzzRbI7C8j7FH zvmtol?wtbpbeDJRslaNpd- zb7{djF<^{fBT(iG0GLe^pC6B^%HB6qw(bU^?*^Iwxqm;HIx&bF?cv)u$WiT$bKAe| zuV;Az}(!kfcTVk!_^gju`ntyYUEK%fFmx5vRV6w$@t>rpA|=vof47^PzkRuVA=`)H&wWl)6VW08p#(j+vk8cErk^DwkXv2V z29L%n$#Mwt`^V8q#8w~nwwBx6t5e?1asCX=O?3dev+G<$(i^7p%WR(7qf1~4buFx! z7R(2vS0Up}lf`BO`zp2*t^YVKf?MNnW5NxFe!aFON&(r>qNS|4SUuOwDH>jhZUJq| zdz2V!dE~(8N5YSGadHIjdGK+o1y(pb5fwWkU|w@tr1yriz09c|_p`YTPv?O(li8e5 zTXt}bYqSkY<;-8!f2<8{|GEdlYc=jlDQ!mu!VA8kalilpJg~v>OXrbqPGBbrwUO9N zq>uzSDvSBTRmK{aBiVTUqi1@$NJX;Y6d6h>-OZ|aIvN7L+vWKTXmY|Ss@wi8ULfvC zqrP>S`zkDT{QFz*Dk?iGU6!eT%hB-<*T8td05tM^(zd#^0HEX9z^^o(-QcsBsgoc( zQ2irWJhS!or{gcbg+Yt|G*LuGbxP4V0Kp&NwErRpUhVrvNUOKfJh$acQqER7Vv?VL zd|nnXRm8;bjQM+}f5g)?YB1Feg>CXRMI@AuUizDqC_e|FYp#W0C|acUkYNrBKL^2) zG_RHUUsiMXh`di2ozfn{O~v6y2LaVbEXOV-A7NP{VgmnNHfO$ki%8W-jYj{A@cs{% zPfyM_8e+Vbn(7Y^T2~O}5K5*%F5m#+(0&sqAwdormE~hu*+;42ozwaFsAefoW=i&m zw2}(n*JtQ95rxPRF}I98sodTG(`Kpr&Pgr(>VdMVuZbM2uV>5=C|M=2897(w^1`Y90+77w;O|)?N(nSFiktpwl4Q5Dtgum z{RqnY-aY82BwEBBqFv4ym>ex>nV|#rthG1PQwK#h#k@7R?ysE{Xwyv(Y5`mW(2nN!qYcwfh%Y>H|k+kSP&Tnp>$5R?$Jyv zoII+0?DQ)ox!NJ%b&Yn00*TksD={$bp$G)qhf_kt8;V}Nn_zWZ_&-y9U=khy3y z1co;7-<8r(OJ5NW*ao8w1{N7X5L>zRf341cj^qj{ee$17>@s!jndk*l_d^ybsgZ%cnVRk9>08Ph^#+)Gje0E@_c@snx2AZ_NZQBfO zT5^m#(AbVZR40lDT$5pdbGSRv=SnbZ&~OjomENc7GiKFBp-mU7UlR%GTDue#)d@qI z_^;`*#$f>N*5+JX+*b+sCXlB<4|aH&fBwJ>u_L#yEiGw&Nz}L=Q4a@bdL*WTFP7Wa%Bl zGTDeBUhGa_)Nu~!pi;-3ecg;vchExsHk?;3lv?HsKZy#zzL_NSEW8rzjrsmuNPy*1 zQsJwwlwE`CFT4hm-q&I40hEvNkzCEubPyZyVI+F}$w67(s(nr{yL?9hTRPSxKX0yf zRInzf>i?9_|72)!Xch( zX8XrvDvYtFlMosp0+zU&EePu@>ze5unXYkTdj~5Pca8mJN)~^V-?O(nMt0Q4bgJE= zf=%{%`WLhAd?BnRfP~6Q-M4bF{$c31E0R&=09Q6&tg&DGjf>yS@EZD<={8}nq*L6RbzynAs|#qHB{)aF!kR8PY1gJF*?1^30D+5hyVyxP#?m?@<-($n#3-9TEXU6kfp4| zN3NXaL-iSHK#~TlpYcdlTA#Eu+add=#TO;W%|{3n03Tm!QIyAm1lQPfOpIkBdg@T2 zdW1w3&l1Nm&Ud@WX1jPE;*UD{-a!)f!{?$Q3X5@`oJ$d_O^}Nl zBu;uFg3F>=-y4P|faYe!!eoDFBfLN^IIpZ(`hjZxCyVlET&T58Uafz$ZgeO=N;IH~ zeE)GkqqVK!a++^;JA$=H%0`v)i^9Jj>#4Rc?Y^v1t-fCLd;oD05DA{xG@(YZWAZ-V zjt9bXx;wf?UI1_!J{tySN2Efb`bq0~W}Folw9= zqAL1u%Ggz*j?_~(>s8+2p$sLaE0(<%m=WW4N0Do+DJFB2T%gVfc|%{tg< z%Mc?$h8x%5000971Cpo9OujU}zOfD)xXKH$nuSk8Pw-l#8V4Q-(K!YG<1SG=3#<0z zpW_}@P+3Go5<-T^X!e;=druH1*i6VUx;**b*N8Vhblbp=mr$aEFImqZ<~6~8V;LQ` zD>B+mSB@`!je1-VeD2@T6gw9}8S3ORJuDK60x@f7Nt|i-O-#Y5DI3Uow%4@|{t5?7+s=i&q{;@f8t@sRek4lYgPm30xt#LL3aJKEFF%`!Ad zx4VRPvx_z!sYjEBCXU5Af^ZQ_=@e`2XfK3X zI@6lj?Silsxulj`VmrdipTrOCEF|F=L#1$_0DN}#&>kco9dV_PQ)D3qxTAqTZfY=q z{-vKs7ePfHt1KB=h@Flr{DD=rMjI_)D2t3`(jOew)soKcyid}qX>41kk~tON<9}f?Ab?}q=oE>b0{QtAHHYh(3Z*;qqFnRjW>codnqS?(c0^2_qBo%!ubZb_ghCF8r4YXQ=|;^xWDg-MAho;!SBZ({DIv93}o!=FB6qWVJwi zWR8=GOxa$Qr)SSOe2^+YmIb5)^hvvv1F|T9_8C+QwEHC^m>xn4Die10HG;fgvyAYg zq`W~k?tC%oj0m7{hUFZ*3jvdp(j6;3F=FpY#XP_(Xi@-Jq9du*ogLZ3qVDixc*{{d z^d+SHo4@0QniB1eyVOaa-wmD<8Fu#o%XlAqnU%s4{L#OH{dCDg3HxMZvhx0GTmHrO z(>hC--wsh-imscmY2|qcy^Un*5Z|y+FMmFwuc~b0FRs@<)wNzeIFElVpbc9~9ne;f zoiQ2XvP#y|K&}_QJ&IN>jGRk4&{AN%;07bG`#zt#19@0u4RkcIL={^w@rnp1*1Q0G z1yye#REadT@x^OV;fU<0YHyDql3Ig*c#C&jLTsf`=g(%$yH4**atf9t*@Z*kEhCJA z5RBq?@F2Sq_T;jqaA#sQD3?RTpiJ38IX)N0)7Cz2UC=}Qby$q<*dQ<=H0{L?N9mu+ zIdC}1MhflFED7&OsS`9--ej#n9}f_n)T|&M>kWht`hhU-dP>|6N(b=c1|3?gcN-{g z$8!w&%AAq3plZy4!E6%qS~I^vC*hw^5@G#8drA>3LJc#~z$P*w%AQj4+IaK(J>BQ{!k)zx>_Dj?Ak? zH!$gcu;`~VcxO9y>xh4{kItBR;2vNu9psmGyChCwBup?jCNK1adSz5rMKlw~6K9*o zqVeOBAv>1C-;1rAmyi{++h}(*C#A_>m5IJQb6$?eFZDSWbQiZ7#UU@TIpHraZ+&M8 zi7cQt(kErzKBbcMeQ%UO&0~v$fZl0(W5d?M1C3TxD56`NCeg3Lux7?_N$wiAjMKHv zF8%jX2-a-5b+{DVLPKNyr462oy?b}O55b44HTMKkUK8pm&N%k+B$)wI&#Dlv%6D@; zZLGdJ8aQDWa{Dc0;Uhx6Bs*K6_kDjB$=COimMmdr9N0}EXPNYR^ys$yskhM#>poYS z3IoNAmc&XuryXHU=_tc0LcbAn5zIQcn;7Ta1)gt?Cz;a zrV2d?E-)R8_W*fHd0?U^Ulk6V|0wWsyH$~LMx6L!$SNy3pTn%Zs0(TBg_b1JHKp*t ztu%D%hjdQTw~_!;5h0*Z*c;zxcA&S@eurj8pFKqZrm58D$|4HjZBxjyJh7<1Btan8 z*+7X;wA_-5FjTQj5L^2h&4C}nwG)>4kml7WTf`{DbtwI@l3#f0@&fE1=Ump>y$kU_ zwhl7Y=JY*7b*I-#L4LX)L7=NXe;M&>z*7tac0;kr%(Ow!FB#lT` zA&7(>Dax2}L9j3Y`A?QHPi}IBVK?k+zjQS!rb}8{pW-7zH9~FQHnvYh@#bZO2m-bv0(CS2b#2~LdFtRtk{ZP1}$W(-kK0ZoL^4+KaQqGX#iygbn z0Wd5wqD;_sToJC53hSfJWB^=dqvJUv3oZ|PIE&erj}4KSNb9*I{Aqu1VWLk7m5m73 zD|LAl+?#QwN{MN@*wpHT-4~JTp+4W+l9{A6Kt| z!f~CJmNGCMEzG6`(GVfg#jA`te{*2TBIw?!#ev{MSO|rA0lKed9>L z@rCUzyx`|PUTMYhuhHDF*BE7QQ!VU%tY)_C#XbxWf_E$Kczwe3h<@-hv02&uFIQ~(gpL0^454EwuAfx#j{wg51F>cIXN zSt1Ht#1a7j?j5{o#|Sq3XqdR*Mb;ui*ydz7jA?jtnCja0lMiyA;4BmC*Z8ZK#)(4~ z-0@f&&wGm~3HF_gmJ%SRlOZulhmk{kmoYs^UKmw1X(d!o9^R`)U;4J>+gz$Qi703^ zo|#srVpCF-;;29YVUQ30d*q|uLG@K&D5yrQYB8kINZaaY@$&a`>whd`%1i}rm(Oud z8(U=SfwLz7A_j5VmMAEjSEM%oqe0GQOE}tEe3P6|G1)lxNQnLkzB-7Qs~U>=XydWq z*i3w1F0(nJk{=`bRkx8^^pyt|yCJnm@Tr61P`d?IiXcc9MMLr2PE{raTs)3oF@bbW zRW^GXdKb-A1`xIDy=lmZk#(n~&^X1N#x&2KA(C&(vDL}F)QdD!IAZ!j?j(AT2r1we z#@ir%?#*Bd*+=KQQ9GT2b(=0=quYm3lRgmkxzP*9DcEP}wpX}fVo!#t;OG_x2zP`gE)rGJx^^MxwmA^GT3KxJz)&&s0$x+R-Z;3q;-{+iP>-$S`;cLuN<5LUbPgWWM?@JbX@)ds zB`VwS8g+Oo(~D{##2cbBZ8Y@TkV%9(f5u@%1Z#Iia+hdqxlIV;&D0Dz0*234_ zG#NrZ2jNQeJt9i{r}-?Unyusej4U)@0e>CndayoHg*oC3Xr=!US zd@pkf`SXa~ecDpv4tN9&oIqZ(a-slb_!nNH{wJkl{0am&|5&`-oD(~gq*`}DT#@x@!kU#-3+jG~^+#hDKnAX)4dc%j6xw8zIj_PU7ZfyIm z87tA;lohU>G#iAgL%iUk$gveEud-EF$UOL}+(aCL1j%p*PJD*=tg~81UQ*Seq z^_x2Or8nAUI`HP`Tc^fgBh3_OZKl^UXaxeTH$lX-{m0B6V9tm=?wbeb8_ra2#g&fK zsqf(mNqVhENVPEFzyZ;+*+0DmR(mT&3QLUjT{d$gUa ztrDn=A!+*~9IRgDp36nQJOy)KGM-GE(9x>XBrC!+5l@JO9r;ce+ZCv$R<~MK?nW*I zsTi4;tX?uI?PPdtPX9sLVn__+_8A|Xp#Kt`Sy5wN$S~4X^>~VdgP$GgsFz8aY;=|) z#(|Zs9gb1^L*&$6M_OP$bEfxj1QZ?O4exQGsxB%lv8JZr2GF7uP=%1v?_4DL`^8lX zC*Sr-8@7d7V)DlP(sD6vRsu8U^$6Lh&&;eC@kI)(E^jXBXVfq1MQTVh_7Vv0$A9Bz z7Yp=FLrY~BADcYV9v!`=O#Z(IJr4tv-{Ex_8I|HS>Y|&^$|M@s%hVUN-;q~PLi&Fi z1mv&wyTdNwQD%s3AGFmy&WTKfQ-{3K{<(ZzVt-O(CF(^mH z<@$ubyU%K<7zJ`9E-*-E|0Jb$-cd)O*<1?OPf2J;94xAIs;yXt*K8yndDzC~@ORy3 z4PO&1#}xZ@jrkYS5&b5~@^bgAE%~?L?=0sn*iTF4YROdqtjfi-Yo{cedCEi}c3w00O^T?ZYM=m4}vsxnas#03Z?W%=J_04yofAHgWo!v;7YC$Rue zj8@g1D0fR4+-s{ey={uU|0L)4Mri1Zu?Gm|CIo^^V=^UFfqT>VsQ_LQ@+Jr{GGQ>}N!1IxGKP zG$F1%1A6Va*rhSlE#)rIyj|^!gnf-c{%ZZ-P=KHN9)5Xm>-?~F{zjj1{^x`f-4RRU z30@L{FPWa79mIm@`g2JGiFt7hhw!aeYU}v>x5WEUNTJ$<$9DcFHowWW^BQi9Ru467 z@>3-X-#*J|{fi=aN}i$RIK4?f1}iQPk|nebxGs8{Bi+4do$G!M1bb>;`C$-vfCfxH zAzh-%4LdJRO?3K1g1wg`5|dcPvsETw{$rf)x;iD3B0WX{6{lZB3L}&ZA-6?Y4{N+7!ic%rX7V0OfDwezA8YE2{Y6ZX!=@pS^r!AEE zsbu3KfwA+7t`JMqypJVI862G3aXEOE>RY|r066X${}FR@7^QhbQkufCS6%NCsDt!zKCh`sj|_sP`D$bvBMYkU2sSv^7h63`p2zk z=36E0!4zC*734@Wh7*quJ?oNY;*&k=vFNtjT69+bqDot~ zm6MAwZ$q^J(Qy7|;r){PAw4v`>;+H5TU6WSKQI`5Fhy;;D^W;A`hBmVvu=0R+35># zH|N`XXeYZ0L!o*YBNd}GTllhn#j^Fj_X@EWqg=(>$(J83fH4-1WHCZMyF8EVAj(+9 z{tYTgJ^an0^I!)NG*Q_4GHHr=bLY7P@6)@$yf9o5SY4Z=L|MO~1XZkAs{PE=)MqBy zG!J!s7~ZL$;GAH^+nl!62@vxEpaYpS@Hq^yg;YHdsxO#(?bR+4 zG77z40sKkirJ>1s=_tYnK&jJwxA7-HX&&&vfEU^=a#I?(f0~-;ys|YYhFqY3%zukP znLm^Hdr<&hb+KUX*;2{H2tvT2J*d#d!ccO(UJi}c7&>00t;+h?oIfh9Dm4H!KQ-Ue zNRQexy>vt}QDFUk2p+E?MRrz?0Pc3uhS`^J7g3nI8#qcRy_kII7|#mVgL{sSK@`=w z>ozQie1jMj;1v67p2JzZ`qsT2*J{%JKzNhJ#Gr>9PTZl4@`O4em0heYUvx~kP6zM7 zK)B<`YK?A4$5Lo~@^LdpkE!dd*674p@V7@FzAN5@+|*IAn=DV_k9WbHVK)DvvTadJ~uMGs|i z-ZQK~fk!(Z^*MY-AJkIkX+1Re!Hg4iBhzaagz3jnm$w%(LrFfRfJrEgAE|`MVFI+G zTKq{txB(C2$8x0s&N!5zVYvn8YIa93w%`S@0k01eiLiIPuCi@STXS*u^s3vG9ZA8j zZYe$S6l>a~7}vx6+de|dF>YS*7bmh+DYIvh>R++I)KGu8$Ry<907BngB~`9IeX#Eg zb1}YVDuH=JTgC2>=?l{fFydl%T16$hY=`CXCM6KAY;fhRG6XI#66n2(keOCcBL9yK zUyj$r=e@Ld=i#)U+%$Plb;?`<(}BS;zY!xX+T9g$%K!$%m~kW{Ei16Yn%N58??vcO z?t#QVA;vD^jX%75<76vKGk_*BPiar*e*jc72(@ge=5k1{ut3av;@ZIu~1*@=va&~^5 z#bDi)kc>CB4#3B`Wk6i*y3-Bw+Q_+zw*MaQuN8%taNFD1e^ti`R~!$PT5^xPVxhfZ$$QnjQm+kgqMuSZVBKz7+5jNkid-f?q+fLdCsiYKsh#zXU(cM1wFGf682Jr zta~^nYiTap+?`x58-LLC;Gy}9Zjbu+05%?gu+$5dc=+t^tCSG|tHdt2;|EU20&tJ9 zNC0$o$duT?3VzM136=NF6!H*{22aQhwoBi>zBpfMph&qt3$<$95)er!9t-YUV-l4Q zir3M?BeXP&9jA;}nDYY&&4#nX#>qWT24?GWN2Q)6rye?5tp;8-;_Wj|{&rPcReC|p zUH_V@@nd|8LzMI^(|R`S#tdexKQ`{d9nz_b<2CLc{_Y#fP5od1AH@)C+W!evbqNHd zTvSO_OwVFs{08~)&^Ta-&|{Gn-G9TEBx(DT>|!iyV4SnMuZRpAUb&k@3LTpVlv6~# z+JTgzi#|RLU-*%^z=?irRn~~<9DDSfZY{amNa6+DE!|<9)21kYHtBNn&c~@bKncq!8AZPsv*mLAsq8O*c z1Gn2|dfBBitaABPp;A`p0dA$xw)NSp*1GZW3L}8@m4YngYTR3mAwI4ggm2qN!#@3_ zJ-md)SztHV6uRJD2zp)D8%CfyRo9{HrQnDh^Nk^=SsG|%6^_^Q;{e|6Pk;4>#cAS zI4P7eKUw&F6)FO63wFm}&oLaMoYhleMFy}g=#RMKZxKrc=a2EAEv|~eO~yZ9qokh~ zHu&XZ8ktWUB_8I$gq0#*l~IgvXuOnd6_(oN!_|M3Ej!#QUcNkXM`=-$6^Ay zdrB1wBfFKrnLL&!LwBBz_gYEc8Q03S^oq&Zfo8$2sSoHY|EP1%U>8Q$nDnlGR=(R| zcOpm5i`P`FExGnSe1`;izuWMvTE&Z@3B}K7f0>dyUGPc<$9{ zMbTgRC?o>$Kmq4AJWE+~mL{<@=i^lnmB>O=d)TBd$CO++`LJ+t*Kga3!B!zgKHxga zX{JKpsn^(n28~Yv)f=yKe$#5+51&C$ILc4JMSMO^nhxirf>*l^0NymDGIW``h;rD_ zz_vnk{G@_K3c+weMDtAGc2m-28g_RgYoWJ|3z2c!$33Y@APZWE zEA%q{SR&C`tAIBFs=1uRwf6uOGK;{$g5q3$NpKlCN3i_-}{ zNv9vRse+ISS0VUrz65Xi_m3jSHZK)ElJ4oiY{=3@ zg5}#EnZGEo0t|p|!)=*M`l8JSgvTp(_M}^L{)CNKz8e@Fj?4-sxel>gK{O4%-PIPr ztecOki3HP4f&g%|>NAdlCd%V6cSPeIc3RokUIE-ceq^vu4$)_}wzrxjYgqNnsP%3- z#}!j|e!!(2Lr4SeKgfjRGRINN%7ke*F&oJd?Xz$l|DZ13&-Sy{`~Aalvg97T+HkE= z4Lb8(_4w0^hT-d{^H`-*?)&xS0x!Dkl>! z*!?fj-&@D=ZaPd$cnZ+VVp#X?Ei` z%NpikAmEt4vQi-I{&Hi9>OY~1V=}l@?S^oUD=(`Sc$a-M;nqSPiFDKT=;Kh?c05w@j*2lfRh9O2CGFG65I$#S1lr-( zXr*;6@`-aQfK#Sga}N+&?W;x{oY_FSm*jwfdGG*GK6R;E8(Y-u`tW+&?uF_jqg6TH zkjc>kZ9e8gu+WW%-^!Zq^#*eQ_CJ!L$;n@Y%(~6@JLZ7h^?kI%*ih~b=7~vD&v?H& zJ3HgTn_abpLRTJz3u})%{Lotk;O-pX+|NQr6n6I3cbvrQMkzWF23x;OlrSt&J`rr> z3+EPBH1R{?ARr|fb@6zZ4tVj+ST&qHncBDCbpbfL_e<&E&|%wm3Nar@C7z#(`=ial z-6YD>Um(&a)VAw7ZS6S!eHgsqKUUOTZy8MLj3CTVOz;qjAkh(KL4^-lmmgqw1%WRA z;w`a>7LmA}mIk?jK}TwExkQN&=?bjCOniYAs;H5-Aox(Lf_rH1?&c4*_If zk4c(xBKqr;CL#2OP4FleCS6O9 zzQZeRjnG-6gP2div+<-t6ug7N`{6*VVri;Zh4OiS1mTdl7)S!j0=6Rl33jo2gba_T zGLMYV*4)rT`cJ%7m9i`%9?Vf$J!{DTqstOCy-y3)IJSOI>ptF#OlA6KV zg8k4eSoh7C+8-h1s9mShzDpvK{-R+$EIJR}O>aB%HMMCEjT!lopr`Wg^k=`UILw&SF z?xSQmyuHq=oJW`tpL(3LxG8VKI0Qo={tF};PzN6ZPna(MzKI9(eA*{Z#C^E66hSh?zWTkVORi$=OO8HSIMR3VT*1mR>ZLQw z$(@*%Pk9mBjOzLx0}lB`Z7P(LuB-`~2FtQ}RxQt=(iwM(#Sa`>AUFevDhy@x%m^VX z6Jr}7^tGn|PR^C}NVq8+DY5&XSafuRph$+B@jg9ER7;W|*~tO|BopwbP<-Sigj z-o;D9Mm#uXOXk?_vTSotb~Q>b7@0W&Wy;3W1_+M%!6!{LgLLg@X^5R$;S>us_d?dy z6+y6_m77))wh3G63rGwkZsim5$jXz+6R`iA$e*>hD$nLJCLc{Ks30qOy5xlu%jH8= z4LH5j=$2CM%2tsNlC}LXpyts@#FS$%H{3N~AkS6UTPUKMlS-M$5OdI11~zo6ZOnhB zNt)8G@Ew)_NQrrk)emtw4Kp2+{WdDgpOC`qt5teL9pJ#8@MNmDpjlu zJ7ppVzd-7WPc_eprDG?@en;oWVdgcV2tmGtN1JSMk}g_qg|qfDL~OJUF|0c*pI;=D z#&A&MexuIhUhUZEWIxW3nydZ{D>%2HT7nNpP{UMv>_Hsd!&f!H37bV^MOn$xSix^a z8V9ZTs&JqG6%KI1SeQzf3Iv0R<3+7g$dO zA7MD8r^FK6u$iDl-6N8(KOfqPY{(LSAF<*e7`Z=*?t7fS>fv1fZdw=TNg|9#hDlzV zgHJ8f7H=0k3Uh4n38nrmf;X^aU?u6&B3s^-8dhQhw_K^oXJwfM8&unv`{xZ0%1yed zBS0rD02U=hwP+jLJV<>m^({bR5i*06l$sLlmXQXSDNN~#302}U_5F|&VQr8L zW3x`!bN(26_RPLZ@VjBdSKXmac%1tF5HuaYj(XP==ja{ao{mCTj7-gYjE(i+l%B3` zzJl>FIql1uXV#76Cx|&7=+Z%QU9i^L@UPuDvof<$_)SVFDy*-lMxZxYnkcV86P#l? z7v&IjiW~p^M02RxkQLH$n*;LKi+AMM%D8RODH1BvouE1_rX3h=8rF++FVceQl-3NM zpp<((^a1^uMo-$yu-@T4V#nQik;(_TrR$l&%~rkeoqh>DyIWc9K40pgig>;e`G|4S z<5^&U*82+FBxd|l=QK!byjv4FCm*_0Z9jr0oQ3f?Tg?oaV~=eGdE(rs)`QEtd+m9> zwEB>!L{T0?040?Retawvy?)CE?&~zWOGuH{GlwPzrAYM!`sQfVT3B!#PvqJ}m^+-A zAWs>zn?=aY!C;*Wo3YXu#BSI5^;bNtJCkn?b=){6N~lkd5b%q;`eJg{W83vVT>aQ$ z6n!8-o{$G-?yG$X_MlFlD5;31hi;i1ycNZp9^vwiH_}KYkBiWm0%w4#dDrdiLBtJ} zu-o>BF3SUvl)(C*a91r=A&iYGG4en07nc*;B^Eql7u+CaJNmRK1oDrFEAhg}Qny)L zP|4S`^RfRo#!_=nTByK<+OPm%e>J|I5XX7fqE?P}n4lYGFrBSTeZxD0v@64fVgWAX zVMD7Km$q@^krn6t=>$8kYe<`Y{vF|Ojd&mw0Vnes>KG3#GzelbYj&i}yOD*VL;lPc zOU1154q4OH(vz?5d6vEewmv}by{2jlUtufccZTWYILb#?yP;2T0eH)T{^ zZ`jZU=a#OL#P}Yp!5DrROpom5>e#5G$5_m2xhEopf*X~=LiZz4{(t?5$$}z#8IuTc8@_*lN7pq36y)&;kqvI9q+E~a3DjnJ|6N!^ zduFYzDWj1*FlzR5!j|Ec+$TkMzHxilcE?!6yu>9T=ojOEycc8h^(o&aD!fZQbN#du zg*PHQk4-asnv)%yrKMd3pf}$$#8&6wxiosw3^`&rRXz3ub`a_aG_5T=*ea>uicpE6@zT{sLY{9K-s{406&iTg0s%(*L=VoqM6 zN=v{d%+e4l2I(X3hW1W^@uEWJ;s`w#ffyo{OVmKENcGY0Wr&N_omMSFksd>y1o^{= z>0$j}y9%HNCKgNRR7t?k4Ht=%0ssMKgzmn+y%l9i1nE?-{mXA)I|r~{-<+R#kgrH) zC7>b$N=jgB#q#=aRz~7P(LdOwhvN-g3)sz^71li}@EM-~000YYk#FF!pWm%0lej@y<)N6{JJ4Fkx+nD zO@Rkt=bAf&JNzhf5%j~Zx7Ng$I_fnoG1@D^h$EFKE}c<_Pi;zihcg)-6heIu3Rj`O z^#G!bkl>Zzz%*|ln1latVZs%x51|+m+Uc~Nw{Nn&$6js$V`%+G6tZ)gj6UO{FX6b) z!fzVu2VVONpmjjgjR7kfV_ z@1E9Dvwi$D?fvU~HCy zj9@Pm!p|;P=Js+96a=>C8zFX63+~<=hIHDk6Jpf~H?4+HkiOR302<_VFai}cUIl>n zTskb<)#uUZ5;SRW)`z-v zD8`^tv^-Q+X1rvHFsURKtNn?i+dhn=WL>Rl+7vURXOFIc(9IwD-dC2Hp^ zI={aqkejzHhf8y;B4#-Ae4{(h*OX}{Ge!et3DtnbaKT#yj|r^|)o9ay@+tnF+8zmAC5wdaRf7vOy<}I}dg}XzT0N%Z! zL~a{ilW60!i%KMgafoda*+nb4BU&}dj{@FOiskyd*7+-tFGxZ7nJ}GZy%_&I!EH3; zZ=mOkmi34~9C(2kl-!+=q2OoS;p3!k&za2n>eSZ(LwkqL4^OObqD;7pe;E3u^T)%a zySKZf=rCegIU^K9>fCH0yLe#u1Wv8#)Jn(NZba4)Y7~{Qw{sE<4@P+d<~hm?2h0IL zT*H+I)U?HYh?Rbbtw|%O;AvI{#s_PGpH*_qm~0fk+JUre!Ht!J1~~U`Ik$C17OtP=4((!FDcV{uethBLGAPBzF#17Dwh?PLOWgzHNP`d(xllFvs)RBVh zkiP(LE%mmm?#wFFu^L%*-NMUdlEPu!3T!!(M_j~VX+^84h8LqNx>ZhD1HF)9zHA;z zw!pLItKAp85dm7B5G^ zoqBZJ7$Ex&yJ%10I=Y|qrxZPPqKWX_v#*)e%=U!iafxpC2<+@X!67N2%A-y1 zJLs8MTbxlXC1j2n0`w(!DdXpQJ>}N|GGXPoCZpo)a{>V$?8c#+|L~FI-Prn)sH?0R zM3&h3zVS3Jv~7bgmgZIN_{Dw%v|*NbS7h9#vc99rT3| zFUmVoE62hR!ZqkDRJp?`bzaGwv5$_hXSyxS@Od+VMEaW#q~q5_+KG6h#FFuG1-@X# z{(h6WOW1(#s$h-SM3*B;%B%*dW%97KsCZ;Al_859twmtiCj8C0-~=QmFJAC81ZjI! zCv`fAk8@TYCvSCLnU_i?8&tAU)4PAqxv3&MS*on>*~xfEAYt2c5%GO zIXLj!dd-QOfN+k$k9(e)N`YS(#mg=Q97X^D0Q#o@5b{T-OhRPfJGlN)kEEG z`YaKugsjr?xjlkB@~0tox#wE>fdMJiH6A%WODIU31U~&G0Dh0r$fq=h#Rz23xa395 zoJ!Z{>EPe#PJkLoSuM!%4t!;MpeGm#hNt}T@~~yxYV9TQy<*`nddReQoVv({UhfTT z<38|1Ymx~1AeT^u@o|GeE9JhpvEhiLfX!eS61t{=DTH+x@~C-)?A6*v){Rl6E?$U% zI8*N(CG63q!D0tE6};%X)JmMC%SN9d#ro5^7YfAGkTN~xT(hain8|a06=dh-p@f#Y>K6%TFs_90Unwv`9C);x=!jL3i^ z_wFIEQHxuDX+Xb-6R`>z9<(xkt^uiu;-eXCHrgL0zFdibAD`@ToqK?~kcQT)Zd-<_ zSRCu>{vd>lNFsdix%G@9kJC5kG~C-X+SM2WoNz=zIlQu^A0>18k->fGWd^<1Vw0>i)~^ z?15)cDU;v3m^2OFp1@;5I4=nXwQx0?H8HfxiVwvS1ZCWN-u{3xhxbJW7{nSMWtHnBAead! z9)&p7wU={CS`-3A4-)jeP!ewf;Y3XY+0W&$?OugwZh>;i0GNRKbaPw z^;y^8O0|kmqF@Q2%h14O68__8a2h<2U9_T{`Be`>{}So&@+WH{A{<3r{G8NMJm z4IpTwi2uF!`Ql6b$B%Z@;-DyRB*3+N@DBP8{XggdfnepZun^sCXpL)f=OVInrn`tY z5OU7CWGYBIbUocsf0}3zyn*>5@)lP^?q9!KNLY?29T{;d1D3uP8;CGCMA&T zI}%7*Vikl(-Gq=OU&bKd{Y=8gjE!u)jOoP+IlOP8$sqt;MS&sL;9f3kiMb~*|H*a`#0~&2>uzb#BkQYdLB1p1PrCQGjY%G zSU)kOdx&TR>Ah;LC;}7B6y6p9dg*9(iY-9h00RHVq>P652bhi#7Vn+)GsQH)wd?~A zP0p)CjUHCK>8||r;BGHuzRt0ZRMi{sC2!v`=3Z1axo9L{W;PI20rm(eQlWsx9jmrr zz4`Yt*K_WpNK0ldG8#<4{MEv;0ZefizJ}#pS9mN*o8fq#0h(W7cQFtZ`%fZ=e3q@6 z3Arfadk`S;rEyKLF3I>#YiqXhP~91UjqbZe)Eru7*tGkSePQs~2e=>AP&7gf9BLPp zsIb|} zQv#{$cjE-Cju+EbYmk2fmQDn~XbF8s4!1R~#(DbL_Dr(_97EmB7q_MZ9Gz#fh&dTnryP28 z2tKb{f^SwehhwR=6i0VEFRdmz91PMXUSv?0=x^QDGg!~P`u$2^w@vxU=7=? zBC%rYH*Ttxp(ONJY&<;bl^m;lqPb49+5HZrh&5~I4qxMC?UrX0xUjPy2uaU+&1P08 z3eoXIp51Hyz5#SoQ#rJ+C4SXoQp^3?UC6n3i<0_pco-;qUE=gjnGU_43iDu7b?(!q zXn+XM@U|P*TpO?;SiR>IWRqnw_rEsO?392A{M_)76Bk&s6U1xmY}Pby)S#;IIRnWK zSVgg2=bsIS=Q|>fn}>5BgY> zhQYlbL1h2mq#xQZ%jc{-mO%fPRM_9N7|KOHZpS0f$D*&#Wkwy;3>-k6mrM77ky9?3 zk_Hr)ZcmNU$SWS!;<4BcuVDW9t3@*q{J->n=0UX~dVn40hx*=yp0P@Mm5N|@>NJ0A z#zPU)ri7>nzaTz*H?*%Ti98wo2Fs*gV-C(-(0nGR>u}vYw2%kgLrrEWCCo@7Dda)p z-Ccp-Y9dp%mwg~P!XgF*D7COAF=o;P+C$%|CHi=U#y&4Ft(#I7{{a+Wm91G1{d}yr zi&!YjT+NxDf*t2S3d&L^eI`s?r^ zfCQqB1FbDX7@XGP+V*8F$|%OToweJjS}-HX+J3^ig;DEVY)oIL$lIra3J75+qN)5Y zY#IzPG%bp+?(U1$Z3`{vb zw@o60kiuH&UsJQdcL62006oFZJb>Ehnqh@U_h99C_9PR>?FFH>cJi*3vCxtqA`x!IQ#r{ z?Ax8BWY2#M7nK&D=@)G7O6xf*C+MwA$U<9FTZ*+}6VE{Y=jMTTqLz z+Ir%7hbuQ7Gzv*9>w3VF628|5DUDY=y$DDf(FZheJ1DX+WMeYH-vz8UVRG6J z*feN)GfmWiFbcK((k>%1aIxvwAnw;+6Cq-a^c6EjZp5@)_wOhb56bi2a4bgxuCoY7 z-E$NkI~?(VAY-L%(-Ey8I z%@^wszDa<)8t*tTvgwsZWI&2C@VWErgxsn-r&LVkJz;Sr?5;oQy=;eUL@>jfN|?0s zeG^lFYCBTnQ{WWNsrRCx5((pCVl9K_BLkLaq9QIqe2ccMM-IH@Hx!nS`7Ng>?7Oq< zT^3)n9kGoci`#GLl%;bDnM!m300PaC)Z73+)Yn`Wiq3RAp^)k2q6O0XzPc6s^Qqtu ztP&hlyaZW1K&EcPL-5 z^!e@FU*QUD26FBh02q)3&NS-iXMM6krMdCDh=9I`b7p)C{1b-&PM!1^Tn15ru}Z@dvWWs7OtXh1i(WQFhxt}Ju@Fg4uR z2CFmk8fYR8o!i>BHZxp07&$yd6*nNRUS0nKI9$A z{$FtW13Fbx#t8Am%|GsvVVy}p|IOV;uKT+3k!3vUiMP`MB@h4uvv|XrZszz_v%5iE z@+0>1@a2|WrFNB;XfNN*xShjuOX)z zC2juAdGtpGpgC4XYDn?gW4upX%W+jI9t_*6HRAH6B!el#N=96EZDjU{;i4VN*M;qe zQwHdKZ_*>}6c6WQ50=>C)thnm9mJ?zEtVaBb(VV%E%2fV^6n=;<=-GYS~j>Hgn5ja z_A(L|)q4`@%D5d$HiKA0ruOhm3FbjBcBh{whl&nL`WPFBO+c!V@m3@Cwc8!)33VK8 zb~bN9n{BFvFeX2~rD4(jNYQQSBH|ZUI>tao$hy9qDvJWgh|kOJT?^Pj;QZn18GdLr zdFtsrBP+CH*#R|K&YhlduxEG%YwAdFM@|(Or2?%D4UsGP>CS746;*UEv3%3h<-#(j z7}Jsom7(-C4Ij52jmq>MN}`f`X{&!}J9r^Fys2Ea(Qj$Bq$K>pUcI=wJ~(8gDX5t@ zQrP(#2FZ;vAu&ns-@idE`&Dg6=NheyPJ(u{6u@YN=N7>3y^eVX4QB@aXt`SIcCC_> z-odVdl$qmT0ocF@wQQ=%e*xa@cyZ*@iy92%SLGU>Hm{m2yNWyO9@>1}>y8Au&gqN{E#7X_Nth#J^ajT6IQEvZu8CSo4DENdRHrzr*wr6UWWr z1-ux(Y8`z9E>rr$0Oi$_V*HBt1SJl^)3=*p88l$R<0cZIz;dRuFaRQ25U_G8AyK>3 znWN1%4i|xH*Qjp~z?!ZYhx~a%$WaH^Vo-=9wo;n6vdT!~a^wn&Wa5qDuaOQSz}07> z5R1n{0XkLLp&Z?dU=oIQ1c?80crjS>?lTDI8hyr4Jz#Plc${?j><2`v2r{mSy zUgYkrJhe%rllF*|Y$gEqQ{NGFk$PT=qWl0NR<%UY9iF5}zjnnx6QdqU$;a*w*yq#B zFuWS->=G1h8To3;XnAbK)c6&X_Pb+DIQYNOHaABCD2?VrkJrt~_#*QO@eNeEX((g} zN4?7FgEbZvgL>cAz~nbT?TN0jo5lcJLUiqGz|^HSi+U33X!l|$b3!hstpva_9zTO~ z-)wBOIH>n2#Is~9JTP1Bk}APb<*?8F78Z=o-O9UUQTcin2r1a9utpLDq92a)>m_`& zxcjI^#G?tklT*_!C*z@6F5biAdgAEV*dpnlDR{XA8`w+`IbG3>OFx$5I4Nx(W zTpvipy+tNsb1Vg>XIWcL>uB;pD_PI|xUj+wrdfK)YT|82m5Oz^{2uWi#n^^SqJab0 z4VMK+TK~s9DlLq$MlqRNQ|2j7&w_WEw1fY!b)nRCqwFQK&Zi=Q81TN8om`;yUY?c? z8=#;`?Z!veUH0$KD>pDK38r#)kS*ryV^GEx&_$AMG1wG;6Z00&+CLFxajW6CT{J)^ z)y~4Hxqm%6&q+3v;{3e!m1=41f-jQO}+NP?9+h^$IGucsGRMA|Q${>WkOqw$ zj>J729^0?S`k!My>RF#_ugZpI5#{p{VAklXwVzOiJ`N}$T%xnPiXsFRq+(J zZoFmof_)#iwe+9?|I%xge?(i$Jw@?Gly}rglM*r$TBeMUKD84G#2h$xy2%$r6Dv0x zct#a#+P`0coY`@rQyCe|;tgW#bSFujWs~c`}XG3QyN9y}5!vHm(8@7)3RIo%u{(>RFowMHKF`jAA9^ zD&R$%@G7Uj<~qKKyt-ziEL8H`A`i2oNz_r$97(U=@6ZX(Z_E<2s0M<7(PYT09A25 z1VUadiGhBQP2vn`$bW1kK2kqHhZQ(lW_2T~=S@N%6bE4Ey5&Us5 zP}X>OM_ED#ale|PsA;mSfe-s0Jiqd^5im~`?^teHkfUf1d(2rFi-KJ4T|_*}eGx6W z#V6Blb=P?Bx*iypp#ScfG#8=tj&4Qlhs-Od`FMmAe*DX|VPP}oPgrb)C3PbIxC}|u| zVVtRSA&=>>99zH`WE%=zFF_svgD|m;5E@R3uE6>_y+L;N_#^Wre0pptlFnbeyK`rw z(Fki(E=}F%Dzmq0?$^JdN`%CMkT%;=rh^wF0gGUFZzQdC>y6 z?bBs9@VfNaDhYM#MFUOp2( zE-SPr;PNx#B*~{Otld}(kq^@}5Vm_VC^A+5QpoQ-ebh&6#SD|n+z&1B1J@Q+tkRL- z3rd*jL#eT)V~d>9RVT+pYkGhh4Uu|#a5&HiRqxC1ZR>l5@jqQ~;aRZ1j!?`t$^xL0S^y5>a*1`cnHC!S9K?@?jpSv$q{{FH%4J5 zyJ})dNdCGe?B4PJr(m#Jh0*N4&md(xU7IP!q#4~b5@A*3xNVv&x-%*^lyAx1Br?=2G_#Q9FjxnGFOyK6KK;?R~pp#ICFr z!0}pYC<#mlyyCu3kRHo^sX#K%FyNJalk{<7>L)2dw9qsgJu($n|B8U50tR1iuVP+@ zRWB>Kytu^LmrQ4=4$y6foHYSd5O%5A%1!`AVV|+Ow6?CqZoYGx=0^m!h-IY3Wu~hd0?%NTFv?yUT%LbHIpLu&97FP^iZLXzSi7LF_nJi zSe2=U6SzrZ=B%Fr_ZB9WZ=^Lf;ZHqy*w_AILwbWBlE?dNVJ0*_AC_TgrG`4cY|I?u zyM)F;f!vS>MIoQGb;Ly+F-IIg>_rN($KmzyKFbFc5x_%?T8T z17r)3o3d}a)Z{UddM-88(M!o92h3V>u%mzh8BETsd*#Ihorh(N{)~(G&lHb2J-xpV z^%^&yk|JXCQ~^e`$gS7BG`HBVm23>4Cp*>cK(?k{u|xBSZ$k3t?~*yf!1AOLMiJN5oBp!yPLXzNi~8`>-N}2- z?H%#I8|WBA+2AWWd^HeL3>RCygam*LM~;=y$W0_*B&`-Dd|RW#odx3JDrtS*K#h<% zgpm-~8rj3~WAirMS!e+CK>ntwl*1f!yr3ERt1U;4!s8PDI7*P}CEL_P(BudP*$Ugh z&EDnDCa+G7k~k$gD$L&wD$QL3PCywc!Mto`kUe zMZW5vd~8Ot;)B5(PhEfr*qG>HR_TqpJbwOb#5u!aM_X)vdJI|y2q%Wruz|1&fdrM+ z2ZlC$^Og$}9Hu!L&HttW-1HQX@Vh^II`zCRD=q?Fu-@+#a7UvNAO`*^b3$baU13ba zQnUgaHs}SS!QygT7rrH|Ex;E}<+qB~`Tm>SqEn5A$l6ITy*-@SswBG~%c#mi6kXlg zs{4-ja}S8!mA`&0T6;<8<;B_xl?&i!aLNo?vLvVy7GSKF}U--1!CSqa80_%$sR?_yf10ixa*=j~ILJ+9v==|!Io5X|ihVRD{a*x$e z`^x>OqqSv^yb5iJ{u&}M2~TxOD%)BZ?6G5hzZSwFXKYtCo?hNJg}{<$(g3i+!u2W7 zQO3(B!&{n5()7G`wfe*73ppv9H)#rL7A$vC%U0~EoV1Z(Z5?lO3)q|3l-4Uw&A@z{ zag?qiSMMiIWbN{)C>58~gM^kwpjQSELjzV!?0B|+E4Pa1#;ja=U*P%>dyn=Gq70;dHz^ak@I@mX~7}9~7 zVj(R7L30~3IoE+O1Ha`BftZCF)Ki7L;dGr>Tg3perM{^4b>Xc5{;{=RcFw4asfD!( zp~-HU9n}HWvwOHPx_LGY36MFO_Gwmj&}A$bQCLy5InVK@yWt_VB*7>{#~gUzd3{H- zc%&ylMl5?qmxJIQ@4B>GN~b7`|1u#(Lg{pxDG%Pt;m2w}%p$&y02uG%S4jPjK?i^X znNI`#`He%JfKhaUAxPg02gK}MTj+c3AJ^;yrv7MkdWL?omnEL)zw2 zBZeC!Q+nDGVOW~q-cOH@B*ypv006W2KCE(}sZ)Cl5opzss;%gWA})W~gHjMBjo`W` zBnHeRhzQJ#t5Gf99pJT=9cRXEwjp_&1m-<;DRDn+Ec$mYaz$iv6Gr*1)=bM4_epC#~a=$0M!OkW8&wlz1Ln&EfFiz|>^uIgGOeI;iHG?`P?Az~6Vy0kKSO+3%;aGykiz!oBR}q{S&~Wf z7YN>o3-kF|79M#}$rpQVSPQx0kO9D|dkYLebApF9V9W19R*ok)rW3IND*PG>djeq< zw}}@JYTvR{pqkn1={jOkw0Mj%{%UHHi<>4O>jKpUXLu+u=Bq?@YBcWA0OQfs)B7=R z9WCZw-wM%hTWyjt0ZF9z5>CGekoZ5iiazdZhwFY-VB6Ssv;Kg}Tqe7nf0Rqzu{Egu z00Je*TyEXdPa?933K&(wIM%E!I5^qgfdkMRvT&4HzUWoOW6fQr_jyTF2AlV+rGgbe z&%Y;7>M3ExfL;U5n?@kDVCY9C_sb5Snn+@_uNC>=q!B{oHTTxV zI~C09+MBYECMQnHteUf@UkWW)$$1 ztJ-q~`t)G8mQpg}J5KN;Vw@(CVE2V9pHV8eu4S4=h7|It8jwk>*_*GKjhekpFHo9h z*I-*W!IYCj*g1_BQnn~Mrdo}`@xUlBl)bCHn=qi|O%k+fx8O4MK>uC-3Hv1KG~Fu% zG{*#v=yX69{qfAhkBRV%D^Pe&f*Y>fe?cO7fD407h1hmZaG?I|IZD!c0~)s0!~yJ7 z!0xc`Oga{ke!;PFaMp659fx>e!9XWF5z^k6_fi3Ps#-z^q69EHrF}i#K&F=d`ir9( zQ}Q72IoqFK){F6Ui(VmG(eLPgh}ftGd0yoTPpB?cpiLnaa=hFVpGXc1K3wUD7+5Q$ z027|$JyJ8g^&Ll$|s3b5dcdG84w*{NP8-{pgg z4DXey0+u&Ukqnda)}KPZa232~iqP+uuM0=q12&4^xw6CIOjI?-3*fFWyWc)SSVzik zf4A}sMz;!Td|I^&o03AGr#`#6=af>f#>wasz$Gv-q?47uH9sxdlq=onAJ{)}b{>0E z{IVsFxB@<$Sr+YSmcUJ;l|1$WSJc2Uio>N2H>f`dR;sN)*QAQ;O2o=}hhV`Bwv%tf zzg~hnvkl?kw}?X?n(QO=*7z7LPkCAem^@9>&NzPn0{Ve;d&?aq=@sA7!P1kB0UYO%FDA^p7bG2z))u({3}n47 z_lv!mCes7xf22te)#0{tQ4&p) zt;b%i#0mQMPpxb|X*CKWC@=J00uj2X?|)Qeaz6nTOdwN5_6_fsd-N<+Ve-F~h{m{@ z2Dm~9qK3UbV!Hp3AiW3&FNsD^cr6;{DC8CK=4{m=7Awf#NVNzYb*VRy(KDXN1stG@ z50vCW`6P(POARpF1VttQ7ykCQkzt|7{Avw!z23A!69F(y2tNkl4yURANzUX4UG>-p zbHg5;<@qJZ$4k`-@C5%mGKiSBw*3*^^eu!<>h#WBc6DdJt6W?zt<7{wB z?m-{(>bCBXDF~2lXw$0IBmlP2F)pkV*bG=2_u_AZ-96AUv#qe5#;{@rnq+Ah)y`;e zmi1!lRH5CCM~}sF@IUGpB2fn6oI?asm3Id5yT}${XtZasEF&+Z9og`q@M6w2CvvWOX! zbUhp03d%yixX>LMVKZNw=UN87IzJ{YAz$wSxp z3?jh3%d(={b)4GDl~Lk zegxxN;dkR1X-`dm?I%^AB*clA2K^UO`?JMIf8A#W?D~~l5VQs|VFOq27xfKhN!25b zu||{9meMDUE4y$Tn==R;n)2W&c{_hNND4T4k)SV?MI(1t$meIE_XdQbXIz6(LR2I~ z^UF&`90@e)xcSwz_4PMpc-2z()0VAfIxBr?t9Na5EUcD8m39lbqm&(h)PO zAcwbUkhNIVc|?!^xNcL1H%9W{U?^DgT5^NwTrc&i1@o8Oz@RYs)Bqk+2>mg0999io ztM~Y;DT#y(dmOIagmZ6-UXEu&A z5}~~zKba`2J!WpuRex*qSCTSqCH;oKFBw_WclmHVqJSuue|J>Tw)%4hO2RfldMzua zfm!m-qiT{HsQSLCT`$Tl!};B?7WE=2XOOwfz}Dl!?_^n)Vec8jtvKKe9!*13J?r#m z++AGY6Sfn3fls%q5Wa-(oBaH&LAJgFSs4SoXBoel8(QdNffsemO6j1A8H)wiXG;E5 zg`zw1RJuTV5h=ub!dW}pbJCO`m$R~*@JJz&`&nGM(bteklF zIx29+9Fx>{s!))%MiG{mIDA@0Pu16Xl@>6_fJ$WxdZIy_DmHJH`}cB6cRr}^MgJl) z6a@4G^+lioz`$kYc4!vFyDSzNWdH@}!rOe&#d_%`gadaB#fLO>?3lMb5BIPwyED?( zHx5{IdF`_0)5h}#NzzY*h|bnY_AAoI5o~x5*SbNqWj9eB1$JFa7M6-y9Iq`{3bG`< zvRP`~&X6b=Dhcd4@IM{Ztj} z6&z zL{kSH`dk(6i}2oG{u7fb8Y`8-1_cv7WXYkv4n$}Q+=SC8gP(bd-X(8oFYD00XaiY)#b9QiApaFg8Xg#_6EX&xsCe zw(yufU)Tm#B!3t985lli?4~s5>z4{5Pzz>Kal|sZgBoYms zpz0UW-Nzw}pD_U{Hnm0ohjJ5C%fZ}7MHK+wKu-x~WAPJIJ8fBSPsKX?zOEd`VdVt-_4R4)bO0J4(;qLJ{UXO|A9nHjn&$+f!+MK9-6 zT2IEFM-~iLB6pTOVv(=bOp8#eN!1kr;JzpfhA8OWpU*UmpWpxybL|TYpm~f;f+GvqD1pf3ys{l>#aKfL`W+At_B! zal*PirW{$M0Ol@COc(cOr zbdGun&>YfX}Y9KK6#%Yo15PC~V<@N0mdeN+eSN zo-WfQs9zSqkbE!$IH3W(!3Z6QDQh2ZjaIp0ApzHVi+nkN0Hle32Mqw|B~mI@D0N9U zf(5NTF+=oI=!|@sn(t9aH91|7J9xLY=p$!Ge*5&h&`lEMY7S1WE+~ zevsL8uYw6p?EwUn^+^B-@E|?q0fbt>>U0f!F#8z<5WNnl5eB};+D10^Q0`wI9MoEv zh7=uN?hqWLlKAUCh7?U)23<}-9}%$6Scu-@)uC;um7jpugf|nVy4$_`jZ8gL<;;G z+G51u#$FkxWpO0fx9E>a>rDl=H?8g z;gc>SE(A2jCq)-2Yn`Ke->hV{kA7Pp2oJ%r5d}w7dcQ&az41qX21E&^B;u(+dBadI zXN;C&>UbkbRy`Km;m%+K6_O`GNwW1doI^Fvij~7@a;}wsr}xXJtMDLsa5mcenU)Cg zCKE2V-<2&9g=&o~0n3+|M9k3Ylym-?C*=^(XpHpgm5;qQ{kX={Cfe=CWGY%zkY|6u zeGUKs1Q`Tl5Se}#k=YQpU!6~XLrgc#OY}+GQWXkiW3!FqcZiscM0hGcxgelo2JvX( zk%XL%rYG>$h&GnB;UhjQWSmjq+G>t^>pv~Mv0#s3ZH2WIR%d>MxMV7C%r;5X%%L?3hVcL_kGz~VpJh2 zC33tx0>6OmL5e0&aMs`keaOJiflm?t`Jxb~&8crs?Z2RbfBP#IzExSEL=07zWf_47 zb%~D9EbQj%aR{iWVR&}+S#HL2-H#SuZLHc87o;Y$z=|~Q@igFEZ-=Jvat+S) zhM)t`&t@UpxoPf>CY_88jw+XCw5gmr7b}I`4=7HT$}CxdFLUFfHuHf_-h~j_YYUQz z07<%`oZ#1+>hje>kQ(D1Zs~W3xXl!0U8nc??jrDi4++jmR;GY0nsjoJ7oE{Y?DDq+ zW>@V43-iQ`RH*VY$TOrL(?*2e#(op6M>~j@zE)6x_Gy`{PqUXkFK|RGB&f?oz0sR9 z#ql=AtTT=-FEZcBZmwTlR3|Kx+kNxpwHxT671 zRd-<21CPx}S8l{pnr#jfEmX~6=_^Y4>xh+Zy94;P2WimXoE4bB0IODDmPm6i3CBKK_p(v))eRf z0yqE=+yDS16a;mjJ_xMJ0|wO!kWPels+L7SW8I9rY*~D8aph$#w@q)Xs?XmR4&0~X zFaPX@Agd@kykqbfNTu3WaG~`Z4fZ}M_KhB+nWl;60Tj;v3K64uipKDDvLlx5EIwZN_^1h<4>`aK;FB1j5Y7aXOE$SHz zt_t`KGUIQW+LU#C8;^OBYl_qLUgo)x8Zv`kgaPA3)r+KEpVRv|SY@Slf!yyBCP+L@ zG>%Ki4BM_PwXYMcSVk1Wg@YrR9d>FX(hxR90&8(2XACWoRJvbeohngAdi_joWM@)p zGJ?)IrG2Z@7AKo9=l@G zGkKj@yjM(cKIO|>sDmqG(%XnYD_l;K?}Mdg#X z%onqB+RDP!!Vu=*L29Q7aHzD;V|Yn%1eOw0=5ArF6U~R-Bta#3k}2W}T97|M*3BaJ z(owA}2s_Ka1z&G-0Z_kMgWwUiFvV^=GBhIO-jK8Dp!ZHnrvIS`szJ{#vP`1Y)j2N#;T$=+1HobHb3PzNz%Pwy->SaH8^Gn1z~D}V0LXX zDQL#=xKIrTa))6@1(?;Q=;^}*lZ==)hp6@D_!xxtpTCfpjpD$4XrAXnt?k$Me+Yv9lbc45Q zODf`8A76~ds`hXSPewS~mi9?oqlc`&o3h{l2G;mfqZxTKkgK&bb*&^P>S(8YAdr+0 z2KQj5^8ItFt(_BA$_g;cbUVH< z6mi7I`Ksb8x2>e8h#BI_D543-OW6X1rsvGCSxVboGgB5m%6Qas%v+lOMl=p)Ts zsPc#ga#Z8E{!`oLnk_Et@iNTad|6%cw>y7Gl>ryXc;_-{BHj~D79X{U*7G$}cS!T} zDKz3}j}IY$!@o+VAp1#r@A$x0dWAFfUL;^2`p7B*>^^?W zHqLed6cpD(ImGc*&96~&^q#W6UE=LwAg;^n6IsH)iTR0PM;;}sQ8#MwO1oyB73V>J zW~mw0Cn^HKn$H|@C8{-(VI^I6bh9@pXcDM zU>iUH$%b~xf(-qd(?1s%3}R!dEW}tW^a(}y#Uvl*`b$WcgxXo#zK<{XowGVIM;mR) zC^u*tjru-`rx9vOax>^BjJP@t3&9C#c?_=u32;?v)yGGmt(lGK_(Zs!qO$o*#o$AC z)^BA-6$z+E{w3w5V;z$irc~Zi=boqB{_|x7i&+ZSiO2ym!zxg1c%aNBE0`_3aJxPD zU0sgDZB3Z%{ZO!rV*3@8C(PTa$@BDh528MS*Ck@{kU-j7atKfd`#_MKL`XSsMudypJ_!ZomfM#> zI2b3*yQ;Z=OYYRX8l)Jw5uzvr`)%Ns%!MdCEoZPQ?F+?0iVAiZ@HPh8a@J>4N}b)% z;u|*=h4IpK&dK(AAI~T*#Ip-(!brUc)Uvn z$M(0j(zN8TTr<7G@>K$!%L&?PC(S09{DNp|m=*2q|FFW7naE{$X;};;oa4 zx|*giO4Jpv!KBoLUHulSa`Cu_L006YYMYZkpkUa60lPh`EXc5^ytSU%!g;V5Q{5M` z%-0f>QoTG?g(+rJC?9@ej|1`haSgXeSTwBdC`U?68Bt_g?y;^=itK$Ix3hkxn2QhqH0(%AthX$m9*A1#Dak79ySqD?W*I{APPuS4`Cf> zc<5cD=e+VRiha!^!ADy;Rx9?ivlvSkH5iCQL%<@#txWiZ6!&3~@wEj@FzXPNCW-|9 zw%pyD=d8`}FlI~G#c+ZfLsgKcZ)Dl;y;hr9YOP}Z zB?PW?m$o`FYx$+A)MuzaxColxx_FI;E3IWqHwi|KKlWM=Co+C$9bjNBKm%!5Gt}QT zA&LkPPUbB>gyE*8#~9K~fO;>4^@<@5v3m3Nvws^Ryn#hmhz^|W7(8X%RQF)_`)Sm3A#K|u#Kw&$W4pFPK01g@ti2?F&!xUnkEoIUFX)NpH>midxq zqw%}qGPD+$m=$wj*fR+5$njwgb+6*0F)WFles?CxECUE&ooJ#*d;frE2{E*86sDzy zZpW3!;}Mx{j`R7TTh;|$!~;;YE;1#D#nLJb>LY&C_&~O*n>eE8L>O;9Z@ccJ9q~H2 z_$kUhMX(Sw>m1|I@f+NLzfT*ls2Ur?Z>px?Y>3vQ?+u2RW7=IG8|NgwPf)-_nq7%k z4>!nses8eNL&plx*x9G!&PZWx@kOWHiIkd^*k{(~^k$2vk}Lp@ynX)0-I1DWISwMz zGlGhaVPSpyr@$#;(J?AM2{@1egWG1dK9oQnM38zWsRgAozix7<)#oF3n3x;DxMmmv zX74XKvst@pbcvr+kO)`Y>FTyoazjC|@taNQI*QHuE%!MN0rpYZdXpiV!(BeZ{3Ei7 zriM6GG9%?b?-$!}2_H!vcio1Sz7T#|M_%S~}MauAyevuM~k&1hD5nmbAPzIs5Nb8k2 zf$Ca>o2Vs{FtaBZY>3qh8O7nwI!M;@h{9d4FO0z3H%c%%H-oXZN+?Eg?7UlTR{J8}m>4FCf>GK3dYH<(a zXbOQ<6N`$n$rEtgwcaMU<_5OI^(F1`?nRcrkgoci)t35#P6~nNWfx+fYc%1}jVJcS zrUs_FAjRyV#jdK_>p*B=S31ECATEgQLtzg6M41)+!A8XG_th^=Aa+kyPkVNj7+GD~ z>Uw)=6jK#4<11pBw>hIk?nA&k$qt^z0wEBwLC+&s4TNbw4H)QJKO#M0f8#ZkfxZ*; zMq?SnXjqaaC#*=g$CAQlkEt~GG{>z-ILkA?7hT-R9Fpflg{thjrrAN6gKH42>Sh9K zZ@#yF=in7TNT@v8xraP6EIq#>=6iW9ufGl zio?J8WV1y0tsbv?%Uth|;RGX(A0q~ZDTMH-tx!3FkiQl{ zRgD{~gNZE|jib?^x47s)8abUJse(S=8rqf-JO;z1`*03GvTK07*-WIcASR`pEf+F? zS0;P4|8-PC0we&_8@E*yAa)jI1v99f;?nRBqf7V0zeVX%b;nR9u!A&I&Hf_kA_^Wi z88RKEzHopk#k|uAz9PVSLHp!aeFNQ@0CxW+r@N=g@}iKA%_i@@u2i0`ov$VXY~NntdFTkJ20~rOuCEc7^_PEZW!zEKtNy4DCs6xaj+Ki6H(00DpT3K@~=Z*Lr0(kfD4 zwlgM(WF^N0`E5y|YSZlx83}6ZzJnKnJ9$y655hQpTkp_C zH>J#@?3%Wy7C{S_ni9{A@=}rR0CM_f(L_722<9OD6oIbNef)_brMl(`J;ew^vo5gs zQ<_zz4p%imtCx+6pWN7f|BkJYW*dsjur!TPSX9aom6L3&Zl zn86C96;8P;%$L8NgZ>F)2pNlp7zg53ErLwCW;+lZlN3S*zaDbNST)VU}!vJF5M*L9~|GFVoJQDqY!kM`xnLwUOq5fIE4y zb9E#aUe=RaLXB*e_?ee>+>6e0umFEbfc5K76-XB|b;AV1dR0EIA%;q-1yRa!XUN6Wuc z$lGzB0FWDBF}nJ!^aq-)O#RC~SINf8Rue8Jt-xw*v#qE-b&xlQA(O`}oo1^o& zRo`JAQ^{<2Tk>S+?BUu;>azK&+^rJb{%~i>p1^#Zg(`Bv@&r}RK*Q~pp6{SK8Ai7( z#S$E{Q%I_65s@S2-JC?BdqFN>Pj3jMd}LgE`87R ze2)+8E$07N0CQR>!!xvIispzxfOT6Vy3BOpk|yY# zYtN7XEX6*^Sbz%`CkSYDy3*n0Ld_mYDfogz7?rY6xr9W^Jz^>xhIw)7@`0qJ zizQHWkP4XUJ1HusIIY@uKZMju~DqH8JpBgPx9jY2l~JEHX%u^REafzEQ6LK8wO zEaIy3_Jj6m8ArWC^3jNm)JnE5^^}sIoa*>dL^k3qyB;_?5hww!jWsymHB~UWvL)KZ zBoS=)_nGSonSQ2`?4w9i4_;K?!p-G0A*E@vonqS1l4R%3@;N; zBs#2%O_=wkXf-F)Fx6ln8NLJlItr8+#JmGphGtj1mv&yaRSI?U1PJ`WuaNo3Qv+GK8*7)DBoBQIjgsLh^xu(V zd;>)++JJJudGKi9#cYWJt0i77C3QW;ort-T9xL%Rw5Gc4)Cp>S{w~eEM9?+oZYF7r zL%xD6f~#3pWB?*^V`zU1;laUAiu(c8iHY;t8&Ov>{bXuu(S_>*g-~H9`>B~!?8rVz zYG^x%c9cbNh$*9&fmr3vqvn4gOP%*xvh|U@qSeLe;fBWe*MkLGqauog@^+adq@{di zep3*8sun(4F#{o_O2g@GDi*7h5vkye#cx>X)2;GoYlRrpzEsNr;vJm|>9q}_;PR?; ztj}PK^sWzn&!x-eMx-T_snfAH^bQ4Ak}m6vXTKvJmBg@oVF)b51{AD282c@K(YX_- zVwHh(DdH$e3Co$6Y=yYbjkh_}H)JMnCg`d6n`o3K{IiGA}-SnAe<0G69h}t@0csdJj^f|0_0zeOkJXD zmid%A;yl+!Kov}Pm#XzSFqziRAnwNB0??UZI@W6#tH0E1MvzKZaASMl z^G~k8NKvH7Il1wmGE8pc=fd{DFIyG;>h?isLvSQR`oGyHA}(V01zDk3O{x_eazoXpo{9>g%!aktaezkto=so_e1IB@<%8!1e z5|Y`s;N1wcm5B=5620jdCo(xOta!8D)yqsc2<^IazxAwowwB%0hlRM82Uh7a9nfxx zR#I$idFfY@GH0==beGQHj%Ey3G}|5B`Sl8_im@DQWbd*T{KnDKgthW`ZRMB=Pm^X= z9S6Y#BDLFUK{;Y%%4l#`-a3b?zP{`(ldp(2QlE(2Qg+9rYS)#YU__x~$OnzOw}hOt z*B2jf^#TAL9HeC08?9m=ND;l^RVCWsoQF?&v9=EB+0Q=<8r`EE)_?oh;rJW7Dc|KA z3~DvIM{{dhqXiHaP4cZw8;lpUH+6yPv_w8hoeRTUpl2p;_c(xlN3%Ih+!K)YPMulH zQ3s3is55TE4p^s?iq>gstEsfk;2Nkd15L685;ypdj!djz`&TOuY?%?nG?Yq4hyZh9 zRXXH5juw_Z^+?i8a3EEqM`lAX<MLQQ3k6&d0Uyg~3e zikSwRLWyTZN=#cH;Y;f>ovUn~`N9x|>$mBUwUQU9B~Y`#U3=#*<{+_KwRhxqED;3T z3E?P93|*V5E~0jd0mNB&n^)W%DoJy(7D$3e&p<9-+!3UkC)d@eeikkt|6{Bxv^~2| zKf%VI)A7&goRHZhCAlpc+isrvjyvy%H$=iHD$*vO{f~D2z4U+$?U#9}3Urnp!MNIf zWoKsIz0m%Edu{YUVfq5MAzo~GpGv7YMt1qRp`PR4g9><}EOkDp;aVorcVNoBHyjn( za(mz4#((1TQZ15g@hp^x=`v}r3=f4lQgcm~nz#jR=5ru*qVNDkATV^pef5q-^8iEW z0r7&I9Z*%`M%)G$C!7tAP8gyZ?SJ8bcV@#Hbh4)= z*nK3?|KOH}!8yW!{=4jxJ%-S~PXO*1vWp#Z9#R`-2rYxM$Nkx<1%!f3{?rJLmeKB? z%=^F?EBsLcAQT1ow{oMSAM-X)SpT9;R^D+`XJ(LREKzVC6+~xtE5T@Q%--!9f8-@9 z+_K~1jU;$g(rOGdx1EzN3{{u%(%-c*uNIvEwXEyWQrJ@~?r5jNii?(z)ClE;xPb+m zy<#&%hZO6^i}(;RNZ2;Kehj-ldFtj7)9^W>vCPkEqI~|vp`gj#mVy^%&lP9XEHDsP ze%~V6TE)<$70FRN*epzYDpFc!dvBgWeXop0=Fs*dSFyYM|8X~rO+7HER59@yxDomf zF;-;*h=3i8nVLebHhlOgJ?IYxQY!Umbu!v(s`%a%(d?9JlcW3~`rFVR^Om|Lc{Q$< zT`RzS=?bD}oxjbVZ05XDVbNZ4eN1&oUx4n9NXF6X-gnP1V;(};tN2nLXuverO?4z@6uVRI zNu_FaI)*=-HvZn>{x$ivZ09H{`Q8sZK?`#@({dH)8fo2{ppZ_TXC6&PzYgUqXmAse zW_OtE#L{w3ps`yxMCH&KyV%i-EHK72Lo4yQthV3cX$_o(#{|N*t&!=$RY+K18_qO5 zSDOQ10z4FTZE)`E>IXtSM)%b_H_6H^Ylw7SbAQE@|G@NpWm{Mkp|(yTcG)Tu+)5}9 zO`P%8c*o#FqXE?9>`<`X{Ui%G(a_5F*pOl)*L`B5KLd$Hb2!pk&(BM+!=6_?m9I#? zGz;?U_3uf3LL!>UX6WQfxXXPt9)^PHlTVHPcOH*x@5R_uvh(lK<0)dwCwhztJP`{? z!MSRw#*U0~w>5!Y4XR8C%SgW7XcVqiRRD?++y!ENkBUJLYC2Q} z83QZeD^-F3gj$&}a;uX$Xm&Ozm2L~mwaRK1iSky8L9g;$r7%}rj20&LZ6Dy_rz5Fz z!K_u5w8y0^9R= z71CBe5PU5V?kP*Z(Jr__$pM3B?n7>Wd4E{VEMWrhyEn46>NPL#i0&K;CfhFR=a|62Y!AcHm8Dn%>{vfph zNaSCIW_331t%hImi;n)61K@q1qc^VCAEkMs{cmP(h-*t?O2@dtV7Zii4#oQX+SGbQ z#HaH}?;)M&Ia$zSQgM$tWKmHi3Vs)~O2AI>>V+aD*2gr!wX{S-``O+NQ|iq!Rsu_cm_$Y1Nep)Lw-Ar%(Li%&<&^E67tb>bSQ)$6e3T`pXt=`OJpUB%NTZVxEUZ=X( z0PiMyi{erLXoPH;kPi!jW~+Z5GVPX_AUU`$GNy5NkGN&O!^-zcgJG#w(XTiS4k?fGL z3{IjQGKMaFUR6fd%N$0QIu_W{)%x9d*eXxujACvJs}g?+T}QpY1&zuB?SgUnbAnFL z{0|sI)^dazi?BYgA94dZS)+MAqw6tM>a5+x!-Efef4gE-Q-R@zZq}r!$=Tu1*#AxtYKbP7-U1N$7dHmAO`2=$L)I<<9}U zrB^v^gh7%zRX6e;g3<#HoblXa)cpl1f$Y z519J4x&cN$u?!#`8zNcCX4AL*$jtDA!Z5NpsJIFGCbNn`Um6@_r@GEPKE6L*q8g0w^Pl8QGJgASE) zsThUeb?;dQi^ScTpeW4tMNCp0!*no4JFQeQVhmUmFu#4pB||N7Ca$`+)1~%iL2Bv! zcbUQ{NG@k5U|@iXKtp1}Tpt9b16YF!G9eC!f3^#h1!TxX;VxaC(4 zRcMn8n;v-#e68HhVK~b*DxBOmOF;$~TKUGyVAGKOuSv0Nln3(YhDDCjlt1PD%8ET<& zB#%PfY~miV&1~UI4~SuR3j){nV8EXX*He79lAHim-rE&U-;uunJmR9yNg{7wQJ8<7 z=;)1`c)(Cek)qwtD#jQ`D8_N!80tF-&`JXtg^o{CW@ee8gxw?AYa?|6+am)|agvbQ zY8b6m335xsb?SXsqd9;vqD5x>_ zZ}BVJ4*y^5e)|>k4a~xn!(PFy8k4*7l!iAqDO*Bg`e9QS7)Q%dz>f{;oJNEzWyEt4 zC&7)YW<-f+bW;HfW141+jk7ZWc)Wa#*;;Wqha7Tx@MdOoLZ-t+Uc>^(xYPxZXoSSP zr)@9Oc`47K?vTr;en&sRviq+g^sgd6iBD|r^~}?G@Ei%{su(9k{$2Wi<#uculxC~! zjI8?2qEm9_JjIw644to`?Br-gYV|w!JT`hS=$gS_bGh6HmC-aWk}W(+&gSJ6;n=ia z25ACPS0``WjIb$5c0%ZNrB^rldlTdd&2)#w%aaU=@!KtdoG(v zsA#u;ZF9#HA5Q}ia8u`lg2cJ z0|65vhi|;B1T~!26O3^#C~}v#v{537ZR#=(}izwNRNz9Qg{@Ri1L0LZ*{=Ns|l= z3DjG5Luw0*09@2SM^BnZY~Kod>eSu-03C&Xmk6nauHfsY<32P(76b3W?q!bDg``*oWcF#S^NS*0M{} zA)wga>s)G@ukrjIw-?0CZjIQR8$uHTVcc0A*TS9G>3*CH%tieAG0nX-Ot+_!B9u@* zg|9-k7?tDnnn14OecJcF&@hugLwIex78AV+bZh%m9%Py<4*_gDS_z0^ASzDD+!|B0 zu%y9V)04(tNvls`+lID2oz=JKyUwGhW%dk_`+hLQ4GZh4*KIXN!1(D<+VYPlmeE4# zcM;KAhdt-P0uu`ne-W?bC-+Pwd*1~b%2R_KEapzy71l|Gjyge`wA{1w*D8W0ww;dp z)$o8j>T#ns-MOnCb~CWv)w081qA}zSvvK=>{V1_5V5(7Z4M|;#@)R5!wF?y5dePTr zMsWyzPmRyoU?^OpN_LtQW&w(hsk^Z#z#3&oY4&z)g5)FxKD}+4x#8lFHsR!#Lh3;; z34aYc&484y#75%}X!-wqylFUZ;h+3Zp7|TDu)M}6aI4bggv*mEOxmFLrFN;pl%<9s zlxvptr#X2*C!wTM!!{3AJ&yUY$DRs?{S?7E@}T~Ug$F?!_fkt|t**Sgt%3c8uej&p z`f;vaQlF{RMLuZE4q^9A314YL$QsAFLu5nq-zc#IJ6kn8(2c$a%@!ie^}hrCv7@PO z#sGyZd2yG}`?=^>d2i-B`sXkW@k}7}VVn%4j*0nv(#O9qvjimmqKOEWjlzZ15Tj+i zZ&bSf^Rf&f?EilzFfK2MR=;yBm2Y}8K?xt zW!e@HPT6LY$UqDZl9h4!q3+SC3vEt<9UtYc64b1_FPeLnvD;f1C(g%E%?SSi!tqjC z!%G;xcq_+QZ6nK9Yd-9X0cqsQSTi~2Jr>Ll^E^*6_bzA;Xl*z}2KZ+i1P_SeL~uNP zy3!$gq<9;adA6fGq1c>MB-{#*auGl2-g;Yk>o7;P+y%w);6Wo)A6||aK@E=GxuR%cN!of96@A|r zV9{Z3k*F+uSbG7hGM)4in0;)t`8(UU!6Dnaiv9KG4BX zt+xd`P{cm<{^zG3mY{||j|r=YFmErWqnK`w3vOXSG*xT#yTRjmCJu4iXEVI>|4MAZ z?$K8l@NgF(134J+{OmJVOd)cRqH7;V3xqr4f3obVH^9V%d+``anaQzXG`(x`NjEoX z0WVug_eB&@Dp>3Z@*(O`E+%)h639~c**B?;5dI@k&SW;|n7DPHwajGSO$Afphv>$& z!31VRaZ?P;vR_~_ep^2*ZCW*DjLFQqcl0@NUJj_IsFuVm-;QznC^JKOogN3ej3Ts4 zs_d7{G<`(ou+QR5f8*r@T$Zfz?+10WUPQ}l0SMsI7tC5LItnL(&s&e=u9Mbx;R3KD zOYFqiq&*QTmxk&W;&Fv@Z2e?kX0R}jMM||%lu5u=Hf8Ys97ZxC3TC*sJC)q>a z_dkK8LM0t=IB!E)Gz#?8J`=YY2F2+Pw$rU6Wklz~VV+o0pf>e~5L5}l9XCo81yo^1 zs9>@c^4+I{$k@l?v2d;{pvRnzFm5x#x><@M={-lCT#Oa2m0kPh{r!>4u3R)P+!0iX z7aPIcQV8#i-~h4?#vd?lKXV0R;Z+VFekfC;-)$zD(|@>^1`9<`y`5xJM8#6Fkf)*p zIl;hz*QRb7%|V}6?Vgg|%DO8x9v>SM$`8%n*Jd~?c}7*2q{9v+0HWbErV{X|MI7fk z6Yse>Oz891za4n5|8VBmvkEI>iFX^Ai@2j4n>rImV!Ex zIk|<(cEW}a&(h(&O?~{o!2?fzgN5GptCvw>=@pW z2)*)b2^cns;ubVEn?HgcEmkhV*)~Sl^<@Hs7LF80LcG1;srsu@9*T&HfpDnLez zJC;sg%Fb{gtlDnW8H z34lF_!YZi?#$}25)Zg!jCYOJB@^=}+`Ti(u8&yn%GT%#ik&gGy%T6_oB-GXJBHTB` z5^no3wWwBiLgdKywr8fGt>!YZHn$kp`R}wh_mpokpA0H}uSXbAp~UJM8xGaAXLJS1 za_x*;j{!xa^41_@)H20~u)UT9_qHlAaeBh|bW{tF zvUKmi!|G(MVaS8Hnf2qBQ#V$yL<_^8KB%)4P#I=bPQaXlfjbx+TmZEr_exW5Ig=)r zVRSiEPp#8$bN)1d%-Jp+JL==BmCyY%A-PipSe^@T6haDwxW28Igonf&iJ?r81AfM& zk>9KMS14WuwbrYh%;Rf=<|0A6&eIDAATQFlfOl`7d$*L%lxRO0#)@Ii5A?F|FCA4^ zToN2_pb`F*B@rIfvyK%7Grn%wJhB5%m0t5YO zDh#YnChNJS`qnD$qkuY6>O&?oJ|sQMOEx&#u))R?=(&)hddX`g3i)AY-h!IZ~j2|E&oab#wjH(0?HP3 zZ`O4SkwYfH6=H>FIw%FYGFlfkuoj;L2={7dxLWq6>|log0J;9TjrH_8$}QSz3#UIE z#HW>qr6)5UZ#?d?)W&-5p6xo!OwgZvA4Y0XZ*u2W1NOQQ{vR;(68%>Iq)T%&)|ls4 z7esZkUmLMbTg*_ezWQNLSYzCGN5p%McGnRtoS0v+h_+23nX23jD9uqd*RWk;ww2*% zv+_z#(xsd*4xx_|^rmJdB1sxRx!>`gZ+SqAcwxyPVvFNueuineM$1#D`|GHISOnf0h@r-8;l7Zz)FPw z!q%q#jw%0KQ_OC+G`~(ya`ROgDr59xVGvieg|GIZf-B3K7Uy`~Zz$z!w?oQP9S(B4 z$W<)I1b2}vtPN79Wp&SE*dp8?wKvf<6CJ(hXnJul&F4v441LIna7963G}LQvnA>s9@fV z$LjPF`SA=B=1j4NILT-P9Qf&wXx(!Uj%X|c&kfsBAdN4=B7Wy#5}VZ^nTsPFw53K6 z0w1x~qzMB!4OP~tS{ft^lc&mbSahjf5N>i7U-};P?I>MeLkS`H2Q6kW#}2o=YS69t zuyJ}I)leu-2v9hecynMFKb6oMX7t4f^-RE4%k_OAzDeeWiz~J1My+o0FSPPbNPhf)hjM5DUC)xvYQ>uT$fCDpEgq zUo&otKQyg!ez_ZYD%WnV)=r>CyDd(%favq2Z3EJSaaF2k9`Lx4$009kal@pFMmJMWg(KNbwr|4N+Vp{T%Gs@WnP8c?s6Ca+tV<8fVQN%ch<)q%r5)3&oBF;{8gxAcoCt?7Qn?a&l~Y6*`~}VzI&$W3IQz=$8^L zYSaK#Xdq;pt`HJ+;{39q`7Q)@d8tMAen}3(DhS3#x*Uv2?9ip+3^1e_j zYu&BXb-sRpALr#V86AE4B%F^#x3!F-qRT^pXY)G<>1xjB=2<$TE@gEyJewaKOpLdI z|LP^THp8`YY2K2^+X|q|D(IUF>xL3T;l?i^EC?}iQ{Yd3`oIP;3@3&XNDVPuQk>=R z3Vt)l+BzG!DL62DXUa{;p~f_`e)7_5RBYo5GT)0SA_@R6{XP`pwlw8FVUS~V(Zqi# zj9D*}4_o@XO)=+*OWCS7&}Bq4jar5RsF()>r|I!2 z(~i~X>a?{Es#lZXA<`YG1B8mCgnL18;1pN5KEKBoQjKC6N2GliOzk_9E3W*04S5Km zc;T7&ppT;GNVKI!00TAFnv7#xry)b(o&J=Ermo4dsOYAE2w%6!OZ82KQY?DD``|sP)A?snI&M$a z%?q=9)r5ryMkkyb{Bwi9tMJMV!y`OqQ!VuyK*&Ai)~m3|`x-m2QCSAY#Eb*7y9NuP zrOh@{62dRjJPOY|^Q8B+uD1K+>e>yww9ds4O79CktyWe zW$!E%Oze+Ko?Zd6<~7F0!0L%E2lp?0CGTF$QrWN_mp$Tq=c=I%0sQO=EpGZHhY(-5 zl&n)bul|I`qp=2Wy;*ywIJQtKD-@fwe{E6el%h6Wv@M^+X71F*-pm?ue0ah0$jNAA zqdDHJ49+j`hZZj9t?n8LDy`HSn27UW)apC!qC6$T=Nw1zaR}&Nb)d%yi5x2T%sR1b zCM=)YV!dGK!x4iE;?kZ{_mCi9y0lM#zgI$nCbku*n!JZH<09CpAhzJ?inS3Fp`wD! zW)Zjl`cLhjm4XEx33UVz9|t7}MfNwyyBF>6?|4zI5oMPd52<^^dcRDU0dkKlE~#g# zoQ~EhZ6*}QBN)l50~hC_@M6HHmyP*$xb9%gl8@n;F+NZcjeY^_-p$9URh4{s+WuQJ zy)8tAxDH(P-qREW0DxG=p{TPZ>zD*`$8&^bHUtaks55KxKitn_ecxU z|0{%IFLZNFKPZ6I)Qg1B6v6MNXyGKO5b1kBwZ{~-8BV=UF%~ZEeibV#&!*38v(c(Y zdf3O0mC1OVn>6|eC2{jH*Irk}euW64L-w>JA}gWrv7fJ5uDzG8)wJoVZR#NiEf~31 zp}2uSjGlYGvch9r5h~D7)6JQO8{r`+JcZ!AmDHDOrxv@o#yu2Mj2~6?QX#9-Y1k6h zmuP8j)MB*KrQ##%o$aw9S$k$7>I!Swr%%4)B#DOLqJ zWZY^)uF-D4?TsfYUafesJs_zzW8@qjH#!5u^{#u79s(xbl1IA z+Yw4M5N5B;VZCM8bKs`uhwf+wyNrJAcO8PbQx$(fIDT;udKmre0lH zBmmqke=iFubq**|2p}_BxhrACLVSTkM#OI?>))Q2vXDYidf5&F!FiMfS#+~_TwN1o zCJN%>)8qP^w68cllK!?MVH}?9T)V@OR)W_x(nPCu7cx!q-X{lP^43d^@PUlx8=zr4 zitO5OLS=u=PQDn%un(~Z6da)i)+~&S7UTY7lao_A<@KC3+J_gF!7-HpFQKnF!6z(e zjh^Ye-bLd_j9I80ho*IXd9$Zt`mUp1({W^p6is%?ap;MFoU;@pj=~=wf0No{4i248^w= zd=AL1!!)9849Q>&fq7IyY;BTtusmv6ZqbuxbQP6<$x&<41uN(r&(2g2A)GF%*_P=Muxzgx5B6F6$yF*R};xBIaQPC44_?}({8Xhn)4<+5;`sV$gWWf4QbSk4 zFVk29_T%vR0u)zKl(#hvUc#D9(2Be^63b6j==vK)4-_HKSSy*2DVri`u+R4G3c1H5mq9MyWaPW*k zwV)^UkuFDR!-8SJkj;4sbAHI=Gj{{XvpW~-7_C9-%SH|3lLf<2vG?|-1+a+O`Lh(qeq6rF6gGtf#JS%NSp~?fk2qAL?ZAjGYj!OEF?}oV=1?RE3cz zTZlB8IGSIkLy69&PKbiHhwYhd7LzlesB|Z{IHKzJ8Yd50)jNj8OG!tU0KQA+23_6j zXa?pFx-dmklRA1LZ{;s)N9MsUjMSJqIBr3P8f>MmYgOC@V2cL7Z5(kB5ks&}H#~^^)r%$1Sq21uqeFnjnW2(HbA4)Rv%lE`2W^PneLd^7e?R!h?)i$g0`(h& z7Au$&Po6w0j4k=SN=EzQKS)ez4isF`llxI%ER+3Y^-9ufQU+EY4WdHG83ZPgvhn`+ z1fCa`F5v5tnkn5o<4?gbaY>67#AhMpOpLN_*L!T>!ekZ-GS4sSHT8*Cm?u#u4C;1O z_EJ0mc$LNsaEE$ls{IBwNC7Iku8kwaYf?;qYbZ$NT>@UJMP5xxl*6tCH%js_jv}%^ zK}2SsG?M6OGFaIJ!G(8J&e|W=eH?PL$#zloLK&Ty$Yns%>@km)w8ohZA1NX6>hyhG zP`T@w9JiRm|uBZ>f*qd9@~apy8Oc>J%) z?GpgtTOp*39UM{;ug}q^b8jz)?gH&0vpCQN>y0}A-tY&7pI6YyLwbwTIB*KapBM`G zOcB)L8OKrij106=Y88!$b;}M2(X~(&sNhr=NV3<_I=COyXK9M{rpvy)1#3V*VW`x z7HXqC9rlm*rQ5Br{n}YR>^kjXv@StE_4SQnHwAtToJphc4qd9+25KUZZq{0RtQSWx zI4xyHkqNeS`$dis=N*^dh8&-KGqi-j2WcEQW~Ng;34uVwPvRpO6_q1i6nP6QxS#T+ z+Nn%rJ=m!bqowPXa>jse75=X>V;XYBax~i7+PekU63fnX3?jBC^~r^VF|qzjG_NJX zf`Jc0yg zO|B@+E#7uI$I~QP^|H{hppP>D)UQydWe5`{EWuv%Q9Dj$_$oR8R~``Nq`OmdKj7MW zu_-k}m#jn-a2t=fSX0-nWaq&)nHPljTzpxy-c7JC)ICu!A7d9rwI5wb>>$d?qbE8H zlEs|K4C%%#`n@w>n1b<9*{u;P{k&*D^iVf(#xPN4(f`GqSiAi}K_W{B3xfg6p@5=9 znaz~h9rW3?4e=nIA1sa>?3`wZ6=5fImB{fJHhFDJm8GhgF?V_fMK;^HL$Q$Vc0``#LT zoUD>Kyg2|0*E?5R)zd35SJe#xWe}`FCN4CYbkNN08nC!j?%*W*F(if{83T_xDS)*rI)`GZx$RyQhO{i=ej zUj|dRDt2-6el}-D5n zP5Pvk$rwty@Qq^=4=OFq_fw*7@UaZtPPRKIp&cr%zjUoytlrpZEK=+O@mXVZghQt2 zsWYvQRKQ#-DS!lJfgCMD7SVRrx(eP>FBSbPUE5s{LD3FUjSf3M34~{_RAiEYBOqb> z35Lr|@z?^4$OYlUej^JvOdHxu zPGs)KUJU>CqPot#KvMBXPxu99kYac?c8lNnBwzQceom_oeCeWJ6hAQm2Uk#%!sy7% zOkpT+XF)GNgqYRthsg&n|ee~lagrsVrNjfK3DNZHtrm!-K7lp!wvC4(ql)F=M|0Z1&{=y<_D8oeKF zT!8A#pk))*n3!46bh73DLTy_80u!U#6K99;?K%1IJ&t<_UO%uhHfF;sQD1Vu-)T(p zT^77|hSR$9AItlhT-p7*a539O6l8ZTA+P7+dsE{$q@9gyNoF83V_tHtkg_7e=v-L; z7Yn<)a>q-dtSw5DxAji@-(TXee@?nt2T+WTG;!Vz%mxRBvZXQzZfPA*t8O2$pm!AY zW1lo%z1SIEygO+kJvm;KiOQKmJcW1+g<(ESUPxc#(t*N73{$%BLJ!a3PK|H4S1j66`VW8FPl%-}Z3w!D zXliLi6C&W!7h_1za(vaG_gZu_Oh*J%L5!|Kt5B7^Np-_rwlzauoMXUP`bBp-?WhS- z&^GfQ*vq3mcrQ=-F#-7Pv4NRcs0TZIl(&Q8^FPs$qor))9jOA*N`RRy0`&HVk*RuTPu&+L3_J;RQs zxU&@r`Ae-xoP#kT+UN{Q+TZ}vvBQO?G^_hiRqMT~(yvec->3zM+$5FVo!Lt%t=X=E zNuK5Iz3z1NHW!`T^|E|I;P@YdQUy9^nK}cFc@v$F88>3j&1eqO*k#$^#HQZrQ^MYX zb&x2)i^vh8lDg71jaSaomlYwT#b?G7nByveU#}nP8SX$BR8&I$2mS>>@76h8_ZBAw z!Zc0me@McMF+kEV{gAo52NJ3c%m;cu)_Mdq-6HY6p=T&JFZlP)yq_T*Pr~D(MVNNI zHmdV?7)Q*>tDTw!xNa4FYP66U5=e>k{7(zbRWT5b7nNze-t#wFaPze#Br!yXeV*FE zPUq)cT?m&v0msFQZ|^-gE$$nTHRZ2PeqNv_xk@w!l_~jlqyNkZ^mv`ndgmyOVBFQc z#8F1l-8O97AoV%zA3>BVH3?^^4MwZVA{@+6gBS}~_9wj`sy<{KI1MMsamgzz5h4k% ztE*r9xX7zug~Z36a<-pW-1wAsAHyPNm&Cac-(RX%0s}xcb+^{7ZZ25sDHXGeeOKq| zEz?ecItvGKCg3A;X)wI@nhPYexU6Gi!{JN={);bmwy;rKGyjLuM@_h~749V)<#EIy zDx@(}vCpmVZgN8(wu;POl6)~5WtgtcWGU#BDIGY7`=Gfc2cUClK!n`^_BB1r4CcvXw-%x z91zkZCD1_Q(f9mwQHSoD11|-F3{7;_KC$^)de}(%Nyi|3TNc=60l!N&TC!02;1%h< ziQOo`U?THeKZgzBeGAl}aw=i76e*akUj*i4#mETZqeM9m;X?6*yg1x}u#DOWh_VLP z-&Uwt)pZo{<>kcBN?q^aX+U|HkhqlLkg-zvN=Z#&GHO zx~jd)D2|SZjJ)79X7ekH1z6Bg*X)WjWE-u~J@zf2v~p(yG;^8z+vSy^ohf zNQ}gXb;|96s}oXQ{CTKumfF8hMR>!h)B`%OC`ZXLFCsI+rZ7BEp-OO)izj8Md#ssh zzmzHyP~DnSGBj@I5J9+bc6gM*=Z)Awkcs*q$E$uO%Qcx}@_VayIN2@*ugj;dT$w(k ztu6z{lcg8$TWeVYuwdW(fExdIW#9mX01!ozYyb3}sWf)I1K~HoJU4L`Obd`({KRe} zLEF$MMBQ&>2I>p^>tTlnnStgX-CV|jQyVMtEP#94f$GG;ix5ScPrhtv$%-x19+oTwk=Yk^rR4Lxsi|?0pP787bp{QM3H9x^;?a z>Atxw=v7HYgL1CuP@_#n)kBU7P`Rp-S!j0=p)%r*INSei;di-CjVU~bx+80YS zo}@`SHxf)}ab-}l|J>CKPFYN5VCwtNa`<#3`;b$HjRofrFID6Yy@kg}?~dw-ai5VM z_|n-C9)Jq8omc#3uX;D3CDJJR_3?_2qy#v}afx!e%_3b>khhvg;)Ehlg3 zYI>y7lv}D(Ww<6jMgw9iVeD72i)cZVb=goF@{pYJrs??JB5NHQ zx)!^zZJ|_Gt{rMIM8_+uKHRCJ5PU&kv0w$+P1}p%nayMehvg}oM4dff?G?PHowi7- zAAJ9^b^7YPIs%4PNe)*QG?AwHRa--5dBsGp5sRln6L4lc;y03!6Fk?%f(G-#AGs;B zw$GB4=$}3=coR5^1((L}#sk~FG(ik%5CI6=pVkuu+v0VTv-W zIcIq}YgwKt3ndWrA3tqKg1J+e1M*{Wlc4yhLj)cJhZ7v72J5S3O@D_zS!lkyT%>bXECoZ!Kn1kRSeDTu-Y*6f^~HY$gP z+GuN$03XrcMXN8LZ};X8#sA-nMcwt{DzL!R zFt}4RR4AV$*R3TnzWsRYs8PEVLIc{yGK<82l`lTUXEzcRODMYt26w0s{)cu8FnP6D z$rN9ldoG}jK2u-bhD6kb7R`C2O(3p-LV%;ch!acVB;C~7CkV-;T1bEBnvtL(RSam} zdV2`HBv2d)b&cy8l4c?_@8q=kjU8qq98rvHjjidnF}pg1Bso}lQ&d=41TsnrHr{{a zYuY}I8=5QuXRFEbm%qfUa6yvn?{c)EdIji0Dx+8?@|CqHTBcL94UF6BYBXZqhM|2# z`MhLGQp~}!37NsSOJWZsE=>td^C%xH1|9_6!(K~8}B(+26?aQx!(nF@F`H)by0-%PG9740Uq&%V0-CV5^|7e-H zS~P?K%1(4&jd9aVY6~$fGSO!sLMoJNvz>S$2Wr+?h&kw!Vnqnqya=};kid@!Tu`eQ_8_R}dnVGffn_*_PSvW7IHZpl{nf=wLY$YWT z_Y%W3T}OULhQFu>wq__Vd+2l-yiwnB+)qQZuig=wc=%36Q2}uk01!7kERzo*3OgEc z^|V)k$lIaY(G*%Q;C4VHzyjPq4g|;4z%h??u18+xo6+G}D4`x7Qq6!8B~qJ12w2du zp4TXQY*b5J(q@qU+V&m8*iviGt2oE2?T_r}4wKYm*TKM0`0vsci){#eRP;fQ5JRXI zj`5^#hC{=0+y)oTNp!IHfXSyoe+d)+d%vO(<)&zE8ewMP=P{6VEXs?FKE${DNddL>@`RP*B)IZegotm?yy|0CwsNLt`5Z(b%$_L&;H{ z3t}X5A(d6SmI?@=GNLiQa0hpP9(Tu{VL$imuK%K0z@AbXMP-#Fd?QFiB{MAm8mSs{ z++VF<;7CdD7-Kg3U0Mud@1FpMVwI)_TaGP;^`=cs+5A`Q1L%P#M(AGAsyW8k6LgmA zRX%&fgK%4P%r!MeBLQw~#VOqBNq0K4v6jBS=I3#<&&yXj_*5p1P}6fJE$X2O1l zx~g@$K#+7SvVs2Ts#-g9Dz5O@;#DpaC)iRb;oQLZ8c_~4Yq-;$EnuX3Ydkw(bm~~c z_jC};DF16m*Ap75Qzl$zb1b?gTbll$zeGw{3e2PoQjCgu{fZNQ*~-Ml9IU^w+UsrC zjB!G%P0wxXqzC-uHW~3eK_@r@Om2C8j-UH%WNyd8ISaXPF}n4jkN_@oHved?5J&=} zHm5&hbI&8Gj<~fgvI*+5^<8z`fDPJ0@Ei#1edSY5%szB&H zYoNpSBH|KHDSaO$xS&JmzrdRHp&+OHjy1C3Eer8x2^HG*z;BEzJZIMV!89BWv^AD` zR^GJ&3Y&BOQLeDt49NqDg%EaKk>;q&f~!+qSXum$!jybYoxOoR?74Nq@a*&PuZ>b# zt~hFbzO6eP6tJrvu@6JZCJr$WrCt8saK_1-NHu$4v!Dehyjp&L`s}C}{43Ws&aja( z$Y6AGI(7kMO1CLOAl?=4fr~bR+8Bcv&{Uj%@{~!VcoK3F{qNHtQ}71&Y?iZH77uU+ z(;?rA^Fwot1&r9&eC79miC*~&H0?Mj+M9X{2LuJ<=YN671 z9aJE#MZH+F$KXN8>6NpJ)6mU6KCAv0ZyOle;sgCSox}hE<6$%-1(74!-wD%&qH!d^ zkg28y3H*Zcz8jXEE0Wy~z(N85n5|8M4Q zC_bvnaQFmGry#p0Z7DugiM7^x-e47K6Bz7ne>?c2j{ty>FN(YrB+8fP9E!tJSxTVA zO26sp5+X)_Z^cRLVLU$`{H$kV#~IpKGi~4i*J`mfIzW&d;KZ8sF$KsXFjygYf^yzY zMQ4_F%ulyHqpt9i2-7T{2a$m~E<5>Kt5+GcOr2n3x|emFtbUKty(!SrxA3UJdSwMc z_i2)V+rsO>z|{Gi0^}MG5;0z_$nb>s!-G*9Z_Q|7t4zfwHw$H{;au(IK-BjAv4BcJ zCJ@aBcu|`Ts6r3`0AC!lz6`I%fn6X0T?5pUATOG{`P4)q0WMYxI@D`0xHWe409R62 z1$fBu`uJAn$&Y8h)!cuYiqL>a3>3i5VSt=(%mL%JHaV#KCW;As*EOAA$+^6df%yr@;OA&Ka=nzZqW=!!o zA|nnUPns1Aw)=r^^vgr+R66e`Yjin!RHG3!*Rd-wsGf0tI-Pf)FjPF=4a0AR8Y&dB z-Ef=$4Ku8UulmK%)}ZY?P6z-mk+F&)B$<^9-;8%akt3 z-O3e4R|q+W<;XFgz*v!soonHB!>Jt<(?Vm(GghCKRlQNVLh`$S#); zDd^YzyuH}CTj_xLCy91nwVE>SS`PnIVbag>5pM&JP5ns7@BtHQ`o2!V*5%i^s@<>g zTBEXSAwb_7=jSOrF~6f%Fa^)`tzUzi6@GOw4@^snE2R{-Wo@O!;ol7Mmnm|kC~$}; z@_5YPPGpLKRa`tKX>I^)#1{@C?oe+80{^Ek-m@jE$)dYxW9<$golEA|fa%o=lqw5+~86RctlS)|NwL!`u;d{XDY8d2l2YU&d7v zrkAv~003`ft)()V_(Y76a0|(^fdcm9+__<0ZuyM>hZ8*f%hEY z1B*aQ-5go~R<~{2`c$nYi<|Nnv!71N{6h98-hBK7p7iy(&d33)kaXNGHZFaviPeyr zElAKI6(y#*tb){Ihub#;975sqHc90rJ}bi&<)1r`)zExFS7IJ8EDJsZl+H7eOSYYfEYbv-I4* zG`HG|d}Ut_1MOVLHKPguOZ)f@9{CYRHDCCa2rkW&p^HyTaVZ!lP`-R2#+5(d8{s6= zw~XG#0=2WpeVU*S4ru=u`APA@;cN!$cZRVyj(}YD)HiDo9k;`0-~bGNf=*;C3w0fZ z$r%XtXokW2(}?AUXEwg+$vAP}p~>4~WLZ8Z7g1uc8r|eg%k)ThVsl|aVbZGKz=znV zLfEIO ztW^6cF4vuEhH+gt58)~hSvWUM#+XhY4G)m1@bf5zD5tmc15!zUwJ#6}*-={KPE8-r zAs65p*G$-jZmHdt)b_E#zq?svXH|qUGxg3^>XEQf6U<&1I4kx8x`AqmH6SyrA*+qa zp1OVWuRfJ-PpiWbUMD2SGa5VaZ}AcMY4Xg(YdlYCg;FyUuhixw%N3gUj==416zb8p zu~8-T3#w?WaDWO&#|GbPI(ne-qK?4;L~^SoMb117wcjv2y21@Vdz4;d7Zqf`Tbf*F z8;}Bg*Rhh)jSoz{G%96eDzd1%PKBdYCW_;)i|C7n7-k)G)RYI5LP5?F^}%? zdxT%Ui1@=U`k0IvjSJ5SeubZ36n^;Gr*4ypP7x->;ppoT5%W&|V70vqmME{6H*nC0)Ph-a#Y(07oe1wQq00+0KG zy5oW{@vV_86!bQCr3hBPI1m>ROm-$~n9TQy!`b9BB&M7r{8?EQCbXQU@lA12g{k2@ zylKcW-GS#JERSYOb~b#aZD!}~Z@@;$@KnueOOp^XrLrc4V1OvPo1I2A2FJjrk~6SR zIrafwnXuHcstPlH{0IK+&>=u!_Zph&p63w{peD~UE3MHU=_XK&1(02Nvqre5x%ElT z1=mnO32fvRw%I#*92P4XiZv;}%51P`mZHi-KopsAZwLnkF}fwS)QAPn_>Q->W7`34 z%`G=F4IRlM%h&qRB?_Z-uN0-iJLwvA*~I(Fqxa6lIfZ~z5;yUD;kAv28xz>MYvTTz z4<6%o1zaQ!DjyWWyGK-(YMMC;QpIu|FZgs~hn4EM8bV;ur;RB$0hqSTJ6C;$7i3|_ zqng7?5S36fk!jZJA%~KB>m&vf@WYDUQGQ08|bX46`v3Ka^E&{&E z_Pyow!aoq$sJhS-OermiKeFY;oFK;&)mY&9OBxMMIcx~W{k$z3U+2M)U;qLs=iq1m zo+P9EAmPis33q|M?I(m!jtDg1Dl!r&}c55uo^i+0EHDmFZbZR&x}%pnd}#akmus-4@R2UcB&pOZ*JB3+2O=+1vgnjrEXuMF0zX~d1ZZ?^W{o`mw(QbVVA5V4Z` z#i49r;5fz!nZka>q9UeI`34M>D*+0v-=sXqpL+Ld>AXZ98dw!?dREy4kfMz--6*#E zS8^w`(J%P6ar|^gRn!~8U(+a5w~ zP_KZ&ab?CJn!Cn#{PfvIgnL(bLAl*C==2L2iAb=^BXobPO4y%No?GAhAv zr+*$G9>C@;te0+o5zoO7QPV6r4;H_-Dx-88k3j5Hg9uKk-~a((X52<2%YI1Yp6 z?VeWT1zi?V=SHaDoD(-?jMC5j5T!K0EPJ$>aIaFrvY7r7i9*L@eDV&c4pxShHbIt) z)+XXYFMPk81L(YS9i_W`;^|kE3(}xuU7iZ>3RTGEyCUCQr<$sA!rzJsc!?0yEET9H z=%Qiwq*VUWQQw%t(cPz-Q2@t1jo>5#<7tSF=Jo!(EAx#E(qAONkX$*{b-Xa`Q8Aid z91^kffaTp?U$(2MbqS6v_S7!3(M@x_FJN`OtTws&&Edi#AB#(pe6V8 z-O7R_1d}fH@OQXbZaSb1vrBd+f}Os>Qzp{Z0pa+PAwEV-qK1hX5A$RG*H3O)yy+1o z*zBW z4V??id+eDaET=H&$P*0baxjmTY}p3=nJL)ZpVzdok)}e!s<6!0=TppJP#{=FWs`3f z)zvfsmIDOS0BpP&Dp|RX+{+U|AU0(P!SyA>f8>wmP9F zjk13W9RktUu>3UcS1uNDax$kE=>7VGlsYk(Y8_6&sT29VqO47~_70%?asme2=NZQG zv>_-8hs@1DWWNne-nGKedRrp9$lz7v_WqZWxkz=kK~SxBosh1unb0`jEbej7NRgX& z&B5a=zf$Rxed%+211H5Xvaf^+6@P!Om|XNPF7O~`c*JU0;KhjD_n!g%E&`f5<~$|W z+OJc`esLZch;t0VN<`<>?3odRb;a!lWVKJ%YK~`sc6o}EfN-A z#}pJcP{`#(}!vDi*{vjYn5xCl(63LeDfdUUbY_ca^l8YtR#? zY&K{|Y_>rsCVl7F_0lAEvLZ0;;BJ0hDzD%k0vD)^f%PxvW8;EO;V^d<@^DQ zZVveaKbmQEaajdJm$jzq@E&!uCPPk z`pe<_KF6p*MfbDNnS~)y?h`4!!gQjnpsvGww>5n}#&5$B2O(D@J{zK5UMWy`KR!UI zb$v_Y3hV;v8c}$^qcEflb9eRX*6jzS39mRmtiRL;R7Zm9j^@vWOZSBq=EFet6z${m zG&p30r_$_UQ|DU2SAji*E2GXjt>PEgSo3Xt^>to^{8S~xkh-u<3|JL^9N!T2GC8@~ zBBpj5^4wec#0!Q?5aZ_n)y&s$A;%q*wX1WX&R$Cb_KyTvo^vIw>+I6Sb>2O_<_CH2 z4!RHPdQgZ!Qlw{c7+A~7D>c$hL#k9uD3$kB4%gU5wU$V$uX+b`^ofwG1WfcZMH|kr zSs5M0s~T$~cyHI+`t7eAJpH&4^mPXW7{Zyx=gN8FeA0?xwsV81YCdv&P>@Aq7nqmy z3rqd3!%pz;Tf!r}2gepyeND~O$EC|Hbr<2dIsDKnLn#5_9% zQb8W4jTQI>FQhfxIH~@I~U*V&TU$o%`^Apch`G_ZjZuFEy)Ti*O&gsL07a-@7 z#?u`^GoEQ)Wix0gUS9z-;xa|%Q($!tW>t$yyG5S(i3A8P$2(WI&gXc$^%?oOI@7C! z;aQuuUhdkL+h5e{YBa85_ySdEi?JLrp(pMsju z1%?NuTV>lZrKT7Vq!dhzc1PqB~Z#Bq$ZheQhG#$_uNZqrYei<}wNHrr?K^{ka zCeD%&Top-~L(;f#)(!J9Z9erhlZ~wG#hIHGZPrDn)4F&=@eT$`Q0| zvOINFW3&@O;I*D=1Wl0Ag8DFa$<02cqy50g1=Bi=S8u z5pG|GNLn4md1>LA(){(oyWgGX!W;JH<-nRYnPm)+X0u9|CmDF_tg#_+ur%Q86a|l@ ztw?MS2O9d&RfrWU5jM{pn(HHSBt0+VN>LER8MHBH6HS@#8-V5T+Kv1JTgO{*=kjAC zxM_nENT*#H8*qlq;)?tF>=2r+i?%||Usdl$$TH5CVdM~Bwq0$pFY2m8FbFxLh=sLP z2=;e+ThImbp@#_wz3j#2vzKBIjFTO_G{b zUym4deVZL{>GoA)WW0GzD53#HJlbWAw9abuFz1Y2&$BG0uhgu78KPz4F6HN+Ac4X0 zo+JPZjj7R-`n*^!EK5wBFEkd_de;zBzykcS6#{@Vm5^H3!Z&h7_p)IpL~ph+^1XT> zC@}nghp=L%S3qS|wE>z%$HjQHX#5SPS)%_XVdB#>QR6M$QU{;~Inz2jW}t+R;#z_V z(1~T-s?h|avOpaQ=HnSxK7H~t{d4AEO$j~KR+%8)2Hr_?a`&1kwR}G1TXVj~H0<*v z&4D%v*XJ5%d#k+Y?9>!50;3}U7ewn=U3jyi3f47n@VqJMwo+7g+xx}nRln}6zDtUc z$ii`bO)pn{#)Q0>7L$-0H9c4rk>$Bhq&uJv%1{O8g`>%b>1ZYiBx#%`*xLwOco_KHz&NzPs5qiwGPriz#IfgJXc%Ox z?jQkh&a<9}%sMzPU*?p5`O~}VJ=S^_%BeGy+k3HUgTbDpG_U@(lQ~w{3i549z9p?L zrMydfMQ1Sp7ua#3YxRa4z=&z`%)=8`&X$9H6M4NL*<$m*2fUux~EhQ^sSO5ix^$RioViK>E zjSa$?wY4|hoe;Ru@N(OM=w{Z>cnQr&_<`m0&@%xF1>XzIIzC#UGIBo|0Hr9D>cQj+ zPiZD-%YWdSz8f=k3HWj5aG&0{1-g7WjbbPsn!e;J7iL!bp$%wkH7xdRKCI7r z#ReXt?(|3QTUuUb9yUXsajFWw*nH^)!%n90vVcvS(<6Y%jN%A+=c zhhREHP&(>fXg}C^OLgY|sH@_ft<}gbpa^E8dO!YP<)g^+)8fKL#64oQR({qK5O+Z5 z!EBRphra1!K#Fsrc<)8B9%?PGmB@hJjat1{2Gcg0=yV8LavhEFUDFz=^#Ypv1N36wo zy6BqCCtY|Jp6qUHo&d({N*0%UuH;b(F{9cG(V)5<(ORnEuEWm~5~FBy?EQzL7so(u z-+QTni*ry$9F&|F88b@$Hz(vh-=zCVkEQ&}p#YdwXrjHVYS1^ToNTE9M81{hIHF*o zlJn(Yl<`Cat6SRD0i?6?%7d28>2LjZdhIk7a)%c6)6ap3g?5hPdf4o)YUc2Xbd9^) zm|H)fvXS$xQ909Gk4DMGLPG@Z2tSc>O61hT5Qkdfz=4b|1nB9lrxow&K*X#WI21nC zA}V%?FbT~q`}Uv8yLQ~v#p|C>eeIu|MZccHZA)bY6Nl$UF+4u6HLl=^@i4%{QjjI= z9GbvWxp(WFHc|SFT1|sdfv@KjVuRxf`DHzo`NLDW_DXOa1a>~Pcyh_edKAy>k%z=0 z&L1ECPqLxGTKxsz|Fvqa=sed6?Ma|#mTk&G?}p1N2Dp3w=%buqz(oJI2HBnPh5du# zC)_D?@kbhA$;{}q)}0zdP@pD#q33s+#&+6kSH&%~U3 z`Vn*}HtfUPFe9obTsF4L6BF=wY^Kq~xrcRklrc%kTqAo?V_-2~#`u*7dZj#b2>;`j z;<$krRX0&PQIc~4MlsRDc;I!`5>LaurNk7qY{z#g7wh^DynVQ8 zC=^x)eRFC(v-Mv$)G|_$hoy|nMbw=dd-u0=y9TWNLF@V1oo>dYmPDhNlP0Y3*99?b zy`hDOjl=JKN&jD*UHiDi1NevWR&i?f(6Igp>Ean$pdD{=vbqj7XE2=AaGeo-ysaSd zu-J7XXRJGg0vwtV7oU4)6BGfRon3d!>M}15wp~&ISS$sE$RmIU<%d)*7GPvnS9+(( zYUP0LXF%*nBJ!e2!8A)AY3(;=U+}f3(5v(Xg$=<=GG1VyS4Am}4m|$JN)+RpoLGu8 z0)mNVI>Vj3^Ks3JBMAf}rUe>YPDhOQIF@OU*4yoe#`!|kV6(NQ9BMLaW8Al% z?q9U-1E4vJ*$F9O37;pI-z?Hs&Wnc$h*L{8hku^A3mwEJ?*mjb-0SFG@QVKlUMXAl z?{W!2u$0$*(5ArA0Eamn!4a93p-~TnRgz){_)czK;)BG6HaQhur&uPwStx%Y<-$|8 z|G9m%*Me{iNgXbjcN(r-E}S}5zltHjm1UVk+9V!Di!gutqa+8~BITMWn4sJ(u+r1w z4~dF8BzxSB8?Z4!F|1J-@9|4Xp4h7hU+3`P3WB2cZDC&as_g?UNt*&ci-|^Q3so?r z_3reJHcE**vdKRbOeMa@)djN;MBlL3lZ2DcUuXAXZAkU!G5u>z%;**6$T#L;cbJz z4~!&Fo2=sD<{rg@rOVpJ@%oYihsvajr!$1ybDI@aDyfnyT1ROMEX8d^ri91xuK*Y4 zf)YZRMM9fUp#HV@!1=&p>qfGC%TOoV&U&siRHprA+~9^=Rb>$RZW(zYEZN`^o)#2+ zbD8J>)y8H9ylpcV&Ig-4N`xehODkU;(!?^S##@mCm~CKX0(NOmy)t`YPP_gzGCvsw zq5cd(2PpZeu1g{5xfW%0EWfXgtWe4!eLti?M2`!JSVU`(o0K8D)!Q{Pl+i&~%b5YT zbxgXT3&sMA;ZHh-m)bC9*mDa?hs(uAuzod-dsRIc`MP$iZ2m3IcmOFJ1Hs2SCMf%J zhrQ;#?o3a%n^9Q*o47Q2IKmscyEBGpCrW#-HGN9CAf2m8iRQ?DNyhsE$L0lG<4b1CtS;CRl?^=lQ;3BO&T0q**BqA9q_6CeNt^p8XZodwV%erCX@ zwN8}OsPB9kzJ?+%6-2tnpQ zBU$FKzFk`kmb?eN=Z-d{B4(c@13i%72qAWoTNscj^^m>88^Bf`xG`_HEI^HQprtGG zBjkZ|{{kJMM45M1=BvuNg=*Wh9IkT%-9G`7%S(I|(kao*IT96-MI`LQi0%GVIo39` zivY1$1zcGgB`VjDh^KwfyAd)`HMw;goL9lL-$@>nnU=l8V$Ehz+ZlahC*^bzi38g^ ztbHg0?=1cfB(@BuI7&PvJ{U{AWg~pueCz0-2NGj=_*WK0AKB%&J)n~9hu&UM&BJDKFbfCj z^ZU1Sc3$^?02|&0D>p)976<3aI};_51*sr1idx6F-XY`g1nTxWnN3x7-i9$0J4$s3 zX3erc5-K$om}B^J=v>^TVmUMB%p$dj^OEq1`y;SZ7BR8MMJiCObKr+SMtE-r>1HXN zt%=qk>$LojA(ZoEodF=auYM*A>Af&z10vRD+%VSU7T&hkh4SKSa2*F3Z`?y;#re(0$(aI+_gei zxIu!_;KZEBTG0GYFhHOtD_Jw4AvLrF6l+_SqbqB6v1FDMSI>i?*+u2%?QrIY6%3~H z^jMJ@HPM$wRd9D6qqfJIfIcRI-xr-F2o!2L(1O5&8f1Y;gn;kp05@k1ra|$kw2xCI zCwa79*%MeJp@o76HQ(s_;Xm{7wJqC7EscayP*_ zwRI5nyrDg!L}%s-sKMsbj+dl+iVv4@$fGf2hVRO2wx8`>K*UnB@g10m=iT^}AZql_ zuoK7nBIvV8y?F|<^V#gr!2kg(1@o)ubX{J-cXYea9s%iCfKP~*QTJ+nkyBEAYD&`4 z0WQ2=Imy{M8U_ocn#_C*5c|>>%y}_AsdZm!75HN$NoVl(Zw#Yn3J|SJ>?J);RSk&u zSmu$H%2vNySv4EI@|tVGRsVC>0f zLri1TGB!PiBj21RJ$J1NaiR@&Yj%@eQ8Qbp!N;7+#Q`S{hS<4g&S34lWbVH`&teJ{+m54= z?)^<>khb?wAXu*-pb1Mp9f2ey@^a{rB$kC0wPM$;?kHbddwHjtgqt6Fb%YEiYbtB@r>(&b+eRJ`3uSY+w4I6 zry?XzhhFO0D24Gdi`q=~WxsY@!=0#~i(2eVJ3i$FMmXCcBL-ye#W8Och4=`53u~Ok z%7OF(i2I6B7=UQQH(`w^KsN;=Sv>qmBH8x_ja`|*D6t8)$nH0_j@FZ?6{U>%TI9!< zyg)fPp!9edl+pg)gEkNijPmjSCB@>Y)%UXDAWK>lD09X=-I&)QxWq(lAB0c< z939zv^+v>e#hH_$k5%r$SpjrF5D@ypm2LWyEH6%udF*^g@n-b}eYu)ZBFMk8P-IJ_ zySsynEXEmnr%Y7;VtI7{)V1L(pxnZMbT$>tqfQE`=$)h@F%Id?f=;0bz!EoJ?maH2 zl3b&|37b+*a5Pvo68b)Oz9P;7w7q^)uMeltH(HO5qe+_2LbErV%+s-XC{^iYCf#|` zbH8p#*|qMDCF|$vzw%-?Jotj1ev(HcIxc;aHovakNNUY-v8d_~Q7anHUa?9S^LFKm z1hO-tV6=7e)6rB#u1P1M)O<~m*Y>Ko7gQ$GUp1ltML@d0t{h3L*oq^V?6MMWIH%6` zejQf?cPITGQAa3+nC-4&xUl?q0IHe6S`=&=_`}}PBvtly8d6LtBFF?8^gDupd~z`C zU7Ijaz?$xd-E)l!jk*0@5-CofoV+8!LFQP zW7>B#F4xDcZqVOOnHCO2&09_RwFm#yMV5XuTrvXB=`Jk=dBOTtxg;{g@2HQlhfbWi zs(``>O99e00Ybo5iwXtyT)FT717;wAE|DjA@{UU0#EW&(=QViXeJRY;j|_K7zL@dv zwt^!+l`#MHf0U{J&6_*(u4H8Q1XAbgBOvz>=O8Gn5AKd4Uq!s}@g$ zj(6HTX8588%l0~3!uE&aY9#u&DQ838K1a>csztS34nt<%cp$-BK%C&oyJ!UlXRvM} zSb2Y_N>y@7x-pPdNIg_#*{kke7shxc0GQPT=(=ozXOwG5$bh@ud0giH>JJoC6G9mU zpcbps$=`rftd?yYfFe~0KQWW}vsSMD9fOc8Yi3lUB!iq_5#w6Vi-$Lty#t6s zMi{9Wy20Uk;|R9weU;jnFwInWrHS)&))TW-y2f52dz@?l<;l>@JjS-PFCjtOo=Rx` z_@{Wtdhc^Kk5^OFG?;E%R2kg0%eFpUaq5oKkN5xe3NI1}$jU`I zV`8{o@O-Bk3Cs8(<@lKHUTIZr^UgWW=b47|&nRL$-be?B0<(+<65InbBKEgy{b}-L zKAMp;pVtRAA*l|jx&YF`vi3SH(D^y?j^@)pF`lj#ZhcOwkAN5d@@6*F5rYuN{7q*D zO=(|;w^ZttanikBpPSx#Fy5fT>PR#8-&O9*k5N5$W()jEKF84=;&0D6Re&JMYaHb zyl4iK7Z`vvP`1#8&Jbcu@|09>_;79E#{`JZQAEs1KEjnnIWne4r06^lQ^38q>dBg6 zrH~-?d~nP1yzSyB71aMse-=x2}a{1(*Cub|NeTN@3%U^7}|8BwgE$OvH(46+Psg~N}1;S8R$BGDqRDnyazHI z)ek3;Amf6evfj`3yH7tt8#&TfoCFFwWOg~Npf$HCs1-%szwjdb1lmS;+!*+zJ;*_I zVrE>*S^L3fEjT!8$@+T|DGBAVwxdl{fb~snRpaHjBD$-%8I|?o&@W@$hF^`m;Wl5$ zp;GgVTxNUD=aY#@YG*8H^$!VsL~qGK#ykdQjxz4^&R8iH%Mzq6FpTE!?d8?ERY1{S zewg5}4Z_MPPuQOAdZL{Uaa;jQ5>I6!g`XrEwF??A__#oFr&=r zV^dK?9DhUtLZ0J~l2GtIww_z8WIY1LUUlCGZpCs4UT+^W_R`RLgV7)i0}ZR=1VI)- z`VcEf&U`^9!`~k&d%Ez@EHAMlIBB_5L8tzM0@R+zG2ksM$q7I!KXLtNX-Dv|8s7nb zmOZ<<-WL3VuZ2)IydV4e^i>~eO9GDx_4=&GQ)QS)@aeA1zE>X(Rhb#~hUa>Dyg4_5 zV)=%y?vbZU1rgd<{nLmI%|RNu(nV;9X5_|iu}8g4C4$0moY8w_B@)*aGf*_c&j*%n zUNL8R%U3p#UmMAlJ9l9y022C@Kd<~GoF!Zt)ed2#DjAq_sc-wFLY|z+h z#nuzpSbDK@L?$&-ijgu2SL2xzuw4&G%2d=oVa&u-G9S~u#j)?Gpa~Y5zkg75d7g=KuFyj;c`abSlcw`n5>O@B{VR#<3l(kBN_A zId0YC^*>!eZ>EFjuz0CJO(IfQ$Wgl5nF7;07)=77S3XJq^tg0aNo;j{F9nR}W!`@> zAKoe+L*0h!%9!e`A9}liu;Yf%!9<soiyK8}@X`;kLo6j}CvEE6NcKSy|!k7Ge|> z+oQ!ramk@P@8WuyU$$g5a6DduBeo0_A8ROf{eIK>tG)q0+DT>jv+yw7XDL>EBi4G- zV(5_8M%Dpvve4v|U&sm*N$STke$B@V)1=cjI~G(%%4&>1oA8sG)|S#`==wHqB-0|f zFy(?=C#YUt-`)$rW;(gNyX#-n?}@IK)W(iy+wdEp(?@u}rW`_$K1j`SgJ?riGl1DM z$T+kfy+@TyN<&*5k67%pd`U*+h~H~FbUxna-7-nT+&()+@5F2ld?Wk5o`+4((ZatL zkWP|2P91hjRL^!k3I4Jzg3>O{4)w2xbA*RFC1b~fo)LN?rM3@{9Z9e%-?1O!X=FS% zV9sF6ZoBdyoUx4=Q$|T4=l<)JUE8%cE-Q9o%@43b@>^|jQm^3U_CnM(7p}F!9)5KJ z0Ws+KaSwxFUR&lWTGFSh$y#*?!B)XcfFDM)gg{bZpb~hUhnNd8ks~j`Q~rLRkdytS ztNMLe>{gY7D=ut+x1A{|=Moe%w342S`ZHm-J=zZl>+0e6_HQ>QM*M4<*&P?b4E(tv zR`lUqNVI2okGbst^L9SNX05qP>Y-^w=JZo-_H15zj$y?5`7eCF75}6cZgAJ*$NWtG z{cE;Hkf1~q9&!E{)t_L2xP#vCfg;)QQ%Z?$@~aCX37aFKcO(F<7Z~$IfG+zs`ljdo zhNCH8m2`2H@o&cjCDOg07P1g(>(HBUUvt0CdQ=ebL+n8QZA{@(!(ZIM4F{Yk)@|eU zKsJ9zcmr86XF}s20SE=TJ*{5*KYngu4zk(qR?CFf*4GH7q4g0)(|$;(qFu7OgOSGm z{7%nguOaRiK}{$cCskkXEsJq zLHRqyZEG!AM&-@;^T=V-WrAHun65&@FW%dr8#|QueIwVuyYS^WGl$4Hn`3h%xc0%p z`+<{2n5N|-U5uIv-%wvtwik6@P>?+pKp{LntT^ms^sASAv}%y!iW;O! z95n-T5%wjBDAo--f#!82V2xsVh`6chFtpRi9LE;p?WwGX36zJ=2L_1}b+~I+R1z%$ zMl6$3TJYNQ_^>n>xyP&#LOiS)NiGFt%f;_bVmMt1G!N~?!H1=J4Uk>yUdBGe_KJ|4 zXJ1=TT`J=X<&jVil}xlQYnAbyT1NZlv;psESJy*a+xgdWG;nItrQ z?UQP$5K$*^kxC~f%hhEQsz}tQS?q@4TANPhW9JniNnctR0{%1XS~Qi-n4EcCAXz#I z(}!KJ)CQ2x=XT<@zqPWrJ8GmI;8yq;(h=to+oq_xGF?=!0ys&$OA(X?&~BCG-b>)* zLj^$1^_02lYQmn|1rQPK41>R|h_tw+OD8G`kx6YFwKI-ap6hEr7l>-9Q|q z*;&cJ(96$e4Ze<=F7G)0xM4Tm;F|q0f_LzdbMUOr_(W)Ydx2W{eB&|Mg?ISAuQzIF z2XN2F9hl$G`TtFjnjI1kPR@ht0(DnR6e{qvgh{&zuZ(03->V_PFx{?9>V-L@QD{-w z@oU(6c32&NhuX|9mA~N5$P| zxyw)94muYOg3moSNzf2pZ>ywf`~X@7pB-+=!vASL zq|0B{>fa=0NUjbP@R6Gw=JxGY>V}~{B_scp*gEPX-=qtgXmtpPJ5~WH<0+<-NQA+@ zza7*w$5S>f$6Nd@%wb*ND`OIML&XjOY_iS@kuE(bDxt|hz-9=h>Q(Om9bd+A{-td4 zy-`+}>b6vQoZ&v@pLAPtp2s(kik*C zEc(61)_q`}?-pwnc2ZV!>+Fd?VUqC`qMe&O%{Sf~8S~tt0Pa6Mi(|f_#766=feE}z zJ6)lC+ktkMNm5zo-+X=Hk0-NO8BCtXkSJH~`PAGr#lralpx=9fkj)xm@R?iddTcu! zpD8x=-{$tz!l(zFPSQfBN@iV}Gz_NvJAn=OplD`kNZ+1vCIk70aE^l)udcirGgR0| zY>3H%?r`^7e#z+WJO9ieOBt%C8aZUhSexpIQ#(Wm74b|H?3oReUcM&mxDG7(m#cU% z3ZlTEPTdW%4qaJj{hf`L-Nl~kVIz=g*rI8p$J!2`;M>}LFbZ&>tB7)a~p51b=?TZ@Y6@4_+icN z6(<{a3=CpuR0*H!z1M?DK7oh~_jk%HCJun>c8-WEK8&T6nyw@&|)83JbbZyL%1 zB`&K2hJL$?E&yf*7!KGs4& zHS4!UX)zU27v6qgx`Hfv-bxRPL^70@*Ztk1xT2D65_TEat62lGkw=fC zz`>?=T+%sw<X$m%S(T|N3l zlJ#V8nAR~onq2J9?ZQTx=y{z&l{5!O3XM%;!K%VVXqW?E0Q>4@uR?(&ki%gr1*vx% zj>?!vaID1^7>u)<`Ae!G0b7m+q z$CS%%P$h!tT6pu1gkqW-c8CBXKLjQvzqofI(m02w!T)#a#lm(M-Ds?Em!^elz)8M^ z;roSPSJtkN^`g`NlF4P(WfqL#(oMmL^_S_)%u0x8MN^So@+pymYqHntyrL1fiyV`- zk7sD9ToPZsmqsGYpxHoDD?0mmW3Ufyd@(6eyV1(Rsa7t(C|_usVQ^FGj%HXyIZ)>n zJxp=_9&k>qCe7mG8lj`#h8FAqzY)h)$a-9;GuPowPeit!HM@RVRjepOA}IX**fBg1 zpw=tLiI~7f-t<3NZ$QCHXFnp|o01r6p3RPvP7_6BZa7v)Cf$@(JA4(7wx07cpQNW& z^Qej+>KyCP-i~Vt)D5w?{W`f7p*jrDlZSL^xx5|+Xpe%d>X&u~*kdu;%&{wK6D&`N zXLKtfrUPs~Mi@(ACEZz+{7vQw$RxSPmO&ZiR}q~dt*-3=JO=K!Ff?U|Kb)RWgYtjR z1`zgGs-oWT^(mzKH+Bd67&I?b1obk#7fphj{(k+Wr>1#K z@K;n({RyT9+4R_w{3%KK2M#VoKj^+Nyxr#=UOhGvkX}g{p`MVgLh%pq>!|dy6kQLs zef))m8D>>$C**b1WcbkTvGOw%B4HCX#1qN*6|`!H>ArK+8r~ZXJ|>;I72!2|(CsEk zZ!1y2GkebwY@OkY8tfxrdvOzY(75x|A|`-bX~ZC~4VFct0izT13dwtR|E2~xp*A24jd97ow z4EW@rV9+__7X>WqjKj>Qv!8TO*Lob3RK-)YychY!-z}Vt+ z+qDm#G2?oUR%H4|uPy@^Kj!K-wAYuO$5E=3EJJ$3>aW({5!@5by(Z%hr)dnTb#I<1jZPw2jDOe z9l?%h+UgH+sW(3WJP4Weo4KCu`s@-4xEoT6(VPP?yJ!!@Nm^X1kJAaptWGNGnLFRz zxM`s+GD$QnT)*=`pAm?Q$ZiEBUzWOh)a4=XVFkKrRm*h1PDlcrYf>y$Oiic6H{8Wa zi%0MyEIS-h-(ZHCr;p87o!|y`lIWOeHX+hnf0C?e;!HJpEiAQ1qzc-U$V4U2>--^! zy$?qiP_rp-%V`MNl(5nHOB{Q~xWbajss|tN5KPO63Z3zs=vL{b!aZqwXY)LzuCFaH zb>`Jd5bCC+KPQOb{m565YP?eT?R46Q+8s47sd^j2YSEWeZH!1X?v?Qu2EqR-=P;B+gFi9Aw}*hsTj7bzP!Soy zS0H7rP-|y<2<}eTYV%mRHS&^M)ZC;VrG~p_7Dz>2srPHV5V2cfG8yx8Re#Yq!%@eC}^Pmn??bQz|aWZzy9<=rl10ZK`RgXPsqDQq@QpnBk*UZo# z9tfKI6N0pU?YnhDO=}qjf4NbCvB-6#7a7T%e0YlH%5T{k?bMD;?{)_sCAON8 z3WpfhM|dxv;q5#F18w#)6w5juHq63?bcjc>< zH~`th;VaF$Mz2xp5Z*MuE$pONiucs*;%REa_m<^jkh%;`9BNU5?9OC?P};vk9;?8h zF{+heu;kAq9x)sGA}{Cx`6XG7VnzwFCBOG_8i6jalanKuYQj_B3p{S6ee+6@!iaB= zl1dlxC&Y5iEoVEZlJ-csK|>OyxmkGw6Z8v@6rAsC$qh_t+eqJpOMo}D3i^1$*%Lf$ zon`Z&)pS11p`V2&kM>bX>`XtceJ`dQ-@yl4;??m}plG}!GWl0u&n${<@!>H0BFs0J zLm?#U-`73?edx5YIJ=Y*PZ2-53h`%K+-UW;ezcRI!3UyHPy4_{86?BpPT&>11O!d^}wd-doax3HwGY#a89l@r(w z|Q4suvb{cGJ;8r z2rf8qzHKqQ`Z#^k(((@tROAoMu;*}XP9{s@09Flv02^>|&3GG=iROKZdt0fivsOY6 z^gw2+UC7NR#?wF3S*LgxvE@_2u?{KT>*&A1%u!`@Lk^Lq3IH{jwu7nU-@4W&vsnJ{ zU`w$DIQ(V?7kiXgzEo>n?|3w^pfm}Ff)`1y_vPK4Q6L_28&83gdr-^BhkPVeF5Y zB->s%Cz5&3;`;6d4mRBXYKP7Yp3T&{xjrxq`59r;}hJolRn^O7JM>A3)h!0FU`|%)ZAEe zuvlSCr(Cns+x)=VpdVawKzV|K@-ncnDpf2!ca|uyTkZ9X)3aUHoW4S693(NLc)dYf zQc<6L>-jdvCdRRVySq}yM)DTlYs8jv7Z`$uER1RG^7HFRtn70PS45(K0Cfbdb6Gcv z=;Q;2Y@hE}X}1?i6GIxl&kvHha!w5-mfMf_ujp{WZ|8*NdmmDj#d9vktefO3-q{p2 zQ)z$UTTQwJvOunTRp+-x_Al>+&{!XIN_Je=quGCXzGmkL&Vt0~`!oEBr3K9peA2v+ zVH5@O6Wsct`PuB5Qe-D+;ii$ygQGy-Jb(3BaoBlpyPC_|Fb-EbXX~E3$1{)8d?6cE z7}aX$RayZVUvnk}NgQ_iD-7XYHiVLr#;rvi;w9;p@zcnCK8T=wqfSiJap{|_nn|qx zb^+1C56!>}WL0gnftJq!HqpLgONZp_zhV??N{@9@R`Xlwm}e;HuB!Rf7)zhO^xOkG z)hcA)K&h|MF=Xf0Z_iI)a#O&^<3jt2j2Va6)2heKysv4zIDCkE@Ux|+a0ITQ_AL4| zwBwb|bm8mJSt*EH>+zB_frf)eLxJXPG%Br&ko?}ve@3jEHa|IgomxOk$8Iks|DG(% zZn&OPk^xW%G`Qy#daFg}h05?e8rrP_)6FpDVN)A!&v>IHBD>HLIao6tb_YL$LG~-&H?-5=V%Qn$?Enf`;)3PuSb8ypv=?5G1Qc)<*s_k>1bY{kK~ zvK-1QTNfU=qnu!xlRRoKdF@^6DUo5K8a7j;H5oBK(UC|<#vj7AUV_moSl(U;yQ~>L zPfq1mEujME*-V7W#$UhSfDsvral^sqr_|fkV9@vdS}zzUZzq=M5hG2L1M%n_DUb%L z-I2iXEmX=azv}T=i#5NAR$RPKvF*FOS>uG6T#y$T?L4(2a^okLF{`>b7<4rz*xtec z*No7vWzy;=v8UG0|F=*o5?hW_pSL`~z*adv${w2^8 zO1S&(I1JoiQPrg%^5LYf&mDs<6%{HICZEUM| zW8R8_k4R=_0!{00+55YU0C)hZkvc%1q#Ia9m%%&;=a~#C`Yv&dea8pLPe__GpRY*z zq@XK88i!$$;xkVB#Y1nPp^Z4y1l|~w-GtQk%d6W#kk@xGJ)MPk)l=8^+?^`7m)1dP z-*)M0!^sUN>nGn5@n;Fj{_HERu|qTG^0v>$Qa|2=Z}@}Xw6z77S@UCrm^z!!__!$E zSD+k@Y9p>U9&;Qct#g<~h*STY9nD8c5)Ylw=@V}Qyt9h!XshEpJ7~}%14y3A%C})^ z%7qF(W7iX_(Vk)t&Jd;sSLHs)*!djrPz&p7;H0nprZodU5eJ{)@|)3F59TtmNWl&3 zljCiB5YYP+Q@ZcidOeQ1d#g3i!1a{O=Bf(N3% z1!tXu1-uM4$ErP^H<4aP$=8PNvvZl^wWY{JsLPj?P>BA16BQ^-zEX>ALCZ|<0lJ{7 ztK?@iEl?~%9!=5bOI&{mX*mskKX#}Wc=(`Z*N2~A;o}pa1DIy=NrpxlV^U#9;i#RE;?uQ= zy3)!XJEAr}q?lqrgKZn#WzR*oBkvUff?GDSs}qC#Ln$NzFLsBRuX=hGs|A;-Xv6N^ zB~GGsQO?wrvgBMx>193APj=T==2x594yn$#krT6+SyGyL7cCugzeY}0N^1%iBl3iW z?_W5!x)IG$W)Jw|^&kO)#yL-uqK}jYqOkxj@P@g7tD2^#BmVdtpWK|vKi1=mV~38S zer1}>lk{M&w+u2lIU6e{p@^9i`|FXJGN5%RDjcVgP|`*82!^gC+6c~Ih&;3UAI@`|MOgkGA=r+D>#H0@@!Egx8CSl`PSywh& zvh{90pB&{lKCx{kW$R=YeJVd*R?oipd&~rY<_)n?2hRA)4tNV*?ZohTbP{nfR5)@= zCrCwD5b`2IqSQCA6>k;PfT0Yg&6YQZ>H$l&R>(v}pcFVnh8@Iv-i$u%On`xmZ=H~3 z>!GR`S8GC(1L-KiwL>$^BBPf&JCybcA#y}Jl7oYBc$M*?dwVy{{Y~$ZMS@?a!Sqqx z)2mCG@rrphJg~bFeWOi1>SDT0jvxG*F5s+k<@T5rl8Ru)5mDYfSkDJWlB?fKqO8JJ zXJzXqgzlPUyk$qqeJjU()jN`Ws0<_Ejn!)M=GTfvTMyEQC=^Chm3l$*XT>dk1xe#~ zQ>;}{WUgUm;1@YF)Ri3Hlen{e3`An}O6OsT%6y8OVQVEIL>vD9xn}i~*SI$-h#xXs zxx6-c+p5jxpRzd~pe;2&%^B+WN2YVX2@#M2EmAI(iYzkdfpCFogV0L51&2g$s81j} z`1qEnXEo%37>2;C=qx2!U>Kx;DMMEOYj-=*@fA@M$>3VN-%LCM*fQ@5^gS=WB67UP zWNxZ}hbzSps*WA`o+m38dQY}a6*1jNJ~4|_hDRONAnu`>rHIm3w-M6kuKR8^7M9;$ zj^t-ml-h&MRJPOT6^PHxj>35ql(WU`4rWc&76o6(Q%ywY^c1rUw?w}mq=$#!QTTZn zfF#`HT^4k!jgU?E^!?^6TWWzGwl!XI%`rcL4`5u&6K@3c89(^kz#fQ58I|X0e^(^G zj&I-Taz&C6;k(#h~MT{VnXW-OY&=%jP4G#D&+X+S1*lO@|Uq&H* zn4)+4X4}ESWXe$GYg*DBTbO3QI0$bbNi5Z1(rQ($@b_B(Qg57!re~16yqR~Bs5`RK zJD_IdPxFRqrU^%Tl9l##2Cvur^H=kam=D|=)YS2rvfSpub5-?HxYn+oP@C~@IxMP?a-nRbnp23; zn3jkEfsSg={aIq#R41S#xUL^^+i|BRwV8uQ%?m#?&iwbOc*nsnN+Y1S569su?b>e9 z2TxJiyunu|1#AZ}lxLaY8~Io46{}QO^aC@ABa}Qjxbpu3x&Cmqw_TfO@wb^o;(p@> zyAWcK8wUdfvu3*A><;QtKtF&0`gt>EJt*AYzo^DR5D8WJ>PF&!AFxu>npi62rP6|1 z!U;95QaS~#U7CTJYYE>fA-)w*{h%IA`h1-nFXeg=mxhej5Lq)Z*B!xQe=le#Ynqq| z2^Y73foPL(`x{9jlMzn!O5Gg(Z8*OU7HTpDm{SPQxmTE+Ty#!^*+j-0AP0PeKUM~D z9c-Y_>qCfFgkP|LXUzd?zS@GL%a62XDDgY@Ka#9oUQj1&ErC+4h|a14*Dk=wBrtP!+R<$R(;%B3JlMSJ+lW>D>K zKX6H!j*iVT@5lfE^TjY=gyXNGy$b6o$?xsWz4nWnE`ygyKO#@V8QiE9s?V`UGhNv0H`XT^~%Xn5Hi$Z)a6;gFt>(uW< zLCwkYy0>kJn-qnC#2*H~UItYOlj;TlBWsU%R8-sS&O&O_V1}F1m@v>&6H{Zk2AbBs zLOIq@(YqytJ|CwwyTuXn2&55UV(Y>K{Z4h6%B%q?^&4^iaMKBrNpu!O!OwGxUocg% zv;rvbcjbVRq7J!DeZNg)ve=Kbx0$P$tMJQ2aoay{M+9uc7L`L+FQOM=IxaW&kE7xr zpv}tgB3d8avw%Da6ew5;w%H|#w3~SHOzI%alBCIv(|Ge==$Uw4QV1~J;cEc$H{YR+ zVc$1JT}XNH^<b-Wc}|ushjiU|>T@#3?$W=*0pGX##7s9; zSBdJg=4mrbS)CRYi9IFOhx-=|P;o65*|=|^1jfO5xuS0?M!vKQ#xR|GQb zS-=xtu5y0X$W5L;B`8m4?nz)6Kf8Y1XTf>^_RX|w>@#Kt{tvZ^2U|M+Up@08|5d

    1isN(c_o8M~3ddu2rj3mw>t#H@uLDXXpKng*UTte@i-QEY zR1@*<0M_$eeIv55^7#!<98|e@VE%4niE47(3no1sh9UbP^4K$+n1#4kF!dSY?WU%UpNw3eoIEx;<+><&U(7eXJAMyO`D}N&Wr? zV-QPR@_PEW^(G3H7`pncu2-ui45H+e(iL>h7=-kVkHsM3fHRm&+N>3dyZ0skp*Eel z3`on@+#Hm99Nmj8%b-xy^sQnbo3mbdICM(y)ann=*pw&b{>C>^jiQJWxp)(JeUaKB zl{>e706p? z!=eGyWG?mO?-<#GL)~LZHe?#dY*{~yBJ2@F@JVw(wUHhZ+FB`8rtR>lrki)69_+xeIa^K_C9Y1aCbX5nxDBjscpQr8oue9b@UhCDMx{yw{^RH0rK(mD-a!hl^bD4IRXNL6n{ zg&>Msc3@AnP#mR6_%(AiFza`K6)0inNj$K#?B^o2VeJb6gB2%E1laB{_Xd5K&r(hf z$p!XgUrt+2cr*(buc6Tqie|Hs#_nGzX-$F+b-GX+<=~1QtW?ikAH9;@k7;`$-ziYF zFooz(pIHHeRiE64A&e@omzM6lHTd*}1vt58i(LOa*qO{AZuY|nfnFyXy-8zkSVhu* z_?9u%MNsmquoH#S1jeI%s$b&YTB+FuTW$l~1O+`KSL&|yCuC@%yt}Kp`|q{ZvijLt z36n);m*cHBb#7J9%bmQ(N|w49yEdkmbzz90PE#uo=jdsIM>;CMifyJK!U#C813yWMwireodVVrFa{{0- zjT5F85J&xd5HGN0sABzCce2yB+hj#V{^H}POq#{LNDEWC=cltvQ&{cYW;^e0`SI4% z{{0^A#^^;Teu0mKbna54d`+5i?9E=9=q0E()sZ_cg1eNevyuYx!hshOcm>&VGkVlL ztw5$8YQTWa;MjV1bX}=RPx0o4iguP)Ln62B{(vuoO_W#bUtSNJQE}+#;NHyJbzgSD z4O;JT&q>E0F|#3E!^=KUM+I%VT$tzYV#{oPizw`<=iUG7*ACh#iK{N9GWFyoX4Fjj zI@UJ;@iD>{Gi)Z#;^xXf9oSQ{>hLkNWKcu5`>Da1tdWZy7u#hSrYV1z+5E3~ zYclE^xPjlK^)r?{u$Tv)o}!%G#9=4bbAY600$Im`7LyZO`4M#5{o7+Z6>qX=AF+p} zM>vp2-N|jtM1SRFCHR|@yI38|jPWkX4M3Ptvc}V*LOxUD8vl7im;@yO@j{}!I;NJ7 z6d4O|bA~)$gE3k7Gqw5ybYTt+Xvz~*EqYpxkM-3iK8(9LLYYs`40NeZp^-vfMH5-W z(G&E}UqF8&*KZDKonjI3yq_U|NVPf>qRQ>8{D#N-jt}FW(X~ccPyQGDffiBE5wBqk zMQTLK&rc2|NF{ z+#uEtA2+3kP2P5ItubdF#`GMS(m3FBx{vf9`w1DTyz7RsVYAltF7*ynPbg}Tjj7!+ zR^;&_fBHa%*laJ>46=A5PjSlo8uZ*xHkQpM)iMk6_liE{0590c79phPuvl&R`zL%4 zrtE8auAj@3JWMA#nQQi=9Z zg%1$yPXTBQxP3OCw5P}y&a8x@=gTrk{PPE&(p{O;ZS*q(02`=q{C^W~ErWK!h z@h&duLSse1C(g!O$1ywh->#>Ch5B4u?1_@VP=5s-!pn@VX0H7^)r#}$Bkjc=clU$} z%co4(7=A<6cmz0~V-N|)laqe8F_R@c1O?GZ&$~6j9_^O_6e4>x>*ftk_jpmuiO_S&95eJo^E@iK}oHav7>bGhzYee)5jO|eBXQaXK#$4y1vr<~|k7nnq zHg8xn>p$4^NN$!6{NhcTj7eR$q*1pDDYKIOd4-5V&Zbc0;ZZ zYQ$^o#V)Mr$oZyX!;+=9Z7w@QE=XfHtK16xi2#{_LIUY~Dkx>DKHgauA9`hO85r2j zg|Gj@S=dvRKqY(HQ|0Zy=v1ZQN+QqIg1KUpb5ii?1b$=Z3hSKtIXVTq-x|OnxPRiU zI?BCaYtLDRq^7QgAPKm7*HO^+^{h^x{g)5hJJ)eQd;~sNx{ZRYDB1q=O$wt`z)VU& z6qpu9q6}WraaaQa$FM=%XbqhnTW_glApT0IpY@kA2tMRnZ09G?uzNl_K?@emkZpSrOwm z0)o-7dk?}5*2%N*z}v9Vm|KJGh!`PZ=4q^G7VK*il7MJ{z(NJ|e|g|u0*$mVGm{=N z#sh5bzv8m3QN3Qd!%LDDcW}(Sw@>e)>R)9g8WdFOnTGwzYe;o>ns5l7^0I+*{21oT zsaPk!Y#|3KDNOPnqt`dd)jRm<-)WWV_h5QIb@NyGg(%^egHcyRgs7pW+lo9z&q4>A z&jM(k=tSz!0lw700PB#uuoAc^BQeZGbPse@($2kreIfFDqr)pGo2T1BDS0)D#XCgTI+pXpS`!MPOx+7p9I@Q+Jv;^Q zd>b8f4~~2V&b+Y%)~pG&LM0t_>~k3ZhbyW&l-6&v4Y&QFW3$eBO*m>qXoN! zkCVTaZge8aJzj($XO!YLTPas08>hZch=K* z)o6K)D1HCS#0M{H+47cu!vF~O;K7#YFZ`FZ^0qbU&5tvNJo(a9h&Qc9iFlszVkM$5 z_um#p=@clNvas&t2uC!nU%G*rFeSSe02i|g8y*xn<$}o7vB#vr81plOs7RAXzT#FJ zGdz`Npettq71BGUpWzF8rY@95*FifuJ_nt;INY}}{4_04k`aDxKmM_I+EB5(*Kyja zo_z)kvc%A1{t?6gY82Q?uydW-#mGkgf+{-!#)R@CrZB^1h-JU;WmOWjVM_R1LX!@W zBkZw|=Q67wxR%k;dwmwvl$*1pWcdcMq!@8Nw3`C`;2VIro$Jhkf#@lFogNb&hheE0^TJRYF0UMUt2nFAJRGF6 z>hN*z`*7?$+I4livozm~XP!Kd2UWOa&PF5c`{ik~iTOfXp!&TeSu6a__Urh+0;Cw+ z$q8TvFVhj`!AzFmsWBm&6MnN>fwuO;V7O9h85x}9FI?&3G?uD0V_pDv~TgR{>0(j-!sWW#mLhKq^}Yz)Z;U(C!4j!QJl zdw93s7#RJgw9H>-Lv1es->sNzm-=QD$f_Ce*%(myxcAM#uT-- z9=x`0?0A?T8BX(jcC(@8hg$pm2yT2Y?;YS`MHapzeQ6aw=J0}%Y_tFBOK-u5^7RRM zc!ji2Fpw^tMmnpE2swKv%!lTp*I_?`0x43j%c+Oidr;a_NGTM5K3{fZxxS9YL|hwql`P%Y+8 zXL4B|N+^sSpE*q!Cx5SRp|3CS4Q`fV=tMy+OAnZ}fbWui7mvfL*bxt1F%)BBa6mXq z_CR(Q8ZAP@4BV^r1{Mm;ENmm(o`@MfZD>Q*mZsNcmr^Lqu!^0UkXhJWVBz{Gw*Zs? zy!yQV!s)P^*u)o=z*+~F*?yNE%Qa_%whMK>?dB8qwjtH9D<$V5Z%P^}P?gjll^2*q zmHKQfE)J6gb}jSRG=CcD1@sj+U+7K>RV@8VJ~A`$Yf)3pO#gO#$JKzlCo#n9`)<}d zNIR2*xEs+K>hFy#X3SxcGHHoh(aqsLKPO1VL0gU9a1VLCW_}(k`83rF<)_zj)_0=Tp z^;w~dbZn@<(MGp@q(4(Atwfo12@)}fAVk+p`q2#W0`gq%^~*BB*}2Pi;TK>*)_19d zK#8Yl!wR4B3yq31e#>-Kxe62CS=e?9h&QRiS<#B7dJD8v1CI%*urW+0Lgr-7TPoh;x@>HpbGpKUG1O93}Enl_s*X{0H^_o z_4Lsup;xmMji%}8R1(M^0|7jQ-GjU_QCW{ygrmV0$#>bY;pMwv259PLN1G+e1N%ia z5B?keiyWuS^*W?Ye422MIn+)zoei)pG?n*qkyM1gAj0RIdtCX8>?#-<8Yz>U?&U=G zs-G8OtEAi-Vt{-GX>EJ{7)e+?l9*C3#U)&*@Pc%48M$(Dm-<5(L2W*XgRsr)6-IAmM@jRMd#4Tf%ujVDhN8pZgT$$J zBROBe*H1{_eBl)uP_RKoyTPe%2vkE|ekTfG4JiaHr{!Kf-Ml!0k6Tv-Sorhck|^o% zn_-TffR*+rJBzgUrswxWOso_`vAJOe8Gij9rZ*3zkfdH8PA zDNTxcHjiZ1!4%C!EZZzccBPIsf{S|2$Hn~7*>!*Cd#ihRkKG<+485#mjFdTy1!MCU>p|0j1o?iCRr|g>R2blvNkP`J%~M9${njs;2%1-5hEeh`S-6I z_}j?=+rf^4@G6OP zz?c2WV=v*xD|xzTjz5AX`sr1=y0I4*imGMM=rWGO@^?-xpNajRUHh$JG6>qUEeZg7 z7*NyVuW^6|C_EFkRA#MPm%#ncgOLTw@9kfN0dAs$Oo9JbmO3QQ-kN^mJ&)OgX;err zkv*4;Cz_6~Dl}?K7L_b815f4G1kQzR~fVRH;0KD0jkj|5`ZrB_FOwG36G;-(+%FqsW6~@VhdLDf*%*I zE!|oiBf4Pq4(5&kD-M0_v1EC$m&PN_Fr zqO$+&w++XTViSGf=)u`krQT-&9->`jCDApmL@RABtbQC3Ux+MWaS$SjH(2(>==LJ3 zMB1Lu0&;LWW9o(EWXWemkAinm<)Bi?FfTt4`vc4S@R_ZzG`2$V?}r5h(t*Qj0Vq41 zaRb%{);Q;lh3YYf;p3>Sat$=wE%{a4A>CrY?(I$_mOmMv+vd@Q1szr)<8(8GQZW4U z?L)6W?c5ZI+kuB1Go!d}HVII8YmQH0SEs4%_@GKx>;4nj%#U z1zF5yY(&UkiD*2hd8{VX)Q&$6xrE+b(?HIMlRF&VYuC^9(G7HfEtd@L#ul}`YDfXY z0S-ug1k#g`o5fPR7$sK{f8>J4?3zvxnruS>Cslyd)gWcBFb=Oo6g+E*nQ0Sv5yrr& zRSs0#NHd<#Lob>8_m3sX^Ek9L%awmt>_tbwB8%jrg~AA#*}Y3hMSyL@-P?Dnhml?- z3`V%2M*1|bj9c1@@}^}U>iRf#;m`3HW)mLDIEMD+b3aXie;pkRuG=%~?e{rg_SKdV zCMtkKnBwY8468SY1goO=bR%{Pa$P>eK*Fvi((UXIf5eDAgIJ*&ok{h-sY~gkX!oYi z;&Zit>L~^FRLP|G61>3xnEgkZsM?Sj)9vK8li7EuBYHg-%bgiK0kDw>$;vbQLbykb zt>-f^tsejGp8K9eH-a+{YQ!LMg06k61~)kSPh;jc5?0i$IGnO;0gNVoQ{gkh6+~G; z;r{MSfE5n#i-&Gab6UOOnrcuHDp&#ZlqNAp97?M+#CVMJtD6Ivb3SDL8Nsb1|U9eF)E%cuJNLA>eh;sAa_@9mh><{+9oR$35oB@rpPZG&mgc_W|Vb}w> zOOG;U7VU@`h1IdZ90XBnuGus&mGA)dab+WT&aU-GGk&MreLWv{TSa@QzYP{F(S%7;RaAPenAb(wG8ErZfWPLjhh^K2y(aZ>!qgBKIN$C%aL4R?QhjK3kQK0w z8%5R{pdVr*Aeg$k1a4P_mJP#+z4RGBsm$au)Tzjbmh+a-k(M?majPC5;@NSROtQbi zOVe*xxyIMmM^{6N1Ub!o_Lm>xHLxYVE9%V*$RSzI0+DJECNVs1OnlM@BO{QP;_AuF z0(kC(-R&_b$h;zN!gg?JgRpX{y!lbt-+wo6TYjQxBwnws_GeWmkPGl1`f$k$)oo((Fs_FS;~+i@s8J*pfp zXh7gRuK0N00zZ+~riYDnZoT&yh~BhMIh@OuL*4--enx!VNxoUO-n(4XPTFN7Z= zgRe}oA=LBCoqgx>74^9{WQS+mOJTes43d@+K)ciQg@W4S#=hu$L~qp9>$X4b_f!DY zKI&{x`q0l#JBdrp8zren|L#0tZ*XA@4)iz9*$}Q2K@_x%OFN)$E~xLgE7TG2lb+ig zF^Z?X-ARc@=mltJy9OmO)kGtu*hvf`0R$vtk#9>v9gK){G#w^;;S=x$loo)bs`K_G z)U!J~5Cks5UtBq)R%j;cWG%N!l?wo`Xt?<+(R4gHY_u$6q9HYt`JE2)cF$CJ+_*Et`+6xw zd;WR2XfnfOpMVkpbT_4XTs$ z^LzUO1<&JS0Q+p#M0k`25t0DRDD-A#CTt-*?(3s{i;Zr{b)FtYm8d+LK7BpOl{&c~ zdLvIezRoU8_Pc5$VkYg0JGBSec3s`n_l-8H(AAj+-Q|&kf$I$b1##GeGx6ao&*(l< zpciJnQsoNRW5n*_F+WPhdIG>L3GJYNt@#UtyD>7+zh;+vCGc4yEn3o*;3{iTPcU`G z&$G_ZT=O(Wyw;l7vM5J}TK2X-%G}zBGXl9DjMtJiX537DXn-qvq%-^m$8iIH&AaTJ zH%wr`0Ryg^JQJ-2V=Z#UF6UoH)Sj6~6=yY?O@d8?uf5s+B9e-g<0i%Txmk%O+@CGg zZGp$pqF^UVkGl(l2UKaodtFU^&_vJ*iQ#xgtMvX}Y3#EorK(TIbXA#A9y_75mFZip zM4iuQu^rkFE}bp#PaiebHoubt=&uPI8z4bmH^10D*Z>J210l`T3fsG7xjCApVrSIg zdaB@k9ocJzE2zuVK&D&mW5_p+mgvOin^(jeqf=nK#Q%=raqYL}mT%PUia*7C_l20R*iv zPcv25AukhI%==N(eeJsB{gQ8d2B*_xl#87o9SBvjFAV$R@*QNs#u6TU)1k}9DnUiXyP^#GgTo$unXed_e;R(G?teF~i`h_dgdxo=W*}9X*W6UnEv)8p6+Du6@y zRh317QLMO;B1x+4jrPQqalieGO(Q~tW3lBuAM4n*b~v_TlRI`voby)$;0B1Nt~z9g zeD7Ow4lu>-;y%Z-cyg5f>Otvp6{z|cygcccFDklF%pjl!bMK}f8JUus@3h#k36ZNAOrox@zGO4fv+CbWXHs9xgnY$$AH*7^-?yOq| zhH|p+Q=K~5e{g)8!Q~AvZx&P%BbBH2*WHI09w1rAmZh>tei#m7n$<$*A@hzqLK3(S ztWEALTbwv`yHGmIJICc09Tc$=5EHxSQ@F9VR%lb~aOO3mV(*InZMvkxOu z=gAxR~2ldQWgp$t}2M)PUoY|z?tABlo>y_5osd=-dcvw^h znTQF-ex9>u1@d3~ejqwC6HN?y*`aJt{W^|ZdfTUHAL_-nD>It)@ zbLUQ(R6fLCHqG@Q2o}t8ZTL%V>0C4M8Ri%>$*8q$Ur|~fcWER@%h^8X(*G-}&{j1- z=AZZ*rPy6?gN9Xjv*@xaX>8tjMwD?07sT_?&)%V@t=Foq@RFfHw{kk%^8@7GF{}Q& zcZ6(COj3)dtq?J2`3C9sB};@HagC7xoRpJYH?82kg~BB06&^+=q?@5A3RYO@)J@b< z&^lbDIyAqVa_wUvqvb*>_pBM<{#%+%N?4d59bdL4?}HO8fpdTo#(MxSKOyptzM|er z6nLXDlf!|vfy$695@2-^vKY=tVK$=g?4SUxVf1DZp;C1_xV3#s{_zY1LSNZLc~3RO|%65Z89@!(DfGNFX6E${U3Q>X~=sa2c9 z&+X8u;6#3CW&jROAC$j##DLMNoHjA-(wPtIl{~;)u7Kn5^cEgUpF^$6nn_FQk3MwV z@onzL7Byp=?3qnlK#m$~+pUv34EK*ef&T?BD5!F1Ve6dO!Th<3sM?63|}z(tC`!7vmN&$ z2BlvuO=(}Je>+5A@`Ej?b<+J#47tCok-fMt9U#V^#^j|)R z%FmbhsWGv|1(A$o{jjX%lXW36NH%+`Fk0<<8_fL)dt22Sk7XRy>yqAdCqd4C%}kx? zC6`bk20>~4tWjF28Lq0H!(DZp!9B(~4WGaXQ=&3eJxVTEjPFnKb!Fni2*$gl99W-Y zVW906U=?xGA~+V$U{ps*M&n!(!So>R#4&Z};e2EaI?wM=iRL`J)wObh>j;`@ImQ35 z$U?1My*|0muN$$9Wx`IG(xd|}t`{_ce!7-lAc72{WQ^r{3^O}sZW_6T+tdsW?_kl{ zo<`Y=?uTQmnyH+`HH4Etg>YCCfaX+{q!CtmkNfFlEt0t&5^fQ6e^aCJXtnAuapK-= z#a7Dl!S$yktfH&WuJRf*Cp0>rhFA0-u()O=?iB{=+$)-Lw6)#v^ivcHCqAPV=mS@b zp^OG)$APizAso9x#mtN<^PF0N24NZ+j@{N5G=_hi_b<#A)5w>4w zk5Ae0cvwqtW2A-rJTfoJHhbG;%2lrObDP%+;J&uw62YB}K835r~>T-2gT;6;8naMLqv227O9Bu3finN55^y9qvi-`VR#3a(2U# zZH!U{L-X!y#0QrL$aQ$>A7rDuC<>MbEc_K_TFj~2mx9s#Z;zQwE6K!RpZ04NW!$-1 z%bFNTnxJ{euHBl5AbrdC%Ffmp+G#`2eDJn@*+=(&2GBo3x;tlpaoYgN=1P?pWHKt< zy8T@fCRx(ng&SDq*2^9jqpVkaw9t#=AqpK9Qe_v$gOR-PEX<83H4^zkQOE zsQ4>IwQeOSI)N_&+|<2v$^>B2M`zlJQCC(-nkD5eS7y_a3>tl5N>P+jVPx((Bp{2P zLB`1@-Jkh6Oh-A*j{m-|CXpBe^JlV6mG&{OWg$Y%g-O_{UkYa$40*;pan)yO>&?lI1EXl0o=L-0bbxaMCvq<->@`8WN=HNJz@>49?p@Ty2ngPfqcu;Y>cEJs)3yZJZivzZh~_#Yn-uJOT3g z+kXyUi;RUPHtZ{kmHSJ^#zT6R3;%)u_U*;2E{A4~BjYgoVrg%GKS6i+KLcZ@z?O<4 z2v}lZKqbb&zef~7gbwxPGx6)Fph9qJwCUr8bdC;J1F({_27$uIc2kL%f>ed!$c^u=w2y zaJlr_mL+R#7e`W=I>1Yuw-z)8H93YDd+^-I(|4KxY^P67SP!F>uf)n!XGlh#f8yr> zQzX9*@w49I?Pu44)>OT~rt$Q^4Y$-eYF!;SP?;>V@lw%~%?q%Z9392vQJ4cYBxDpf zSw7m*=39_zinV1TiqRhhk=qpKPNR{`V+{Xl=$YK)7_YiWt2;YtSo@M(g@@I|zbxCH zg+uWgUEC}xcLponVyq$sbS!`rgukM)n5C5Sg@hwMROahS5qrLJ!0k z0u}e{rIVvgSLP87v-^r{?wQqAA8p6&g7leIz($A{6v5?Zu&vB}V_W6TZq>HK&A_qE z^w7Q0bBF!#+k}I}GmC{PrN9$UB2Xw0QXbplDdBvZ746+Wt67ywo7bO;AQ=6eps<-F z!3%pjSjjq0_29nQ6d!aUgKBAz?$}#WFc~|=asTDZ(shq(M(^R-0mTspuO(2o4fa=t zN2z1){WTAwH3Z&raqDNs0h6nhaQ{6^VnE-q^{T~;*ywC%6y95i1R>^|(>etW6 z2ROF=+7;XHG_wNMJ?6go%7S5tcj)}*Qf$6XwBX*Z37>3S?r{he-^;HnrV>7q*#P$A z2~afp^rzI0T{h*f%W1;CH=KjPY|uH%lt@#I)R!WG$qsLMH&veE2W&5KMD^Enx8 z3tBGp{$z%&LV;L|g5`o8Q5XQ3`Vss$9ol3?tHINcN;TE6vcIqI$UQ~-2h!IMowz>l z;`?ezZ7pQ+vtHoj!ab#bz*!NWfK&cU_V4WN1{+Tvz$zhE`INu#P%PObe`U} zLvPdEvy+kh(8=I^*wF;KynwZULd)Zw9|987OnPrgXKZ)D-_#N_`pCk!f+(&JxsKzE z2?kRP2or_5DBi03ThJE`Q+J`f2!F)h;a?%3hLq2wVYrQx2Poglg55SbCXXUZuUL zzbL%&{Yba7ri+vri7l5&#GW+wR_zgrS3hS%cpshw?JvwdTA-OCVd<}zX(6R%D=4zqhZ+hL-<8I{pMm0tytj9#M1pdd;88Hqx!~)6Bq{%q0ZQkYo22A z@Gh80qSdD;L;p6zH>6G-u0mML0;ZU8-!>_(CL zGdOcv6C6U4-rUVK*yIKE(0c-BG~KQfwA@9loyx3m;(ae!H;;If6PPbL6>X;!h^h75 zmKkgR!WT5m#cWh<#mO_#Jz8ikR0;Y9UY7WWTpSA^MFoHseKEs8TC8FHZjse|4*O^( z7KvB(+86=aqFrKXh_ZJAtCz|w9WxnKH?X~BY1}p_e?l5SFS@wBVpm#>hA~X`LNDeO z*x3Hbg`nto@-r*+;j{gSf4Ou15(@03k~b<{sgoc&01dWzIBI(ZoLASr+(#0cR@AFF zO@$oShlw_VkZLc}Wdp(OG?mv2=|axb8*cY+J3urUImu$p{yC;ROsbE7%?*QWOC_A& zis2pSC_`FBKa+mUNo!b(bG9prfJr`Z_;Z-Nk%DmfW`J=!K|k;-&gHkHwsi+5ZbjYr z246C(X!>MSkFa6->h^OeHGZ~Fu26&^D~E~ITEF9*tP?jw&R@YC!bQ>}l{#wPQWD{^8CIl83c>w`!b4%cfRZr6ZhZDKb zd&6INTAMnR=o1={&iTI?0?8dq7LL6=PQ%2pcY7L!o?B^`ZXN`1MjJCp4n`LTi3-e( zI&0c;;_*`c1>G959i1SKThVoT^5SN+l6c?PE#OU)?Mvjwn!!PuL#cq&7tA_%SWBRPg26PM)r3)@Q`nlQ00O5QuXkiIGC1MCe5MI^&_E9izD zNSNWCs_UTY`q&tl1Ud%+7y;9BDF^i7$ubzYGoZ(p=7cAV99Gv$SNdLMqepP^|V=>q%U3o7U*kC_hXNW*nWxlAp^LidEEr`6#o|F1;Ap28t(B- z-8X1TD`GAhJ!l`^Qz5v?URE(>IeZ%02^1<;sdO4gyYpZ(Eea^fb2pGup7;+gvws`D zvl+D_wz&Ym)OkkQzur}XW6}e*wA@XKcfq(oX zMcarkEaw7l!oDJW>?Qxg0LHLSGk6J(&_(?hONK46*H{t&)R-#Q4L1>Vx?0|<{B

    0-lf7I!F^xcuGCEod4c}e@VU;Y$3w9^auHcF93?zP4I% z$W4$ygwZiuNVuv+k`X@xGrU+;mTznC%)vBCS_O=)`uAhc&rn_r+ZM;CjjdB-=oYB& z4`empCTd%kyNqJeO(g3-r4KI3V9zrFp5TgPaj&^#m6okc#wJX{v0l)6z>p!aT^%w_ zHOYI83dA|-!M;bGINV=A9vlE>!(5fH1BOca8EKdZPohj|`S<_=oVWDC*tAKYf+A z&M@U&x+9&(9*_?wsK@;Cw&4P!k#5T4e;hbmBXjOFZK4X5Rh@Ys8A?Q)Q#40ncIqhn z6$px-@1pq2AU=xXdcc6aBLG%UcY?Fl@&3kzdQbA9OlULIB=CMGYE47Tg-+O6jkE*^ zd>?>H22G;{E5HC8RuOPof|g637-g>%kH%+&*i6I~z9|J#@H$qD0FyDKsX#~{wrdga z(8s-H8x3TySKW~aZ*0=2K#L&AcL{qQL)H(E{f#j0L9UCj%9!8prjni$ZE5w-iW1qe zXtYCweC2z?yzU?CfrCdw__<_IPUt04Hfmci4SeN10WC0{ zolJW(@u}Nz7m~|l^w7mqIk*A==mCk?CRO=I1E<<%6Oc9pES(}${ytXGJJ80nItJJP zaHI(U6=#Xk>9{+}o0ztbyi(9ZLb^v+7=c=vqWBjh$)K~vHG!yIWfaNWmw?Y9C-n@y zYgf?*95Y+H@Ov!US_Ie)<|yi8Z|AT5^fGfja`&P#p$->-+I96hncbV%srcUtbJDAu z&jiLD-SjkU`|AaAgDbT?S0-^F3b!k*OBnzB+0t-_I8==68WEQvouy~TfB<3#MZnyX zW%Ek$??Qg!O85EIGE}cKLnKN~cfnLij=;2~l1vl)Z!|QNhflV5Z4nad-%{;PrU#7- z%LV5FAHtD6w*>mvG4*nOmMnk^B&h^~dm(#nNnKs3LT=%?#S?6)52-KmM1~f~c{oO2 z?ZoJr_qFGxAK&A|L!(SaPL-L#m~w4Ub#&E*zPh4DO4Zy=ng#%6e@fpN^`P2F6rfb0 zXY{~JGnEbnswHuV;+uwP)qo16_e@m61t^sUyC06HiOX}SxK55@K_R){A77$Kd&*ZZ>AkrWp zMxdUws!}L|3~qr(-NvL^%k&ejrF^O#%W3CF%k|sQAXL#k8HAD^#be*l2sYoIXqYv( zju#Q9_K<&j44x$=u0PQ6FrvSwVch^2;5RTIS|cL!2tC*$;%(q@&Eqb`Sau45xn4uy z0ChS*pRexWk%P)|6yTi`)81&D<=A4g_l9V1$3zr)^$|-^1)u=xJ=4>U^0Q6dYgax& ziwVj)O{Z?p)VyWnTLB;hs#iqj^duXC;C=cH)%2ni{&`7SmPYQ=WH^}B0n4-obWdz1 z{yR4wH&JLn z;qbU_>`)HabU*tacj5As)ll}Y8mfr7v_uP@=fkuW5=GzV zqNBBHr$S}OzS#ZgTLO&0@H@RPe$(5MtWjX0;TViOgy7Jv0`x2~ub!cd4Wp0ADxxV* z1M-NMdA|-i9|#E~1EvO!t!TPQs!ltP)3>h-19FRq6nVE160{1=%v#S{@`lJmU&?W^x}Pvi}41xkdBgy zEnjVXa$fAUt;PQoU=AMiNB{&!$@sZVvM(Z(0HywZlL#v-Z!WBDPwaI9l09Vc)@}G_ z|4piV5B*-c2`lQ#?jO3Z6k~)*`Otb+2na%EP$?fbl(?4t->VP-!O6GCmG>75<+C97 zi<WjW64KWwSxWo2#o^!ls>VAIH(nuL4RJC_n(&nF}TZtNmMie^~T(2HAh{M6gUq zy5Mx*3*Ik`fm{?Ix?rB_cbcW&jAhr~_08%$Sx}?rq5L7^0 zcI-dVlmvm8%VSH2bx2i3!@SEA0Hgx$D3-HirQNK!0n;=$Y9SEf@GluuS@^4h$O$h4 zZ8K;OTZcQDILYJ!W_K9)M3;~N09-92MPE%+7~9n>6=M|WV9AI#^YY_I5JK7$(Pe+1 zO`!>z3B5&}`Zye_17iIQ=E!o*h0)5ursvQ`v1jw#8JZ`YYbb*r($qskJ6Dz2WmB5K zGziN>M&?{AT-kNn&UzFfj0V0UPi01AJ2oCP*r5!fNi-!WSR~-Q0P4zCf4bv=juA+G|wpTfsSm}z~ zZaYG_hK$yNU#ocWTs06LHr=atKsqX@IhhbpaEX8b2^;w{>#yo7j}mI=26P$!Qr>*sF?w0%_VOC{5O20DdAIIa9LxkfJ3T za{_iXjzsT3zZRzJvovt)rb-gJU)4%I>O zC$;yXz9=>Prs3rdB5=$S+}8qJTjPE7`peaB><$irscccQSuh|F@qE{S>GEDVjtVWX zRgtKOKv{gU>G~b*wAPLy1w5AWp9R`6a|%zXKmaa8EHVH|hEt0div6#VE#Dd%ho&)=7e)645@uOx@TXtVb{bEVs^;2|pUcZhwp< z#EK&5C*|OR`>+521w0de952cnUQgRkU2iR#S%~zO-ehJCo!F3s$JpzdIR5FQ(7Foo zUs>f<+b4}q4K)1h9!tWA1&vyjqrQ)oX@rFYNTgYM^e}A0_$V1lUng_)HW|yc~`06GWIoL**^!q}reH4Ej+@<`QSUAL<;tm?FYbO@D$ z3Y0d3ddR9j)6)N=j^tReF7 z<{8DgNwrQ*zyJiagYf&}f7IU+M=ab9?hTc|r2%@!Q2#P)AD6>Xh_YILld?{hyc ztCo|0DD2wQY2x;#*gROu~s1?%y05^FYI5Py_g~n zMP0C(0f%9|x169o%a-JbL$yGB3_kh!-T22DL5Dc8xHDogjXLZfmu%}!zyMB#GlADO z^NjO&=ugf-2eWE-mWOclFPPH3PopEJYT1};dV|w|6SFqO_?d~NjIU@vF!;30`_jYz z#;^TtUp@C6v0lCC4#%)j@R|lAyNNZErxT!y|9E)~!mNwN_5cEwO0U0L5l%-C98jq% zKoT%ff7xBQyNV_v0000#_yX7DEmIOeF3`-V7^R;)n5g==LV$29=0}LJJd6Upu&t*X z2b3bYp%6{zaCm)F#7BfMWxuXX53IldK|laCy3_#%G<|v*0EGo}t$^ksD}$*SHTKZm zE}T`6UyFW}OUzucb_NO4xYODEC{z`nP}%5VDi8oOLgW^?dDvA<_!BXP$#@~In!5e~ zVB`P*7XxrAw}h=6UM{;Dn8eCb=xD*Zx*(5t+jskfjlP*TFb^X+q9&Z`By&f@uD{d$ z$l0+>POJgF|bmWn8E_Z9qu&U;xEN@23`HPxt@=X4+IF^a8n(8*h?z z|7x6@1>;Je{Xrr-R*}&f50001TO|(%m@Bjb-TmaULHC>T#Ga#7D+e3~$x{I^D zZ!R;P1^f=Q*51d{;g8$&{a_FKky+HeVhn*H0dU@zB<9EsAHXc0OuW=HWsPrK%Z5Hh zuUT3#t|~*@%fpW?$r2G~0Bk{{6x*is0!adycRBuo^F1WZKoqKX6mDw(6s!OM1B4VfnyR|5qSJH>~%fKUEB@r-QxR zOwC$AWC*uyG6>$+Q}3ELf7;88CP$gqJ;-sh^tl`e&k~U3?W45DF6m_zcXIn zC>{oR2QBD*I-w%OmP4>D*L242fS=~(P%+(gI#o`474*1!NA0u2=NO5mh~03-Ck zo=Un7;BEjqUcI`U@t#+W$R>^%ZRJ!KuLbXw%RvewW}`sYPjUU?^O zrw~*m!Y&-3cd~1N56uIrb)RdQeXh5W!yYwcd~x${Vnr;3p9(ZztpDc=HElX11P47S zy88C)X{HvkyZsyY4A>cZlgoXFO7LF`k5%egoc?}kH>>h?w(4FiRBoN9l6b@c-F-`~ zKBlZ0&@4?rl*{u&zC`bLOb%_-#$?;2xB!M7Ei>YMp8zYE!2kdWyGPJDD>}KnPXMcW z+XPMxvIYG2R~2kS{zW9Runz}Azq*T6j(}%Viei^aT7P``Jdg>Q#<1^mZS5!ot?FV0 zptaTx`yDchHD{=4)z1=2-F4BvXIZhE+q_a3Xh0@sFTF^iQZfs+p=Y;sMxZr`F!(%n zQ!%6inDcJu_T2c@{F5_m3pHr}!!K)6Sp>vAIZL^uTxNlV+DJ{$RhSvmzyJV$4!eXI zjk({gBb1UWG(7SE0fPVouzrIEK8HX!0c0?8tazi;Bp`Ze1)1=6q%yh1cFnoL7#0Da-7Bqb`RINpM#+)B ziZyE&=_SgAWB>pF00aBb7e;o3RZ8RWM}m{5fgt1p0EdV(bP{=JNv#JNLv zO^dyO{ssmt13c$Q!CwbE!FV_wI9tA&EXRPE8Xr-m3XBPSdP!WkNe$yWEXb2(UJ%#&mJ+r(1EK<>zyO2bY-Gl2c5tThi&yy1o0gunm*3BZ0kqycUY zqV2<$1E)l1fGj<--Uos)Sq`PB+R21SojHzJ}`C>C`j#5E@33Asuv;F=|Qx|Uv0 zNUOkoEE;EK7*(fwW*6!PoI3@1P9(O7S&2m7cfgZbF0laH@Y|&aOZ4?4hyVZp0Xb!F z!w$kATn#+Smnx?P^Jp$IinTDmN8s5#3yLQ*0B+3%@T&>db6@}oK&*(9 z@awEwj79iv_`i6dS+R}OufseCPnp$A*fdNKno|-ds8jPL!p8rRf$(76&naX9^u`67 zxvA$O4xPBWtYoSP)+|pxhPQ~DGW)WPGljAV@2^q7DmSqeoHD-bJ+CLK{G|BdcGF6d zB98vO*TES%?F}4lc`MqIV%h3$`z;gs38M;4bb`n=RvDIxz}0M@cCu$E7b zk!ky;YhMq!%*h_tC!aXf=zL4k(1pM%z;iE{-*I3I#MW_Xtj|5FOUV_ z0g`sd$XL)El=;(XIww6ItaQ%e`3Q!+AJ=FVU+pKcakH|BiD(BJk=5!ffDCR>!D*`0 zENpsi4pO}Yd1qh&H>Wvj=@|e>s>mm1vNndbN;n{UFGO6BF~^cilygqWXadwvWMBXT zV}LeE^)>y5x>luYjmbfG5}$jLeaq>qF*jcC@JMCJFF6kzpOdGRc@VU>I^VdK58O)R z`5p)A14=wd@)*hWM2RP08Pn)QsGU_^mij|K;||=u%y$t0eGJ4 ziTmnP@;m{bow_{>y>A*=#D-u11_!7Rq=yf?$>BB(zziYAySbYt$Cyw`ImJBjE_ zz2)FN*Ej1v+9=`WVY$&~|03%q>LtA=h5Tms1CB7SgR~7M%v!1CJqktQt_BvI{OZk8 zG1GsB_)Os;kH0tH*z9FgI@0xluYNj#1V8|7-X*;&;W1Mx90`bIZZFXN^%L@^*LRem zJZIJ zWo3ipyH@%c`YOr7UW8zt4U+0@uEdn3SI*qlkHL>#5vD-O0X0XIvEja;3@sRGQtidn zKJ^e%s9f%}EoAO%d(<$e3}=9YX~PB3Uu>DBQ{jigb9n)RX^c z*__v?E#=%qUIW-Bl4oMU`s`@~_D?e18+0kgSQQg@-OIbAJ|bw8FZ!G=W+f^nqW+QD zZ!V~jJO3*&Cwu>wZ$bZT1`i-z65ik;wH z9Dv3Rs7GSX`SuP@H^1Q^BIa+{$|2;MKkB#lko(b z)yg|5FsA7YCS>dL1v2s=^fAhrF75NCY$wd3NA%8;=AXStOF$X6iK*~7oX^AGBNHE5 z2WS067C;ZhbKwDwMkIpEhqR*FJBMls&v+Q*c)tWr39vX$s9_s|ATEGD6vg-6K7VNIqXv*t5v4`e4^1Y&30;Cowz@@HNz2qS+TG_3jDJ_mr ztox;$J}I}aWYWo7_I1VPCdr4AH?OSh@>DqXjaP)8BaAU;_zQa886P$~w6ZUKwb78^ zsd3PXi9V0l#as<0VVRU>WU0+Ih5wdlVMrX!9Ar(|@t+uEiBPS9c&1QBvhBTn15lRe{Tplzjkc&dNvNa537Upc-dj zl@(a~-P)!>JzT%Mc}##$poaHzhHlmmQ_zEvOzpDgDNI3_#&~|&mUIZQ(13>Ek8lm! zLZhx?c}WHyXa*uu6@#EsXx^=s<5Y*qfKeb+gQ8}Omg7{3QZtUu=?ZiW8aA~46zsfS z7q32uaxMe0G{C&AWRRr*6yk}``u+d`6(H_l1D_<-hE@MMSud4L?HV&os*825x6?p< zWH56J9(O;)@Pux$AR9H+rLVRZ{mQuZ5=3}xNt)+~?54qVZci>Q^&I-&e^Fgelae_x9_WUl}CVD3Dt(K?T+U&>zUYTW{7K!!OtK zLtNJbZA-ut3XlyY2NA0B00m5C5_t^qUE`_v6&qGqNLrRl&l%}uTTaFVE#{2gq{FT*80t<-8*XEv8(MU2%Rq}#|JbU9mul>5AwmpdG9y`zRW}W4)X#; z9hz3Z6S>{H=EPo#9|>>pfOD8@q8jJ1lW@*h$JqbDQ+@*1&7&eA8)9L{59&gmp7V(b zW}JgSi3>RcaM`A-`i^)$ApxEYQ$Oyz4l)rKW4f}PdthMc!ctXq&5qUT2B0FKXa7Fb z#I_fxfr;+`PIE8$B!dV7S~K9uJqQbE#Ar}JLUT=MT>!oYN=sEx$xEdF7;&KwmE}pj zquDh6nJ~n!YRo?hA|FByOtFc9!o1zqw#N!4PY0WJP0o(wp>%+cnJUrgso>^p8G{4U zOYIGEHeg1jj?Dcy9z91Kkd*VboMxFzBh2NFlV=)L9x#2D9lh~pW33>-CJBd@mp}zN zIs@yoFwg)3$_`c5QrP+Vjvj=IY(-cUHSW&SW&mv&;_@%|Z#*8@k)HKG17Aoe6Mm>O z{fT`uczG1bRrR; zKqh%>aRyo#5^SA9;GF~ZcDTS5m;fTVMEgr4xHN?-HTN)>)5PaY#p@ZcEOr#O7zsVk z6!W`b0jdUqK6;`k>nH+J6jl0JqjH+^<(Hw6H`ShcPAUi$_3xk3i6m<=r2tMEFSM%5 z52`UG<4}Y6HnYyls&%{_FQm~TvhDl|;yiepV6&*EL8;@^LpGFFN)j1+iYFA)zUmXW zMaf zsMCd(Md@gQ`mPQjCpuB&4ts%0swXf*bLyeoIY*T6@7pI=LmqtHCT{u}D96J?V_!UA z?me%y^z0a1UvG_wK#=e|ksQNl4GiI3Q)vL!q&V;C$3#?UNKT72)CtId*n-UvqFlZR zys7-Rj|K1;YNjEt^g|rhl4z%b1fbG3kHbC|ABX$^USZdxhc&(G$OkQa>GJ$b?6i1` zOemmJ><{eKjR~(_AkI0GVnQ|EFcW6Ulo@1w$>8`A0Gk%4<8$<2{l#)rm=kL4*Xs^> zKvT0?C$feXE>MA;2f#ak1@>A1nlpm+!>&soHD#(tUha7@QA zfP^ogt>YGmRINV(QrEhEL4Lw?_ADA1TgI*FdzAH=TJz3;+XMh~xT>?7)$8I(`8l%$ z?Dg&NauYjd=HshC<{)KTT{bY^i5~-Gqoq8#L72@1dVOl#6+H%!?{2z8FLuTWxwp{) z=<>t=Q$w1a2`kYtN*~t3Bn`+p8iIOUx(kXB%aqJk_A}r$gbJqgN4esd4gh38VHwBp zx~1*AujSSf%+zOpqaZO5LpVEIOLy-+&+*#6peCTsDoEwL)F~%>A%H|mGOz#xXPlU7 zu)2Qays293A`>$u!UL#bjT_y7?x3`1#6e-n;ct7UCwBi@>*|iC8~~v%BdjnP?RH@y z?hg#}XdnRJG-#?jAOW8@hev&RgVw2lxNf}fE}~2t4eZm5mP;`SWoJ!&B!H*L#|_3k zKNqe}ij1${f_u`mxVKs{&`rz}b;hx1a-SqrgLUaJBeN1i;EFhS8bkuLI!pdO4n+^R zF+hrMmo2U`f$)BaN zy{76LgRmtq%Zhf?l%ZJ*DYT&Hlopm?H7M`88IMbF&A2f_+Ae5&rH&y$?)B~00Lo|ltH$2HG+u&tb+qyEm@HU@7hUFh zbotvnK0>)mjSp`dikoAc$)(I(W^}F}c+R*2jDN}1Lfu^k1y<2iXm!4T0o|uGU=mX{ z0+q97Sdh*^E63B_&w}3SmQf(RpTf3ozq6mOHd|U!wDe?xF`Nixf{^}zlC#_3a{iFhC84-qV#zxN@Cv7;8N3!9ZxaT3xJr> zyJ@(B=OP>DcBKdYs6H%kf1dewO6$%YEWUp{ovqzH*>F0Sq%!vc1!>{T62cuYygvj) zkqyWAYtrXH0UtqLeuAuCi{Dq+;*z8Xn)Z5?zQl+|cAZF~X9oBl!kG|X7K`N8{M)}Z z84w82GvOo(WQVSR0)5~B8QJIqZd1oHdYbV?;$Q8Y zO%Ehqg|nt_c+%mL1S6pwh2h%28;M-h^N#)yGo|GA^Z&{5m`qR45qQ)8Y2HA7Mi;$d z)*d%x9*Lj~f=ZD;&yZYl9tGYa3JiJGQ4j#1A6A@^wQgLA>=Ym%_{LUBYYj(q`Nagb z)OeVEhN&KVEMo^{9JLh%<(AIJQ zxaaVr?eY1aO4{|tUX_#W5__lx9rZMt)cV8aaPFzTHrc`?$ePhl+Y~) zob9$%wdQ6{!@#67wbdpN22XXlQfzs{NoD|}F&as{UW}zUu4Ik#>e<$;;KXdn%#}~m za029Ycw3Hu%R~yDcCqA)I(h&?qJYLZdw>|40|Q82MdJ4On~?2b04_rmQw-m_J$dc@ zf^>yY#rsI!&Pg?3ikrza#d4xn2w;lA8TpP|zo||Gd#p^~H&20j#9u zD4tThVBhgApKJg;uk3-uMvUZJxc-SwTz+AUkl}6u=bRlnQeBKJCW9j;%|%h6sRtoK z)fpDKUjrBb8ylMXIWGkMe7W%cFTDUao8Z;Th zqYxEvJr8BK4*&$SO)J|{Ir$fJeMuw=H2cK_Ansl6_6B<=%p}C>GnT@vr@sUCOt>H{ z9R*R`*0nN*ojD{jF1}$f^CG&j8=nFq0SM%}G5|zdMv{o7BeB>9szdfVg6%S^rosWT zN#t9i`Sc<@08|df7s)v5?roH?o*lX(XJG>F!XA{#d;+5=FjQm-hynR&$6t6ka%3f! zmFZU4-g(xi&WvjOkfdp~=w=7m=PX0@No^q)ykCS+g)cfUQSHJT4qmL9tuT)~CjRj9 z*Qdrh#UQotM-)kn6wbi{L8_1bj4sJKyy=Rt>sAEofK~+z-pOh`Mkx6F41fS@Ne@tN zEEKbdy}svtl~libO2k5TT3S*%l9X_i8FY@RWgi8zJPX!8#Xa?`bE})rbW0`}LbA4L zJN0$s@1pCWW4TNt|EtJf@v{@>eUl4*8oj}AnuNmG(l0|1zQ4&X>B}Ceta3!Ra;oTI z-#^4ez5zMe13s4(`Q=vagv{0g0Jj3NF}bf02?#(;K+xRLW&6%2z$Td9+wx9rbf3w8 z$yX^RlwE5p>cw5zJBcYdK{wU0C|uLODBUG(&qVpenQ31h$n_fx<5{NwS9qn%m>8?x zm9Cjiuw1%9(d&MU?BfD0uF>#u(@!jEp&I25z7* zHvHa(AO#D+PJeI$Gh~8zdqzMlI_X0L{&*MzkNS>|f&yq6d4;8l$PuLn05nr(QPUs< z4n!^kxtaiDy(RpCR*vVdj~$AM|MZZjP~1%DN<`m38ab|Cpe$teqjE9Xl4X}(2)Wr# z`n2rz-M%rK$BhMMeexE=azL>~18?+X#~{Kczg(S2CrBmsLvA9J5RpTLzd(Cn>Egwm zp!6bk$H7c^S9h}EGN?Dc4OEI02+3R&&SX~@{tZOGRW;dRXL=;dpNUyM?;soz;Gc=$ z)Bs5M0Mbl{h|YJO-$!5?U}fg%$^8ZuIg~J{2Yvz+==(o|hQMtEhKe#Xa+p{af`!{8 zXcyDA($j2Zq}8H!lOJq6WFg6f0vjB$b*=m*@L`P9ecqZlf=fZ&!*E1eFe6^p+FeRe zrN~fu^KE2P<@;}M8|3_HDg?}HU`fyqL_Ua9A!YHY3312(47Sqp-3IK0;RU4uehDMMcDM;c z$|WThqyX71nqD!J>ydd&!Yu0tN481epirFR@Dx}2l5jRbtHUpG_ z;Vya8yH3lCa5&u9auX22hL{}mTsCMGq;VrSR-7`apMg2)1y;W+kQ=b&_^pF<)q(@r zsQk8j%ae%GyCQG)27Cft;0`LY3W$MFp;9$_$adR&?eZArHDi~o$QxR$VYgm~02*RU zRl!vViKkG5&$b77x!B|ERWCSr_HC6?dGTD~xy{^O(uUr%_u_@)w{*P4PNxfSc^h2= zT0}xUohl*fH|+`4+$ELyv{P#(h@K^#R|}HF1h~T|+GI>hP1$UhzN;4>VIw?6GbAXz5Ky-%ny%DSrODYyNAx`hD=mRX@|)5;H0Kki~z$1e^2(XvO}M`}gW8DGFZ zJ+0ebSrN@azA7Ypx&V8~;8)l^%KEJm@RwL|^ku~Qqm?giW*RbW2RSd$aAReU%)k#2 zPj;3ZTF_n0BAQYiy&=K`lh5SwE`2=b2(Tsa=eCHifL(g$-cS3by0{+B`C_AAnc{bM zhI6GERPGQBb#1HGv7je)*{Deqlp~{5sXC*0D~H-s(Gw z^`Yz&C60#g6IlNNu+T+pin85rz$>r{eOlb!Ac?#>HEdXQvAe0y&j_&e~alaV&# zyV7hqf3L7%?9e+b&l4t7lJALYV#c;9C5IH)jFc^J3sYf!f-4B0=c!TcZl0sa*(Kt8 z`fc>{cj31rYW-UTPM6{0CAAE$C;Q}_myX*E(qDTYE`j(S*ERTCJgdtq8QKRn;=wsB z1p>d$Y*;VLK^uk^JE&pvOd_3|0b>Z9ZF7^VnmGViPJtlVgjoS`R?I8U`HR|uIP4)2 zTA;5JGg>ti+(qI09Gsm}N;xlkAF{4__5sMt64LvX6j3_zayAN(t>^%^2eM9^n=!6N z$b7jtAPo+GrnxSLS|r{AC>xfks%z_EhDO0{^2;RlOO>-;+0T0CQNObTWLO0SGzMhx z(i48DKIf>Bg(7GcfTfvh;1-1>P6(L-W_G5W8Sv@y?;+&*-nbhbja|S!nL@?nJr>og zBheEy`%=@sUSn}-f&6Kan-m4$aJ0wlT2PnwS2+-m3cQu)X;tDi`HjI@0W(u$-LG z5h%RS`L&6Uc!3N5mk6Uz?gr=Ai4;SUpcOnewW_XK_S!Z_4AzX%+J;(I)~ zT(?i9v}!`RU|5Rh)T&tcBe4zDH&szgv|_2WohL5=^E_#X$4a8dr)^0orDIP|J53L$ zAFvzlS`EtHDV_!SOvZKN2iv81>E+1tCy2_fzD!Dh@7Y0$l^(QIDmmX2AL*WP zyMS0V7@l&+r-CsZsQJqcG4SH&_T%z!=J}#%oBvf^ddWXaI?#km2p-{K>xT}wtCuYt z+QpUhPdq*Qocb)#jV!nU0$xcRL`uQ~&LS+&4m}{Z@sM-Qu?k>;jo~2qXtw{{O6%;( zPJy~9T_R1|Cbvw{O5Q2np?HiDpa45+X$ridQoz&lQN-u^o1j%L`*5)NVjx8qlOU6% zrwJAlTo)U|*k%;4FOySo5K3+NeA0hEZ5pHO5cSzbQ9@g*I^TcDa3o)Ln|Oik&r%=PD3SbU@w8$a17Q3U8s{XOLd=3=CMoQ zBYibYQ@%w2o9%uM-I5hR!1%VFJ3SAi1q#V2yK}C~@KK|JYf1@5C z=Tigi;eta39U9c&sTpE+i=Dm=L)Z%urR+o+*jG8$=!onsZfPeDVeyH)6MAXV$g}GB z$Lc*R`ujb)jZ{#}-iELI!hK5Mv9C}i{t322D?M-Wev9IcbTlGbweHM$~~O#b#{g~b$_}vKEajEEbl+9{v6`Y6|YGE z^wj>5t>PX4w~MtPv1vr{4g?#ZKmsJ-C?T&J>X~q$JvB(I8&JaMm}MY9{5TA|(QIgk zbqeur&UW3$->$doUX@;F8FvAu@z(#mSnel@m54^2XbvYYMKCAAgrWF8Y7w^aI|f1+ zEzecFuMg@=nh(QC`}bzPh32I8;S>_|w`I3P3CScD2m?e*`^X1&F_2o{`EAR1c&I+U zz+Vc=dPO}|mn4_$C|~aMX}`h{u^=XO(rfNZM_~URCSZ+-F_KV{Ep66C*FuVUT7%j# zM)P>y7my6umQ$M;83(Mb=R)~vY1}NCkY5|H{Q!EAb$54cE-VUc+nSvr@Nb+DB}AO0 zs2W&3t+dp(IvDoclD$G(RExtMr*u9b0kOd@AHa999V1vM-fM(slW^|?#uj|9E2^|N zh@c+ZK~nr%=~aU3vlZ=Ug3!y?Qm!wHS#L!e)S8Uc={s8;RnQ zeV^7jxmC5OAAIhRz!B>v-_)&f$xIR&M zZawpwdqtm9l<_+~3M))SyJB9V6qn4fuF{#!`9+#F0D`r;)3-l3la22g%a_>i=#2Lg zB@esd67IxOULjV%VD9HA2Ucm6$4f)&BG&f)8Z2_jScp0=SBq9@|A{EN&J#SRICgZI zAj3M9Y}5(F)7`Roy)fCL4>AdF+J%u$z;kAfQmp8DeFX$heQ<)y=0DY2I)F-X)MX6d zV0M^a5B+$B8z%h${$Cb{CauV|gf)O8U-iSb!*&#o1{A%M$2It--cPh)%mAnrYHo#1 z(5oL+%IW%UKU#ELq(3|RND2bzK#5Ykhoiz z=XUVi3M!hWb~D%ixqqAdh#LaagYQT4$;j?6m)N$wO(GIcDS8J9Nzx)bDUy67r%20PuEz;3b*d!Hiknt;S=s`yb*B zp8lQ+?OrMv!Wsr-qH_3IzT*TIpbu_X8uIA;?gPf{*N1t6<4WZt!?L!UDP-Zu^ZtvXW);F#5P3Aaf_yCyu-h19{=~wwRQk<7OeJj#pL8Plo8%)36YxhDR!04i%@{y zYyxdLlV+_Qo4MTAvz%-mFzJ@p9$PuC0+0y_6Y{ZIe=P8z2XFx1J;Xi&Sk>R5NwLpK zZu7)0p(KMJCVYbtFPEH_t!1?QpF)uw56V+ElJeKZq9YgD-vRuf003M-9{T-01QT^2 zqiMI?ESmv(#jm^$!9FY{t54>&a$XKX<3kVGz+0#nIu z(6Nd$S^NwikfLQ{M!x!~UExdqz?YnFH7}bj10okXjqB-nE=K8D#LBpt&Emf6N*^OM zzlZN3s^lv~3vCj&uNJIsO^`;C4*D!nM-oOAL26r;07smhUd|^1ECEjqp@d=eC_?HZ zt~|wnz&KNU1;b6q-*{MbV34SFen_aOdrZiUOiypo0B_@IaI5V$9bGy;+A;QUs4u0b zg4*74gTsTCEnd5-F&NsD5bAFPZ4!1To+oFzP7W&j#cFcoeMeGTk=^#ETSGG+yWfEXaB?GKAI*XkLR--9F?1r7N)<3RxSinZk)A!w$G6B%8zmVEo>a{w&(B zHtHJkU<>_daq|NRqMyLkSl7CIZ&b8SyP8(%O0^g&rK$3cVc#7${jUMQW6Yv5l58`P z|65XQ5WT8vb#$$zGY*`|ud*f`{2)*B+w}gslTry_du~{WjZW>~j^*5LiL_Pfmz z^Sp9N3owJCwtD8LW_->Bu0eCfaN z@3aRbg5j~(P#a7&XbnQt2Z6YC4ZxG^^ZF11r7lS!i7|78wk^{#dj*7SJWF^X4 z5wadI?;vMIDluB|?L0(29%$8gNc?_o9q4cC zE08FkK%WKV+Yu_u{JojbXhl`p?U#iSDi(zKuqkcvA}3oS-CrzL$}!K>PgoS*xiHdR z7FBa9cE+@JB&w($mRDF&Hf`s8e&!)Hi%JJ)PgEq&(dm*F6hYiUiI0K<{vebEzb zZ7W5?R1t`K5CGXEXHK1%jX0OSOVZ0Rnp-(p`8XBF%rqg^gm#C+hqnH?Y$SY4!>nc+ z%FA#?mFa{}fl77s?XTD`S(n6-Gdk{Z@_Ci}H0ottEhufz16^bz6Ef)ab|9-usQ zSPcEZ77FYI5k(p_$IH0*p_8(wvY^rG zy+E4N=0@sTDMLnEn2B5WvfRql8i@tu_wZmQ{^1OGnipj9Vy-xg?WTNY?YmTpf2VC>+9&zx0^Ip94m4EbTlF)fB|&u zcF5ud>1_s1{uQ;@c?dMd+aq8Ef-e5wAPFtKcWQ`(A#KM6-Wn=Kb~P%~!$H~I$s{_b zk9hZPT*QO?*?l`03|s#TfXAl8Bi{{Hwr8^CWa)BTllz#24LP!6o{=K9x~wzM>U!N2 zFu(zr+iyiv0(*f0+Z4u^kcBU`Z!)e6HaR(+;g-Bzi%JOD!*#eH8^v;7cbM(0RC5$+ zK{5t8HhFJBNILj@10SKH1mIr=3=s39^gj*6|5VYB;z3>y%MYr+FvH<7(HGTEGx$sv zIjNjQM0KLcb158FWs_G z_CD?}9%DKA!@e4V3_{G%^H(pXdkxmBvsJOTyG%t-xLYX>1d4 zec@2@Jg8$02q{C3u64vWFwl()lLoKj3e>+4)-YjSZdT?G3N~YjH^JWj(`k09kZnc!IelErUznQUw=g zgyJ$I1`rr{br|9PQK0|j#XPm+2Qoo;{k=oV=<_OA_V=c;*Es7R(1}fj8ppSdcvS^o zp%SN7r={4Nh=wil@$+YOY+OGh?5je^Ums(!`5S`CDWCpRxaJKOFw0z^sUJK?@{!>h zm@?gubhx2eUe#r@P81GAexz zj6jMhC>a5)T!%m?6f;8pU@jBNoU>hv`tg*t1D zV^$Gn>nd<(-U;S#1Nv}p1MJ<8k?=CN)dDnkBs->@-*Cn~_1C3Rrw*@i;eic;o=J+s z{Yww6OOeLSPk;zP$N&Xag24mGV|2UwJz$!D&(OFR!XGE~ZF=t4ji+ID!AjBdvu2E+ z^hCIRJA}Bnp?fa<+`a)oH+A}VDX4+njeCo}9j4|%E>3UN6*vs~((cuGsfQPgKf87Z zJ#y!*?h}xGq88G)l&_D6et6(FwLA3`l+`GhF$>LHV+`6_pU{f6_tKM_iuC*?tMjuu~f{j>!s}0u3 z>I25>_T15j=^P|N=zyxUzE$1k+ck`EnFw(~dqh?OKB3$Vji}QEhjzc*6tA$Ql$m-K z%KOLZ%P+vG&~-Z-2RrW(kfVv|zSs*PLJ$j}@zoZud#CsitpY1%QeUBCCAqdORG-K; zg3_&&i)=;QI9}AAsn*S%X#c`EfsSr)g*6_o@e5Zd&$9}A;N|LkkHdk5E%o)R z^{c`Ig$HlvMh5mrYcJ#ORtq=WO%%d>#>rD@$k7Q6e0ltQ6Ydgg(jAb<>d53*62n}4 zG|r|GSL~ai6U1-^(YgeGMF?cO&6&k+n5ed?uvI8CiEq=C11IZGSL>)`EK9b@s5w9( zoWueTg^k$@w z9qp=66b}-XDjVS+Orf$`uBZ^nYHSC_(&syixmoqL;5H^%(DnHD^LFxP%`>%6JHvJ- z%E;~Zp$(E`Rvm<^?b?vFvbRh$ZuF#`p)*_%9}(|Y(SKn}+T9)6Y-y{#vdBUQ z*0PA-a!Rw^NuHyAuVQCw6HgyDtcWP--n}i2F;I^E60ZpiNiYY}YlCp&b8=L?xlAu# z-f9UmDjOrjhYEI}3^2(B#RJSiE5K1qe@j4Jr!pqL?}J=Fg#F(Cg)(XaF#)6yCE`l$ zVoY$61s>MMk2%2#x$|F^#6UWCC8XG_-Rv=q)tR;NI7dHvQN+Z?inbT1_gFY^)}CQ0 z#+|=FSEI~bIVBc&mMu-+Q#L`fgbA+Ua)tje(Es3w$>N!az`HZV*IJ74Fa7K#F%rX-+ZCqy? zO2<)Z&kuuKeXQ-Ek0}OuJo~b6vRVGm=L_g#)@6q87y7mQB1TChUKWnZ2h5jzQ$PPF zIs1SQ#=$P8I_^%8pQuZaAC@x@GbeNkd2Op{cy0gX9M>^68RdtoJcUL~N2#`vmNR~_ z;4x!?-C6K)qYdfv{VZSdJ_{rU9Y?m=6V>~`%+OpL$e6Y$k$8Jjj4?L3b-r*P`);BZVd zk?WZ(iX`)tGRM~gf`DCKoiD-pwcCPg@MU3-mB=jS+{okaoP0|vB@t?yK%2$4j><-M z+BXB6k!AKzhEs&(4;Eg{Dq}-NV@}M@@F==&ICoXLHz@Zdq*D7xnnzx4Am2?~^RwVW+0gl>zFLqS5KiGpI<=qSTcGk{-Pyl)O`TWdwnB^7 zpVUl(I-d%*ZBg4W6A_&30}})eS!V2pm#0^OepS?LqUo9{bENtp)D;KvWuf|H4C*~g z(K~cKM)>-J|CI0&$pps8E72CWX+#vBVmjtbS8l^iu_qV0PqH*LX~p#iC#NXjqSwhZ zx(ZBdjJA)b-@LzXuLF%CB}~*twVU`Q&ZL*X3NaZ@z)*F|xQ8ZR+jGK>?4b<2mJp(v zPIHmXzJ2;0ZUan#opP&skCU5$I0QazPBjWLQ5l8zE;#HJ{VH|`GpxB^fK2q~jKPdP zNf9FcdOXo6M+-!ryF}rK0V1(C$QP|kVCTxdoaGRyO}q8GzO55TGi;^ye0^e# zi8%2&Fvti?wByMJ*PZnl?4Y$rG}xuv@#{o)qBHzc71Bi<&(qE2M>xN@FSQkkd{?6{ zEYr!;vwD-U;D7dzo}s8=<`Z8!BdWkzcNVRx@FkF-(@?QvmmA>b5_!-nMfhEw@31#d z)x6nscLrai5xXol$c>*&dh}2+8~qBLq!cJdSb-U*Nu&)*3hFihcLs$%TFneOPW9W> zjL~vv%*9QbxN~a)2|y_L<;#0nT*KWe7|+U+aJ|zQ?sBq~m3Zlf6M)Mcv&K2(Lfr5T zf4*G;o$l}e6MaUM1ovep^fx!OLG1fdcV&GpV#tXt^w1VQR66 zv#iZMJ8Wb|{lG>@wgafy-i8o#bz)vdINprU#7PFblY+)VY#c;Q0B_n}KfO-TM85^yMJ z2cA%xXNet2p{gv;$<({pGY1LZ!K=t33E17)WSvppH3DmZy~Tr3Gbw8q^q+6e>>iHE z;ubA!Nbr4<$!)KB5WWN+857}tzlAyZum{C5gExOOimnN0{hB_pl%nE2zD%b&mT1&k zlwei0EH1XH1sS`+R%D*ftRW0_`0UnM^dZ>k=Xaa}P-Bv0Ux!ENP$6ug&9v17i$L8? zOh^}n*ktM1GnUM6 zI7FBjSO9161&9RgzS#(P-wu_0mF)Cjf;L8%8iyp}Yd_;L%}eZe>7I|q6L znS{yJ>P5yUj}zzu!Js{o{DJ$QWD*xA2qU?t>GWj=kWDJ%vz>9G87?*%Y>4Sjx%KK3 z^5uOmyz~U1v8+#6B@453O!a1R$4P`^Mc{ddcMXYSKxu>XQ&%V0 z>bM76nzu1Mqct~lbVS?qeOqKURKsPET)ob*e?}((Xm=+fSIk3@o)$PWGL##9Wmzz8 z5D951_B;5oNA%J?}2#Zw*L4o5;s zbCI(fz)TRde5U@cx7_8v2iOouD%a-L1KbuV(XI^_v3B&Qt#K{p6^W>*g%%<7Zjpof zjs3Z0tcsC~4)+*-m11-&WbKEDGTiDY8g&KWADM3vmtye-)qKhF<+#VQ%(0R^q?LMJ z+&em6aSh&|Nfyg?!}+v6VSk5Rd4y~4*xIu`+;uSnH(XzZR87ttqCzgbVvinPF?-B$ zFIOUYO+7x2XSsipLAD?h?9MXM6L$42#O;)sS4!Ni+(l4S_ez{i_<*qGBv;b?g%UdB z);{{S$(D+=BfERw098)ODx5MMTcAZ@<*hq=Xm#)DV|8Y`ZP&1c`z-V|?Nc*&do=UT zXV$)5rVzD}0zEt=z~M?BxTf(Rs=;RIfzYNtq`;T7aY2S--`z!9tci{THpX*xoQX!Swrq|sv#mlBM{iUJJeNu$!m7;%=LKZ1Oa2Fn~UK&mJBp=s+~v6d1M9&mo9# zs<(+eD5!~~3dTZ+1*uAS8cZKW-@YvnF~A4DQE@`Ce%zu1>MJ5-u&`cC3=>~L=3mD{O>^I{g!Jidk7^&Qp*-RlF<*mg$}Y1D*ymU$P|y7!jy_HyYrm@6}#A_Y8pfo8hAM)au0i7J{i;1hbz?{zNa&t z%0kkm{3e_hgmi(!z9KV2@STXsRn@5g@fMDsY_1o}rm1t6q7tzFrO=mWFO1CvkU1u) z-YBW&`uB_}faunT5QYwLc^&qdanpqMdPovjnb;+-Ca5;CU_0Cv2dFcp#oVRKkCX5OmAXrn8nQM&ZDIoc(e*S=%D{6A90m*vz4u@?ROv z(Gzkl>j4A&k7GZ7cw1Za9Vyzz>Qj=@+enU5K76E%Z$XI5X(>9d$D-w4Qogw(T9j%1 z!3~o2fF(~ix|sN4YJwxxkCYVT<>bUOs2ky9=;Ozj=upc#8y;au(Pp>~@J9Q4o^O_* zZw1Y^E!Y9M4&!xH_L7V4wadLO@OkM-CfqCF#}_{Ryj60LLL?%I^X@XBBLVh{+1n44 z<{WD$uI9FlAmX81`MHa%wqaV9wu8#lAbMR+=Z)$6K*9G>@u9!o#xA;aIm5B`q@o3> zBD`oiRxx&=!H+fG)92+0=L+=V-QV0$XwvWFUT#2S7F;W~B`s(~MDk>;9_n(wN?MU% ze@RO@)Cd9?>oqdv=bZcwfoN;EpN!BX$1wxY;%sA}(s|o<5(B}#S0YX6LoD>x{H_Dv zng^U4E-ul5?y9L!8?XXjR29C5jc_kqLf~Hwfx|p*{SFpY$rr3$14G+{ zCPDuPQLv~Ta@pFSlpGV;%if}6Z1pIOD%$P1PdOqy5(>J?Ch*rC=u<{h>Tn98)ESaq zjs(pI;mEX!%R|kw^&vvbt;Bwraw{=8d>rw=>5`ssVqg4|KJ8B^k(5EU4BZn~C3Uw0 zGIMl*hQe5vJF{Hj-O{mHV&s=$tVPqU_X2^PXApE4VM@Z0M)%hD`?9&x@9cSWnk`k3 z(&><*Px?oUCGgh90nI-O2BBheN*;uV*2~U3J>fNHM&J>5K;mP0f+s*1aI;_Gh+r6s zE-#fZ-@p2B#*L<%#%keaUY3H?4@AsD)d(i1`{z8KT>zb_{MjXpdy28Bl03`gMdrV5_-WvRh*}VT+gzq4_nRA|Q`(*;`6^JU znq~2NyJEllc~@h_WrCS`B)`quS?}mh!W%a>3{uF)Tv9$$q|B~LMZebD`sY? za{JU{ryc7$9bci_2Y%UgYi;F@`_KQWd8UX64t@{&E5z|6CV=1g98w~Az&+BC z8ua;FI+!ylP+fcsj^iRUjnc~$m03S+d|Fs&1EasH!hULR-681W_6mZC7UR46#8KFe zCquG}XTx-Fv7*_G@)Z23s~noKvbiVaRR1EvzXmzN_d|am_^#>IIg6`rTP}`%jV|)D z@`-NXShe+bQw|tRk9eS*I@iEP_Xdg9KuzII6L`@}+WsZGSIa_u|F3)lWGc9s%t$$Yr1br4|&)r`gF2!S5&2YE-!5JgWd)Fa;HqXx50BAMN_lEN(BRO zYfP4nK%_MADb``>TU@3_-(MbaLN9!< z)#;X9ZExhx1bUM(<~g^(_KuGj&2fh-NY(rdFsEYGykq_}yi1J$AeO=%Gt}u+z)Gjy z3Bd(@?J5-}73jgL1g| zSHeeB2qq27htb<>qX@%`|E|dN{PjcIAPCXGBOzerLMh=hqKI`9_*kH)cJ6*5Pa?ab zY$8E00!L_Y8xtiF^#IWKPsvw!enoCB<1YMmE#(vCxTwrj{ z*hY2wx>6q6*N8FA^PXBZmXN~~K#a>HM}~?qru)!G_v7MXMnpN@lN5DrTkDXAr|A<- z-yD3X7S?ZiOtg-@&Gjb1cA7Y{@8A?ag+VQ!OcQ>+g#JnMh8yMewo1I5AO_w#PU-jr z$ZibYNq8i7>Tf++k-&MFAFQWfd0zV?N(Lw;LhffEBhE0XzL1j6ig4FzEl=&EfF;u~ zAkE~w$cv*)81hJ_I_h01QIoQRwg^s2|IBJFP1| zHa^WatL|YDRAI&!<+b)=KXwq>p`j!)SN~%XvEvEhe)`o9HhaEeE0h-FARn9Pjn+_| z{C7RVJbJB;`IaM52lqR*8^Jy}u?y+qcD%LTyg;77o0Etmc5SC_yUiY^dnU}*CF)t2 zePFEa>>hbih&|!EZ?d5+u9Q2C<4*nbivo?6PI0&gwoCbDvJ?$sy|PQgAQ)M;5{1Ai z>ZG7vRWP&ge@fYSlU$7tWUF+!i-dO^!S(BtMs=ED`pY4>uAgbOJF9li+h6t&z3@F9 zbojgBiF~oST3vibjHp;YJ)bi|W}Dz3lDf@Tz8j#!)T|wJH#97dsSdgUSV>?Xs_K~` z-b$I2(YrRC@X0RP)1dP}d!0e0V-k@f!&#LN!D$qVAiNV!xUrN%wc!`9Eda0S&9#q4 z)>RZx$DL$1Ugum@33dQz9P<680N%m)Kf6#;!DFT`Ux1sl4%*!}=Ci@1Pm zG&ps*gYN|mXZ@xEoRO6`IA9`s&4*#1(MWR)rM5g`rU8 zt5LD*UC%j| zm|JbiyAnZgWm}D|OYPO6{0HM(th1%)dFi*vH=iO7#?nEZ>)hIDg&R4L$R2t?K3kAWX2 zJ&Wi>7KCec3!QKKz3)#&yDJ+1@Z2ey8p?QVMJ zZTz|~9EY?tk|bH10$V3UideF+351~p;4Hn&v4$$C>Kl`L1}`0)m}^isNke*&H(wY& zTEUQJmFqjL=*Xs6NHYvr_^**tyK-=iW~zDvE;P0G($6!=+)+6~lQqFY1d&&H0e)px z`Ylj2qoE&1bQe27JxA&{|QrX+45vmuDjsMI0Z`6Ak&IVFjF*!?zFpIx{uJjtDG`feON>V^S z)n8^MV*Rn*zLsX-IY=9C#mR~Z4*3-3YU#h=zfc#@tqG zNAqH~gU0qxAc>WbHM?+_1L*3fplicwaWlzNKO=OvWWPx&p^6*Z3iVJ7+(ga2-XQhs zRYI)9jX%3*a+%Qagyv%?^m2LV{p^B@h!BZo3EE#@qxnqSB~%e9U%fe|*wUFX84T;q zpQ5e3xH@u05%UM+b~p>NHnU=T>vX)&s5=BaCp+uQMwom#KB=3WQ57QOYM|vRr;+b~ z#Zu57MU0&{Ah|bIUWIYS794g%|MW$O{SH7#%s^v6K?`T^6o6d2u$Wwa%r;}&UXUHh zTAfUD_MJ7h38+H#5;^c=APx(@jja<aziH=t0ST@l5u{IG^JV91rjA+n)8>?As=#0`+3E%OAWZ1Bv_=c2hn{@v5 zU$6RM(*r-OK5~!D90-;wCTAIUr&7)EuW<2TAdVz93Sb$hnJVKskhPYz!8*l0ao}9= zeyJS*_Vvvty&(Z~{P-U|(!bgrKGDRTi_LA%93=SDvVt1ub(de(u;Y85;C%X1}oix<~CIQNLPk5L*;$gm4W$sEJ7#QM4_~=>L4Jva}?@GxPBL zNEDIkF1-Qt-TJMaIiN(ty}(Ru9Phm(Ersag_x{u!tBloM_74tW8YV^M;Slk>=cgmQ zexE_ZMJCx*yU$ZXp=_c*MM<&#_GZ;qerNRhPSCE)42|`D9A*60C%0LieR&&G=EJ3%Q*zU*h2 zdE32tuRKx+Kjg{wU;Y~7AW3q~v6H<%OMd@M!9s*?AR6ZM{|hZ+;`8SB^MgPbl+|WWQ4#=u2+eGk-k<)!UUIGX=LPx>$|WEZV?X@JM`|7NRevdE#G`x@mpX~+UsXu%}AM(f|HlsZPY z49H9ZPcRXKf(*{pAl`6V4724k3oP|vi;6Y_P^@E);uGZtg&$bOJV6ZV6(+=NHH5cK zm!V{NS^+-pC)GOm#%x0=O6a*kdbQ@JkEP;=DbE$l!pO9oa+`2AxK&A%b^$%{jll!> z#!hC^;<*uSH)DOF(`~^U;L`QtsL(7+ODJBUwWdOg?oQ?ch9s$clMTsCC-#FpDv)Mn zmej zWu9R61h)+F!?XH`-wXN(pP#8fe2r#)w8d7GY4QAVhcdACE%@!8-|yMrKMUz}+a!3)^8m)gW2?YPr9lsrt;{tkdaP_-?WDzthNbt4U6w5FRpI9H!O}}R_;Nl@ z92Vncc3jXUyZ$+X)Qs}a`<)qp=cdI`UQc+jbB{(`B^5&@Vz!JV&KHN-KDg+RBGG`g zQ1NFqVsGYt_QE(>lCS0Ts$xi~dTcHkV_cECq2DT-l@oPCn`S5O{Coj{khx~@$bxMGX+ zTAuALY&9C-oyT(RT4b9fsSS{;Fd%+$)^*N{B3?Z6RWb^a z8$oHI<`c@|t7iXbtIkcc_y4S~NP@6Kj+qkLVpFPV#m(1Zh}RiL{|x^G$VaFZSop~8 zl)P39eEgG?N0FN}iv2?BPf{mcha%vUbF)R#nLznRqMse0MH$KVplHc{A#P(p^$q&9 z1=a?UD^(AD$O6x{j~Xz*EFr43{eZD-p}!V5*x+g39hwEf}o>^Ik8D7!so4O zlx^k>#}C5k8x-N=vQ~q-YJ3#|x;Q^eO2=DapT3)Zp#uG(6PNH@NAGO8zltZ3!D}(qi#p7BU)m>8&f=Ob_t-$$PI3;EA%!C7vG^S}YklFqulb+m{t126NqHY^%^L~oga*EfPZXYD z_TeHVx%f#<{WdN;>tTN|yXlajUa9V7fPpr(<5B^^gkgR@x!DEh2ZI=j&%G&G0qJez zQ3St}MkA_3iQ@&O#Q0e1S1oga#^UzH+|AxbUTS!=jvsIux^MS3J>2qmFC=`loOM%= zyybb=yZPr{RzM8z(1{J&H$A{l^4Sj5*B{YYl7mo_DaUf5zW7QGd_hTuD+EduuU#Wb zh+E?xK=6qABBRPT^EF8$@Hy_3Du?&a&vY!jItoy&r=>HSR;jTPHdEp53D-S(*@Q<8 zn#yVkRY+w2VA{aNj!1C}it7@8av>0DhAZB@h;w+Jx4DeO?sUpQ>P`@05Jc>#W`h@J(jY@~?5q8Xix zldZ#M{R8J9E+Ot-$>^*v&SWv)z$$d#wLgvqWydoD^-Aw^Wh!4@xdGY=iK5OCGn?OmfC&Jm9#Nxf`pkdKFdyw}3)9xcG6hnMdt)2d(*XD*7NjW)!&?5lo_ z2q%oDefihGkeE(586w@gZxPWbnK{S|JQGV4tkOO-W=OC04;2FVJ<{)c2KF3^iIDN_ zSF%kq)?}Gv_+IbR^b}L=B>lpGhskO8_g5@?sl80o*B8?I{Zc29ea zw91jG3{FXH+6r*1gj9t9k7R%O&(D6vsjv=pZF<^gv+E!9Rj1s&t2ievI^yIu85QQ>x ziEr_1D~H;BUM|}8s?@xtnS^s{m!F)V`sfW^nk|35KE_`{+w`i|-Ym<}rI`6s_e|uY zX-p{~rPJggRDy4*uL)X>k8iRefaFpIaeallpZODe)diyW^rifqUKmW_V2u~+bD$<0 zN20=QWSwKllqB_yZmt%RsWoQ~LT$9yJO%<$amsAjU4!SnCDY(fKF4@3Evl>j7hhWc zdf0Co*Libag95Ly(&%}d5c+P5D!E^$2(Uk$UJV$g^!H3&m2QJgQ5^$ty^XRE{q4rW zW`Tb`6jG4i!{b@(!|g3GodkWSipJwoZK|>|H5k3i#>-A5yvI>fz`URJ2CmNohFd*x zI3tRRFeyata4`&;QKc~YZ`o8-vOV~A(Y35)GNx0j&#;R>(uSciHU8^ntW3mVjuL8l z*5genC_SKfB!ttFs#Hk9M&VN6r(W4M)vNH!%Bh;Z8B{bU8^bf2+!-{_O%CKKTJj+u z${GGY`77wX_gsxZpmydA#V@9%K(-iosOV$WFFcdg%xs3WbztSDCX@rpuPvJ(eY|DO z1ww9aYx8h5FH_jFeJCl}B5V_B8b)(7P18rRLKIw-t0)NtdP(@^jm-sZsk)6q)Lb_e zY9=wQZx9(Fe$hP_7hRzd)4)wEBmWV@oe7LB=C0_SQGo2*=I@k z+O<5Y86_QmCGP9pP$T07VP07Y0yMtBMU08LE*DgXcg2mlKK z4*&uH000I6005E!5C8%I000UA005Y6U3+X(WfcFN+jj4{2ZO<$)$vl+aeLdY?GRxd ztEfDNuqX-9lx;v^g9-Q+g7{#H%52mG2noTN7>JJ`8byN!@edHx5EF$Uf)R;=k(lsE zG}hnuwfC|ZZ*%YY^?c{`opXBb{iDg1a=1u^A4nBE8Uwqe+QGZ|-h+$`Er?(1=2C92 zSQ=Ll@0VL0n_q28!kxAA{lGXI=f}uHYkz-l50V|rR;}#u`Ypwp$&=nQ)E{nYZt??` zX$4#SW{VZ@`hzWjXp3nM*Sc}zHak9J`Nka%UOjNr^;iccWbry+5Ku9@O)Fpxy6m`( z#|GUFerYh17s?sC2Fo;G;oXDf4&Iv*sJt;=V}HtU{2olX9R87%+rh_Ex!D+)*;IZO zml78^x+hZ=n$MgWKc${fapq9k_$~Fa_Ukso0i;sb@lMIuNvDCGhMnJ%&vv?OT=>nd z%B(Ne>~+z57nS58BgCVa!+_p=k4^Y z(0%1i&YjQNu-E7P~q^4P)R8rr~3rP*nF>nDjhKM?mmlp zn@>rv<|{kraiiU5o+3188OGzOz&P8crv~F4T^A-e@?$Z{w&Q7p&z31(hb9{{cat5w z0H&im4*{Fc!Ub*242B%+Mzf9O2ZU|RjJFKKQydK3>R>lo9Sq#*U<0$A7#3oVuH&QJ zZvt~Q=0CVRCvo>M`S}i3eZT>;9?xMZ(s)Nw@`!XuD7pR@M3mIVuOFQqJLk z?PUg7E^;*)3OL$*Q-TjowSdNqAiX{iC$WQB~EFk}3Y z5_8Z=-7#DnsjrLsdy{L{n&!7+xZIwc+`P^uy@{o3Iv+~(KG?HxZL+UtO;@6~r?aPj zRoAjo8G)R1?aUiKf1`ZLwj*?uS5{d&!8bWFRrL~ovbv`T)bD-xF)f`=UW4nxQ|a`R zoLkS|oKFAx2{83{3Pm#`32nq1W&}f#KwC883$&R5U$8wI^hKjq+-J7NLlG+!h{esA zHXQ5l;(@4Xu7ueZ4YviXHlOK_H2Z?FNX!=vTYg_W6mF0C&2W3z3Q*72TGm|1*~YmAB_7V?V&bbFcfO{wZ@{YJ}Vw-w#-)3Z-(@ZS?LLKuI}L= z-eV{4xJuqU|2(Tyc6kbpGmH82ttLNDt6};b#j7_^sbTsb7tfG_%Y{W*|B4+}Ox_`i zOUg!!s;+Nn47I3C@NlwOocZotXW5QffDF?SwF_X&ayXAZ`UOhTf03i_4y5{SL|Vkt z^Pi^=@8U$)3UBv=iC*u+$?hI+SE8?Hb;28LvikbGOD6l9nwc)9fKwI59A1b#yt-KQ zzj@Vsrj*0j<`+~DslYP9QNvdc33y4S==Kufz literal 0 HcmV?d00001 diff --git a/poetry.lock b/poetry.lock index fbf0431bc..bb82228de 100644 --- a/poetry.lock +++ b/poetry.lock @@ -1,4 +1,4 @@ -# This file is automatically @generated by Poetry 1.8.4 and should not be changed by hand. +# This file is automatically @generated by Poetry 1.8.2 and should not be changed by hand. [[package]] name = "absl-py" @@ -1292,10 +1292,6 @@ files = [ {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_armv7l.manylinux2014_armv7l.whl", hash = "sha256:78656d3ae1282a142a5fed410ec3a6f725fdf8d9f9192ed673e336ea3b083e12"}, {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_i686.manylinux2014_i686.whl", hash = "sha256:681e22c8ecb3b48d11cb9019f8a32d4ae1e353e20d4ce3a0f0eedd0ccbd95e5f"}, {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:4598572bab6f726ec41fabb43bf0f7e3cf8082ea0f6f8f4e57845a6c919f31b3"}, - {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:157fc1fed50946646f09df75c6d52198735a5973e53d252199bbb1c65e1594d2"}, - {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_armv7l.whl", hash = "sha256:7ae2724c181be10692c24fb8d9ce2a99a9afc57237332c3658e2ea6f4f33c091"}, - {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_i686.whl", hash = "sha256:3d324835f292edd81b962f8c0df44f7f47c0a6f8fe6f7d081951aeb1f5ba57d2"}, - {file = "dora_rs-0.3.6-cp37-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:474c087b5e584293685a7d4837165b2ead96dc74fb435ae50d5fa0ac168a0de0"}, {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:297350f05f5f87a0bf647a1e5b4446728e5f800788c6bb28b462bcd167f1de7f"}, {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_i686.whl", hash = "sha256:b1870a8e30f0ac298d17fd546224348d13a648bcfa0cbc51dba7e5136c1af928"}, {file = "dora_rs-0.3.6-cp37-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:182a189212d41be0c960fd3299bf6731af2e771f8858cfb1be7ebcc17d60a254"}, @@ -1417,6 +1413,19 @@ files = [ [package.extras] devel = ["colorama", "json-spec", "jsonschema", "pylint", "pytest", "pytest-benchmark", "pytest-cache", "validictory"] +[[package]] +name = "feetech-servo-sdk" +version = "1.0.0" +description = "This is source code from official feetech repository" +optional = true +python-versions = "*" +files = [ + {file = "feetech-servo-sdk-1.0.0.tar.gz", hash = "sha256:d4d3832e4b1b22a8222133a414db9f868224c2fb639426a1b11d96ddfe84e69c"}, +] + +[package.dependencies] +pyserial = "*" + [[package]] name = "filelock" version = "3.16.1" @@ -7420,6 +7429,7 @@ aloha = ["gym-aloha"] dev = ["debugpy", "pre-commit"] dora = ["gym-dora"] dynamixel = ["dynamixel-sdk", "pynput"] +feetech = ["feetech-servo-sdk", "pynput"] intelrealsense = ["pyrealsense2"] pusht = ["gym-pusht"] stretch = ["hello-robot-stretch-body", "pynput", "pyrealsense2", "pyrender"] @@ -7431,4 +7441,4 @@ xarm = ["gym-xarm"] [metadata] lock-version = "2.0" python-versions = ">=3.10,<3.13" -content-hash = "cd59da219818a9906018a25462e76e15c5d2c0e6419531e8ddbdc2ae998854c1" +content-hash = "7ff63d36a5524a77cba916d212741082adcb49dfdc0dc49f8bf8ccee53c02254" diff --git a/pyproject.toml b/pyproject.toml index ee898db80..42cdf5813 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -65,6 +65,7 @@ pandas = {version = ">=2.2.2", optional = true} scikit-image = {version = ">=0.23.2", optional = true} dynamixel-sdk = {version = ">=3.7.31", optional = true} pynput = {version = ">=1.7.7", optional = true} +feetech-servo-sdk = {version = ">=1.0.0", optional = true} setuptools = {version = "!=71.0.1", optional = true} # TODO(rcadene, aliberts): 71.0.1 has a bug pyrealsense2 = {version = ">=2.55.1.6486", markers = "sys_platform != 'darwin'", optional = true} # TODO(rcadene, aliberts): Fix on Mac pyrender = {git = "https://github.com/mmatl/pyrender.git", markers = "sys_platform == 'linux'", optional = true} @@ -82,6 +83,7 @@ test = ["pytest", "pytest-cov", "pyserial"] umi = ["imagecodecs"] video_benchmark = ["scikit-image", "pandas"] dynamixel = ["dynamixel-sdk", "pynput"] +feetech = ["feetech-servo-sdk", "pynput"] intelrealsense = ["pyrealsense2"] stretch = ["hello-robot-stretch-body", "pyrender", "pyrealsense2", "pynput"] diff --git a/tests/mock_dynamixel_sdk.py b/tests/mock_dynamixel_sdk.py index 6d0ed20e5..a790dff05 100644 --- a/tests/mock_dynamixel_sdk.py +++ b/tests/mock_dynamixel_sdk.py @@ -18,6 +18,19 @@ def convert_to_bytes(value, bytes): return value +def get_default_motor_values(motor_index): + return { + # Key (int) are from X_SERIES_CONTROL_TABLE + 7: motor_index, # ID + 8: DEFAULT_BAUDRATE, # Baud_rate + 10: 0, # Drive_Mode + 64: 0, # Torque_Enable + # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144 + # For other joints, 2560 will be autocorrected to be in calibration range + 132: 2560, # Present_Position + } + + class PortHandler: def __init__(self, port): self.port = port @@ -52,18 +65,9 @@ def __init__(self, port_handler, packet_handler, address, bytes): self.packet_handler = packet_handler def addParam(self, motor_index): # noqa: N802 + # Initialize motor default values if motor_index not in self.packet_handler.data: - # Initialize motor default values - self.packet_handler.data[motor_index] = { - # Key (int) are from X_SERIES_CONTROL_TABLE - 7: motor_index, # ID - 8: DEFAULT_BAUDRATE, # Baud_rate - 10: 0, # Drive_Mode - 64: 0, # Torque_Enable - # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144 - # For other joints, 2560 will be autocorrected to be in calibration range - 132: 2560, # Present_Position - } + self.packet_handler.data[motor_index] = get_default_motor_values(motor_index) def txRxPacket(self): # noqa: N802 return COMM_SUCCESS @@ -78,6 +82,9 @@ def __init__(self, port_handler, packet_handler, address, bytes): self.address = address def addParam(self, index, data): # noqa: N802 + # Initialize motor default values + if index not in self.packet_handler.data: + self.packet_handler.data[index] = get_default_motor_values(index) self.changeParam(index, data) def txPacket(self): # noqa: N802 diff --git a/tests/mock_scservo_sdk.py b/tests/mock_scservo_sdk.py new file mode 100644 index 000000000..596978c00 --- /dev/null +++ b/tests/mock_scservo_sdk.py @@ -0,0 +1,103 @@ +"""Mocked classes and functions from dynamixel_sdk to allow for continuous integration +and testing code logic that requires hardware and devices (e.g. robot arms, cameras) + +Warning: These mocked versions are minimalist. They do not exactly mock every behaviors +from the original classes and functions (e.g. return types might be None instead of boolean). +""" + +# from dynamixel_sdk import COMM_SUCCESS + +DEFAULT_BAUDRATE = 1_000_000 +COMM_SUCCESS = 0 # tx or rx packet communication success + + +def convert_to_bytes(value, bytes): + # TODO(rcadene): remove need to mock `convert_to_bytes` by implemented the inverse transform + # `convert_bytes_to_value` + del bytes # unused + return value + + +def get_default_motor_values(motor_index): + return { + # Key (int) are from SCS_SERIES_CONTROL_TABLE + 5: motor_index, # ID + 6: DEFAULT_BAUDRATE, # Baud_rate + 10: 0, # Drive_Mode + 21: 32, # P_Coefficient + 22: 32, # D_Coefficient + 23: 0, # I_Coefficient + 40: 0, # Torque_Enable + 41: 254, # Acceleration + 31: -2047, # Offset + 33: 0, # Mode + 55: 1, # Lock + # Set 2560 since calibration values for Aloha gripper is between start_pos=2499 and end_pos=3144 + # For other joints, 2560 will be autocorrected to be in calibration range + 56: 2560, # Present_Position + 58: 0, # Present_Speed + 69: 0, # Present_Current + 85: 150, # Maximum_Acceleration + } + + +class PortHandler: + def __init__(self, port): + self.port = port + # factory default baudrate + self.baudrate = DEFAULT_BAUDRATE + + def openPort(self): # noqa: N802 + return True + + def closePort(self): # noqa: N802 + pass + + def setPacketTimeoutMillis(self, timeout_ms): # noqa: N802 + del timeout_ms # unused + + def getBaudRate(self): # noqa: N802 + return self.baudrate + + def setBaudRate(self, baudrate): # noqa: N802 + self.baudrate = baudrate + + +class PacketHandler: + def __init__(self, protocol_version): + del protocol_version # unused + # Use packet_handler.data to communicate across Read and Write + self.data = {} + + +class GroupSyncRead: + def __init__(self, port_handler, packet_handler, address, bytes): + self.packet_handler = packet_handler + + def addParam(self, motor_index): # noqa: N802 + # Initialize motor default values + if motor_index not in self.packet_handler.data: + self.packet_handler.data[motor_index] = get_default_motor_values(motor_index) + + def txRxPacket(self): # noqa: N802 + return COMM_SUCCESS + + def getData(self, index, address, bytes): # noqa: N802 + return self.packet_handler.data[index][address] + + +class GroupSyncWrite: + def __init__(self, port_handler, packet_handler, address, bytes): + self.packet_handler = packet_handler + self.address = address + + def addParam(self, index, data): # noqa: N802 + if index not in self.packet_handler.data: + self.packet_handler.data[index] = get_default_motor_values(index) + self.changeParam(index, data) + + def txPacket(self): # noqa: N802 + return COMM_SUCCESS + + def changeParam(self, index, data): # noqa: N802 + self.packet_handler.data[index][self.address] = data diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 2c0bca9b6..97ce28a64 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -36,7 +36,7 @@ from lerobot.scripts.control_robot import calibrate, record, replay, teleoperate from lerobot.scripts.train import make_optimizer_and_scheduler from tests.test_robots import make_robot -from tests.utils import DEFAULT_CONFIG_PATH, DEVICE, TEST_ROBOT_TYPES, require_robot +from tests.utils import DEFAULT_CONFIG_PATH, DEVICE, TEST_ROBOT_TYPES, mock_calibration_dir, require_robot @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @@ -49,6 +49,7 @@ def test_teleoperate(tmpdir, request, robot_type, mock): # and avoid writing calibration files in user .cache/calibration folder tmpdir = Path(tmpdir) calibration_dir = tmpdir / robot_type + mock_calibration_dir(calibration_dir) overrides = [f"calibration_dir={calibration_dir}"] else: # Use the default .cache/calibration folder when mock=False @@ -89,6 +90,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 + mock_calibration_dir(calibration_dir) overrides.append(f"calibration_dir={calibration_dir}") root = Path(tmpdir) / "data" @@ -121,6 +123,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 + mock_calibration_dir(calibration_dir) overrides = [f"calibration_dir={calibration_dir}"] else: # Use the default .cache/calibration folder when mock=False or for aloha @@ -162,6 +165,12 @@ def test_record_and_replay_and_policy(tmpdir, request, robot_type, mock): elif robot_type in ["koch", "koch_bimanual"]: env_name = "koch_real" policy_name = "act_koch_real" + elif robot_type == "so100": + env_name = "so100_real" + policy_name = "act_so100_real" + elif robot_type == "moss": + env_name = "moss_real" + policy_name = "act_moss_real" else: raise NotImplementedError(robot_type) @@ -248,6 +257,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 + mock_calibration_dir(calibration_dir) overrides = [f"calibration_dir={calibration_dir}"] else: # Use the default .cache/calibration folder when mock=False or for aloha @@ -311,6 +321,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 + mock_calibration_dir(calibration_dir) overrides = [f"calibration_dir={calibration_dir}"] else: # Use the default .cache/calibration folder when mock=False or for aloha @@ -360,6 +371,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 + mock_calibration_dir(calibration_dir) overrides = [f"calibration_dir={calibration_dir}"] else: # Use the default .cache/calibration folder when mock=False or for aloha @@ -410,6 +422,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 + mock_calibration_dir(calibration_dir) overrides = [f"calibration_dir={calibration_dir}"] else: # Use the default .cache/calibration folder when mock=False or for aloha diff --git a/tests/test_motors.py b/tests/test_motors.py index 672234071..2f668926c 100644 --- a/tests/test_motors.py +++ b/tests/test_motors.py @@ -30,8 +30,8 @@ import numpy as np import pytest -from lerobot.common.robot_devices.motors.dynamixel import find_port from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.scripts.find_motors_bus_port import find_port from tests.utils import TEST_MOTOR_TYPES, make_motors_bus, require_motor @@ -52,12 +52,24 @@ def test_configure_motors_all_ids_1(request, motor_type, mock): if mock: request.getfixturevalue("patch_builtins_input") + if motor_type == "dynamixel": + # see X_SERIES_BAUDRATE_TABLE + smaller_baudrate = 9_600 + smaller_baudrate_value = 0 + elif motor_type == "feetech": + # see SCS_SERIES_BAUDRATE_TABLE + smaller_baudrate = 19_200 + smaller_baudrate_value = 7 + else: + raise ValueError(motor_type) + input("Are you sure you want to re-configure the motors? Press enter to continue...") # This test expect the configuration was already correct. motors_bus = make_motors_bus(motor_type, mock=mock) motors_bus.connect() - motors_bus.write("Baud_Rate", [0] * len(motors_bus.motors)) - motors_bus.set_bus_baudrate(9_600) + motors_bus.write("Baud_Rate", [smaller_baudrate_value] * len(motors_bus.motors)) + + motors_bus.set_bus_baudrate(smaller_baudrate) motors_bus.write("ID", [1] * len(motors_bus.motors)) del motors_bus diff --git a/tests/test_robots.py b/tests/test_robots.py index 13ad8c450..05966ff15 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -30,7 +30,7 @@ from lerobot.common.robot_devices.robots.manipulator import ManipulatorRobot from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError -from tests.utils import TEST_ROBOT_TYPES, make_robot, require_robot +from tests.utils import TEST_ROBOT_TYPES, make_robot, mock_calibration_dir, require_robot @pytest.mark.parametrize("robot_type, mock", TEST_ROBOT_TYPES) @@ -39,7 +39,6 @@ def test_robot(tmpdir, request, robot_type, mock): # TODO(rcadene): measure fps in nightly? # TODO(rcadene): test logs # TODO(rcadene): add compatibility with other robots - robot_kwargs = {"robot_type": robot_type} if robot_type == "aloha" and mock: @@ -54,6 +53,7 @@ def test_robot(tmpdir, request, robot_type, mock): tmpdir = Path(tmpdir) calibration_dir = tmpdir / robot_type overrides_calibration_dir = [f"calibration_dir={calibration_dir}"] + mock_calibration_dir(calibration_dir) robot_kwargs["calibration_dir"] = calibration_dir # Test connecting without devices raises an error diff --git a/tests/utils.py b/tests/utils.py index 0c4b94d89..f24b3551c 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -13,10 +13,12 @@ # 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 json import os import platform from copy import copy from functools import wraps +from pathlib import Path import pytest import torch @@ -52,7 +54,7 @@ OPENCV_CAMERA_INDEX = int(os.environ.get("LEROBOT_TEST_OPENCV_CAMERA_INDEX", 0)) INTELREALSENSE_CAMERA_INDEX = int(os.environ.get("LEROBOT_TEST_INTELREALSENSE_CAMERA_INDEX", 128422271614)) -DYNAMIXEL_PORT = "/dev/tty.usbmodem575E0032081" +DYNAMIXEL_PORT = os.environ.get("LEROBOT_TEST_DYNAMIXEL_PORT", "/dev/tty.usbmodem575E0032081") DYNAMIXEL_MOTORS = { "shoulder_pan": [1, "xl430-w250"], "shoulder_lift": [2, "xl430-w250"], @@ -62,6 +64,16 @@ "gripper": [6, "xl330-m288"], } +FEETECH_PORT = os.environ.get("LEROBOT_TEST_FEETECH_PORT", "/dev/tty.usbmodem585A0080971") +FEETECH_MOTORS = { + "shoulder_pan": [1, "sts3215"], + "shoulder_lift": [2, "sts3215"], + "elbow_flex": [3, "sts3215"], + "wrist_flex": [4, "sts3215"], + "wrist_roll": [5, "sts3215"], + "gripper": [6, "sts3215"], +} + def require_x86_64_kernel(func): """ @@ -271,13 +283,39 @@ def wrapper(*args, **kwargs): return wrapper +def mock_calibration_dir(calibration_dir): + # TODO(rcadene): remove this hack + # calibration file produced with Moss v1, but works with Koch, Koch bimanual and SO-100 + example_calib = { + "homing_offset": [-1416, -845, 2130, 2872, 1950, -2211], + "drive_mode": [0, 0, 1, 1, 1, 0], + "start_pos": [1442, 843, 2166, 2849, 1988, 1835], + "end_pos": [2440, 1869, -1106, -1848, -926, 3235], + "calib_mode": ["DEGREE", "DEGREE", "DEGREE", "DEGREE", "DEGREE", "LINEAR"], + "motor_names": ["shoulder_pan", "shoulder_lift", "elbow_flex", "wrist_flex", "wrist_roll", "gripper"], + } + Path(str(calibration_dir)).mkdir(parents=True, exist_ok=True) + with open(calibration_dir / "main_follower.json", "w") as f: + json.dump(example_calib, f) + with open(calibration_dir / "main_leader.json", "w") as f: + json.dump(example_calib, f) + with open(calibration_dir / "left_follower.json", "w") as f: + json.dump(example_calib, f) + with open(calibration_dir / "left_leader.json", "w") as f: + json.dump(example_calib, f) + with open(calibration_dir / "right_follower.json", "w") as f: + json.dump(example_calib, f) + with open(calibration_dir / "right_leader.json", "w") as f: + json.dump(example_calib, f) + + def make_robot(robot_type: str, overrides: list[str] | None = None, mock=False) -> Robot: if mock: overrides = [] if overrides is None else copy(overrides) # Explicitely add mock argument to the cameras and set it to true # TODO(rcadene, aliberts): redesign when we drop hydra - if robot_type == "koch": + if robot_type in ["koch", "so100", "moss"]: overrides.append("+leader_arms.main.mock=true") overrides.append("+follower_arms.main.mock=true") if "~cameras" not in overrides: @@ -338,5 +376,12 @@ def make_motors_bus(motor_type: str, **kwargs) -> MotorsBus: motors = kwargs.pop("motors", DYNAMIXEL_MOTORS) return DynamixelMotorsBus(port, motors, **kwargs) + elif motor_type == "feetech": + from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus + + port = kwargs.pop("port", FEETECH_PORT) + motors = kwargs.pop("motors", FEETECH_MOTORS) + return FeetechMotorsBus(port, motors, **kwargs) + else: raise ValueError(f"The motor type '{motor_type}' is not valid.") From 55e4ff67423e10c50c51b8424503ce976e241572 Mon Sep 17 00:00:00 2001 From: Remi Date: Sat, 26 Oct 2024 12:15:17 +0200 Subject: [PATCH 12/29] Fix autocalib moss (#486) --- .../robot_devices/robots/feetech_calibration.py | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/lerobot/common/robot_devices/robots/feetech_calibration.py b/lerobot/common/robot_devices/robots/feetech_calibration.py index 1fca07f43..b015951a0 100644 --- a/lerobot/common/robot_devices/robots/feetech_calibration.py +++ b/lerobot/common/robot_devices/robots/feetech_calibration.py @@ -64,7 +64,7 @@ def move_until_block(arm, motor_name, positive_direction=True, while_move_hook=N # print(f"{present_voltage=}") # print(f"{present_temperature=}") - if present_speed == 0 and present_current > 50: + if present_speed == 0 and present_current > 40: count += 1 if count > 100 or present_current > 300: return present_pos @@ -306,16 +306,16 @@ def run_arm_auto_calibration_moss(arm: MotorsBus, robot_type: str, arm_name: str calib = {} print("Calibrate shoulder_pan") - calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan", load_threshold=350, count_threshold=200) + calib["shoulder_pan"] = move_to_calibrate(arm, "shoulder_pan") arm.write("Goal_Position", calib["shoulder_pan"]["zero_pos"], "shoulder_pan") time.sleep(1) print("Calibrate gripper") - calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True, count_threshold=200) + calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True) time.sleep(1) print("Calibrate wrist_flex") - calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex", invert_drive_mode=True, count_threshold=200) + calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex", invert_drive_mode=True) calib["wrist_flex"] = apply_offset(calib["wrist_flex"], offset=-210 + 1024) wr_pos = arm.read("Present_Position", "wrist_roll") @@ -329,7 +329,7 @@ def run_arm_auto_calibration_moss(arm: MotorsBus, robot_type: str, arm_name: str time.sleep(1) print("Calibrate wrist_roll") - calib["wrist_roll"] = move_to_calibrate(arm, "wrist_roll", invert_drive_mode=True, count_threshold=200) + calib["wrist_roll"] = move_to_calibrate(arm, "wrist_roll", invert_drive_mode=True) calib["wrist_roll"] = apply_offset(calib["wrist_roll"], offset=790) arm.write("Goal_Position", calib["wrist_roll"]["zero_pos"] - 1024, "wrist_roll") @@ -348,7 +348,6 @@ def in_between_move_elbow_flex_hook(): arm, "elbow_flex", invert_drive_mode=True, - count_threshold=200, in_between_move_hook=in_between_move_elbow_flex_hook, ) arm.write("Goal_Position", calib["wrist_flex"]["zero_pos"] - 1024, "wrist_flex") From 172809a5022d8d59019680942aa3fef77248aa75 Mon Sep 17 00:00:00 2001 From: Remi Date: Sat, 26 Oct 2024 15:27:21 +0200 Subject: [PATCH 13/29] [Fix] Move back to manual calibration (#488) --- examples/10_use_so100.md | 18 +++++++++--------- examples/11_use_moss.md | 16 ++++++++-------- .../robot_devices/robots/manipulator.py | 9 +-------- media/moss/follower_rest.webp | Bin 0 -> 156426 bytes media/moss/follower_rotated.webp | Bin 0 -> 213252 bytes media/moss/follower_zero.webp | Bin 0 -> 303388 bytes media/so100/follower_rest.webp | Bin 0 -> 148184 bytes media/so100/follower_rotated.webp | Bin 0 -> 97420 bytes media/so100/follower_zero.webp | Bin 0 -> 137504 bytes 9 files changed, 18 insertions(+), 25 deletions(-) create mode 100644 media/moss/follower_rest.webp create mode 100644 media/moss/follower_rotated.webp create mode 100644 media/moss/follower_zero.webp create mode 100644 media/so100/follower_rest.webp create mode 100644 media/so100/follower_rotated.webp create mode 100644 media/so100/follower_zero.webp diff --git a/examples/10_use_so100.md b/examples/10_use_so100.md index ffadb1f3e..405e80ec0 100644 --- a/examples/10_use_so100.md +++ b/examples/10_use_so100.md @@ -123,22 +123,22 @@ Follow step 4 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5 Next, you'll need to calibrate your SO-100 robot to ensure that the leader and follower arms have the same position values when they are in the same physical position. This calibration is essential because it allows a neural network trained on one SO-100 robot to work on another. -**Auto-calibration of follower arm** -Follow step 5 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the auto-calibration of the follower arm. You first need to manually move your follower arm to this initial position: +**Manual calibration of follower arm** +/!\ Contrarily to step 6 of the [assembly video](https://www.youtube.com/watch?v=FioA2oeFZ5I) which illustrates the auto calibration, we will actually do manual calibration of follower for now. -