From 21cd2940a91ca19aeab9dac4883d20b6608dd5e7 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Wed, 26 Feb 2025 16:22:07 +0100 Subject: [PATCH 001/190] Reorganize files --- .../{robot_devices => }/cameras/configs.py | 0 .../cameras/intelrealsense.py | 4 ++-- .../{robot_devices => }/cameras/opencv.py | 4 ++-- .../{robot_devices => }/cameras/utils.py | 10 ++++---- lerobot/common/datasets/lerobot_dataset.py | 2 +- lerobot/common/datasets/utils.py | 2 +- .../v2/batch_convert_dataset_v1_to_v2.py | 2 +- .../datasets/v2/convert_dataset_v1_to_v2.py | 4 ++-- .../{robot_devices => }/motors/configs.py | 0 .../{robot_devices => }/motors/dynamixel.py | 4 ++-- .../dynamixel_calibration.py | 4 ++-- .../{robot_devices => }/motors/feetech.py | 4 ++-- .../robots => motors}/feetech_calibration.py | 4 ++-- .../{robot_devices => }/motors/utils.py | 10 ++++---- .../{robot_devices => }/robots/configs.py | 4 ++-- .../robots => robots/lekiwi}/lekiwi_remote.py | 8 +++---- .../{robot_devices => }/robots/manipulator.py | 20 ++++++++-------- .../robots/mobile_manipulator.py | 14 +++++------ lerobot/common/robots/robot_abstraction.py | 0 .../stretch3/stretch3_robot.py} | 2 +- .../{robot_devices => }/robots/utils.py | 8 +++---- .../{robot_devices => utils}/control_utils.py | 4 ++-- .../utils.py => utils/robot_utils.py} | 0 .../control_configs.py => configs/control.py} | 2 +- lerobot/scripts/configure_motor.py | 8 +++---- lerobot/scripts/control_robot.py | 24 +++++++++---------- lerobot/scripts/control_sim_robot.py | 6 ++--- tests/conftest.py | 2 +- tests/test_cameras.py | 6 ++--- tests/test_control_robot.py | 2 +- tests/test_datasets.py | 2 +- tests/test_motors.py | 2 +- tests/test_robots.py | 4 ++-- tests/utils.py | 8 +++---- 34 files changed, 90 insertions(+), 90 deletions(-) rename lerobot/common/{robot_devices => }/cameras/configs.py (100%) rename lerobot/common/{robot_devices => }/cameras/intelrealsense.py (99%) rename lerobot/common/{robot_devices => }/cameras/opencv.py (99%) rename lerobot/common/{robot_devices => }/cameras/utils.py (74%) rename lerobot/common/{robot_devices => }/motors/configs.py (100%) rename lerobot/common/{robot_devices => }/motors/dynamixel.py (99%) rename lerobot/common/{robot_devices/robots => motors}/dynamixel_calibration.py (98%) rename lerobot/common/{robot_devices => }/motors/feetech.py (99%) rename lerobot/common/{robot_devices/robots => motors}/feetech_calibration.py (99%) rename lerobot/common/{robot_devices => }/motors/utils.py (75%) rename lerobot/common/{robot_devices => }/robots/configs.py (99%) rename lerobot/common/{robot_devices/robots => robots/lekiwi}/lekiwi_remote.py (95%) rename lerobot/common/{robot_devices => }/robots/manipulator.py (96%) rename lerobot/common/{robot_devices => }/robots/mobile_manipulator.py (97%) create mode 100644 lerobot/common/robots/robot_abstraction.py rename lerobot/common/{robot_devices/robots/stretch.py => robots/stretch3/stretch3_robot.py} (99%) rename lerobot/common/{robot_devices => }/robots/utils.py (86%) rename lerobot/common/{robot_devices => utils}/control_utils.py (98%) rename lerobot/common/{robot_devices/utils.py => utils/robot_utils.py} (100%) rename lerobot/{common/robot_devices/control_configs.py => configs/control.py} (98%) diff --git a/lerobot/common/robot_devices/cameras/configs.py b/lerobot/common/cameras/configs.py similarity index 100% rename from lerobot/common/robot_devices/cameras/configs.py rename to lerobot/common/cameras/configs.py diff --git a/lerobot/common/robot_devices/cameras/intelrealsense.py b/lerobot/common/cameras/intelrealsense.py similarity index 99% rename from lerobot/common/robot_devices/cameras/intelrealsense.py rename to lerobot/common/cameras/intelrealsense.py index 7e65dba9..c3372fc5 100644 --- a/lerobot/common/robot_devices/cameras/intelrealsense.py +++ b/lerobot/common/cameras/intelrealsense.py @@ -17,8 +17,8 @@ from threading import Thread import numpy as np from PIL import Image -from lerobot.common.robot_devices.cameras.configs import IntelRealSenseCameraConfig -from lerobot.common.robot_devices.utils import ( +from lerobot.common.cameras.configs import IntelRealSenseCameraConfig +from lerobot.common.utils.robot_utils import ( RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError, busy_wait, diff --git a/lerobot/common/robot_devices/cameras/opencv.py b/lerobot/common/cameras/opencv.py similarity index 99% rename from lerobot/common/robot_devices/cameras/opencv.py rename to lerobot/common/cameras/opencv.py index 93c791fa..60aae5e5 100644 --- a/lerobot/common/robot_devices/cameras/opencv.py +++ b/lerobot/common/cameras/opencv.py @@ -15,8 +15,8 @@ from threading import Thread import numpy as np from PIL import Image -from lerobot.common.robot_devices.cameras.configs import OpenCVCameraConfig -from lerobot.common.robot_devices.utils import ( +from lerobot.common.cameras.configs import OpenCVCameraConfig +from lerobot.common.utils.robot_utils import ( RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError, busy_wait, diff --git a/lerobot/common/robot_devices/cameras/utils.py b/lerobot/common/cameras/utils.py similarity index 74% rename from lerobot/common/robot_devices/cameras/utils.py rename to lerobot/common/cameras/utils.py index 88288ea3..7394acce 100644 --- a/lerobot/common/robot_devices/cameras/utils.py +++ b/lerobot/common/cameras/utils.py @@ -2,7 +2,7 @@ from typing import Protocol import numpy as np -from lerobot.common.robot_devices.cameras.configs import ( +from lerobot.common.cameras.configs import ( CameraConfig, IntelRealSenseCameraConfig, OpenCVCameraConfig, @@ -22,12 +22,12 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> list[C for key, cfg in camera_configs.items(): if cfg.type == "opencv": - from lerobot.common.robot_devices.cameras.opencv import OpenCVCamera + from lerobot.common.cameras.opencv import OpenCVCamera cameras[key] = OpenCVCamera(cfg) elif cfg.type == "intelrealsense": - from lerobot.common.robot_devices.cameras.intelrealsense import IntelRealSenseCamera + from lerobot.common.cameras.intelrealsense import IntelRealSenseCamera cameras[key] = IntelRealSenseCamera(cfg) else: @@ -38,13 +38,13 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> list[C def make_camera(camera_type, **kwargs) -> Camera: if camera_type == "opencv": - from lerobot.common.robot_devices.cameras.opencv import OpenCVCamera + from lerobot.common.cameras.opencv import OpenCVCamera config = OpenCVCameraConfig(**kwargs) return OpenCVCamera(config) elif camera_type == "intelrealsense": - from lerobot.common.robot_devices.cameras.intelrealsense import IntelRealSenseCamera + from lerobot.common.cameras.intelrealsense import IntelRealSenseCamera config = IntelRealSenseCameraConfig(**kwargs) return IntelRealSenseCamera(config) diff --git a/lerobot/common/datasets/lerobot_dataset.py b/lerobot/common/datasets/lerobot_dataset.py index f1eb11a0..e643fb3c 100644 --- a/lerobot/common/datasets/lerobot_dataset.py +++ b/lerobot/common/datasets/lerobot_dataset.py @@ -69,7 +69,7 @@ from lerobot.common.datasets.video_utils import ( encode_video_frames, get_video_info, ) -from lerobot.common.robot_devices.robots.utils import Robot +from lerobot.common.robots.utils import Robot CODEBASE_VERSION = "v2.1" diff --git a/lerobot/common/datasets/utils.py b/lerobot/common/datasets/utils.py index 2d90798f..07a3c188 100644 --- a/lerobot/common/datasets/utils.py +++ b/lerobot/common/datasets/utils.py @@ -39,7 +39,7 @@ from lerobot.common.datasets.backward_compatibility import ( BackwardCompatibilityError, ForwardCompatibilityError, ) -from lerobot.common.robot_devices.robots.utils import Robot +from lerobot.common.robots.utils import Robot from lerobot.common.utils.utils import is_valid_numpy_dtype_string from lerobot.configs.types import DictLike, FeatureType, PolicyFeature diff --git a/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py index 4cd93a2d..d12c9186 100644 --- a/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py @@ -27,7 +27,7 @@ from textwrap import dedent from lerobot import available_datasets from lerobot.common.datasets.v2.convert_dataset_v1_to_v2 import convert_dataset -from lerobot.common.robot_devices.robots.configs import AlohaRobotConfig +from lerobot.common.robots.configs import AlohaRobotConfig LOCAL_DIR = Path("data/") diff --git a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py index 99864e3b..d0fcee2e 100644 --- a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py @@ -141,8 +141,8 @@ from lerobot.common.datasets.video_utils import ( get_image_pixel_channels, get_video_info, ) -from lerobot.common.robot_devices.robots.configs import RobotConfig -from lerobot.common.robot_devices.robots.utils import make_robot_config +from lerobot.common.robots.configs import RobotConfig +from lerobot.common.robots.utils import make_robot_config V16 = "v1.6" V20 = "v2.0" diff --git a/lerobot/common/robot_devices/motors/configs.py b/lerobot/common/motors/configs.py similarity index 100% rename from lerobot/common/robot_devices/motors/configs.py rename to lerobot/common/motors/configs.py diff --git a/lerobot/common/robot_devices/motors/dynamixel.py b/lerobot/common/motors/dynamixel.py similarity index 99% rename from lerobot/common/robot_devices/motors/dynamixel.py rename to lerobot/common/motors/dynamixel.py index 54836d8e..f5a3710d 100644 --- a/lerobot/common/robot_devices/motors/dynamixel.py +++ b/lerobot/common/motors/dynamixel.py @@ -8,8 +8,8 @@ from copy import deepcopy import numpy as np import tqdm -from lerobot.common.robot_devices.motors.configs import DynamixelMotorsBusConfig -from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.motors.configs import DynamixelMotorsBusConfig +from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from lerobot.common.utils.utils import capture_timestamp_utc PROTOCOL_VERSION = 2.0 diff --git a/lerobot/common/robot_devices/robots/dynamixel_calibration.py b/lerobot/common/motors/dynamixel_calibration.py similarity index 98% rename from lerobot/common/robot_devices/robots/dynamixel_calibration.py rename to lerobot/common/motors/dynamixel_calibration.py index 5c4932d2..e7c08bd0 100644 --- a/lerobot/common/robot_devices/robots/dynamixel_calibration.py +++ b/lerobot/common/motors/dynamixel_calibration.py @@ -3,12 +3,12 @@ import numpy as np -from lerobot.common.robot_devices.motors.dynamixel import ( +from lerobot.common.motors.dynamixel import ( CalibrationMode, TorqueMode, convert_degrees_to_steps, ) -from lerobot.common.robot_devices.motors.utils import MotorsBus +from lerobot.common.motors.utils import MotorsBus URL_TEMPLATE = ( "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp" diff --git a/lerobot/common/robot_devices/motors/feetech.py b/lerobot/common/motors/feetech.py similarity index 99% rename from lerobot/common/robot_devices/motors/feetech.py rename to lerobot/common/motors/feetech.py index a59db7df..e532bf71 100644 --- a/lerobot/common/robot_devices/motors/feetech.py +++ b/lerobot/common/motors/feetech.py @@ -8,8 +8,8 @@ from copy import deepcopy import numpy as np import tqdm -from lerobot.common.robot_devices.motors.configs import FeetechMotorsBusConfig -from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.motors.configs import FeetechMotorsBusConfig +from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from lerobot.common.utils.utils import capture_timestamp_utc PROTOCOL_VERSION = 0 diff --git a/lerobot/common/robot_devices/robots/feetech_calibration.py b/lerobot/common/motors/feetech_calibration.py similarity index 99% rename from lerobot/common/robot_devices/robots/feetech_calibration.py rename to lerobot/common/motors/feetech_calibration.py index b015951a..5d046281 100644 --- a/lerobot/common/robot_devices/robots/feetech_calibration.py +++ b/lerobot/common/motors/feetech_calibration.py @@ -5,12 +5,12 @@ import time import numpy as np -from lerobot.common.robot_devices.motors.feetech import ( +from lerobot.common.motors.feetech import ( CalibrationMode, TorqueMode, convert_degrees_to_steps, ) -from lerobot.common.robot_devices.motors.utils import MotorsBus +from lerobot.common.motors.utils import MotorsBus URL_TEMPLATE = ( "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp" diff --git a/lerobot/common/robot_devices/motors/utils.py b/lerobot/common/motors/utils.py similarity index 75% rename from lerobot/common/robot_devices/motors/utils.py rename to lerobot/common/motors/utils.py index fc64f050..8d146034 100644 --- a/lerobot/common/robot_devices/motors/utils.py +++ b/lerobot/common/motors/utils.py @@ -1,6 +1,6 @@ from typing import Protocol -from lerobot.common.robot_devices.motors.configs import ( +from lerobot.common.motors.configs import ( DynamixelMotorsBusConfig, FeetechMotorsBusConfig, MotorsBusConfig, @@ -21,12 +21,12 @@ def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig for key, cfg in motors_bus_configs.items(): if cfg.type == "dynamixel": - from lerobot.common.robot_devices.motors.dynamixel import DynamixelMotorsBus + from lerobot.common.motors.dynamixel import DynamixelMotorsBus motors_buses[key] = DynamixelMotorsBus(cfg) elif cfg.type == "feetech": - from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus + from lerobot.common.motors.feetech import FeetechMotorsBus motors_buses[key] = FeetechMotorsBus(cfg) @@ -38,13 +38,13 @@ def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig def make_motors_bus(motor_type: str, **kwargs) -> MotorsBus: if motor_type == "dynamixel": - from lerobot.common.robot_devices.motors.dynamixel import DynamixelMotorsBus + from lerobot.common.motors.dynamixel import DynamixelMotorsBus config = DynamixelMotorsBusConfig(**kwargs) return DynamixelMotorsBus(config) elif motor_type == "feetech": - from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus + from lerobot.common.motors.feetech import FeetechMotorsBus config = FeetechMotorsBusConfig(**kwargs) return FeetechMotorsBus(config) diff --git a/lerobot/common/robot_devices/robots/configs.py b/lerobot/common/robots/configs.py similarity index 99% rename from lerobot/common/robot_devices/robots/configs.py rename to lerobot/common/robots/configs.py index 88cb4e6f..7c02e5b3 100644 --- a/lerobot/common/robot_devices/robots/configs.py +++ b/lerobot/common/robots/configs.py @@ -4,12 +4,12 @@ from typing import Sequence import draccus -from lerobot.common.robot_devices.cameras.configs import ( +from lerobot.common.cameras.configs import ( CameraConfig, IntelRealSenseCameraConfig, OpenCVCameraConfig, ) -from lerobot.common.robot_devices.motors.configs import ( +from lerobot.common.motors.configs import ( DynamixelMotorsBusConfig, FeetechMotorsBusConfig, MotorsBusConfig, diff --git a/lerobot/common/robot_devices/robots/lekiwi_remote.py b/lerobot/common/robots/lekiwi/lekiwi_remote.py similarity index 95% rename from lerobot/common/robot_devices/robots/lekiwi_remote.py rename to lerobot/common/robots/lekiwi/lekiwi_remote.py index fd9491fa..ad720725 100644 --- a/lerobot/common/robot_devices/robots/lekiwi_remote.py +++ b/lerobot/common/robots/lekiwi/lekiwi_remote.py @@ -7,7 +7,7 @@ from pathlib import Path import cv2 import zmq -from lerobot.common.robot_devices.robots.mobile_manipulator import LeKiwi +from lerobot.common.robots.mobile_manipulator import LeKiwi def setup_zmq_sockets(config): @@ -47,7 +47,7 @@ def calibrate_follower_arm(motors_bus, calib_dir_str): calib_dir.mkdir(parents=True, exist_ok=True) calib_file = calib_dir / "main_follower.json" try: - from lerobot.common.robot_devices.robots.feetech_calibration import run_arm_manual_calibration + from lerobot.common.motors.feetech_calibration import run_arm_manual_calibration except ImportError: print("[WARNING] Calibration function not available. Skipping calibration.") return @@ -79,8 +79,8 @@ def run_lekiwi(robot_config): - Processes incoming commands (arm and wheel commands) and sends back sensor and camera data. """ # Import helper functions and classes - from lerobot.common.robot_devices.cameras.utils import make_cameras_from_configs - from lerobot.common.robot_devices.motors.feetech import FeetechMotorsBus, TorqueMode + from lerobot.common.cameras.utils import make_cameras_from_configs + from lerobot.common.motors.feetech import FeetechMotorsBus, TorqueMode # Initialize cameras from the robot configuration. cameras = make_cameras_from_configs(robot_config.cameras) diff --git a/lerobot/common/robot_devices/robots/manipulator.py b/lerobot/common/robots/manipulator.py similarity index 96% rename from lerobot/common/robot_devices/robots/manipulator.py rename to lerobot/common/robots/manipulator.py index 9c82d069..d55c49c7 100644 --- a/lerobot/common/robot_devices/robots/manipulator.py +++ b/lerobot/common/robots/manipulator.py @@ -13,11 +13,11 @@ from pathlib import Path import numpy as np import torch -from lerobot.common.robot_devices.cameras.utils import make_cameras_from_configs -from lerobot.common.robot_devices.motors.utils import MotorsBus, make_motors_buses_from_configs -from lerobot.common.robot_devices.robots.configs import ManipulatorRobotConfig -from lerobot.common.robot_devices.robots.utils import get_arm_id -from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.motors.utils import MotorsBus, make_motors_buses_from_configs +from lerobot.common.robots.configs import ManipulatorRobotConfig +from lerobot.common.robots.utils import get_arm_id +from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError def ensure_safe_goal_position( @@ -228,9 +228,9 @@ class ManipulatorRobot: self.leader_arms[name].connect() if self.robot_type in ["koch", "koch_bimanual", "aloha"]: - from lerobot.common.robot_devices.motors.dynamixel import TorqueMode + from lerobot.common.motors.dynamixel import TorqueMode elif self.robot_type in ["so100", "moss", "lekiwi"]: - from lerobot.common.robot_devices.motors.feetech import TorqueMode + from lerobot.common.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. @@ -295,12 +295,12 @@ class ManipulatorRobot: print(f"Missing calibration file '{arm_calib_path}'") if self.robot_type in ["koch", "koch_bimanual", "aloha"]: - from lerobot.common.robot_devices.robots.dynamixel_calibration import run_arm_calibration + from lerobot.common.motors.dynamixel_calibration import run_arm_calibration calibration = run_arm_calibration(arm, self.robot_type, name, arm_type) elif self.robot_type in ["so100", "moss", "lekiwi"]: - from lerobot.common.robot_devices.robots.feetech_calibration import ( + from lerobot.common.motors.feetech_calibration import ( run_arm_manual_calibration, ) @@ -322,7 +322,7 @@ class ManipulatorRobot: def set_koch_robot_preset(self): def set_operating_mode_(arm): - from lerobot.common.robot_devices.motors.dynamixel import TorqueMode + from lerobot.common.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.") diff --git a/lerobot/common/robot_devices/robots/mobile_manipulator.py b/lerobot/common/robots/mobile_manipulator.py similarity index 97% rename from lerobot/common/robot_devices/robots/mobile_manipulator.py rename to lerobot/common/robots/mobile_manipulator.py index b20c61f7..3450b97d 100644 --- a/lerobot/common/robot_devices/robots/mobile_manipulator.py +++ b/lerobot/common/robots/mobile_manipulator.py @@ -9,13 +9,13 @@ import numpy as np import torch import zmq -from lerobot.common.robot_devices.cameras.utils import make_cameras_from_configs -from lerobot.common.robot_devices.motors.feetech import TorqueMode -from lerobot.common.robot_devices.motors.utils import MotorsBus, make_motors_buses_from_configs -from lerobot.common.robot_devices.robots.configs import LeKiwiRobotConfig -from lerobot.common.robot_devices.robots.feetech_calibration import run_arm_manual_calibration -from lerobot.common.robot_devices.robots.utils import get_arm_id -from lerobot.common.robot_devices.utils import RobotDeviceNotConnectedError +from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.motors.feetech import TorqueMode +from lerobot.common.motors.feetech_calibration import run_arm_manual_calibration +from lerobot.common.motors.utils import MotorsBus, make_motors_buses_from_configs +from lerobot.common.robots.configs import LeKiwiRobotConfig +from lerobot.common.robots.utils import get_arm_id +from lerobot.common.utils.robot_utils import RobotDeviceNotConnectedError PYNPUT_AVAILABLE = True try: diff --git a/lerobot/common/robots/robot_abstraction.py b/lerobot/common/robots/robot_abstraction.py new file mode 100644 index 00000000..e69de29b diff --git a/lerobot/common/robot_devices/robots/stretch.py b/lerobot/common/robots/stretch3/stretch3_robot.py similarity index 99% rename from lerobot/common/robot_devices/robots/stretch.py rename to lerobot/common/robots/stretch3/stretch3_robot.py index b63bf941..12a18035 100644 --- a/lerobot/common/robot_devices/robots/stretch.py +++ b/lerobot/common/robots/stretch3/stretch3_robot.py @@ -22,7 +22,7 @@ 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.robots.configs import StretchRobotConfig +from lerobot.common.robots.configs import StretchRobotConfig class StretchRobot(StretchAPI): diff --git a/lerobot/common/robot_devices/robots/utils.py b/lerobot/common/robots/utils.py similarity index 86% rename from lerobot/common/robot_devices/robots/utils.py rename to lerobot/common/robots/utils.py index 47e2519b..8a30c496 100644 --- a/lerobot/common/robot_devices/robots/utils.py +++ b/lerobot/common/robots/utils.py @@ -1,6 +1,6 @@ from typing import Protocol -from lerobot.common.robot_devices.robots.configs import ( +from lerobot.common.robots.configs import ( AlohaRobotConfig, KochBimanualRobotConfig, KochRobotConfig, @@ -54,15 +54,15 @@ def make_robot_config(robot_type: str, **kwargs) -> RobotConfig: def make_robot_from_config(config: RobotConfig): if isinstance(config, ManipulatorRobotConfig): - from lerobot.common.robot_devices.robots.manipulator import ManipulatorRobot + from lerobot.common.robots.manipulator import ManipulatorRobot return ManipulatorRobot(config) elif isinstance(config, LeKiwiRobotConfig): - from lerobot.common.robot_devices.robots.mobile_manipulator import MobileManipulator + from lerobot.common.robots.mobile_manipulator import MobileManipulator return MobileManipulator(config) else: - from lerobot.common.robot_devices.robots.stretch import StretchRobot + from lerobot.common.robots.stretch3.stretch3_robot import StretchRobot return StretchRobot(config) diff --git a/lerobot/common/robot_devices/control_utils.py b/lerobot/common/utils/control_utils.py similarity index 98% rename from lerobot/common/robot_devices/control_utils.py rename to lerobot/common/utils/control_utils.py index 6c97d0cb..8ff47b47 100644 --- a/lerobot/common/robot_devices/control_utils.py +++ b/lerobot/common/utils/control_utils.py @@ -19,8 +19,8 @@ from termcolor import colored from lerobot.common.datasets.image_writer import safe_stop_image_writer from lerobot.common.datasets.lerobot_dataset import LeRobotDataset from lerobot.common.datasets.utils import get_features_from_robot -from lerobot.common.robot_devices.robots.utils import Robot -from lerobot.common.robot_devices.utils import busy_wait +from lerobot.common.robots.utils import Robot +from lerobot.common.utils.robot_utils import busy_wait from lerobot.common.utils.utils import get_safe_torch_device, has_method diff --git a/lerobot/common/robot_devices/utils.py b/lerobot/common/utils/robot_utils.py similarity index 100% rename from lerobot/common/robot_devices/utils.py rename to lerobot/common/utils/robot_utils.py diff --git a/lerobot/common/robot_devices/control_configs.py b/lerobot/configs/control.py similarity index 98% rename from lerobot/common/robot_devices/control_configs.py rename to lerobot/configs/control.py index c3e920b1..2c6620be 100644 --- a/lerobot/common/robot_devices/control_configs.py +++ b/lerobot/configs/control.py @@ -4,7 +4,7 @@ from pathlib import Path import draccus -from lerobot.common.robot_devices.robots.configs import RobotConfig +from lerobot.common.robots.configs import RobotConfig from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs import parser from lerobot.configs.policies import PreTrainedConfig diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py index f7e07070..b6f58410 100644 --- a/lerobot/scripts/configure_motor.py +++ b/lerobot/scripts/configure_motor.py @@ -18,8 +18,8 @@ import time def get_motor_bus_cls(brand: str) -> tuple: if brand == "feetech": - from lerobot.common.robot_devices.motors.configs import FeetechMotorsBusConfig - from lerobot.common.robot_devices.motors.feetech import ( + from lerobot.common.motors.configs import FeetechMotorsBusConfig + from lerobot.common.motors.feetech import ( MODEL_BAUDRATE_TABLE, SCS_SERIES_BAUDRATE_TABLE, FeetechMotorsBus, @@ -28,8 +28,8 @@ def get_motor_bus_cls(brand: str) -> tuple: return FeetechMotorsBusConfig, FeetechMotorsBus, MODEL_BAUDRATE_TABLE, SCS_SERIES_BAUDRATE_TABLE elif brand == "dynamixel": - from lerobot.common.robot_devices.motors.configs import DynamixelMotorsBusConfig - from lerobot.common.robot_devices.motors.dynamixel import ( + from lerobot.common.motors.configs import DynamixelMotorsBusConfig + from lerobot.common.motors.dynamixel import ( MODEL_BAUDRATE_TABLE, X_SERIES_BAUDRATE_TABLE, DynamixelMotorsBus, diff --git a/lerobot/scripts/control_robot.py b/lerobot/scripts/control_robot.py index 32f3b181..d4284e19 100644 --- a/lerobot/scripts/control_robot.py +++ b/lerobot/scripts/control_robot.py @@ -129,15 +129,8 @@ from pprint import pformat # from safetensors.torch import load_file, save_file from lerobot.common.datasets.lerobot_dataset import LeRobotDataset from lerobot.common.policies.factory import make_policy -from lerobot.common.robot_devices.control_configs import ( - CalibrateControlConfig, - ControlPipelineConfig, - RecordControlConfig, - RemoteRobotConfig, - ReplayControlConfig, - TeleoperateControlConfig, -) -from lerobot.common.robot_devices.control_utils import ( +from lerobot.common.robots.utils import Robot, make_robot_from_config +from lerobot.common.utils.control_utils import ( control_loop, init_keyboard_listener, log_control_info, @@ -148,10 +141,17 @@ from lerobot.common.robot_devices.control_utils import ( stop_recording, warmup_record, ) -from lerobot.common.robot_devices.robots.utils import Robot, make_robot_from_config -from lerobot.common.robot_devices.utils import busy_wait, safe_disconnect +from lerobot.common.utils.robot_utils import busy_wait, safe_disconnect from lerobot.common.utils.utils import has_method, init_logging, log_say from lerobot.configs import parser +from lerobot.configs.control import ( + CalibrateControlConfig, + ControlPipelineConfig, + RecordControlConfig, + RemoteRobotConfig, + ReplayControlConfig, + TeleoperateControlConfig, +) ######################################################################################## # Control modes @@ -368,7 +368,7 @@ def control_robot(cfg: ControlPipelineConfig): elif isinstance(cfg.control, ReplayControlConfig): replay(robot, cfg.control) elif isinstance(cfg.control, RemoteRobotConfig): - from lerobot.common.robot_devices.robots.lekiwi_remote import run_lekiwi + from lerobot.common.robots.lekiwi.lekiwi_remote import run_lekiwi run_lekiwi(cfg.robot) diff --git a/lerobot/scripts/control_sim_robot.py b/lerobot/scripts/control_sim_robot.py index 8d69bf31..7441d91e 100644 --- a/lerobot/scripts/control_sim_robot.py +++ b/lerobot/scripts/control_sim_robot.py @@ -80,7 +80,8 @@ import numpy as np import torch from lerobot.common.datasets.lerobot_dataset import LeRobotDataset -from lerobot.common.robot_devices.control_utils import ( +from lerobot.common.robots.utils import Robot, make_robot +from lerobot.common.utils.control_utils import ( init_keyboard_listener, init_policy, is_headless, @@ -90,8 +91,7 @@ from lerobot.common.robot_devices.control_utils import ( sanity_check_dataset_robot_compatibility, stop_recording, ) -from lerobot.common.robot_devices.robots.utils import Robot, make_robot -from lerobot.common.robot_devices.utils import busy_wait +from lerobot.common.utils.robot_utils import busy_wait from lerobot.common.utils.utils import init_hydra_config, init_logging, log_say raise NotImplementedError("This script is currently deactivated") diff --git a/tests/conftest.py b/tests/conftest.py index dc746142..d8d5a17c 100644 --- a/tests/conftest.py +++ b/tests/conftest.py @@ -20,7 +20,7 @@ import pytest from serial import SerialException from lerobot import available_cameras, available_motors, available_robots -from lerobot.common.robot_devices.robots.utils import make_robot +from lerobot.common.robots.utils import make_robot from tests.utils import DEVICE, make_camera, make_motors_bus # Import fixture modules as plugins diff --git a/tests/test_cameras.py b/tests/test_cameras.py index 7c043c25..68f47b59 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -24,7 +24,7 @@ pytest -sx 'tests/test_cameras.py::test_camera[intelrealsense-True]' import numpy as np import pytest -from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from tests.utils import TEST_CAMERA_TYPES, make_camera, require_camera # Maximum absolute difference between two consecutive images recored by a camera. @@ -185,9 +185,9 @@ def test_camera(request, camera_type, mock): def test_save_images_from_cameras(tmp_path, request, camera_type, mock): # TODO(rcadene): refactor if camera_type == "opencv": - from lerobot.common.robot_devices.cameras.opencv import save_images_from_cameras + from lerobot.common.cameras.opencv import save_images_from_cameras elif camera_type == "intelrealsense": - from lerobot.common.robot_devices.cameras.intelrealsense import save_images_from_cameras + from lerobot.common.cameras.intelrealsense import save_images_from_cameras # Small `record_time_s` to speedup unit tests save_images_from_cameras(tmp_path, record_time_s=0.02, mock=mock) diff --git a/tests/test_control_robot.py b/tests/test_control_robot.py index 12b68641..94dcc686 100644 --- a/tests/test_control_robot.py +++ b/tests/test_control_robot.py @@ -30,7 +30,7 @@ import pytest from lerobot.common.policies.act.configuration_act import ACTConfig from lerobot.common.policies.factory import make_policy -from lerobot.common.robot_devices.control_configs import ( +from lerobot.configs.control import ( CalibrateControlConfig, RecordControlConfig, ReplayControlConfig, diff --git a/tests/test_datasets.py b/tests/test_datasets.py index 61b68aa8..bd8444ba 100644 --- a/tests/test_datasets.py +++ b/tests/test_datasets.py @@ -41,7 +41,7 @@ from lerobot.common.datasets.utils import ( ) from lerobot.common.envs.factory import make_env_config from lerobot.common.policies.factory import make_policy_config -from lerobot.common.robot_devices.robots.utils import make_robot +from lerobot.common.robots.utils import make_robot from lerobot.configs.default import DatasetConfig from lerobot.configs.train import TrainPipelineConfig from tests.fixtures.constants import DUMMY_CHW, DUMMY_HWC, DUMMY_REPO_ID diff --git a/tests/test_motors.py b/tests/test_motors.py index 2f668926..1342d985 100644 --- a/tests/test_motors.py +++ b/tests/test_motors.py @@ -30,7 +30,7 @@ import time import numpy as np import pytest -from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.utils.robot_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 diff --git a/tests/test_robots.py b/tests/test_robots.py index 6c300b71..4e60cff1 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -26,8 +26,8 @@ pytest -sx 'tests/test_robots.py::test_robot[aloha-True]' import pytest import torch -from lerobot.common.robot_devices.robots.utils import make_robot -from lerobot.common.robot_devices.utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.robots.utils import make_robot +from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from tests.utils import TEST_ROBOT_TYPES, mock_calibration_dir, require_robot diff --git a/tests/utils.py b/tests/utils.py index c49b5b9f..9ffa9ad2 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -23,10 +23,10 @@ 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.cameras.utils import make_camera as make_camera_device -from lerobot.common.robot_devices.motors.utils import MotorsBus -from lerobot.common.robot_devices.motors.utils import make_motors_bus as make_motors_bus_device +from lerobot.common.cameras.utils import Camera +from lerobot.common.cameras.utils import make_camera as make_camera_device +from lerobot.common.motors.utils import MotorsBus +from lerobot.common.motors.utils import make_motors_bus as make_motors_bus_device from lerobot.common.utils.import_utils import is_package_available DEVICE = os.environ.get("LEROBOT_TEST_DEVICE", "cuda") if torch.cuda.is_available() else "cpu" From 59bdd29106bf55744d3a84087da32eaee44655f3 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Wed, 26 Feb 2025 18:48:58 +0100 Subject: [PATCH 002/190] Move more files & objects around --- .../v2/batch_convert_dataset_v1_to_v2.py | 2 +- .../datasets/v2/convert_dataset_v1_to_v2.py | 2 +- .../common/robots/aloha/README.md | 0 .../robots/aloha/configuration_aloha.py | 132 ++++ lerobot/common/robots/config_abc.py | 59 ++ lerobot/common/robots/configs.py | 599 ------------------ .../common/robots/koch/configuration_koch.py | 165 +++++ .../common/robots/lekiwi/README.md | 0 .../robots/lekiwi/configuration_lekiwi.py | 88 +++ .../robot_lekiwi.py} | 0 lerobot/common/robots/manipulator.py | 2 +- lerobot/common/robots/mobile_manipulator.py | 2 +- .../common/robots/moss/README.md | 0 .../common/robots/moss/configuration_moss.py | 68 ++ lerobot/common/robots/robot_abc.py | 24 + .../common/robots/so_100/README.md | 0 .../robots/so_100/configuration_so_100.py | 68 ++ lerobot/common/robots/so_100/robot_so_100.py | 0 .../common/robots/stretch3/README.md | 0 .../robots/stretch3/configuration_stretch3.py | 40 ++ .../{stretch3_robot.py => robot_stretch3.py} | 2 +- lerobot/common/robots/utils.py | 17 +- lerobot/configs/control.py | 2 +- 23 files changed, 658 insertions(+), 614 deletions(-) rename examples/9_use_aloha.md => lerobot/common/robots/aloha/README.md (100%) create mode 100644 lerobot/common/robots/aloha/configuration_aloha.py create mode 100644 lerobot/common/robots/config_abc.py delete mode 100644 lerobot/common/robots/configs.py create mode 100644 lerobot/common/robots/koch/configuration_koch.py rename examples/11_use_lekiwi.md => lerobot/common/robots/lekiwi/README.md (100%) create mode 100644 lerobot/common/robots/lekiwi/configuration_lekiwi.py rename lerobot/common/robots/{robot_abstraction.py => lekiwi/robot_lekiwi.py} (100%) rename examples/11_use_moss.md => lerobot/common/robots/moss/README.md (100%) create mode 100644 lerobot/common/robots/moss/configuration_moss.py create mode 100644 lerobot/common/robots/robot_abc.py rename examples/10_use_so100.md => lerobot/common/robots/so_100/README.md (100%) create mode 100644 lerobot/common/robots/so_100/configuration_so_100.py create mode 100644 lerobot/common/robots/so_100/robot_so_100.py rename examples/8_use_stretch.md => lerobot/common/robots/stretch3/README.md (100%) create mode 100644 lerobot/common/robots/stretch3/configuration_stretch3.py rename lerobot/common/robots/stretch3/{stretch3_robot.py => robot_stretch3.py} (99%) diff --git a/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py index 475096ff..41dd33b6 100644 --- a/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/batch_convert_dataset_v1_to_v2.py @@ -27,7 +27,7 @@ from textwrap import dedent from lerobot import available_datasets from lerobot.common.datasets.v2.convert_dataset_v1_to_v2 import convert_dataset -from lerobot.common.robots.configs import AlohaRobotConfig +from lerobot.common.robots.aloha.configuration_aloha import AlohaRobotConfig LOCAL_DIR = Path("data/") diff --git a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py index 8f8a7898..5e0533af 100644 --- a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py @@ -141,7 +141,7 @@ from lerobot.common.datasets.video_utils import ( get_image_pixel_channels, get_video_info, ) -from lerobot.common.robots.configs import RobotConfig +from lerobot.common.robots.config_abc import RobotConfig from lerobot.common.robots.utils import make_robot_config V16 = "v1.6" diff --git a/examples/9_use_aloha.md b/lerobot/common/robots/aloha/README.md similarity index 100% rename from examples/9_use_aloha.md rename to lerobot/common/robots/aloha/README.md diff --git a/lerobot/common/robots/aloha/configuration_aloha.py b/lerobot/common/robots/aloha/configuration_aloha.py new file mode 100644 index 00000000..8efdbcc4 --- /dev/null +++ b/lerobot/common/robots/aloha/configuration_aloha.py @@ -0,0 +1,132 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras.configs import CameraConfig, IntelRealSenseCameraConfig +from lerobot.common.motors.configs import DynamixelMotorsBusConfig, MotorsBusConfig +from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig + + +@RobotConfig.register_subclass("aloha") +@dataclass +class AlohaRobotConfig(ManipulatorRobotConfig): + # Specific to Aloha, LeRobot comes with default calibration files. Assuming the motors have been + # properly assembled, no manual calibration step is expected. If you need to run manual calibration, + # simply update this path to ".cache/calibration/aloha" + calibration_dir: str = ".cache/calibration/aloha_default" + + # /!\ FOR SAFETY, READ THIS /!\ + # `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. + # For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default. + # When you feel more confident with teleoperation or running the policy, you can extend + # this safety limit and even removing it by setting it to `null`. + # Also, everything is expected to work safely out-of-the-box, but we highly advise to + # first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml), + # then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully + max_relative_target: int | None = 5 + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "left": DynamixelMotorsBusConfig( + # window_x + port="/dev/ttyDXL_leader_left", + motors={ + # name: (index, model) + "waist": [1, "xm430-w350"], + "shoulder": [2, "xm430-w350"], + "shoulder_shadow": [3, "xm430-w350"], + "elbow": [4, "xm430-w350"], + "elbow_shadow": [5, "xm430-w350"], + "forearm_roll": [6, "xm430-w350"], + "wrist_angle": [7, "xm430-w350"], + "wrist_rotate": [8, "xl430-w250"], + "gripper": [9, "xc430-w150"], + }, + ), + "right": DynamixelMotorsBusConfig( + # window_x + port="/dev/ttyDXL_leader_right", + motors={ + # name: (index, model) + "waist": [1, "xm430-w350"], + "shoulder": [2, "xm430-w350"], + "shoulder_shadow": [3, "xm430-w350"], + "elbow": [4, "xm430-w350"], + "elbow_shadow": [5, "xm430-w350"], + "forearm_roll": [6, "xm430-w350"], + "wrist_angle": [7, "xm430-w350"], + "wrist_rotate": [8, "xl430-w250"], + "gripper": [9, "xc430-w150"], + }, + ), + } + ) + + follower_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "left": DynamixelMotorsBusConfig( + port="/dev/ttyDXL_follower_left", + motors={ + # name: (index, model) + "waist": [1, "xm540-w270"], + "shoulder": [2, "xm540-w270"], + "shoulder_shadow": [3, "xm540-w270"], + "elbow": [4, "xm540-w270"], + "elbow_shadow": [5, "xm540-w270"], + "forearm_roll": [6, "xm540-w270"], + "wrist_angle": [7, "xm540-w270"], + "wrist_rotate": [8, "xm430-w350"], + "gripper": [9, "xm430-w350"], + }, + ), + "right": DynamixelMotorsBusConfig( + port="/dev/ttyDXL_follower_right", + motors={ + # name: (index, model) + "waist": [1, "xm540-w270"], + "shoulder": [2, "xm540-w270"], + "shoulder_shadow": [3, "xm540-w270"], + "elbow": [4, "xm540-w270"], + "elbow_shadow": [5, "xm540-w270"], + "forearm_roll": [6, "xm540-w270"], + "wrist_angle": [7, "xm540-w270"], + "wrist_rotate": [8, "xm430-w350"], + "gripper": [9, "xm430-w350"], + }, + ), + } + ) + + # Troubleshooting: If one of your IntelRealSense cameras freeze during + # data recording due to bandwidth limit, you might need to plug the camera + # on another USB hub or PCIe card. + cameras: dict[str, CameraConfig] = field( + default_factory=lambda: { + "cam_high": IntelRealSenseCameraConfig( + serial_number=128422271347, + fps=30, + width=640, + height=480, + ), + "cam_low": IntelRealSenseCameraConfig( + serial_number=130322270656, + fps=30, + width=640, + height=480, + ), + "cam_left_wrist": IntelRealSenseCameraConfig( + serial_number=218622272670, + fps=30, + width=640, + height=480, + ), + "cam_right_wrist": IntelRealSenseCameraConfig( + serial_number=130322272300, + fps=30, + width=640, + height=480, + ), + } + ) + + mock: bool = False diff --git a/lerobot/common/robots/config_abc.py b/lerobot/common/robots/config_abc.py new file mode 100644 index 00000000..83216c49 --- /dev/null +++ b/lerobot/common/robots/config_abc.py @@ -0,0 +1,59 @@ +import abc +from dataclasses import dataclass +from typing import Sequence + +import draccus + +from lerobot.common.cameras.configs import CameraConfig +from lerobot.common.motors.configs import MotorsBusConfig, field + + +@dataclass +class RobotConfig(draccus.ChoiceRegistry, abc.ABC): + @property + def type(self) -> str: + return self.get_choice_name(self.__class__) + + +# TODO(rcadene, aliberts): remove ManipulatorRobotConfig abstraction +@dataclass +class ManipulatorRobotConfig(RobotConfig): + leader_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) + follower_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) + cameras: dict[str, CameraConfig] = field(default_factory=lambda: {}) + + # Optionally limit 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 (assumes all follower arms have the same number of + # motors). + max_relative_target: list[float] | float | None = None + + # Optionally set the leader arm in torque mode with the gripper motor set to this angle. This makes it + # possible to squeeze the gripper and have it spring back to an open position on its own. If None, the + # gripper is not put in torque mode. + gripper_open_degree: float | None = None + + mock: bool = False + + def __post_init__(self): + if self.mock: + for arm in self.leader_arms.values(): + if not arm.mock: + arm.mock = True + for arm in self.follower_arms.values(): + if not arm.mock: + arm.mock = True + for cam in self.cameras.values(): + if not cam.mock: + cam.mock = True + + if self.max_relative_target is not None and isinstance(self.max_relative_target, Sequence): + for name in self.follower_arms: + if len(self.follower_arms[name].motors) != len(self.max_relative_target): + raise ValueError( + f"len(max_relative_target)={len(self.max_relative_target)} but the follower arm with name {name} has " + f"{len(self.follower_arms[name].motors)} motors. Please make sure that the " + f"`max_relative_target` list has as many parameters as there are motors per arm. " + "Note: This feature does not yet work with robots where different follower arms have " + "different numbers of motors." + ) diff --git a/lerobot/common/robots/configs.py b/lerobot/common/robots/configs.py deleted file mode 100644 index 7c02e5b3..00000000 --- a/lerobot/common/robots/configs.py +++ /dev/null @@ -1,599 +0,0 @@ -import abc -from dataclasses import dataclass, field -from typing import Sequence - -import draccus - -from lerobot.common.cameras.configs import ( - CameraConfig, - IntelRealSenseCameraConfig, - OpenCVCameraConfig, -) -from lerobot.common.motors.configs import ( - DynamixelMotorsBusConfig, - FeetechMotorsBusConfig, - MotorsBusConfig, -) - - -@dataclass -class RobotConfig(draccus.ChoiceRegistry, abc.ABC): - @property - def type(self) -> str: - return self.get_choice_name(self.__class__) - - -# TODO(rcadene, aliberts): remove ManipulatorRobotConfig abstraction -@dataclass -class ManipulatorRobotConfig(RobotConfig): - leader_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) - follower_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) - cameras: dict[str, CameraConfig] = field(default_factory=lambda: {}) - - # Optionally limit 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 (assumes all follower arms have the same number of - # motors). - max_relative_target: list[float] | float | None = None - - # Optionally set the leader arm in torque mode with the gripper motor set to this angle. This makes it - # possible to squeeze the gripper and have it spring back to an open position on its own. If None, the - # gripper is not put in torque mode. - gripper_open_degree: float | None = None - - mock: bool = False - - def __post_init__(self): - if self.mock: - for arm in self.leader_arms.values(): - if not arm.mock: - arm.mock = True - for arm in self.follower_arms.values(): - if not arm.mock: - arm.mock = True - for cam in self.cameras.values(): - if not cam.mock: - cam.mock = True - - if self.max_relative_target is not None and isinstance(self.max_relative_target, Sequence): - for name in self.follower_arms: - if len(self.follower_arms[name].motors) != len(self.max_relative_target): - raise ValueError( - f"len(max_relative_target)={len(self.max_relative_target)} but the follower arm with name {name} has " - f"{len(self.follower_arms[name].motors)} motors. Please make sure that the " - f"`max_relative_target` list has as many parameters as there are motors per arm. " - "Note: This feature does not yet work with robots where different follower arms have " - "different numbers of motors." - ) - - -@RobotConfig.register_subclass("aloha") -@dataclass -class AlohaRobotConfig(ManipulatorRobotConfig): - # Specific to Aloha, LeRobot comes with default calibration files. Assuming the motors have been - # properly assembled, no manual calibration step is expected. If you need to run manual calibration, - # simply update this path to ".cache/calibration/aloha" - calibration_dir: str = ".cache/calibration/aloha_default" - - # /!\ FOR SAFETY, READ THIS /!\ - # `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. - # For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default. - # When you feel more confident with teleoperation or running the policy, you can extend - # this safety limit and even removing it by setting it to `null`. - # Also, everything is expected to work safely out-of-the-box, but we highly advise to - # first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml), - # then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully - max_relative_target: int | None = 5 - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - # window_x - port="/dev/ttyDXL_leader_left", - motors={ - # name: (index, model) - "waist": [1, "xm430-w350"], - "shoulder": [2, "xm430-w350"], - "shoulder_shadow": [3, "xm430-w350"], - "elbow": [4, "xm430-w350"], - "elbow_shadow": [5, "xm430-w350"], - "forearm_roll": [6, "xm430-w350"], - "wrist_angle": [7, "xm430-w350"], - "wrist_rotate": [8, "xl430-w250"], - "gripper": [9, "xc430-w150"], - }, - ), - "right": DynamixelMotorsBusConfig( - # window_x - port="/dev/ttyDXL_leader_right", - motors={ - # name: (index, model) - "waist": [1, "xm430-w350"], - "shoulder": [2, "xm430-w350"], - "shoulder_shadow": [3, "xm430-w350"], - "elbow": [4, "xm430-w350"], - "elbow_shadow": [5, "xm430-w350"], - "forearm_roll": [6, "xm430-w350"], - "wrist_angle": [7, "xm430-w350"], - "wrist_rotate": [8, "xl430-w250"], - "gripper": [9, "xc430-w150"], - }, - ), - } - ) - - follower_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - port="/dev/ttyDXL_follower_left", - motors={ - # name: (index, model) - "waist": [1, "xm540-w270"], - "shoulder": [2, "xm540-w270"], - "shoulder_shadow": [3, "xm540-w270"], - "elbow": [4, "xm540-w270"], - "elbow_shadow": [5, "xm540-w270"], - "forearm_roll": [6, "xm540-w270"], - "wrist_angle": [7, "xm540-w270"], - "wrist_rotate": [8, "xm430-w350"], - "gripper": [9, "xm430-w350"], - }, - ), - "right": DynamixelMotorsBusConfig( - port="/dev/ttyDXL_follower_right", - motors={ - # name: (index, model) - "waist": [1, "xm540-w270"], - "shoulder": [2, "xm540-w270"], - "shoulder_shadow": [3, "xm540-w270"], - "elbow": [4, "xm540-w270"], - "elbow_shadow": [5, "xm540-w270"], - "forearm_roll": [6, "xm540-w270"], - "wrist_angle": [7, "xm540-w270"], - "wrist_rotate": [8, "xm430-w350"], - "gripper": [9, "xm430-w350"], - }, - ), - } - ) - - # Troubleshooting: If one of your IntelRealSense cameras freeze during - # data recording due to bandwidth limit, you might need to plug the camera - # on another USB hub or PCIe card. - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "cam_high": IntelRealSenseCameraConfig( - serial_number=128422271347, - fps=30, - width=640, - height=480, - ), - "cam_low": IntelRealSenseCameraConfig( - serial_number=130322270656, - fps=30, - width=640, - height=480, - ), - "cam_left_wrist": IntelRealSenseCameraConfig( - serial_number=218622272670, - fps=30, - width=640, - height=480, - ), - "cam_right_wrist": IntelRealSenseCameraConfig( - serial_number=130322272300, - fps=30, - width=640, - height=480, - ), - } - ) - - mock: bool = False - - -@RobotConfig.register_subclass("koch") -@dataclass -class KochRobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".cache/calibration/koch" - # `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: int | None = None - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0085511", - motors={ - # name: (index, model) - "shoulder_pan": [1, "xl330-m077"], - "shoulder_lift": [2, "xl330-m077"], - "elbow_flex": [3, "xl330-m077"], - "wrist_flex": [4, "xl330-m077"], - "wrist_roll": [5, "xl330-m077"], - "gripper": [6, "xl330-m077"], - }, - ), - } - ) - - follower_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - motors={ - # name: (index, model) - "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"], - }, - ), - } - ) - - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - - # ~ Koch specific settings ~ - # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible - # to squeeze the gripper and have it spring back to an open position on its own. - gripper_open_degree: float = 35.156 - - mock: bool = False - - -@RobotConfig.register_subclass("koch_bimanual") -@dataclass -class KochBimanualRobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".cache/calibration/koch_bimanual" - # `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: int | None = None - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0085511", - motors={ - # name: (index, model) - "shoulder_pan": [1, "xl330-m077"], - "shoulder_lift": [2, "xl330-m077"], - "elbow_flex": [3, "xl330-m077"], - "wrist_flex": [4, "xl330-m077"], - "wrist_roll": [5, "xl330-m077"], - "gripper": [6, "xl330-m077"], - }, - ), - "right": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem575E0031751", - motors={ - # name: (index, model) - "shoulder_pan": [1, "xl330-m077"], - "shoulder_lift": [2, "xl330-m077"], - "elbow_flex": [3, "xl330-m077"], - "wrist_flex": [4, "xl330-m077"], - "wrist_roll": [5, "xl330-m077"], - "gripper": [6, "xl330-m077"], - }, - ), - } - ) - - follower_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - motors={ - # name: (index, model) - "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"], - }, - ), - "right": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem575E0032081", - motors={ - # name: (index, model) - "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"], - }, - ), - } - ) - - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - - # ~ Koch specific settings ~ - # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible - # to squeeze the gripper and have it spring back to an open position on its own. - gripper_open_degree: float = 35.156 - - mock: bool = False - - -@RobotConfig.register_subclass("moss") -@dataclass -class MossRobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".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: int | None = None - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - 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: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - 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: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - - mock: bool = False - - -@RobotConfig.register_subclass("so100") -@dataclass -class So100RobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".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: int | None = None - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - 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: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - 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: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - - mock: bool = False - - -@RobotConfig.register_subclass("stretch") -@dataclass -class StretchRobotConfig(RobotConfig): - # `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: int | None = None - - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "navigation": OpenCVCameraConfig( - camera_index="/dev/hello-nav-head-camera", - fps=10, - width=1280, - height=720, - rotation=-90, - ), - "head": IntelRealSenseCameraConfig( - name="Intel RealSense D435I", - fps=30, - width=640, - height=480, - rotation=90, - ), - "wrist": IntelRealSenseCameraConfig( - name="Intel RealSense D405", - fps=30, - width=640, - height=480, - ), - } - ) - - mock: bool = False - - -@RobotConfig.register_subclass("lekiwi") -@dataclass -class LeKiwiRobotConfig(RobotConfig): - # `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: int | None = None - - # Network Configuration - ip: str = "192.168.0.193" - port: int = 5555 - video_port: int = 5556 - - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "front": OpenCVCameraConfig( - camera_index="/dev/video0", fps=30, width=640, height=480, rotation=90 - ), - "wrist": OpenCVCameraConfig( - camera_index="/dev/video2", fps=30, width=640, height=480, rotation=180 - ), - } - ) - - calibration_dir: str = ".cache/calibration/lekiwi" - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - 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: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - port="/dev/ttyACM0", - 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"], - "left_wheel": (7, "sts3215"), - "back_wheel": (8, "sts3215"), - "right_wheel": (9, "sts3215"), - }, - ), - } - ) - - teleop_keys: dict[str, str] = field( - default_factory=lambda: { - # Movement - "forward": "w", - "backward": "s", - "left": "a", - "right": "d", - "rotate_left": "z", - "rotate_right": "x", - # Speed control - "speed_up": "r", - "speed_down": "f", - # quit teleop - "quit": "q", - } - ) - - mock: bool = False diff --git a/lerobot/common/robots/koch/configuration_koch.py b/lerobot/common/robots/koch/configuration_koch.py new file mode 100644 index 00000000..a014d51d --- /dev/null +++ b/lerobot/common/robots/koch/configuration_koch.py @@ -0,0 +1,165 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig +from lerobot.common.motors.configs import DynamixelMotorsBusConfig, MotorsBusConfig +from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig + + +@RobotConfig.register_subclass("koch") +@dataclass +class KochRobotConfig(ManipulatorRobotConfig): + calibration_dir: str = ".cache/calibration/koch" + # `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: int | None = None + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem585A0085511", + motors={ + # name: (index, model) + "shoulder_pan": [1, "xl330-m077"], + "shoulder_lift": [2, "xl330-m077"], + "elbow_flex": [3, "xl330-m077"], + "wrist_flex": [4, "xl330-m077"], + "wrist_roll": [5, "xl330-m077"], + "gripper": [6, "xl330-m077"], + }, + ), + } + ) + + follower_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem585A0076891", + motors={ + # name: (index, model) + "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"], + }, + ), + } + ) + + cameras: dict[str, CameraConfig] = field( + default_factory=lambda: { + "laptop": OpenCVCameraConfig( + camera_index=0, + fps=30, + width=640, + height=480, + ), + "phone": OpenCVCameraConfig( + camera_index=1, + fps=30, + width=640, + height=480, + ), + } + ) + + # ~ Koch specific settings ~ + # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible + # to squeeze the gripper and have it spring back to an open position on its own. + gripper_open_degree: float = 35.156 + + mock: bool = False + + +@RobotConfig.register_subclass("koch_bimanual") +@dataclass +class KochBimanualRobotConfig(ManipulatorRobotConfig): + calibration_dir: str = ".cache/calibration/koch_bimanual" + # `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: int | None = None + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "left": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem585A0085511", + motors={ + # name: (index, model) + "shoulder_pan": [1, "xl330-m077"], + "shoulder_lift": [2, "xl330-m077"], + "elbow_flex": [3, "xl330-m077"], + "wrist_flex": [4, "xl330-m077"], + "wrist_roll": [5, "xl330-m077"], + "gripper": [6, "xl330-m077"], + }, + ), + "right": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem575E0031751", + motors={ + # name: (index, model) + "shoulder_pan": [1, "xl330-m077"], + "shoulder_lift": [2, "xl330-m077"], + "elbow_flex": [3, "xl330-m077"], + "wrist_flex": [4, "xl330-m077"], + "wrist_roll": [5, "xl330-m077"], + "gripper": [6, "xl330-m077"], + }, + ), + } + ) + + follower_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "left": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem585A0076891", + motors={ + # name: (index, model) + "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"], + }, + ), + "right": DynamixelMotorsBusConfig( + port="/dev/tty.usbmodem575E0032081", + motors={ + # name: (index, model) + "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"], + }, + ), + } + ) + + cameras: dict[str, CameraConfig] = field( + default_factory=lambda: { + "laptop": OpenCVCameraConfig( + camera_index=0, + fps=30, + width=640, + height=480, + ), + "phone": OpenCVCameraConfig( + camera_index=1, + fps=30, + width=640, + height=480, + ), + } + ) + + # ~ Koch specific settings ~ + # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible + # to squeeze the gripper and have it spring back to an open position on its own. + gripper_open_degree: float = 35.156 + + mock: bool = False diff --git a/examples/11_use_lekiwi.md b/lerobot/common/robots/lekiwi/README.md similarity index 100% rename from examples/11_use_lekiwi.md rename to lerobot/common/robots/lekiwi/README.md diff --git a/lerobot/common/robots/lekiwi/configuration_lekiwi.py b/lerobot/common/robots/lekiwi/configuration_lekiwi.py new file mode 100644 index 00000000..7878841e --- /dev/null +++ b/lerobot/common/robots/lekiwi/configuration_lekiwi.py @@ -0,0 +1,88 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig +from lerobot.common.motors.configs import FeetechMotorsBusConfig, MotorsBusConfig +from lerobot.common.robots.config_abc import RobotConfig + + +@RobotConfig.register_subclass("lekiwi") +@dataclass +class LeKiwiRobotConfig(RobotConfig): + # `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: int | None = None + + # Network Configuration + ip: str = "192.168.0.193" + port: int = 5555 + video_port: int = 5556 + + cameras: dict[str, CameraConfig] = field( + default_factory=lambda: { + "front": OpenCVCameraConfig( + camera_index="/dev/video0", fps=30, width=640, height=480, rotation=90 + ), + "wrist": OpenCVCameraConfig( + camera_index="/dev/video2", fps=30, width=640, height=480, rotation=180 + ), + } + ) + + calibration_dir: str = ".cache/calibration/lekiwi" + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + 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: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/ttyACM0", + 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"], + "left_wheel": (7, "sts3215"), + "back_wheel": (8, "sts3215"), + "right_wheel": (9, "sts3215"), + }, + ), + } + ) + + teleop_keys: dict[str, str] = field( + default_factory=lambda: { + # Movement + "forward": "w", + "backward": "s", + "left": "a", + "right": "d", + "rotate_left": "z", + "rotate_right": "x", + # Speed control + "speed_up": "r", + "speed_down": "f", + # quit teleop + "quit": "q", + } + ) + + mock: bool = False diff --git a/lerobot/common/robots/robot_abstraction.py b/lerobot/common/robots/lekiwi/robot_lekiwi.py similarity index 100% rename from lerobot/common/robots/robot_abstraction.py rename to lerobot/common/robots/lekiwi/robot_lekiwi.py diff --git a/lerobot/common/robots/manipulator.py b/lerobot/common/robots/manipulator.py index 3099c86c..556dc81d 100644 --- a/lerobot/common/robots/manipulator.py +++ b/lerobot/common/robots/manipulator.py @@ -15,7 +15,7 @@ import torch from lerobot.common.cameras.utils import make_cameras_from_configs from lerobot.common.motors.utils import MotorsBus, make_motors_buses_from_configs -from lerobot.common.robots.configs import ManipulatorRobotConfig +from lerobot.common.robots.config_abc import ManipulatorRobotConfig from lerobot.common.robots.utils import get_arm_id from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError diff --git a/lerobot/common/robots/mobile_manipulator.py b/lerobot/common/robots/mobile_manipulator.py index 3450b97d..50e68838 100644 --- a/lerobot/common/robots/mobile_manipulator.py +++ b/lerobot/common/robots/mobile_manipulator.py @@ -13,7 +13,7 @@ from lerobot.common.cameras.utils import make_cameras_from_configs from lerobot.common.motors.feetech import TorqueMode from lerobot.common.motors.feetech_calibration import run_arm_manual_calibration from lerobot.common.motors.utils import MotorsBus, make_motors_buses_from_configs -from lerobot.common.robots.configs import LeKiwiRobotConfig +from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig from lerobot.common.robots.utils import get_arm_id from lerobot.common.utils.robot_utils import RobotDeviceNotConnectedError diff --git a/examples/11_use_moss.md b/lerobot/common/robots/moss/README.md similarity index 100% rename from examples/11_use_moss.md rename to lerobot/common/robots/moss/README.md diff --git a/lerobot/common/robots/moss/configuration_moss.py b/lerobot/common/robots/moss/configuration_moss.py new file mode 100644 index 00000000..da37f7a2 --- /dev/null +++ b/lerobot/common/robots/moss/configuration_moss.py @@ -0,0 +1,68 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig +from lerobot.common.motors.configs import FeetechMotorsBusConfig, MotorsBusConfig +from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig + + +@RobotConfig.register_subclass("moss") +@dataclass +class MossRobotConfig(ManipulatorRobotConfig): + calibration_dir: str = ".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: int | None = None + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + 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: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem585A0076891", + 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: dict[str, CameraConfig] = field( + default_factory=lambda: { + "laptop": OpenCVCameraConfig( + camera_index=0, + fps=30, + width=640, + height=480, + ), + "phone": OpenCVCameraConfig( + camera_index=1, + fps=30, + width=640, + height=480, + ), + } + ) + + mock: bool = False diff --git a/lerobot/common/robots/robot_abc.py b/lerobot/common/robots/robot_abc.py new file mode 100644 index 00000000..3b592f0a --- /dev/null +++ b/lerobot/common/robots/robot_abc.py @@ -0,0 +1,24 @@ +import abc + + +class Robot(abc.ABC): + robot_type: str + features: dict + + @abc.abstractmethod + def connect(self): ... + + @abc.abstractmethod + def calibrate(self): ... + + @abc.abstractmethod + def teleop_step(self, record_data=False): ... + + @abc.abstractmethod + def capture_observation(self): ... + + @abc.abstractmethod + def send_action(self, action): ... + + @abc.abstractmethod + def disconnect(self): ... diff --git a/examples/10_use_so100.md b/lerobot/common/robots/so_100/README.md similarity index 100% rename from examples/10_use_so100.md rename to lerobot/common/robots/so_100/README.md diff --git a/lerobot/common/robots/so_100/configuration_so_100.py b/lerobot/common/robots/so_100/configuration_so_100.py new file mode 100644 index 00000000..95ba8bd2 --- /dev/null +++ b/lerobot/common/robots/so_100/configuration_so_100.py @@ -0,0 +1,68 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig +from lerobot.common.motors.configs import FeetechMotorsBusConfig, MotorsBusConfig +from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig + + +@RobotConfig.register_subclass("so100") +@dataclass +class So100RobotConfig(ManipulatorRobotConfig): + calibration_dir: str = ".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: int | None = None + + leader_arms: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + 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: dict[str, MotorsBusConfig] = field( + default_factory=lambda: { + "main": FeetechMotorsBusConfig( + port="/dev/tty.usbmodem585A0076891", + 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: dict[str, CameraConfig] = field( + default_factory=lambda: { + "laptop": OpenCVCameraConfig( + camera_index=0, + fps=30, + width=640, + height=480, + ), + "phone": OpenCVCameraConfig( + camera_index=1, + fps=30, + width=640, + height=480, + ), + } + ) + + mock: bool = False diff --git a/lerobot/common/robots/so_100/robot_so_100.py b/lerobot/common/robots/so_100/robot_so_100.py new file mode 100644 index 00000000..e69de29b diff --git a/examples/8_use_stretch.md b/lerobot/common/robots/stretch3/README.md similarity index 100% rename from examples/8_use_stretch.md rename to lerobot/common/robots/stretch3/README.md diff --git a/lerobot/common/robots/stretch3/configuration_stretch3.py b/lerobot/common/robots/stretch3/configuration_stretch3.py new file mode 100644 index 00000000..8520c471 --- /dev/null +++ b/lerobot/common/robots/stretch3/configuration_stretch3.py @@ -0,0 +1,40 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras.configs import CameraConfig, IntelRealSenseCameraConfig, OpenCVCameraConfig +from lerobot.common.robots.config_abc import RobotConfig + + +@RobotConfig.register_subclass("stretch") +@dataclass +class StretchRobotConfig(RobotConfig): + # `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: int | None = None + + cameras: dict[str, CameraConfig] = field( + default_factory=lambda: { + "navigation": OpenCVCameraConfig( + camera_index="/dev/hello-nav-head-camera", + fps=10, + width=1280, + height=720, + rotation=-90, + ), + "head": IntelRealSenseCameraConfig( + name="Intel RealSense D435I", + fps=30, + width=640, + height=480, + rotation=90, + ), + "wrist": IntelRealSenseCameraConfig( + name="Intel RealSense D405", + fps=30, + width=640, + height=480, + ), + } + ) + + mock: bool = False diff --git a/lerobot/common/robots/stretch3/stretch3_robot.py b/lerobot/common/robots/stretch3/robot_stretch3.py similarity index 99% rename from lerobot/common/robots/stretch3/stretch3_robot.py rename to lerobot/common/robots/stretch3/robot_stretch3.py index c00d1a19..c3be2d9c 100644 --- a/lerobot/common/robots/stretch3/stretch3_robot.py +++ b/lerobot/common/robots/stretch3/robot_stretch3.py @@ -22,7 +22,7 @@ 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.robots.configs import StretchRobotConfig +from .configuration_stretch3 import StretchRobotConfig class StretchRobot(StretchAPI): diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py index 8a30c496..cb798632 100644 --- a/lerobot/common/robots/utils.py +++ b/lerobot/common/robots/utils.py @@ -1,16 +1,15 @@ from typing import Protocol -from lerobot.common.robots.configs import ( - AlohaRobotConfig, - KochBimanualRobotConfig, - KochRobotConfig, - LeKiwiRobotConfig, +from lerobot.common.robots.aloha.configuration_aloha import AlohaRobotConfig +from lerobot.common.robots.config_abc import ( ManipulatorRobotConfig, - MossRobotConfig, RobotConfig, - So100RobotConfig, - StretchRobotConfig, ) +from lerobot.common.robots.koch.configuration_koch import KochBimanualRobotConfig, KochRobotConfig +from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig +from lerobot.common.robots.moss.configuration_moss import MossRobotConfig +from lerobot.common.robots.so_100.configuration_so_100 import So100RobotConfig +from lerobot.common.robots.stretch3.configuration_stretch3 import StretchRobotConfig def get_arm_id(name, arm_type): @@ -62,7 +61,7 @@ def make_robot_from_config(config: RobotConfig): return MobileManipulator(config) else: - from lerobot.common.robots.stretch3.stretch3_robot import StretchRobot + from lerobot.common.robots.stretch3.robot_stretch3 import StretchRobot return StretchRobot(config) diff --git a/lerobot/configs/control.py b/lerobot/configs/control.py index 6f49b9a4..94922d1f 100644 --- a/lerobot/configs/control.py +++ b/lerobot/configs/control.py @@ -4,7 +4,7 @@ from pathlib import Path import draccus -from lerobot.common.robots.configs import RobotConfig +from lerobot.common.robots.config_abc import RobotConfig from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs import parser from lerobot.configs.policies import PreTrainedConfig From 731fb6ebaf5cb7cd4bf96c4bb28a3b2ccf5a6ff7 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Wed, 26 Feb 2025 19:02:15 +0100 Subject: [PATCH 003/190] Fix import --- lerobot/common/robots/config_abc.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lerobot/common/robots/config_abc.py b/lerobot/common/robots/config_abc.py index 83216c49..7a390ead 100644 --- a/lerobot/common/robots/config_abc.py +++ b/lerobot/common/robots/config_abc.py @@ -1,11 +1,11 @@ import abc -from dataclasses import dataclass +from dataclasses import dataclass, field from typing import Sequence import draccus from lerobot.common.cameras.configs import CameraConfig -from lerobot.common.motors.configs import MotorsBusConfig, field +from lerobot.common.motors.configs import MotorsBusConfig @dataclass From c7dfd32b43b32621f4fe6c6ae7b270332104dfd6 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Sun, 2 Mar 2025 21:29:35 +0100 Subject: [PATCH 004/190] Update DynamixelMotorsBus signature --- lerobot/common/motors/dynamixel.py | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/lerobot/common/motors/dynamixel.py b/lerobot/common/motors/dynamixel.py index 2d90076d..d2b8bd4d 100644 --- a/lerobot/common/motors/dynamixel.py +++ b/lerobot/common/motors/dynamixel.py @@ -8,7 +8,6 @@ from copy import deepcopy import numpy as np import tqdm -from lerobot.common.motors.configs import DynamixelMotorsBusConfig from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from lerobot.common.utils.utils import capture_timestamp_utc @@ -274,11 +273,10 @@ class DynamixelMotorsBus: motor_index = 6 motor_model = "xl330-m288" - config = DynamixelMotorsBusConfig( + motors_bus = DynamixelMotorsBus( port="/dev/tty.usbmodem575E0031751", motors={motor_name: (motor_index, motor_model)}, ) - motors_bus = DynamixelMotorsBus(config) motors_bus.connect() position = motors_bus.read("Present_Position") @@ -294,11 +292,13 @@ class DynamixelMotorsBus: def __init__( self, - config: DynamixelMotorsBusConfig, + port: str, + motors: dict[str, tuple[int, str]], + mock: bool = False, ): - self.port = config.port - self.motors = config.motors - self.mock = config.mock + self.port = port + self.motors = motors + self.mock = mock self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE) self.model_resolution = deepcopy(MODEL_RESOLUTION) From 48469ec6745e2b71cfeb6b134e60c75fc2ac0a34 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Sun, 2 Mar 2025 21:33:22 +0100 Subject: [PATCH 005/190] Move motor files --- lerobot/common/motors/{ => dynamixel}/dynamixel.py | 0 .../motors/{ => dynamixel}/dynamixel_calibration.py | 2 +- lerobot/common/motors/{ => feetech}/feetech.py | 0 .../common/motors/{ => feetech}/feetech_calibration.py | 2 +- lerobot/common/motors/utils.py | 8 ++++---- 5 files changed, 6 insertions(+), 6 deletions(-) rename lerobot/common/motors/{ => dynamixel}/dynamixel.py (100%) rename lerobot/common/motors/{ => dynamixel}/dynamixel_calibration.py (99%) rename lerobot/common/motors/{ => feetech}/feetech.py (100%) rename lerobot/common/motors/{ => feetech}/feetech_calibration.py (99%) diff --git a/lerobot/common/motors/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py similarity index 100% rename from lerobot/common/motors/dynamixel.py rename to lerobot/common/motors/dynamixel/dynamixel.py diff --git a/lerobot/common/motors/dynamixel_calibration.py b/lerobot/common/motors/dynamixel/dynamixel_calibration.py similarity index 99% rename from lerobot/common/motors/dynamixel_calibration.py rename to lerobot/common/motors/dynamixel/dynamixel_calibration.py index ae4914ce..fc1e2c4a 100644 --- a/lerobot/common/motors/dynamixel_calibration.py +++ b/lerobot/common/motors/dynamixel/dynamixel_calibration.py @@ -3,7 +3,7 @@ import numpy as np -from lerobot.common.motors.dynamixel import ( +from lerobot.common.motors.dynamixel.dynamixel import ( CalibrationMode, TorqueMode, convert_degrees_to_steps, diff --git a/lerobot/common/motors/feetech.py b/lerobot/common/motors/feetech/feetech.py similarity index 100% rename from lerobot/common/motors/feetech.py rename to lerobot/common/motors/feetech/feetech.py diff --git a/lerobot/common/motors/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py similarity index 99% rename from lerobot/common/motors/feetech_calibration.py rename to lerobot/common/motors/feetech/feetech_calibration.py index 651432e0..b3ec125c 100644 --- a/lerobot/common/motors/feetech_calibration.py +++ b/lerobot/common/motors/feetech/feetech_calibration.py @@ -5,7 +5,7 @@ import time import numpy as np -from lerobot.common.motors.feetech import ( +from lerobot.common.motors.feetech.feetech import ( CalibrationMode, TorqueMode, convert_degrees_to_steps, diff --git a/lerobot/common/motors/utils.py b/lerobot/common/motors/utils.py index 8d146034..2060679c 100644 --- a/lerobot/common/motors/utils.py +++ b/lerobot/common/motors/utils.py @@ -21,12 +21,12 @@ def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig for key, cfg in motors_bus_configs.items(): if cfg.type == "dynamixel": - from lerobot.common.motors.dynamixel import DynamixelMotorsBus + from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus motors_buses[key] = DynamixelMotorsBus(cfg) elif cfg.type == "feetech": - from lerobot.common.motors.feetech import FeetechMotorsBus + from lerobot.common.motors.feetech.feetech import FeetechMotorsBus motors_buses[key] = FeetechMotorsBus(cfg) @@ -38,13 +38,13 @@ def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig def make_motors_bus(motor_type: str, **kwargs) -> MotorsBus: if motor_type == "dynamixel": - from lerobot.common.motors.dynamixel import DynamixelMotorsBus + from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus config = DynamixelMotorsBusConfig(**kwargs) return DynamixelMotorsBus(config) elif motor_type == "feetech": - from lerobot.common.motors.feetech import FeetechMotorsBus + from lerobot.common.motors.feetech.feetech import FeetechMotorsBus config = FeetechMotorsBusConfig(**kwargs) return FeetechMotorsBus(config) From 212c6095a21144ff86061b1324c18ec88ff358b1 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:01:48 +0100 Subject: [PATCH 006/190] Move & organize cameras, add base class --- lerobot/common/cameras/__init__.py | 4 + lerobot/common/cameras/camera.py | 25 ++++++ lerobot/common/cameras/configs.py | 89 ------------------- lerobot/common/cameras/intel/__init__.py | 4 + .../camera_realsense.py} | 75 ++++++++-------- .../cameras/intel/configuration_realsense.py | 57 ++++++++++++ lerobot/common/cameras/opencv/__init__.py | 4 + .../{opencv.py => opencv/camera_opencv.py} | 17 ++-- .../cameras/opencv/configuration_opencv.py | 38 ++++++++ lerobot/common/cameras/utils.py | 35 +++----- 10 files changed, 187 insertions(+), 161 deletions(-) create mode 100644 lerobot/common/cameras/__init__.py create mode 100644 lerobot/common/cameras/camera.py create mode 100644 lerobot/common/cameras/intel/__init__.py rename lerobot/common/cameras/{intelrealsense.py => intel/camera_realsense.py} (83%) create mode 100644 lerobot/common/cameras/intel/configuration_realsense.py create mode 100644 lerobot/common/cameras/opencv/__init__.py rename lerobot/common/cameras/{opencv.py => opencv/camera_opencv.py} (97%) create mode 100644 lerobot/common/cameras/opencv/configuration_opencv.py diff --git a/lerobot/common/cameras/__init__.py b/lerobot/common/cameras/__init__.py new file mode 100644 index 00000000..4df6fd88 --- /dev/null +++ b/lerobot/common/cameras/__init__.py @@ -0,0 +1,4 @@ +from .camera import Camera +from .configs import CameraConfig + +__all__ = ["Camera", "CameraConfig"] diff --git a/lerobot/common/cameras/camera.py b/lerobot/common/cameras/camera.py new file mode 100644 index 00000000..5d9ac509 --- /dev/null +++ b/lerobot/common/cameras/camera.py @@ -0,0 +1,25 @@ +import abc + +import numpy as np + + +class Camera(abc.ABC): + @abc.abstractmethod + def connect(self): + pass + + @abc.abstractmethod + def read(self, temporary_color: str | None = None) -> np.ndarray: + pass + + @abc.abstractmethod + def async_read(self) -> np.ndarray: + pass + + @abc.abstractmethod + def disconnect(self): + pass + + def __del__(self): + if getattr(self, "is_connected", False): + self.disconnect() diff --git a/lerobot/common/cameras/configs.py b/lerobot/common/cameras/configs.py index 6acdbd3e..4c796a03 100644 --- a/lerobot/common/cameras/configs.py +++ b/lerobot/common/cameras/configs.py @@ -9,92 +9,3 @@ class CameraConfig(draccus.ChoiceRegistry, abc.ABC): @property def type(self) -> str: return self.get_choice_name(self.__class__) - - -@CameraConfig.register_subclass("opencv") -@dataclass -class OpenCVCameraConfig(CameraConfig): - """ - Example of tested options for Intel Real Sense D405: - - ```python - OpenCVCameraConfig(0, 30, 640, 480) - OpenCVCameraConfig(0, 60, 640, 480) - OpenCVCameraConfig(0, 90, 640, 480) - OpenCVCameraConfig(0, 30, 1280, 720) - ``` - """ - - camera_index: int - fps: int | None = None - width: int | None = None - height: int | None = None - color_mode: str = "rgb" - channels: int | None = None - rotation: int | None = None - mock: bool = False - - def __post_init__(self): - if self.color_mode not in ["rgb", "bgr"]: - raise ValueError( - f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." - ) - - self.channels = 3 - - if self.rotation not in [-90, None, 90, 180]: - raise ValueError(f"`rotation` must be in [-90, None, 90, 180] (got {self.rotation})") - - -@CameraConfig.register_subclass("intelrealsense") -@dataclass -class IntelRealSenseCameraConfig(CameraConfig): - """ - Example of tested options for Intel Real Sense D405: - - ```python - IntelRealSenseCameraConfig(128422271347, 30, 640, 480) - IntelRealSenseCameraConfig(128422271347, 60, 640, 480) - IntelRealSenseCameraConfig(128422271347, 90, 640, 480) - IntelRealSenseCameraConfig(128422271347, 30, 1280, 720) - IntelRealSenseCameraConfig(128422271347, 30, 640, 480, use_depth=True) - IntelRealSenseCameraConfig(128422271347, 30, 640, 480, rotation=90) - ``` - """ - - name: str | None = None - serial_number: int | None = None - fps: int | None = None - width: int | None = None - height: int | None = None - color_mode: str = "rgb" - channels: int | None = None - use_depth: bool = False - force_hardware_reset: bool = True - rotation: int | None = None - mock: bool = False - - def __post_init__(self): - # bool is stronger than is None, since it works with empty strings - if bool(self.name) and bool(self.serial_number): - raise ValueError( - f"One of them must be set: name or serial_number, but {self.name=} and {self.serial_number=} provided." - ) - - if self.color_mode not in ["rgb", "bgr"]: - raise ValueError( - f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." - ) - - self.channels = 3 - - 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." - ) - - if self.rotation not in [-90, None, 90, 180]: - raise ValueError(f"`rotation` must be in [-90, None, 90, 180] (got {self.rotation})") diff --git a/lerobot/common/cameras/intel/__init__.py b/lerobot/common/cameras/intel/__init__.py new file mode 100644 index 00000000..d875ebf4 --- /dev/null +++ b/lerobot/common/cameras/intel/__init__.py @@ -0,0 +1,4 @@ +from .camera_realsense import RealSenseCamera +from .configuration_realsense import RealSenseCameraConfig + +__all__ = ["RealSenseCamera", "RealSenseCameraConfig"] diff --git a/lerobot/common/cameras/intelrealsense.py b/lerobot/common/cameras/intel/camera_realsense.py similarity index 83% rename from lerobot/common/cameras/intelrealsense.py rename to lerobot/common/cameras/intel/camera_realsense.py index c3372fc5..c7017d2b 100644 --- a/lerobot/common/cameras/intelrealsense.py +++ b/lerobot/common/cameras/intel/camera_realsense.py @@ -17,14 +17,15 @@ from threading import Thread import numpy as np from PIL import Image -from lerobot.common.cameras.configs import IntelRealSenseCameraConfig +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from lerobot.common.utils.robot_utils import ( - RobotDeviceAlreadyConnectedError, - RobotDeviceNotConnectedError, busy_wait, ) from lerobot.common.utils.utils import capture_timestamp_utc +from ..camera import Camera +from .configuration_realsense import RealSenseCameraConfig + SERIAL_NUMBER_INDEX = 1 @@ -94,13 +95,11 @@ def save_images_from_cameras( cameras = [] for cam_sn in serial_numbers: print(f"{cam_sn=}") - config = IntelRealSenseCameraConfig( - serial_number=cam_sn, fps=fps, width=width, height=height, mock=mock - ) - camera = IntelRealSenseCamera(config) + config = RealSenseCameraConfig(serial_number=cam_sn, fps=fps, width=width, height=height, mock=mock) + camera = RealSenseCamera(config) camera.connect() print( - f"IntelRealSenseCamera({camera.serial_number}, fps={camera.fps}, width={camera.width}, height={camera.height}, color_mode={camera.color_mode})" + f"RealSenseCamera({camera.serial_number}, fps={camera.fps}, width={camera.width}, height={camera.height}, color_mode={camera.color_mode})" ) cameras.append(camera) @@ -152,11 +151,11 @@ def save_images_from_cameras( camera.disconnect() -class IntelRealSenseCamera: +class RealSenseCamera(Camera): """ - The IntelRealSenseCamera class is similar to OpenCVCamera class but adds additional features for Intel Real Sense cameras: + The RealSenseCamera class is similar to OpenCVCamera class but adds additional features for Intel Real Sense cameras: - 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(), + - can also be instantiated with the camera's name — if it's unique — using RealSenseCamera.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: @@ -164,15 +163,15 @@ class IntelRealSenseCamera: python lerobot/common/robot_devices/cameras/intelrealsense.py --images-dir outputs/images_from_intelrealsense_cameras ``` - When an IntelRealSenseCamera is instantiated, if no specific config is provided, the default fps, width, height and color_mode + When an RealSenseCamera is instantiated, if no specific config is provided, the default fps, width, height and color_mode of the given camera will be used. Example of instantiating with a serial number: ```python - from lerobot.common.robot_devices.cameras.configs import IntelRealSenseCameraConfig + from lerobot.common.robot_devices.cameras.configs import RealSenseCameraConfig - config = IntelRealSenseCameraConfig(serial_number=128422271347) - camera = IntelRealSenseCamera(config) + config = RealSenseCameraConfig(serial_number=128422271347) + camera = RealSenseCamera(config) camera.connect() color_image = camera.read() # when done using the camera, consider disconnecting @@ -181,21 +180,21 @@ class IntelRealSenseCamera: Example of instantiating with a name if it's unique: ``` - config = IntelRealSenseCameraConfig(name="Intel RealSense D405") + config = RealSenseCameraConfig(name="Intel RealSense D405") ``` Example of changing default fps, width, height and color_mode: ```python - config = IntelRealSenseCameraConfig(serial_number=128422271347, fps=30, width=1280, height=720) - config = IntelRealSenseCameraConfig(serial_number=128422271347, fps=90, width=640, height=480) - config = IntelRealSenseCameraConfig(serial_number=128422271347, fps=90, width=640, height=480, color_mode="bgr") + config = RealSenseCameraConfig(serial_number=128422271347, fps=30, width=1280, height=720) + config = RealSenseCameraConfig(serial_number=128422271347, fps=90, width=640, height=480) + config = RealSenseCameraConfig(serial_number=128422271347, fps=90, width=640, height=480, color_mode="bgr") # Note: might error out upon `camera.connect()` if these settings are not compatible with the camera ``` Example of returning depth: ```python - config = IntelRealSenseCameraConfig(serial_number=128422271347, use_depth=True) - camera = IntelRealSenseCamera(config) + config = RealSenseCameraConfig(serial_number=128422271347, use_depth=True) + camera = RealSenseCamera(config) camera.connect() color_image, depth_map = camera.read() ``` @@ -203,7 +202,7 @@ class IntelRealSenseCamera: def __init__( self, - config: IntelRealSenseCameraConfig, + config: RealSenseCameraConfig, ): self.config = config if config.name is not None: @@ -258,9 +257,7 @@ class IntelRealSenseCamera: def connect(self): if self.is_connected: - raise RobotDeviceAlreadyConnectedError( - f"IntelRealSenseCamera({self.serial_number}) is already connected." - ) + raise DeviceAlreadyConnectedError(f"RealSenseCamera({self.serial_number}) is already connected.") if self.mock: import tests.mock_pyrealsense2 as rs @@ -302,7 +299,7 @@ class IntelRealSenseCamera: "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.serial_number}).") + raise OSError(f"Can't access RealSenseCamera({self.serial_number}).") color_stream = profile.get_stream(rs.stream.color) color_profile = color_stream.as_video_stream_profile() @@ -314,15 +311,15 @@ class IntelRealSenseCamera: 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.serial_number}). Actual value is {actual_fps}." + f"Can't set {self.fps=} for RealSenseCamera({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.serial_number}). Actual value is {actual_width}." + f"Can't set {self.width=} for RealSenseCamera({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.serial_number}). Actual value is {actual_height}." + f"Can't set {self.height=} for RealSenseCamera({self.serial_number}). Actual value is {actual_height}." ) self.fps = round(actual_fps) @@ -342,8 +339,8 @@ class IntelRealSenseCamera: If you are reading data from other sensors, we advise to use `camera.async_read()` which is non blocking version of `camera.read()`. """ if not self.is_connected: - raise RobotDeviceNotConnectedError( - f"IntelRealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." + raise DeviceNotConnectedError( + f"RealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." ) if self.mock: @@ -358,7 +355,7 @@ class IntelRealSenseCamera: color_frame = frame.get_color_frame() if not color_frame: - raise OSError(f"Can't capture color image from IntelRealSenseCamera({self.serial_number}).") + raise OSError(f"Can't capture color image from RealSenseCamera({self.serial_number}).") color_image = np.asanyarray(color_frame.get_data()) @@ -390,7 +387,7 @@ class IntelRealSenseCamera: 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.serial_number}).") + raise OSError(f"Can't capture depth image from RealSenseCamera({self.serial_number}).") depth_map = np.asanyarray(depth_frame.get_data()) @@ -417,8 +414,8 @@ class IntelRealSenseCamera: def async_read(self): """Access the latest color image""" if not self.is_connected: - raise RobotDeviceNotConnectedError( - f"IntelRealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." + raise DeviceNotConnectedError( + f"RealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." ) if self.thread is None: @@ -444,8 +441,8 @@ class IntelRealSenseCamera: def disconnect(self): if not self.is_connected: - raise RobotDeviceNotConnectedError( - f"IntelRealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." + raise DeviceNotConnectedError( + f"RealSenseCamera({self.serial_number}) is not connected. Try running `camera.connect()` first." ) if self.thread is not None and self.thread.is_alive(): @@ -467,14 +464,14 @@ class IntelRealSenseCamera: if __name__ == "__main__": parser = argparse.ArgumentParser( - description="Save a few frames using `IntelRealSenseCamera` for all cameras connected to the computer, or a selected subset." + description="Save a few frames using `RealSenseCamera` for all cameras connected to the computer, or a selected subset." ) parser.add_argument( "--serial-numbers", type=int, nargs="*", default=None, - help="List of serial numbers used to instantiate the `IntelRealSenseCamera`. If not provided, find and use all available camera indices.", + help="List of serial numbers used to instantiate the `RealSenseCamera`. If not provided, find and use all available camera indices.", ) parser.add_argument( "--fps", diff --git a/lerobot/common/cameras/intel/configuration_realsense.py b/lerobot/common/cameras/intel/configuration_realsense.py new file mode 100644 index 00000000..5dae89b9 --- /dev/null +++ b/lerobot/common/cameras/intel/configuration_realsense.py @@ -0,0 +1,57 @@ +from dataclasses import dataclass + +from ..configs import CameraConfig + + +@CameraConfig.register_subclass("intelrealsense") +@dataclass +class RealSenseCameraConfig(CameraConfig): + """ + Example of tested options for Intel Real Sense D405: + + ```python + RealSenseCameraConfig(128422271347, 30, 640, 480) + RealSenseCameraConfig(128422271347, 60, 640, 480) + RealSenseCameraConfig(128422271347, 90, 640, 480) + RealSenseCameraConfig(128422271347, 30, 1280, 720) + RealSenseCameraConfig(128422271347, 30, 640, 480, use_depth=True) + RealSenseCameraConfig(128422271347, 30, 640, 480, rotation=90) + ``` + """ + + name: str | None = None + serial_number: int | None = None + fps: int | None = None + width: int | None = None + height: int | None = None + color_mode: str = "rgb" + channels: int | None = None + use_depth: bool = False + force_hardware_reset: bool = True + rotation: int | None = None + mock: bool = False + + def __post_init__(self): + # bool is stronger than is None, since it works with empty strings + if bool(self.name) and bool(self.serial_number): + raise ValueError( + f"One of them must be set: name or serial_number, but {self.name=} and {self.serial_number=} provided." + ) + + if self.color_mode not in ["rgb", "bgr"]: + raise ValueError( + f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." + ) + + self.channels = 3 + + 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." + ) + + if self.rotation not in [-90, None, 90, 180]: + raise ValueError(f"`rotation` must be in [-90, None, 90, 180] (got {self.rotation})") diff --git a/lerobot/common/cameras/opencv/__init__.py b/lerobot/common/cameras/opencv/__init__.py new file mode 100644 index 00000000..edfd6df3 --- /dev/null +++ b/lerobot/common/cameras/opencv/__init__.py @@ -0,0 +1,4 @@ +from .camera_opencv import OpenCVCamera +from .configuration_opencv import OpenCVCameraConfig + +__all__ = ["OpenCVCamera", "OpenCVCameraConfig"] diff --git a/lerobot/common/cameras/opencv.py b/lerobot/common/cameras/opencv/camera_opencv.py similarity index 97% rename from lerobot/common/cameras/opencv.py rename to lerobot/common/cameras/opencv/camera_opencv.py index 60aae5e5..b35380b4 100644 --- a/lerobot/common/cameras/opencv.py +++ b/lerobot/common/cameras/opencv/camera_opencv.py @@ -15,14 +15,15 @@ from threading import Thread import numpy as np from PIL import Image -from lerobot.common.cameras.configs import OpenCVCameraConfig +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from lerobot.common.utils.robot_utils import ( - RobotDeviceAlreadyConnectedError, - RobotDeviceNotConnectedError, busy_wait, ) from lerobot.common.utils.utils import capture_timestamp_utc +from ..camera import Camera +from .configuration_opencv import OpenCVCameraConfig + # 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. @@ -176,7 +177,7 @@ def save_images_from_cameras( print(f"Images have been saved to {images_dir}") -class OpenCVCamera: +class OpenCVCamera(Camera): """ The OpenCVCamera class allows to efficiently record images from cameras. It relies on opencv2 to communicate with the cameras. Most cameras are compatible. For more info, see the [Video I/O with OpenCV Overview](https://docs.opencv.org/4.x/d0/da7/videoio_overview.html). @@ -260,7 +261,7 @@ class OpenCVCamera: def connect(self): if self.is_connected: - raise RobotDeviceAlreadyConnectedError(f"OpenCVCamera({self.camera_index}) is already connected.") + raise DeviceAlreadyConnectedError(f"OpenCVCamera({self.camera_index}) is already connected.") if self.mock: import tests.mock_cv2 as cv2 @@ -339,7 +340,7 @@ class OpenCVCamera: If you are reading data from other sensors, we advise to use `camera.async_read()` which is non blocking version of `camera.read()`. """ if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"OpenCVCamera({self.camera_index}) is not connected. Try running `camera.connect()` first." ) @@ -396,7 +397,7 @@ class OpenCVCamera: def async_read(self): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"OpenCVCamera({self.camera_index}) is not connected. Try running `camera.connect()` first." ) @@ -418,7 +419,7 @@ class OpenCVCamera: def disconnect(self): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"OpenCVCamera({self.camera_index}) is not connected. Try running `camera.connect()` first." ) diff --git a/lerobot/common/cameras/opencv/configuration_opencv.py b/lerobot/common/cameras/opencv/configuration_opencv.py new file mode 100644 index 00000000..983199bf --- /dev/null +++ b/lerobot/common/cameras/opencv/configuration_opencv.py @@ -0,0 +1,38 @@ +from dataclasses import dataclass + +from ..configs import CameraConfig + + +@CameraConfig.register_subclass("opencv") +@dataclass +class OpenCVCameraConfig(CameraConfig): + """ + Example of tested options for Intel Real Sense D405: + + ```python + OpenCVCameraConfig(0, 30, 640, 480) + OpenCVCameraConfig(0, 60, 640, 480) + OpenCVCameraConfig(0, 90, 640, 480) + OpenCVCameraConfig(0, 30, 1280, 720) + ``` + """ + + camera_index: int + fps: int | None = None + width: int | None = None + height: int | None = None + color_mode: str = "rgb" + channels: int | None = None + rotation: int | None = None + mock: bool = False + + def __post_init__(self): + if self.color_mode not in ["rgb", "bgr"]: + raise ValueError( + f"`color_mode` is expected to be 'rgb' or 'bgr', but {self.color_mode} is provided." + ) + + self.channels = 3 + + if self.rotation not in [-90, None, 90, 180]: + raise ValueError(f"`rotation` must be in [-90, None, 90, 180] (got {self.rotation})") diff --git a/lerobot/common/cameras/utils.py b/lerobot/common/cameras/utils.py index 7394acce..56e71a48 100644 --- a/lerobot/common/cameras/utils.py +++ b/lerobot/common/cameras/utils.py @@ -1,35 +1,20 @@ -from typing import Protocol - -import numpy as np - -from lerobot.common.cameras.configs import ( - CameraConfig, - IntelRealSenseCameraConfig, - OpenCVCameraConfig, -) +from .camera import Camera +from .configs import CameraConfig -# Defines a camera type -class Camera(Protocol): - def connect(self): ... - def read(self, temporary_color: str | None = None) -> np.ndarray: ... - def async_read(self) -> np.ndarray: ... - def disconnect(self): ... - - -def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> list[Camera]: +def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> dict[str, Camera]: cameras = {} for key, cfg in camera_configs.items(): if cfg.type == "opencv": - from lerobot.common.cameras.opencv import OpenCVCamera + from .opencv import OpenCVCamera cameras[key] = OpenCVCamera(cfg) elif cfg.type == "intelrealsense": - from lerobot.common.cameras.intelrealsense import IntelRealSenseCamera + from .intel.camera_realsense import RealSenseCamera - cameras[key] = IntelRealSenseCamera(cfg) + cameras[key] = RealSenseCamera(cfg) else: raise ValueError(f"The motor type '{cfg.type}' is not valid.") @@ -38,16 +23,16 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> list[C def make_camera(camera_type, **kwargs) -> Camera: if camera_type == "opencv": - from lerobot.common.cameras.opencv import OpenCVCamera + from .opencv import OpenCVCamera, OpenCVCameraConfig config = OpenCVCameraConfig(**kwargs) return OpenCVCamera(config) elif camera_type == "intelrealsense": - from lerobot.common.cameras.intelrealsense import IntelRealSenseCamera + from .intel import RealSenseCamera, RealSenseCameraConfig - config = IntelRealSenseCameraConfig(**kwargs) - return IntelRealSenseCamera(config) + config = RealSenseCameraConfig(**kwargs) + return RealSenseCamera(config) else: raise ValueError(f"The camera type '{camera_type}' is not valid.") From 3d3a176940caff2c0abf914a900526a840109a83 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:18:24 +0100 Subject: [PATCH 007/190] Move & organize motors, add base class --- lerobot/common/motors/__init__.py | 3 ++ lerobot/common/motors/dynamixel/__init__.py | 4 ++ lerobot/common/motors/dynamixel/dynamixel.py | 32 +++++++++++-- .../motors/dynamixel/dynamixel_calibration.py | 4 +- lerobot/common/motors/feetech/__init__.py | 3 ++ lerobot/common/motors/feetech/feetech.py | 24 +++++----- .../motors/feetech/feetech_calibration.py | 4 +- lerobot/common/motors/motors_bus.py | 46 +++++++++++++++++++ lerobot/common/motors/utils.py | 27 ++++------- 9 files changed, 107 insertions(+), 40 deletions(-) create mode 100644 lerobot/common/motors/__init__.py create mode 100644 lerobot/common/motors/dynamixel/__init__.py create mode 100644 lerobot/common/motors/feetech/__init__.py create mode 100644 lerobot/common/motors/motors_bus.py diff --git a/lerobot/common/motors/__init__.py b/lerobot/common/motors/__init__.py new file mode 100644 index 00000000..6c8699a1 --- /dev/null +++ b/lerobot/common/motors/__init__.py @@ -0,0 +1,3 @@ +from .motors_bus import MotorsBus + +__all__ = ["MotorsBus"] diff --git a/lerobot/common/motors/dynamixel/__init__.py b/lerobot/common/motors/dynamixel/__init__.py new file mode 100644 index 00000000..fbe65a27 --- /dev/null +++ b/lerobot/common/motors/dynamixel/__init__.py @@ -0,0 +1,4 @@ +from .dynamixel import DynamixelMotorsBus, TorqueMode, set_operating_mode +from .dynamixel_calibration import run_arm_calibration + +__all__ = ["DynamixelMotorsBus", "TorqueMode", "set_operating_mode", "run_arm_calibration"] diff --git a/lerobot/common/motors/dynamixel/dynamixel.py b/lerobot/common/motors/dynamixel/dynamixel.py index d2b8bd4d..3c87c12a 100644 --- a/lerobot/common/motors/dynamixel/dynamixel.py +++ b/lerobot/common/motors/dynamixel/dynamixel.py @@ -8,7 +8,7 @@ from copy import deepcopy import numpy as np import tqdm -from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from lerobot.common.utils.utils import capture_timestamp_utc PROTOCOL_VERSION = 2.0 @@ -313,7 +313,7 @@ class DynamixelMotorsBus: def connect(self): if self.is_connected: - raise RobotDeviceAlreadyConnectedError( + raise DeviceAlreadyConnectedError( f"DynamixelMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice." ) @@ -670,7 +670,7 @@ class DynamixelMotorsBus: def read(self, data_name, motor_names: str | list[str] | None = None): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`." ) @@ -772,7 +772,7 @@ class DynamixelMotorsBus: def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"DynamixelMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`." ) @@ -841,7 +841,7 @@ class DynamixelMotorsBus: def disconnect(self): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"DynamixelMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first." ) @@ -857,3 +857,25 @@ class DynamixelMotorsBus: def __del__(self): if getattr(self, "is_connected", False): self.disconnect() + + +def set_operating_mode(arm: DynamixelMotorsBus): + if (arm.read("Torque_Enable") != TorqueMode.DISABLED.value).any(): + raise ValueError("To run set robot preset, the torque must be disabled on all motors.") + + # Use 'extended position mode' for all motors except gripper, because in joint mode the servos can't + # rotate more than 360 degrees (from 0 to 4095) And some mistake can happen while assembling the arm, + # you could end up with a servo with a position 0 or 4095 at a crucial point See [ + # https://emanual.robotis.com/docs/en/dxl/x/x_series/#operating-mode11] + all_motors_except_gripper = [name for name in arm.motor_names if name != "gripper"] + if len(all_motors_except_gripper) > 0: + # 4 corresponds to Extended Position on Koch motors + arm.write("Operating_Mode", 4, all_motors_except_gripper) + + # Use 'position control current based' for gripper to be limited by the limit of the current. + # For the follower gripper, it means it can grasp an object without forcing too much even tho, + # it's goal position is a complete grasp (both gripper fingers are ordered to join and reach a touch). + # For the leader gripper, it means we can use it as a physical trigger, since we can force with our finger + # to make it move, and it will move back to its original target position when we release the force. + # 5 corresponds to Current Controlled Position on Koch gripper motors "xl330-m077, xl330-m288" + arm.write("Operating_Mode", 5, "gripper") diff --git a/lerobot/common/motors/dynamixel/dynamixel_calibration.py b/lerobot/common/motors/dynamixel/dynamixel_calibration.py index fc1e2c4a..72056e49 100644 --- a/lerobot/common/motors/dynamixel/dynamixel_calibration.py +++ b/lerobot/common/motors/dynamixel/dynamixel_calibration.py @@ -3,12 +3,12 @@ import numpy as np -from lerobot.common.motors.dynamixel.dynamixel import ( +from ..motors_bus import MotorsBus +from .dynamixel import ( CalibrationMode, TorqueMode, convert_degrees_to_steps, ) -from lerobot.common.motors.utils import MotorsBus URL_TEMPLATE = ( "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp" diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py new file mode 100644 index 00000000..77501820 --- /dev/null +++ b/lerobot/common/motors/feetech/__init__.py @@ -0,0 +1,3 @@ +from .feetech import FeetechMotorsBus, TorqueMode + +__all__ = ["FeetechMotorsBus", "TorqueMode"] diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py index cb409eff..494c834b 100644 --- a/lerobot/common/motors/feetech/feetech.py +++ b/lerobot/common/motors/feetech/feetech.py @@ -8,8 +8,7 @@ from copy import deepcopy import numpy as np import tqdm -from lerobot.common.motors.configs import FeetechMotorsBusConfig -from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from lerobot.common.utils.utils import capture_timestamp_utc PROTOCOL_VERSION = 0 @@ -253,11 +252,10 @@ class FeetechMotorsBus: motor_index = 6 motor_model = "sts3215" - config = FeetechMotorsBusConfig( + motors_bus = FeetechMotorsBus( port="/dev/tty.usbmodem575E0031751", motors={motor_name: (motor_index, motor_model)}, ) - motors_bus = FeetechMotorsBus(config) motors_bus.connect() position = motors_bus.read("Present_Position") @@ -273,11 +271,13 @@ class FeetechMotorsBus: def __init__( self, - config: FeetechMotorsBusConfig, + port: str, + motors: dict[str, tuple[int, str]], + mock: bool = False, ): - self.port = config.port - self.motors = config.motors - self.mock = config.mock + self.port = port + self.motors = motors + self.mock = mock self.model_ctrl_table = deepcopy(MODEL_CONTROL_TABLE) self.model_resolution = deepcopy(MODEL_RESOLUTION) @@ -294,7 +294,7 @@ class FeetechMotorsBus: def connect(self): if self.is_connected: - raise RobotDeviceAlreadyConnectedError( + raise DeviceAlreadyConnectedError( f"FeetechMotorsBus({self.port}) is already connected. Do not call `motors_bus.connect()` twice." ) @@ -693,7 +693,7 @@ class FeetechMotorsBus: import scservo_sdk as scs if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`." ) @@ -797,7 +797,7 @@ class FeetechMotorsBus: def write(self, data_name, values: int | float | np.ndarray, motor_names: str | list[str] | None = None): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"FeetechMotorsBus({self.port}) is not connected. You need to run `motors_bus.connect()`." ) @@ -866,7 +866,7 @@ class FeetechMotorsBus: def disconnect(self): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( f"FeetechMotorsBus({self.port}) is not connected. Try running `motors_bus.connect()` first." ) diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py index b3ec125c..4f4a6dca 100644 --- a/lerobot/common/motors/feetech/feetech_calibration.py +++ b/lerobot/common/motors/feetech/feetech_calibration.py @@ -5,12 +5,12 @@ import time import numpy as np -from lerobot.common.motors.feetech.feetech import ( +from ..motors_bus import MotorsBus +from .feetech import ( CalibrationMode, TorqueMode, convert_degrees_to_steps, ) -from lerobot.common.motors.utils import MotorsBus URL_TEMPLATE = ( "https://raw.githubusercontent.com/huggingface/lerobot/main/media/{robot}/{arm}_{position}.webp" diff --git a/lerobot/common/motors/motors_bus.py b/lerobot/common/motors/motors_bus.py new file mode 100644 index 00000000..ca95a4da --- /dev/null +++ b/lerobot/common/motors/motors_bus.py @@ -0,0 +1,46 @@ +import abc + + +class MotorsBus(abc.ABC): + """The main LeRobot class for implementing motors buses.""" + + def __init__( + self, + motors: dict[str, tuple[int, str]], + ): + self.motors = motors + + def __len__(self): + return len(self.motors) + + @abc.abstractmethod + def connect(self): + pass + + @abc.abstractmethod + def reconnect(self): + pass + + @abc.abstractmethod + def set_calibration(self, calibration: dict[str, list]): + pass + + @abc.abstractmethod + def apply_calibration(self): + pass + + @abc.abstractmethod + def revert_calibration(self): + pass + + @abc.abstractmethod + def read(self): + pass + + @abc.abstractmethod + def write(self): + pass + + @abc.abstractmethod + def disconnect(self): + pass diff --git a/lerobot/common/motors/utils.py b/lerobot/common/motors/utils.py index 2060679c..1de3bdad 100644 --- a/lerobot/common/motors/utils.py +++ b/lerobot/common/motors/utils.py @@ -1,19 +1,5 @@ -from typing import Protocol - -from lerobot.common.motors.configs import ( - DynamixelMotorsBusConfig, - FeetechMotorsBusConfig, - MotorsBusConfig, -) - - -class MotorsBus(Protocol): - def motor_names(self): ... - def set_calibration(self): ... - def apply_calibration(self): ... - def revert_calibration(self): ... - def read(self): ... - def write(self): ... +from .configs import MotorsBusConfig +from .motors_bus import MotorsBus def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig]) -> list[MotorsBus]: @@ -21,7 +7,7 @@ def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig for key, cfg in motors_bus_configs.items(): if cfg.type == "dynamixel": - from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus + from .dynamixel import DynamixelMotorsBus motors_buses[key] = DynamixelMotorsBus(cfg) @@ -38,13 +24,16 @@ def make_motors_buses_from_configs(motors_bus_configs: dict[str, MotorsBusConfig def make_motors_bus(motor_type: str, **kwargs) -> MotorsBus: if motor_type == "dynamixel": - from lerobot.common.motors.dynamixel.dynamixel import DynamixelMotorsBus + from .configs import DynamixelMotorsBusConfig + from .dynamixel import DynamixelMotorsBus config = DynamixelMotorsBusConfig(**kwargs) return DynamixelMotorsBus(config) elif motor_type == "feetech": - from lerobot.common.motors.feetech.feetech import FeetechMotorsBus + from feetech import FeetechMotorsBus + + from .configs import FeetechMotorsBusConfig config = FeetechMotorsBusConfig(**kwargs) return FeetechMotorsBus(config) From 3111ba78ada9f5fff9768726b4ed8207287cb1e8 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:44:15 +0100 Subject: [PATCH 008/190] Add errors --- lerobot/common/errors.py | 23 +++++++++++++++++++++++ 1 file changed, 23 insertions(+) create mode 100644 lerobot/common/errors.py diff --git a/lerobot/common/errors.py b/lerobot/common/errors.py new file mode 100644 index 00000000..aba958a1 --- /dev/null +++ b/lerobot/common/errors.py @@ -0,0 +1,23 @@ +class ConnectionError(Exception): + """Base exception class for connection errors.""" + + pass + + +class DeviceNotConnectedError(ConnectionError): + """Exception raised when the device is not connected.""" + + def __init__(self, message="This device is not connected. Try calling `connect()` first."): + self.message = message + super().__init__(self.message) + + +class DeviceAlreadyConnectedError(ConnectionError): + """Exception raised when the device is already connected.""" + + def __init__( + self, + message="This device is already connected. Try not calling `connect()` twice.", + ): + self.message = message + super().__init__(self.message) From c0137e89b9be41bae6672f247fe65d0d41461299 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:44:39 +0100 Subject: [PATCH 009/190] Add calibration dir --- lerobot/common/constants.py | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/lerobot/common/constants.py b/lerobot/common/constants.py index d0c9845a..bd22201b 100644 --- a/lerobot/common/constants.py +++ b/lerobot/common/constants.py @@ -10,6 +10,9 @@ OBS_IMAGE = "observation.image" OBS_IMAGES = "observation.images" ACTION = "action" +ROBOTS = "robots" +TELEOPERATORS = "teleoperators" + # files & directories CHECKPOINTS_DIR = "checkpoints" LAST_CHECKPOINT_LINK = "last" @@ -21,12 +24,16 @@ OPTIMIZER_STATE = "optimizer_state.safetensors" OPTIMIZER_PARAM_GROUPS = "optimizer_param_groups.json" SCHEDULER_STATE = "scheduler_state.json" -# cache dir -default_cache_path = Path(HF_HOME) / "lerobot" -HF_LEROBOT_HOME = Path(os.getenv("HF_LEROBOT_HOME", default_cache_path)).expanduser() - if "LEROBOT_HOME" in os.environ: raise ValueError( f"You have a 'LEROBOT_HOME' environment variable set to '{os.getenv('LEROBOT_HOME')}'.\n" "'LEROBOT_HOME' is deprecated, please use 'HF_LEROBOT_HOME' instead." ) + +# cache dir +default_cache_path = Path(HF_HOME) / "lerobot" +HF_LEROBOT_HOME = Path(os.getenv("HF_LEROBOT_HOME", default_cache_path)).expanduser() + +# calibration dir +default_calibration_path = HF_LEROBOT_HOME / ".calibration" +HF_LEROBOT_CALIBRATION = Path(os.getenv("HF_LEROBOT_CALIBRATION", default_calibration_path)).expanduser() From c93cbb83114ebab30feb3e4cfb5602fae7f9d73c Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:49:40 +0100 Subject: [PATCH 010/190] Fix base robot class --- lerobot/common/robots/config.py | 17 ++++++++ lerobot/common/robots/config_abc.py | 59 -------------------------- lerobot/common/robots/robot.py | 64 +++++++++++++++++++++++++++++ lerobot/common/robots/robot_abc.py | 24 ----------- 4 files changed, 81 insertions(+), 83 deletions(-) create mode 100644 lerobot/common/robots/config.py delete mode 100644 lerobot/common/robots/config_abc.py create mode 100644 lerobot/common/robots/robot.py delete mode 100644 lerobot/common/robots/robot_abc.py diff --git a/lerobot/common/robots/config.py b/lerobot/common/robots/config.py new file mode 100644 index 00000000..83a13ca9 --- /dev/null +++ b/lerobot/common/robots/config.py @@ -0,0 +1,17 @@ +import abc +from dataclasses import dataclass +from pathlib import Path + +import draccus + + +@dataclass(kw_only=True) +class RobotConfig(draccus.ChoiceRegistry, abc.ABC): + # Allows to distinguish between different robots of the same type + id: str | None = None + # Directory to store calibration file + calibration_dir: Path | None = None + + @property + def type(self) -> str: + return self.get_choice_name(self.__class__) diff --git a/lerobot/common/robots/config_abc.py b/lerobot/common/robots/config_abc.py deleted file mode 100644 index 7a390ead..00000000 --- a/lerobot/common/robots/config_abc.py +++ /dev/null @@ -1,59 +0,0 @@ -import abc -from dataclasses import dataclass, field -from typing import Sequence - -import draccus - -from lerobot.common.cameras.configs import CameraConfig -from lerobot.common.motors.configs import MotorsBusConfig - - -@dataclass -class RobotConfig(draccus.ChoiceRegistry, abc.ABC): - @property - def type(self) -> str: - return self.get_choice_name(self.__class__) - - -# TODO(rcadene, aliberts): remove ManipulatorRobotConfig abstraction -@dataclass -class ManipulatorRobotConfig(RobotConfig): - leader_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) - follower_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) - cameras: dict[str, CameraConfig] = field(default_factory=lambda: {}) - - # Optionally limit 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 (assumes all follower arms have the same number of - # motors). - max_relative_target: list[float] | float | None = None - - # Optionally set the leader arm in torque mode with the gripper motor set to this angle. This makes it - # possible to squeeze the gripper and have it spring back to an open position on its own. If None, the - # gripper is not put in torque mode. - gripper_open_degree: float | None = None - - mock: bool = False - - def __post_init__(self): - if self.mock: - for arm in self.leader_arms.values(): - if not arm.mock: - arm.mock = True - for arm in self.follower_arms.values(): - if not arm.mock: - arm.mock = True - for cam in self.cameras.values(): - if not cam.mock: - cam.mock = True - - if self.max_relative_target is not None and isinstance(self.max_relative_target, Sequence): - for name in self.follower_arms: - if len(self.follower_arms[name].motors) != len(self.max_relative_target): - raise ValueError( - f"len(max_relative_target)={len(self.max_relative_target)} but the follower arm with name {name} has " - f"{len(self.follower_arms[name].motors)} motors. Please make sure that the " - f"`max_relative_target` list has as many parameters as there are motors per arm. " - "Note: This feature does not yet work with robots where different follower arms have " - "different numbers of motors." - ) diff --git a/lerobot/common/robots/robot.py b/lerobot/common/robots/robot.py new file mode 100644 index 00000000..50fd9154 --- /dev/null +++ b/lerobot/common/robots/robot.py @@ -0,0 +1,64 @@ +import abc + +import numpy as np + +from lerobot.common.constants import HF_LEROBOT_CALIBRATION, ROBOTS + +from .config import RobotConfig + + +class Robot(abc.ABC): + """The main LeRobot class for implementing robots.""" + + # Set these in ALL subclasses + config_class: RobotConfig + name: str + + def __init__(self, config: RobotConfig): + self.robot_type = self.name + self.calibration_dir = ( + config.calibration_dir if config.calibration_dir else HF_LEROBOT_CALIBRATION / ROBOTS / self.name + ) + self.calibration_dir.mkdir(parents=True, exist_ok=True) + + # TODO(aliberts): create a proper Feature class for this that links with datasets + @abc.abstractproperty + def state_feature(self) -> dict: + pass + + @abc.abstractproperty + def action_feature(self) -> dict: + pass + + @abc.abstractproperty + def camera_features(self) -> dict[str, dict]: + pass + + @abc.abstractmethod + def connect(self) -> None: + """Connects to the robot.""" + pass + + @abc.abstractmethod + def calibrate(self) -> None: + """Calibrates the robot.""" + pass + + @abc.abstractmethod + def get_observation(self) -> dict[str, np.ndarray]: + """Gets observation from the robot.""" + pass + + @abc.abstractmethod + def send_action(self, action: np.ndarray) -> np.ndarray: + """Sends actions to the robot.""" + pass + + @abc.abstractmethod + def disconnect(self) -> None: + """Disconnects from the robot.""" + pass + + def __del__(self): + if getattr(self, "is_connected", False): + self.disconnect() diff --git a/lerobot/common/robots/robot_abc.py b/lerobot/common/robots/robot_abc.py deleted file mode 100644 index 3b592f0a..00000000 --- a/lerobot/common/robots/robot_abc.py +++ /dev/null @@ -1,24 +0,0 @@ -import abc - - -class Robot(abc.ABC): - robot_type: str - features: dict - - @abc.abstractmethod - def connect(self): ... - - @abc.abstractmethod - def calibrate(self): ... - - @abc.abstractmethod - def teleop_step(self, record_data=False): ... - - @abc.abstractmethod - def capture_observation(self): ... - - @abc.abstractmethod - def send_action(self, action): ... - - @abc.abstractmethod - def disconnect(self): ... From ea4d8d990cfe484c252c567179be39e300f780b0 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:53:45 +0100 Subject: [PATCH 011/190] Add Koch robot --- lerobot/common/robots/koch/__init__.py | 4 + .../common/robots/koch/configuration_koch.py | 163 ++----------- lerobot/common/robots/koch/robot_koch.py | 219 ++++++++++++++++++ 3 files changed, 239 insertions(+), 147 deletions(-) create mode 100644 lerobot/common/robots/koch/__init__.py create mode 100644 lerobot/common/robots/koch/robot_koch.py diff --git a/lerobot/common/robots/koch/__init__.py b/lerobot/common/robots/koch/__init__.py new file mode 100644 index 00000000..dfbe6369 --- /dev/null +++ b/lerobot/common/robots/koch/__init__.py @@ -0,0 +1,4 @@ +from .configuration_koch import KochRobotConfig +from .robot_koch import KochRobot + +__all__ = ["KochRobotConfig", "KochRobot"] diff --git a/lerobot/common/robots/koch/configuration_koch.py b/lerobot/common/robots/koch/configuration_koch.py index a014d51d..1db724c5 100644 --- a/lerobot/common/robots/koch/configuration_koch.py +++ b/lerobot/common/robots/koch/configuration_koch.py @@ -1,165 +1,34 @@ from dataclasses import dataclass, field -from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig -from lerobot.common.motors.configs import DynamixelMotorsBusConfig, MotorsBusConfig -from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig +from lerobot.common.cameras import CameraConfig + +from ..config import RobotConfig @RobotConfig.register_subclass("koch") @dataclass -class KochRobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".cache/calibration/koch" +class KochRobotConfig(RobotConfig): + # Port to connect to the robot + port: str + # `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: int | None = None - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0085511", - motors={ - # name: (index, model) - "shoulder_pan": [1, "xl330-m077"], - "shoulder_lift": [2, "xl330-m077"], - "elbow_flex": [3, "xl330-m077"], - "wrist_flex": [4, "xl330-m077"], - "wrist_roll": [5, "xl330-m077"], - "gripper": [6, "xl330-m077"], - }, - ), - } - ) - - follower_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - motors={ - # name: (index, model) - "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"], - }, - ), - } - ) - - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - - # ~ Koch specific settings ~ # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible # to squeeze the gripper and have it spring back to an open position on its own. gripper_open_degree: float = 35.156 mock: bool = False + # motors + shoulder_pan: tuple = (1, "xl430-w250") + shoulder_lift: tuple = (2, "xl430-w250") + elbow_flex: tuple = (3, "xl330-m288") + wrist_flex: tuple = (4, "xl330-m288") + wrist_roll: tuple = (5, "xl330-m288") + gripper: tuple = (6, "xl330-m288") -@RobotConfig.register_subclass("koch_bimanual") -@dataclass -class KochBimanualRobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".cache/calibration/koch_bimanual" - # `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: int | None = None - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0085511", - motors={ - # name: (index, model) - "shoulder_pan": [1, "xl330-m077"], - "shoulder_lift": [2, "xl330-m077"], - "elbow_flex": [3, "xl330-m077"], - "wrist_flex": [4, "xl330-m077"], - "wrist_roll": [5, "xl330-m077"], - "gripper": [6, "xl330-m077"], - }, - ), - "right": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem575E0031751", - motors={ - # name: (index, model) - "shoulder_pan": [1, "xl330-m077"], - "shoulder_lift": [2, "xl330-m077"], - "elbow_flex": [3, "xl330-m077"], - "wrist_flex": [4, "xl330-m077"], - "wrist_roll": [5, "xl330-m077"], - "gripper": [6, "xl330-m077"], - }, - ), - } - ) - - follower_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - motors={ - # name: (index, model) - "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"], - }, - ), - "right": DynamixelMotorsBusConfig( - port="/dev/tty.usbmodem575E0032081", - motors={ - # name: (index, model) - "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"], - }, - ), - } - ) - - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - - # ~ Koch specific settings ~ - # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible - # to squeeze the gripper and have it spring back to an open position on its own. - gripper_open_degree: float = 35.156 - - mock: bool = False + # cameras + cameras: dict[str, CameraConfig] = field(default_factory=dict) diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py new file mode 100644 index 00000000..f206b0bf --- /dev/null +++ b/lerobot/common/robots/koch/robot_koch.py @@ -0,0 +1,219 @@ +#!/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 json +import logging +import time + +import numpy as np + +from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.dynamixel import ( + DynamixelMotorsBus, + TorqueMode, + run_arm_calibration, + set_operating_mode, +) + +from ..robot import Robot +from ..utils import ensure_safe_goal_position +from .configuration_koch import KochRobotConfig + + +class KochRobot(Robot): + """ + - [Koch v1.0](https://github.com/AlexanderKoch-Koch/low_cost_robot), with and without the wrist-to-elbow + expansion, developed by Alexander Koch from [Tau Robotics](https://tau-robotics.com) + - [Koch v1.1](https://github.com/jess-moss/koch-v1-1) developed by Jess Moss + """ + + config_class = KochRobotConfig + name = "koch" + + def __init__(self, config: KochRobotConfig): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.arm = DynamixelMotorsBus( + port=self.config.port, + motors={ + "shoulder_pan": config.shoulder_pan, + "shoulder_lift": config.shoulder_lift, + "elbow_flex": config.elbow_flex, + "wrist_flex": config.wrist_flex, + "wrist_roll": config.wrist_roll, + "gripper": config.gripper, + }, + ) + self.cameras = make_cameras_from_configs(config.cameras) + + self.is_connected = False + self.logs = {} + + @property + def state_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def action_feature(self) -> dict: + return self.state_feature + + @property + def camera_features(self) -> dict[str, dict]: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + cam_ft[cam_key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + + def connect(self) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + logging.info("Connecting arm.") + self.arm.connect() + + # We assume that at connection time, arm is in a rest position, + # and torque can be safely disabled to run calibration. + self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) + self.calibrate() + + set_operating_mode(self.arm) + + # Set better PID values to close the gap between recorded states and actions + # TODO(rcadene): Implement an automatic procedure to set optimal PID values for each motor + self.arm.write("Position_P_Gain", 1500, "elbow_flex") + self.arm.write("Position_I_Gain", 0, "elbow_flex") + self.arm.write("Position_D_Gain", 600, "elbow_flex") + + logging.info("Activating torque.") + self.arm.write("Torque_Enable", TorqueMode.ENABLED.value) + + # Check arm can be read + self.arm.read("Present_Position") + + # Connect the cameras + for name in self.cameras: + self.cameras[name].connect() + + self.is_connected = True + + def calibrate(self) -> None: + """After calibration all motors function in human interpretable ranges. + Rotations are expressed in degrees in nominal range of [-180, 180], + and linear motions (like gripper of Aloha) in nominal range of [0, 100]. + """ + arm_calib_path = self.calibration_dir / f"{self.config.id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + # TODO(rcadene): display a warning in __init__ if calibration file not available + logging.info(f"Missing calibration file '{arm_calib_path}'") + calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "follower") + + logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") + arm_calib_path.parent.mkdir(parents=True, exist_ok=True) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + self.arm.set_calibration(calibration) + + def get_observation(self) -> dict[str, np.ndarray]: + """The returned observations do not have a batch dimension.""" + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + obs_dict = {} + + # Read arm position + before_read_t = time.perf_counter() + obs_dict["observation.state"] = self.arm.read("Present_Position") + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + # Capture images from cameras + for cam_key, cam in self.cameras.items(): + before_camread_t = time.perf_counter() + obs_dict[f"observation.images.{cam_key}"] = cam.async_read() + self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] + self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t + + return obs_dict + + def send_action(self, action: np.ndarray) -> np.ndarray: + """Command arm to move to a target joint configuration. + + The relative action magnitude may be clipped depending on the configuration parameter + `max_relative_target`. In this case, the action sent differs from original action. + Thus, this function always returns the action actually sent. + + Args: + action (np.ndarray): array containing the goal positions for the motors. + + Raises: + RobotDeviceNotConnectedError: if robot is not connected. + + Returns: + np.ndarray: the action sent to the motors, potentially clipped. + """ + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + goal_pos = action + + # Cap goal position when too far away from present position. + # /!\ Slower fps expected due to reading from the follower. + if self.config.max_relative_target is not None: + present_pos = self.arm.read("Present_Position") + goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target) + + # Send goal position to the arm + self.arm.write("Goal_Position", goal_pos.astype(np.int32)) + + return goal_pos + + def print_logs(self): + # TODO(aliberts): move robot-specific logs logic here + pass + + def disconnect(self): + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + + self.arm.disconnect() + for cam in self.cameras.values(): + cam.disconnect() + + self.is_connected = False From d75d904e43722102f8bd1bd96157f4a2efdb2979 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:55:59 +0100 Subject: [PATCH 012/190] Add teleoperator base class --- lerobot/common/teleoperators/__init__.py | 4 ++ lerobot/common/teleoperators/config.py | 17 ++++++ lerobot/common/teleoperators/teleoperator.py | 60 ++++++++++++++++++++ 3 files changed, 81 insertions(+) create mode 100644 lerobot/common/teleoperators/__init__.py create mode 100644 lerobot/common/teleoperators/config.py create mode 100644 lerobot/common/teleoperators/teleoperator.py diff --git a/lerobot/common/teleoperators/__init__.py b/lerobot/common/teleoperators/__init__.py new file mode 100644 index 00000000..9dd9b962 --- /dev/null +++ b/lerobot/common/teleoperators/__init__.py @@ -0,0 +1,4 @@ +from .config import TeleoperatorConfig +from .teleoperator import Teleoperator + +__all__ = ["TeleoperatorConfig", "Teleoperator"] diff --git a/lerobot/common/teleoperators/config.py b/lerobot/common/teleoperators/config.py new file mode 100644 index 00000000..997c51f1 --- /dev/null +++ b/lerobot/common/teleoperators/config.py @@ -0,0 +1,17 @@ +import abc +from dataclasses import dataclass +from pathlib import Path + +import draccus + + +@dataclass(kw_only=True) +class TeleoperatorConfig(draccus.ChoiceRegistry, abc.ABC): + # Allows to distinguish between different teleoperators of the same type + id: str | None = None + # Directory to store calibration file + calibration_dir: Path | None = None + + @property + def type(self) -> str: + return self.get_choice_name(self.__class__) diff --git a/lerobot/common/teleoperators/teleoperator.py b/lerobot/common/teleoperators/teleoperator.py new file mode 100644 index 00000000..f06b1983 --- /dev/null +++ b/lerobot/common/teleoperators/teleoperator.py @@ -0,0 +1,60 @@ +import abc + +import numpy as np + +from lerobot.common.constants import HF_LEROBOT_CALIBRATION, TELEOPERATORS + +from .config import TeleoperatorConfig + + +class Teleoperator(abc.ABC): + """The main LeRobot class for implementing teleoperation devices.""" + + # Set these in ALL subclasses + config_class: TeleoperatorConfig + name: str + + def __init__(self, config: TeleoperatorConfig): + self.calibration_dir = ( + config.calibration_dir + if config.calibration_dir + else HF_LEROBOT_CALIBRATION / TELEOPERATORS / self.name + ) + self.calibration_dir.mkdir(parents=True, exist_ok=True) + + @abc.abstractproperty + def action_feature(self) -> dict: + pass + + @abc.abstractproperty + def feedback_feature(self) -> dict: + pass + + @abc.abstractmethod + def connect(self) -> None: + """Connects to the teleoperator.""" + pass + + @abc.abstractmethod + def calibrate(self) -> None: + """Calibrates the teleoperator.""" + pass + + @abc.abstractmethod + def get_action(self) -> np.ndarray: + """Gets the action to send to a teleoperator.""" + pass + + @abc.abstractmethod + def send_feedback(self, feedback: np.ndarray) -> None: + """Sends feedback captured from a robot to the teleoperator.""" + pass + + @abc.abstractmethod + def disconnect(self) -> None: + """Disconnects from the teleoperator.""" + pass + + def __del__(self): + if getattr(self, "is_connected", False): + self.disconnect() From ac89c8d2261a484cbbe79c01770564673f43b273 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 18:58:54 +0100 Subject: [PATCH 013/190] Add Koch teleop --- lerobot/common/teleoperators/koch/__init__.py | 4 + .../teleoperators/koch/configuration_koch.py | 40 +++++ .../common/teleoperators/koch/teleop_koch.py | 146 ++++++++++++++++++ 3 files changed, 190 insertions(+) create mode 100644 lerobot/common/teleoperators/koch/__init__.py create mode 100644 lerobot/common/teleoperators/koch/configuration_koch.py create mode 100644 lerobot/common/teleoperators/koch/teleop_koch.py diff --git a/lerobot/common/teleoperators/koch/__init__.py b/lerobot/common/teleoperators/koch/__init__.py new file mode 100644 index 00000000..f86454d1 --- /dev/null +++ b/lerobot/common/teleoperators/koch/__init__.py @@ -0,0 +1,4 @@ +from .configuration_koch import KochTeleopConfig +from .teleop_koch import KochTeleop + +__all__ = ["KochTeleopConfig", "KochTeleop"] diff --git a/lerobot/common/teleoperators/koch/configuration_koch.py b/lerobot/common/teleoperators/koch/configuration_koch.py new file mode 100644 index 00000000..334c3134 --- /dev/null +++ b/lerobot/common/teleoperators/koch/configuration_koch.py @@ -0,0 +1,40 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import dataclass + +from ..config import TeleoperatorConfig + + +@TeleoperatorConfig.register_subclass("koch") +@dataclass +class KochTeleopConfig(TeleoperatorConfig): + # Port to connect to the teloperator + port: str + + # Sets the arm in torque mode with the gripper motor set to this angle. This makes it possible + # to squeeze the gripper and have it spring back to an open position on its own. + gripper_open_degree: float = 35.156 + + mock: bool = False + + # motors + shoulder_pan: tuple = (1, "xl330-m077") + shoulder_lift: tuple = (2, "xl330-m077") + elbow_flex: tuple = (3, "xl330-m077") + wrist_flex: tuple = (4, "xl330-m077") + wrist_roll: tuple = (5, "xl330-m077") + gripper: tuple = (6, "xl330-m077") diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py new file mode 100644 index 00000000..6146d9e1 --- /dev/null +++ b/lerobot/common/teleoperators/koch/teleop_koch.py @@ -0,0 +1,146 @@ +#!/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 json +import logging +import time + +import numpy as np + +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.dynamixel import ( + DynamixelMotorsBus, + TorqueMode, + run_arm_calibration, + set_operating_mode, +) + +from ..teleoperator import Teleoperator +from .configuration_koch import KochTeleopConfig + + +class KochTeleop(Teleoperator): + """ + - [Koch v1.0](https://github.com/AlexanderKoch-Koch/low_cost_robot), with and without the wrist-to-elbow + expansion, developed by Alexander Koch from [Tau Robotics](https://tau-robotics.com) + - [Koch v1.1](https://github.com/jess-moss/koch-v1-1) developed by Jess Moss + """ + + config_class = KochTeleopConfig + name = "koch" + + def __init__(self, config: KochTeleopConfig): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.arm = DynamixelMotorsBus( + port=self.config.port, + motors={ + "shoulder_pan": config.shoulder_pan, + "shoulder_lift": config.shoulder_lift, + "elbow_flex": config.elbow_flex, + "wrist_flex": config.wrist_flex, + "wrist_roll": config.wrist_roll, + "gripper": config.gripper, + }, + ) + + self.is_connected = False + self.logs = {} + + @property + def action_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def feedback_feature(self) -> dict: + return {} + + def connect(self) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + logging.info("Connecting arm.") + self.arm.connect() + + # We assume that at connection time, arm is in a rest position, + # and torque can be safely disabled to run calibration. + self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) + self.calibrate() + + set_operating_mode(self.arm) + + # Enable torque on the gripper and move it to 45 degrees so that we can use it as a trigger. + logging.info("Activating torque.") + self.arm.write("Torque_Enable", TorqueMode.ENABLED.value, "gripper") + self.arm.write("Goal_Position", self.config.gripper_open_degree, "gripper") + + # Check arm can be read + self.arm.read("Present_Position") + + self.is_connected = True + + def calibrate(self) -> None: + """After calibration all motors function in human interpretable ranges. + Rotations are expressed in degrees in nominal range of [-180, 180], + and linear motions (like gripper of Aloha) in nominal range of [0, 100]. + """ + arm_calib_path = self.calibration_dir / f"{self.id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + # TODO(rcadene): display a warning in __init__ if calibration file not available + logging.info(f"Missing calibration file '{arm_calib_path}'") + calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "leader") + + logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") + arm_calib_path.parent.mkdir(parents=True, exist_ok=True) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + self.arm.set_calibration(calibration) + + def get_action(self) -> np.ndarray: + """The returned action does not have a batch dimension.""" + # Read arm position + before_read_t = time.perf_counter() + action = self.arm.read("Present_Position") + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + return action + + def send_feedback(self, feedback: np.ndarray) -> None: + # TODO(rcadene, aliberts): Implement force feedback + pass + + def disconnect(self) -> None: + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + + self.arm.disconnect() + self.is_connected = False From 95f61ee9d44dbb3733314980b89b902f1001a142 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 20:17:18 +0100 Subject: [PATCH 014/190] Add SO-100 robot --- .../common/robots/{so_100 => so100}/README.md | 0 lerobot/common/robots/so100/__init__.py | 4 + .../robots/so100/configuration_so100.py | 30 +++ lerobot/common/robots/so100/robot_so100.py | 224 ++++++++++++++++++ .../robots/so_100/configuration_so_100.py | 68 ------ lerobot/common/robots/so_100/robot_so_100.py | 0 6 files changed, 258 insertions(+), 68 deletions(-) rename lerobot/common/robots/{so_100 => so100}/README.md (100%) create mode 100644 lerobot/common/robots/so100/__init__.py create mode 100644 lerobot/common/robots/so100/configuration_so100.py create mode 100644 lerobot/common/robots/so100/robot_so100.py delete mode 100644 lerobot/common/robots/so_100/configuration_so_100.py delete mode 100644 lerobot/common/robots/so_100/robot_so_100.py diff --git a/lerobot/common/robots/so_100/README.md b/lerobot/common/robots/so100/README.md similarity index 100% rename from lerobot/common/robots/so_100/README.md rename to lerobot/common/robots/so100/README.md diff --git a/lerobot/common/robots/so100/__init__.py b/lerobot/common/robots/so100/__init__.py new file mode 100644 index 00000000..f3803002 --- /dev/null +++ b/lerobot/common/robots/so100/__init__.py @@ -0,0 +1,4 @@ +from .configuration_so100 import So100RobotConfig +from .robot_so100 import So100Robot + +__all__ = ["So100RobotConfig", "So100Robot"] diff --git a/lerobot/common/robots/so100/configuration_so100.py b/lerobot/common/robots/so100/configuration_so100.py new file mode 100644 index 00000000..ac04b847 --- /dev/null +++ b/lerobot/common/robots/so100/configuration_so100.py @@ -0,0 +1,30 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras import CameraConfig + +from ..config import RobotConfig + + +@RobotConfig.register_subclass("so100") +@dataclass +class So100RobotConfig(RobotConfig): + # Port to connect to the robot + port: str + + # `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: int | None = None + + mock: bool = False + + # motors + shoulder_pan: tuple = (1, "sts3215") + shoulder_lift: tuple = (2, "sts3215") + elbow_flex: tuple = (3, "sts3215") + wrist_flex: tuple = (4, "sts3215") + wrist_roll: tuple = (5, "sts3215") + gripper: tuple = (6, "sts3215") + + # cameras + cameras: dict[str, CameraConfig] = field(default_factory=dict) diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py new file mode 100644 index 00000000..1895627e --- /dev/null +++ b/lerobot/common/robots/so100/robot_so100.py @@ -0,0 +1,224 @@ +#!/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 json +import logging +import time + +import numpy as np + +from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.constants import OBS_IMAGES, OBS_STATE +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.feetech import ( + FeetechMotorsBus, + TorqueMode, + run_arm_manual_calibration, +) + +from ..robot import Robot +from ..utils import ensure_safe_goal_position +from .configuration_so100 import So100RobotConfig + + +class So100Robot(Robot): + """ + [SO-100 Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio + """ + + config_class = So100RobotConfig + name = "koch" + + def __init__(self, config: So100RobotConfig): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.arm = FeetechMotorsBus( + port=self.config.port, + motors={ + "shoulder_pan": config.shoulder_pan, + "shoulder_lift": config.shoulder_lift, + "elbow_flex": config.elbow_flex, + "wrist_flex": config.wrist_flex, + "wrist_roll": config.wrist_roll, + "gripper": config.gripper, + }, + ) + self.cameras = make_cameras_from_configs(config.cameras) + + self.is_connected = False + self.logs = {} + + @property + def state_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def action_feature(self) -> dict: + return self.state_feature + + @property + def camera_features(self) -> dict[str, dict]: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + cam_ft[cam_key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + + def connect(self) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + logging.info("Connecting arm.") + self.arm.connect() + + # We assume that at connection time, arm is in a rest position, + # and torque can be safely disabled to run calibration. + self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) + self.calibrate() + + # Mode=0 for Position Control + self.arm.write("Mode", 0) + # Set P_Coefficient to lower value to avoid shakiness (Default is 32) + self.arm.write("P_Coefficient", 16) + # Set I_Coefficient and D_Coefficient to default value 0 and 32 + self.arm.write("I_Coefficient", 0) + self.arm.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.arm.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.arm.write("Maximum_Acceleration", 254) + self.arm.write("Acceleration", 254) + + logging.info("Activating torque.") + self.arm.write("Torque_Enable", TorqueMode.ENABLED.value) + + # Check arm can be read + self.arm.read("Present_Position") + + # Connect the cameras + for cam in self.cameras.values(): + cam.connect() + + self.is_connected = True + + def calibrate(self) -> None: + """After calibration all motors function in human interpretable ranges. + Rotations are expressed in degrees in nominal range of [-180, 180], + and linear motions (like gripper of Aloha) in nominal range of [0, 100]. + """ + arm_calib_path = self.calibration_dir / f"{self.config.id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + # TODO(rcadene): display a warning in __init__ if calibration file not available + logging.info(f"Missing calibration file '{arm_calib_path}'") + calibration = run_arm_manual_calibration(self.arm, self.robot_type, self.name, "follower") + + logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") + arm_calib_path.parent.mkdir(parents=True, exist_ok=True) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + self.arm.set_calibration(calibration) + + def get_observation(self) -> dict[str, np.ndarray]: + """The returned observations do not have a batch dimension.""" + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + obs_dict = {} + + # Read arm position + before_read_t = time.perf_counter() + obs_dict[OBS_STATE] = self.arm.read("Present_Position") + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + # Capture images from cameras + for cam_key, cam in self.cameras.items(): + before_camread_t = time.perf_counter() + obs_dict[f"{OBS_IMAGES}.{cam_key}"] = cam.async_read() + self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] + self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t + + return obs_dict + + def send_action(self, action: np.ndarray) -> np.ndarray: + """Command arm to move to a target joint configuration. + + The relative action magnitude may be clipped depending on the configuration parameter + `max_relative_target`. In this case, the action sent differs from original action. + Thus, this function always returns the action actually sent. + + Args: + action (np.ndarray): array containing the goal positions for the motors. + + Raises: + RobotDeviceNotConnectedError: if robot is not connected. + + Returns: + np.ndarray: the action sent to the motors, potentially clipped. + """ + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + goal_pos = action + + # Cap goal position when too far away from present position. + # /!\ Slower fps expected due to reading from the follower. + if self.config.max_relative_target is not None: + present_pos = self.arm.read("Present_Position") + goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target) + + # Send goal position to the arm + self.arm.write("Goal_Position", goal_pos.astype(np.int32)) + + return goal_pos + + def print_logs(self): + # TODO(aliberts): move robot-specific logs logic here + pass + + def disconnect(self): + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + + self.arm.disconnect() + for cam in self.cameras.values(): + cam.disconnect() + + self.is_connected = False diff --git a/lerobot/common/robots/so_100/configuration_so_100.py b/lerobot/common/robots/so_100/configuration_so_100.py deleted file mode 100644 index 95ba8bd2..00000000 --- a/lerobot/common/robots/so_100/configuration_so_100.py +++ /dev/null @@ -1,68 +0,0 @@ -from dataclasses import dataclass, field - -from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig -from lerobot.common.motors.configs import FeetechMotorsBusConfig, MotorsBusConfig -from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig - - -@RobotConfig.register_subclass("so100") -@dataclass -class So100RobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".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: int | None = None - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - 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: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - 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: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - - mock: bool = False diff --git a/lerobot/common/robots/so_100/robot_so_100.py b/lerobot/common/robots/so_100/robot_so_100.py deleted file mode 100644 index e69de29b..00000000 From 5ab418dbeb038476cf761b0b8a4ccadf25cb2b6b Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 20:17:54 +0100 Subject: [PATCH 015/190] Add feetech calibration --- lerobot/common/motors/feetech/__init__.py | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py index 77501820..48e0b1c8 100644 --- a/lerobot/common/motors/feetech/__init__.py +++ b/lerobot/common/motors/feetech/__init__.py @@ -1,3 +1,4 @@ from .feetech import FeetechMotorsBus, TorqueMode +from .feetech_calibration import run_arm_manual_calibration -__all__ = ["FeetechMotorsBus", "TorqueMode"] +__all__ = ["FeetechMotorsBus", "TorqueMode", "run_arm_manual_calibration"] From 418866007ee55f2184262587f43613fdd878e816 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 20:19:23 +0100 Subject: [PATCH 016/190] Fixes for Koch robot --- lerobot/common/constants.py | 4 ++-- lerobot/common/robots/koch/configuration_koch.py | 4 ---- lerobot/common/robots/koch/robot_koch.py | 9 +++++---- 3 files changed, 7 insertions(+), 10 deletions(-) diff --git a/lerobot/common/constants.py b/lerobot/common/constants.py index bd22201b..9e83bf33 100644 --- a/lerobot/common/constants.py +++ b/lerobot/common/constants.py @@ -4,8 +4,8 @@ from pathlib import Path from huggingface_hub.constants import HF_HOME -OBS_ENV = "observation.environment_state" -OBS_ROBOT = "observation.state" +OBS_ENV_STATE = "observation.environment_state" +OBS_STATE = "observation.state" OBS_IMAGE = "observation.image" OBS_IMAGES = "observation.images" ACTION = "action" diff --git a/lerobot/common/robots/koch/configuration_koch.py b/lerobot/common/robots/koch/configuration_koch.py index 1db724c5..d6ec3da5 100644 --- a/lerobot/common/robots/koch/configuration_koch.py +++ b/lerobot/common/robots/koch/configuration_koch.py @@ -16,10 +16,6 @@ class KochRobotConfig(RobotConfig): # the number of motors in your follower arms. max_relative_target: int | None = None - # Sets the leader arm in torque mode with the gripper motor set to this angle. This makes it possible - # to squeeze the gripper and have it spring back to an open position on its own. - gripper_open_degree: float = 35.156 - mock: bool = False # motors diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py index f206b0bf..469953c2 100644 --- a/lerobot/common/robots/koch/robot_koch.py +++ b/lerobot/common/robots/koch/robot_koch.py @@ -21,6 +21,7 @@ import time import numpy as np from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.constants import OBS_IMAGES, OBS_STATE from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from lerobot.common.motors.dynamixel import ( DynamixelMotorsBus, @@ -118,8 +119,8 @@ class KochRobot(Robot): self.arm.read("Present_Position") # Connect the cameras - for name in self.cameras: - self.cameras[name].connect() + for cam in self.cameras.values(): + cam.connect() self.is_connected = True @@ -156,13 +157,13 @@ class KochRobot(Robot): # Read arm position before_read_t = time.perf_counter() - obs_dict["observation.state"] = self.arm.read("Present_Position") + obs_dict[OBS_STATE] = self.arm.read("Present_Position") self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t # Capture images from cameras for cam_key, cam in self.cameras.items(): before_camread_t = time.perf_counter() - obs_dict[f"observation.images.{cam_key}"] = cam.async_read() + obs_dict[f"{OBS_IMAGES}.{cam_key}"] = cam.async_read() self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t From 2c7e0f17b60bb1b5f4fec93077686736ee2fc70d Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 20:31:04 +0100 Subject: [PATCH 017/190] Add SO-100 teleop --- .../common/teleoperators/so100/__init__.py | 4 + .../so100/configuration_so100.py | 36 +++++ .../teleoperators/so100/teleop_so100.py | 141 ++++++++++++++++++ 3 files changed, 181 insertions(+) create mode 100644 lerobot/common/teleoperators/so100/__init__.py create mode 100644 lerobot/common/teleoperators/so100/configuration_so100.py create mode 100644 lerobot/common/teleoperators/so100/teleop_so100.py diff --git a/lerobot/common/teleoperators/so100/__init__.py b/lerobot/common/teleoperators/so100/__init__.py new file mode 100644 index 00000000..a319b5bc --- /dev/null +++ b/lerobot/common/teleoperators/so100/__init__.py @@ -0,0 +1,4 @@ +from .configuration_so100 import SO100TeleopConfig +from .teleop_so100 import SO100Teleop + +__all__ = ["SO100TeleopConfig", "SO100Teleop"] diff --git a/lerobot/common/teleoperators/so100/configuration_so100.py b/lerobot/common/teleoperators/so100/configuration_so100.py new file mode 100644 index 00000000..57a08e15 --- /dev/null +++ b/lerobot/common/teleoperators/so100/configuration_so100.py @@ -0,0 +1,36 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import dataclass + +from ..config import TeleoperatorConfig + + +@TeleoperatorConfig.register_subclass("so100") +@dataclass +class SO100TeleopConfig(TeleoperatorConfig): + # Port to connect to the teloperator + port: str + + mock: bool = False + + # motors + shoulder_pan: tuple = (1, "sts3215") + shoulder_lift: tuple = (2, "sts3215") + elbow_flex: tuple = (3, "sts3215") + wrist_flex: tuple = (4, "sts3215") + wrist_roll: tuple = (5, "sts3215") + gripper: tuple = (6, "sts3215") diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py new file mode 100644 index 00000000..6b953393 --- /dev/null +++ b/lerobot/common/teleoperators/so100/teleop_so100.py @@ -0,0 +1,141 @@ +#!/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 json +import logging +import time + +import numpy as np + +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.feetech import ( + FeetechMotorsBus, + TorqueMode, + run_arm_manual_calibration, +) + +from ..teleoperator import Teleoperator +from .configuration_so100 import SO100TeleopConfig + + +class SO100Teleop(Teleoperator): + """ + [SO-100 Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio + """ + + config_class = SO100TeleopConfig + name = "so100" + + def __init__(self, config: SO100TeleopConfig): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.arm = FeetechMotorsBus( + port=self.config.port, + motors={ + "shoulder_pan": config.shoulder_pan, + "shoulder_lift": config.shoulder_lift, + "elbow_flex": config.elbow_flex, + "wrist_flex": config.wrist_flex, + "wrist_roll": config.wrist_roll, + "gripper": config.gripper, + }, + ) + + self.is_connected = False + self.logs = {} + + @property + def action_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def feedback_feature(self) -> dict: + return {} + + def connect(self) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + logging.info("Connecting arm.") + self.arm.connect() + + # We assume that at connection time, arm is in a rest position, + # and torque can be safely disabled to run calibration. + self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) + self.calibrate() + + # Enable torque on the gripper and move it to 45 degrees so that we can use it as a trigger. + logging.info("Activating torque.") + self.arm.write("Torque_Enable", TorqueMode.ENABLED.value, "gripper") + self.arm.write("Goal_Position", self.config.gripper_open_degree, "gripper") + + # Check arm can be read + self.arm.read("Present_Position") + + self.is_connected = True + + def calibrate(self) -> None: + """After calibration all motors function in human interpretable ranges. + Rotations are expressed in degrees in nominal range of [-180, 180], + and linear motions (like gripper of Aloha) in nominal range of [0, 100]. + """ + arm_calib_path = self.calibration_dir / f"{self.id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + # TODO(rcadene): display a warning in __init__ if calibration file not available + logging.info(f"Missing calibration file '{arm_calib_path}'") + calibration = run_arm_manual_calibration(self.arm, self.robot_type, self.name, "leader") + + logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") + arm_calib_path.parent.mkdir(parents=True, exist_ok=True) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + self.arm.set_calibration(calibration) + + def get_action(self) -> np.ndarray: + """The returned action does not have a batch dimension.""" + # Read arm position + before_read_t = time.perf_counter() + action = self.arm.read("Present_Position") + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + return action + + def send_feedback(self, feedback: np.ndarray) -> None: + # TODO(rcadene, aliberts): Implement force feedback + pass + + def disconnect(self) -> None: + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + + self.arm.disconnect() + self.is_connected = False From a13e49073c57739b3fe5cebe14c41aff3c4493d1 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 3 Mar 2025 20:42:48 +0100 Subject: [PATCH 018/190] Add Moss Robot --- lerobot/common/robots/moss/__init__.py | 4 + .../common/robots/moss/configuration_moss.py | 74 ++---- lerobot/common/robots/moss/robot_moss.py | 224 ++++++++++++++++++ 3 files changed, 246 insertions(+), 56 deletions(-) create mode 100644 lerobot/common/robots/moss/__init__.py create mode 100644 lerobot/common/robots/moss/robot_moss.py diff --git a/lerobot/common/robots/moss/__init__.py b/lerobot/common/robots/moss/__init__.py new file mode 100644 index 00000000..f7c840a3 --- /dev/null +++ b/lerobot/common/robots/moss/__init__.py @@ -0,0 +1,4 @@ +from .configuration_moss import MossRobotConfig +from .robot_moss import MossRobot + +__all__ = ["MossRobotConfig", "MossRobot"] diff --git a/lerobot/common/robots/moss/configuration_moss.py b/lerobot/common/robots/moss/configuration_moss.py index da37f7a2..ece3a018 100644 --- a/lerobot/common/robots/moss/configuration_moss.py +++ b/lerobot/common/robots/moss/configuration_moss.py @@ -1,68 +1,30 @@ from dataclasses import dataclass, field -from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig -from lerobot.common.motors.configs import FeetechMotorsBusConfig, MotorsBusConfig -from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig +from lerobot.common.cameras import CameraConfig + +from ..config import RobotConfig @RobotConfig.register_subclass("moss") @dataclass -class MossRobotConfig(ManipulatorRobotConfig): - calibration_dir: str = ".cache/calibration/moss" +class MossRobotConfig(RobotConfig): + # Port to connect to the robot + port: str + # `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: int | None = None - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - 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: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "main": FeetechMotorsBusConfig( - port="/dev/tty.usbmodem585A0076891", - 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: dict[str, CameraConfig] = field( - default_factory=lambda: { - "laptop": OpenCVCameraConfig( - camera_index=0, - fps=30, - width=640, - height=480, - ), - "phone": OpenCVCameraConfig( - camera_index=1, - fps=30, - width=640, - height=480, - ), - } - ) - mock: bool = False + + # motors + shoulder_pan: tuple = (1, "sts3215") + shoulder_lift: tuple = (2, "sts3215") + elbow_flex: tuple = (3, "sts3215") + wrist_flex: tuple = (4, "sts3215") + wrist_roll: tuple = (5, "sts3215") + gripper: tuple = (6, "sts3215") + + # cameras + cameras: dict[str, CameraConfig] = field(default_factory=dict) diff --git a/lerobot/common/robots/moss/robot_moss.py b/lerobot/common/robots/moss/robot_moss.py new file mode 100644 index 00000000..81703135 --- /dev/null +++ b/lerobot/common/robots/moss/robot_moss.py @@ -0,0 +1,224 @@ +#!/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 json +import logging +import time + +import numpy as np + +from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.constants import OBS_IMAGES, OBS_STATE +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.feetech import ( + FeetechMotorsBus, + TorqueMode, + run_arm_manual_calibration, +) + +from ..robot import Robot +from ..utils import ensure_safe_goal_position +from .configuration_moss import MossRobotConfig + + +class MossRobot(Robot): + """ + [Moss Arm](https://github.com/jess-moss/moss-robot-arms) designed by Jess Moss + """ + + config_class = MossRobotConfig + name = "moss" + + def __init__(self, config: MossRobotConfig): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.arm = FeetechMotorsBus( + port=self.config.port, + motors={ + "shoulder_pan": config.shoulder_pan, + "shoulder_lift": config.shoulder_lift, + "elbow_flex": config.elbow_flex, + "wrist_flex": config.wrist_flex, + "wrist_roll": config.wrist_roll, + "gripper": config.gripper, + }, + ) + self.cameras = make_cameras_from_configs(config.cameras) + + self.is_connected = False + self.logs = {} + + @property + def state_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def action_feature(self) -> dict: + return self.state_feature + + @property + def camera_features(self) -> dict[str, dict]: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + cam_ft[cam_key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + + def connect(self) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + logging.info("Connecting arm.") + self.arm.connect() + + # We assume that at connection time, arm is in a rest position, + # and torque can be safely disabled to run calibration. + self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) + self.calibrate() + + # Mode=0 for Position Control + self.arm.write("Mode", 0) + # Set P_Coefficient to lower value to avoid shakiness (Default is 32) + self.arm.write("P_Coefficient", 16) + # Set I_Coefficient and D_Coefficient to default value 0 and 32 + self.arm.write("I_Coefficient", 0) + self.arm.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.arm.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.arm.write("Maximum_Acceleration", 254) + self.arm.write("Acceleration", 254) + + logging.info("Activating torque.") + self.arm.write("Torque_Enable", TorqueMode.ENABLED.value) + + # Check arm can be read + self.arm.read("Present_Position") + + # Connect the cameras + for cam in self.cameras.values(): + cam.connect() + + self.is_connected = True + + def calibrate(self) -> None: + """After calibration all motors function in human interpretable ranges. + Rotations are expressed in degrees in nominal range of [-180, 180], + and linear motions (like gripper of Aloha) in nominal range of [0, 100]. + """ + arm_calib_path = self.calibration_dir / f"{self.config.id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + # TODO(rcadene): display a warning in __init__ if calibration file not available + logging.info(f"Missing calibration file '{arm_calib_path}'") + calibration = run_arm_manual_calibration(self.arm, self.robot_type, self.name, "follower") + + logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") + arm_calib_path.parent.mkdir(parents=True, exist_ok=True) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + self.arm.set_calibration(calibration) + + def get_observation(self) -> dict[str, np.ndarray]: + """The returned observations do not have a batch dimension.""" + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + obs_dict = {} + + # Read arm position + before_read_t = time.perf_counter() + obs_dict[OBS_STATE] = self.arm.read("Present_Position") + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + # Capture images from cameras + for cam_key, cam in self.cameras.items(): + before_camread_t = time.perf_counter() + obs_dict[f"{OBS_IMAGES}.{cam_key}"] = cam.async_read() + self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] + self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t + + return obs_dict + + def send_action(self, action: np.ndarray) -> np.ndarray: + """Command arm to move to a target joint configuration. + + The relative action magnitude may be clipped depending on the configuration parameter + `max_relative_target`. In this case, the action sent differs from original action. + Thus, this function always returns the action actually sent. + + Args: + action (np.ndarray): array containing the goal positions for the motors. + + Raises: + RobotDeviceNotConnectedError: if robot is not connected. + + Returns: + np.ndarray: the action sent to the motors, potentially clipped. + """ + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + goal_pos = action + + # Cap goal position when too far away from present position. + # /!\ Slower fps expected due to reading from the follower. + if self.config.max_relative_target is not None: + present_pos = self.arm.read("Present_Position") + goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target) + + # Send goal position to the arm + self.arm.write("Goal_Position", goal_pos.astype(np.int32)) + + return goal_pos + + def print_logs(self): + # TODO(aliberts): move robot-specific logs logic here + pass + + def disconnect(self): + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + + self.arm.disconnect() + for cam in self.cameras.values(): + cam.disconnect() + + self.is_connected = False From 2b24feb604b6b6b6e67de9aed2d2eec8a47141c6 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Tue, 4 Mar 2025 11:07:15 +0100 Subject: [PATCH 019/190] Update constants --- lerobot/common/envs/configs.py | 10 +++++----- .../common/policies/diffusion/modeling_diffusion.py | 8 ++++---- lerobot/common/policies/pi0/modeling_pi0.py | 10 +++++----- lerobot/common/policies/tdmpc/modeling_tdmpc.py | 6 +++--- 4 files changed, 17 insertions(+), 17 deletions(-) diff --git a/lerobot/common/envs/configs.py b/lerobot/common/envs/configs.py index 6259ca94..d000d1dd 100644 --- a/lerobot/common/envs/configs.py +++ b/lerobot/common/envs/configs.py @@ -3,7 +3,7 @@ from dataclasses import dataclass, field import draccus -from lerobot.common.constants import ACTION, OBS_ENV, OBS_IMAGE, OBS_IMAGES, OBS_ROBOT +from lerobot.common.constants import ACTION, OBS_ENV_STATE, OBS_IMAGE, OBS_IMAGES, OBS_STATE from lerobot.configs.types import FeatureType, PolicyFeature @@ -39,7 +39,7 @@ class AlohaEnv(EnvConfig): features_map: dict[str, str] = field( default_factory=lambda: { "action": ACTION, - "agent_pos": OBS_ROBOT, + "agent_pos": OBS_STATE, "top": f"{OBS_IMAGE}.top", "pixels/top": f"{OBS_IMAGES}.top", } @@ -80,8 +80,8 @@ class PushtEnv(EnvConfig): features_map: dict[str, str] = field( default_factory=lambda: { "action": ACTION, - "agent_pos": OBS_ROBOT, - "environment_state": OBS_ENV, + "agent_pos": OBS_STATE, + "environment_state": OBS_ENV_STATE, "pixels": OBS_IMAGE, } ) @@ -122,7 +122,7 @@ class XarmEnv(EnvConfig): features_map: dict[str, str] = field( default_factory=lambda: { "action": ACTION, - "agent_pos": OBS_ROBOT, + "agent_pos": OBS_STATE, "pixels": OBS_IMAGE, } ) diff --git a/lerobot/common/policies/diffusion/modeling_diffusion.py b/lerobot/common/policies/diffusion/modeling_diffusion.py index 9ecadcb0..3edaf852 100644 --- a/lerobot/common/policies/diffusion/modeling_diffusion.py +++ b/lerobot/common/policies/diffusion/modeling_diffusion.py @@ -33,7 +33,7 @@ from diffusers.schedulers.scheduling_ddim import DDIMScheduler from diffusers.schedulers.scheduling_ddpm import DDPMScheduler from torch import Tensor, nn -from lerobot.common.constants import OBS_ENV, OBS_ROBOT +from lerobot.common.constants import OBS_ENV_STATE, OBS_STATE from lerobot.common.policies.diffusion.configuration_diffusion import DiffusionConfig from lerobot.common.policies.normalize import Normalize, Unnormalize from lerobot.common.policies.pretrained import PreTrainedPolicy @@ -238,8 +238,8 @@ class DiffusionModel(nn.Module): def _prepare_global_conditioning(self, batch: dict[str, Tensor]) -> Tensor: """Encode image features and concatenate them all together along with the state vector.""" - batch_size, n_obs_steps = batch[OBS_ROBOT].shape[:2] - global_cond_feats = [batch[OBS_ROBOT]] + batch_size, n_obs_steps = batch[OBS_STATE].shape[:2] + global_cond_feats = [batch[OBS_STATE]] # Extract image features. if self.config.image_features: if self.config.use_separate_rgb_encoder_per_camera: @@ -269,7 +269,7 @@ class DiffusionModel(nn.Module): global_cond_feats.append(img_features) if self.config.env_state_feature: - global_cond_feats.append(batch[OBS_ENV]) + global_cond_feats.append(batch[OBS_ENV_STATE]) # Concatenate features then flatten to (B, global_cond_dim). return torch.cat(global_cond_feats, dim=-1).flatten(start_dim=1) diff --git a/lerobot/common/policies/pi0/modeling_pi0.py b/lerobot/common/policies/pi0/modeling_pi0.py index c8b12caf..555a86bd 100644 --- a/lerobot/common/policies/pi0/modeling_pi0.py +++ b/lerobot/common/policies/pi0/modeling_pi0.py @@ -57,7 +57,7 @@ import torch.nn.functional as F # noqa: N812 from torch import Tensor, nn from transformers import AutoTokenizer -from lerobot.common.constants import ACTION, OBS_ROBOT +from lerobot.common.constants import ACTION, OBS_STATE from lerobot.common.policies.normalize import Normalize, Unnormalize from lerobot.common.policies.pi0.configuration_pi0 import PI0Config from lerobot.common.policies.pi0.paligemma_with_expert import ( @@ -271,7 +271,7 @@ class PI0Policy(PreTrainedPolicy): self.eval() if self.config.adapt_to_pi_aloha: - batch[OBS_ROBOT] = self._pi_aloha_decode_state(batch[OBS_ROBOT]) + batch[OBS_STATE] = self._pi_aloha_decode_state(batch[OBS_STATE]) batch = self.normalize_inputs(batch) @@ -303,7 +303,7 @@ class PI0Policy(PreTrainedPolicy): def forward(self, batch: dict[str, Tensor], noise=None, time=None) -> tuple[Tensor, dict[str, Tensor]]: """Do a full training forward pass to compute the loss""" if self.config.adapt_to_pi_aloha: - batch[OBS_ROBOT] = self._pi_aloha_decode_state(batch[OBS_ROBOT]) + batch[OBS_STATE] = self._pi_aloha_decode_state(batch[OBS_STATE]) batch[ACTION] = self._pi_aloha_encode_actions_inv(batch[ACTION]) batch = self.normalize_inputs(batch) @@ -380,7 +380,7 @@ class PI0Policy(PreTrainedPolicy): def prepare_language(self, batch) -> tuple[Tensor, Tensor]: """Tokenize the text input""" - device = batch[OBS_ROBOT].device + device = batch[OBS_STATE].device tasks = batch["task"] # PaliGemma prompt has to end with a new line @@ -427,7 +427,7 @@ class PI0Policy(PreTrainedPolicy): def prepare_state(self, batch): """Pad state""" - state = pad_vector(batch[OBS_ROBOT], self.config.max_state_dim) + state = pad_vector(batch[OBS_STATE], self.config.max_state_dim) return state def prepare_action(self, batch): diff --git a/lerobot/common/policies/tdmpc/modeling_tdmpc.py b/lerobot/common/policies/tdmpc/modeling_tdmpc.py index 0940f198..615c156c 100644 --- a/lerobot/common/policies/tdmpc/modeling_tdmpc.py +++ b/lerobot/common/policies/tdmpc/modeling_tdmpc.py @@ -35,7 +35,7 @@ import torch.nn as nn import torch.nn.functional as F # noqa: N812 from torch import Tensor -from lerobot.common.constants import OBS_ENV, OBS_ROBOT +from lerobot.common.constants import OBS_ENV_STATE, OBS_STATE from lerobot.common.policies.normalize import Normalize, Unnormalize from lerobot.common.policies.pretrained import PreTrainedPolicy from lerobot.common.policies.tdmpc.configuration_tdmpc import TDMPCConfig @@ -753,9 +753,9 @@ class TDMPCObservationEncoder(nn.Module): ) ) if self.config.env_state_feature: - feat.append(self.env_state_enc_layers(obs_dict[OBS_ENV])) + feat.append(self.env_state_enc_layers(obs_dict[OBS_ENV_STATE])) if self.config.robot_state_feature: - feat.append(self.state_enc_layers(obs_dict[OBS_ROBOT])) + feat.append(self.state_enc_layers(obs_dict[OBS_STATE])) return torch.stack(feat, dim=0).mean(0) From f6c10494744a62a198bbf2c8761b67051e460044 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Tue, 4 Mar 2025 11:24:05 +0100 Subject: [PATCH 020/190] Update errors --- lerobot/common/errors.py | 6 ------ lerobot/common/utils/robot_utils.py | 21 --------------------- 2 files changed, 27 deletions(-) diff --git a/lerobot/common/errors.py b/lerobot/common/errors.py index aba958a1..4f506b61 100644 --- a/lerobot/common/errors.py +++ b/lerobot/common/errors.py @@ -1,9 +1,3 @@ -class ConnectionError(Exception): - """Base exception class for connection errors.""" - - pass - - class DeviceNotConnectedError(ConnectionError): """Exception raised when the device is not connected.""" diff --git a/lerobot/common/utils/robot_utils.py b/lerobot/common/utils/robot_utils.py index 19bb637e..593773b5 100644 --- a/lerobot/common/utils/robot_utils.py +++ b/lerobot/common/utils/robot_utils.py @@ -28,24 +28,3 @@ def safe_disconnect(func): raise e return wrapper - - -class RobotDeviceNotConnectedError(Exception): - """Exception raised when the robot device is not connected.""" - - def __init__( - self, message="This robot device is not connected. Try calling `robot_device.connect()` first." - ): - self.message = message - super().__init__(self.message) - - -class RobotDeviceAlreadyConnectedError(Exception): - """Exception raised when the robot device is already connected.""" - - def __init__( - self, - message="This robot device is already connected. Try not calling `robot_device.connect()` twice.", - ): - self.message = message - super().__init__(self.message) From e2d13ba7e4b839cab7c65fc375b789edecd6d468 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Tue, 4 Mar 2025 11:38:31 +0100 Subject: [PATCH 021/190] Update paths --- lerobot/common/cameras/utils.py | 17 --------- lerobot/common/robots/__init__.py | 4 ++ lerobot/common/robots/utils.py | 59 ++++++++++++++++++++++-------- lerobot/configs/control.py | 2 +- lerobot/scripts/configure_motor.py | 4 +- tests/test_cameras.py | 14 +++---- tests/test_motors.py | 10 ++--- tests/test_robots.py | 14 +++---- tests/utils.py | 17 ++++++--- 9 files changed, 82 insertions(+), 59 deletions(-) create mode 100644 lerobot/common/robots/__init__.py diff --git a/lerobot/common/cameras/utils.py b/lerobot/common/cameras/utils.py index 56e71a48..f0b6ce5f 100644 --- a/lerobot/common/cameras/utils.py +++ b/lerobot/common/cameras/utils.py @@ -19,20 +19,3 @@ def make_cameras_from_configs(camera_configs: dict[str, CameraConfig]) -> dict[s raise ValueError(f"The motor type '{cfg.type}' is not valid.") return cameras - - -def make_camera(camera_type, **kwargs) -> Camera: - if camera_type == "opencv": - from .opencv import OpenCVCamera, OpenCVCameraConfig - - config = OpenCVCameraConfig(**kwargs) - return OpenCVCamera(config) - - elif camera_type == "intelrealsense": - from .intel import RealSenseCamera, RealSenseCameraConfig - - config = RealSenseCameraConfig(**kwargs) - return RealSenseCamera(config) - - else: - raise ValueError(f"The camera type '{camera_type}' is not valid.") diff --git a/lerobot/common/robots/__init__.py b/lerobot/common/robots/__init__.py new file mode 100644 index 00000000..58b868ed --- /dev/null +++ b/lerobot/common/robots/__init__.py @@ -0,0 +1,4 @@ +from .config import RobotConfig +from .robot import Robot + +__all__ = ["RobotConfig", "Robot"] diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py index cb798632..8f253146 100644 --- a/lerobot/common/robots/utils.py +++ b/lerobot/common/robots/utils.py @@ -1,15 +1,9 @@ +import logging from typing import Protocol -from lerobot.common.robots.aloha.configuration_aloha import AlohaRobotConfig -from lerobot.common.robots.config_abc import ( - ManipulatorRobotConfig, - RobotConfig, -) -from lerobot.common.robots.koch.configuration_koch import KochBimanualRobotConfig, KochRobotConfig -from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig -from lerobot.common.robots.moss.configuration_moss import MossRobotConfig -from lerobot.common.robots.so_100.configuration_so_100 import So100RobotConfig -from lerobot.common.robots.stretch3.configuration_stretch3 import StretchRobotConfig +import numpy as np + +from lerobot.common.robots import RobotConfig def get_arm_id(name, arm_type): @@ -19,8 +13,8 @@ def get_arm_id(name, arm_type): return f"{name}_{arm_type}" +# TODO(aliberts): Remove and point to lerobot.common.robots.Robot class Robot(Protocol): - # TODO(rcadene, aliberts): Add unit test checking the protocol is implemented in the corresponding classes robot_type: str features: dict @@ -34,24 +28,39 @@ class Robot(Protocol): def make_robot_config(robot_type: str, **kwargs) -> RobotConfig: if robot_type == "aloha": + from .aloha.configuration_aloha import AlohaRobotConfig + return AlohaRobotConfig(**kwargs) elif robot_type == "koch": + from .koch.configuration_koch import KochRobotConfig + return KochRobotConfig(**kwargs) - elif robot_type == "koch_bimanual": - return KochBimanualRobotConfig(**kwargs) + # elif robot_type == "koch_bimanual": + # return KochBimanualRobotConfig(**kwargs) elif robot_type == "moss": + from .moss.configuration_moss import MossRobotConfig + return MossRobotConfig(**kwargs) elif robot_type == "so100": + from .so100.configuration_so100 import So100RobotConfig + return So100RobotConfig(**kwargs) elif robot_type == "stretch": + from .stretch3.configuration_stretch3 import StretchRobotConfig + return StretchRobotConfig(**kwargs) elif robot_type == "lekiwi": + from .lekiwi.configuration_lekiwi import LeKiwiRobotConfig + return LeKiwiRobotConfig(**kwargs) else: raise ValueError(f"Robot type '{robot_type}' is not available.") def make_robot_from_config(config: RobotConfig): + from .lekiwi.configuration_lekiwi import LeKiwiRobotConfig + from .manipulator import ManipulatorRobotConfig + if isinstance(config, ManipulatorRobotConfig): from lerobot.common.robots.manipulator import ManipulatorRobot @@ -61,11 +70,31 @@ def make_robot_from_config(config: RobotConfig): return MobileManipulator(config) else: - from lerobot.common.robots.stretch3.robot_stretch3 import StretchRobot + from lerobot.common.robots.stretch3.robot_stretch3 import Stretch3Robot - return StretchRobot(config) + return Stretch3Robot(config) def make_robot(robot_type: str, **kwargs) -> Robot: config = make_robot_config(robot_type, **kwargs) return make_robot_from_config(config) + + +def ensure_safe_goal_position( + goal_pos: np.ndarray, present_pos: np.ndarray, max_relative_target: float | list[float] +): + # Cap relative action target magnitude for safety. + diff = goal_pos - present_pos + max_relative_target = np.array(max_relative_target) + safe_diff = np.min(diff, max_relative_target) + safe_diff = np.max(safe_diff, -max_relative_target) + safe_goal_pos = present_pos + safe_diff + + if not np.allclose(goal_pos, safe_goal_pos): + logging.warning( + "Relative goal position magnitude had to be clamped to be safe.\n" + f" requested relative goal position target: {diff}\n" + f" clamped relative goal position target: {safe_diff}" + ) + + return safe_goal_pos diff --git a/lerobot/configs/control.py b/lerobot/configs/control.py index 94922d1f..109b0ba9 100644 --- a/lerobot/configs/control.py +++ b/lerobot/configs/control.py @@ -4,7 +4,7 @@ from pathlib import Path import draccus -from lerobot.common.robots.config_abc import RobotConfig +from lerobot.common.robots import RobotConfig from lerobot.common.utils.utils import auto_select_torch_device, is_amp_available, is_torch_device_available from lerobot.configs import parser from lerobot.configs.policies import PreTrainedConfig diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py index b6f58410..1a55c6fc 100644 --- a/lerobot/scripts/configure_motor.py +++ b/lerobot/scripts/configure_motor.py @@ -19,7 +19,7 @@ import time def get_motor_bus_cls(brand: str) -> tuple: if brand == "feetech": from lerobot.common.motors.configs import FeetechMotorsBusConfig - from lerobot.common.motors.feetech import ( + from lerobot.common.motors.feetech.feetech import ( MODEL_BAUDRATE_TABLE, SCS_SERIES_BAUDRATE_TABLE, FeetechMotorsBus, @@ -29,7 +29,7 @@ def get_motor_bus_cls(brand: str) -> tuple: elif brand == "dynamixel": from lerobot.common.motors.configs import DynamixelMotorsBusConfig - from lerobot.common.motors.dynamixel import ( + from lerobot.common.motors.dynamixel.dynamixel import ( MODEL_BAUDRATE_TABLE, X_SERIES_BAUDRATE_TABLE, DynamixelMotorsBus, diff --git a/tests/test_cameras.py b/tests/test_cameras.py index 686d1423..54f39df0 100644 --- a/tests/test_cameras.py +++ b/tests/test_cameras.py @@ -24,7 +24,7 @@ pytest -sx 'tests/test_cameras.py::test_camera[intelrealsense-True]' import numpy as np import pytest -from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from tests.utils import TEST_CAMERA_TYPES, make_camera, require_camera # Maximum absolute difference between two consecutive images recorded by a camera. @@ -57,11 +57,11 @@ def test_camera(request, camera_type, mock): camera = make_camera(**camera_kwargs) # Test reading, async reading, disconnecting before connecting raises an error - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): camera.read() - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): camera.async_read() - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): camera.disconnect() # Test deleting the object without connecting first @@ -76,7 +76,7 @@ def test_camera(request, camera_type, mock): assert camera.height is not None # Test connecting twice raises an error - with pytest.raises(RobotDeviceAlreadyConnectedError): + with pytest.raises(DeviceAlreadyConnectedError): camera.connect() # Test reading from the camera @@ -185,9 +185,9 @@ def test_camera(request, camera_type, mock): def test_save_images_from_cameras(tmp_path, request, camera_type, mock): # TODO(rcadene): refactor if camera_type == "opencv": - from lerobot.common.cameras.opencv import save_images_from_cameras + from lerobot.common.cameras.opencv.camera_opencv import save_images_from_cameras elif camera_type == "intelrealsense": - from lerobot.common.cameras.intelrealsense import save_images_from_cameras + from lerobot.common.cameras.intel.camera_realsense import save_images_from_cameras # Small `record_time_s` to speedup unit tests save_images_from_cameras(tmp_path, record_time_s=0.02, mock=mock) diff --git a/tests/test_motors.py b/tests/test_motors.py index 0e8ae9aa..0ad6b4d3 100644 --- a/tests/test_motors.py +++ b/tests/test_motors.py @@ -30,7 +30,7 @@ import time import numpy as np import pytest -from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from lerobot.scripts.find_motors_bus_port import find_port from tests.utils import TEST_MOTOR_TYPES, make_motors_bus, require_motor @@ -89,11 +89,11 @@ def test_motors_bus(request, motor_type, mock): motors_bus = make_motors_bus(motor_type, mock=mock) # Test reading and writing before connecting raises an error - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): motors_bus.read("Torque_Enable") - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): motors_bus.write("Torque_Enable", 1) - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): motors_bus.disconnect() # Test deleting the object without connecting first @@ -104,7 +104,7 @@ def test_motors_bus(request, motor_type, mock): motors_bus.connect() # Test connecting twice raises an error - with pytest.raises(RobotDeviceAlreadyConnectedError): + with pytest.raises(DeviceAlreadyConnectedError): motors_bus.connect() # Test disabling torque and reading torque on all motors diff --git a/tests/test_robots.py b/tests/test_robots.py index 90fd8819..6def3a87 100644 --- a/tests/test_robots.py +++ b/tests/test_robots.py @@ -26,8 +26,8 @@ pytest -sx 'tests/test_robots.py::test_robot[aloha-True]' import pytest import torch +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError from lerobot.common.robots.utils import make_robot -from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError from tests.utils import TEST_ROBOT_TYPES, mock_calibration_dir, require_robot @@ -54,15 +54,15 @@ def test_robot(tmp_path, request, robot_type, mock): # Test using robot before connecting raises an error robot = make_robot(**robot_kwargs) - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): robot.teleop_step() - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): robot.teleop_step(record_data=True) - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): robot.capture_observation() - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): robot.send_action(None) - with pytest.raises(RobotDeviceNotConnectedError): + with pytest.raises(DeviceNotConnectedError): robot.disconnect() # Test deleting the object without connecting first @@ -74,7 +74,7 @@ def test_robot(tmp_path, request, robot_type, mock): assert robot.is_connected # Test connecting twice raises an error - with pytest.raises(RobotDeviceAlreadyConnectedError): + with pytest.raises(DeviceAlreadyConnectedError): robot.connect() # TODO(rcadene, aliberts): Test disconnecting with `__del__` instead of `disconnect` diff --git a/tests/utils.py b/tests/utils.py index 9ffa9ad2..12b30597 100644 --- a/tests/utils.py +++ b/tests/utils.py @@ -23,9 +23,8 @@ import pytest import torch from lerobot import available_cameras, available_motors, available_robots -from lerobot.common.cameras.utils import Camera -from lerobot.common.cameras.utils import make_camera as make_camera_device -from lerobot.common.motors.utils import MotorsBus +from lerobot.common.cameras import Camera +from lerobot.common.motors.motors_bus import MotorsBus from lerobot.common.motors.utils import make_motors_bus as make_motors_bus_device from lerobot.common.utils.import_utils import is_package_available @@ -306,11 +305,19 @@ def mock_calibration_dir(calibration_dir): def make_camera(camera_type: str, **kwargs) -> Camera: if camera_type == "opencv": camera_index = kwargs.pop("camera_index", OPENCV_CAMERA_INDEX) - return make_camera_device(camera_type, camera_index=camera_index, **kwargs) + kwargs["camera_index"] = camera_index + from lerobot.common.cameras.opencv import OpenCVCamera, OpenCVCameraConfig + + config = OpenCVCameraConfig(**kwargs) + return OpenCVCamera(config) elif camera_type == "intelrealsense": serial_number = kwargs.pop("serial_number", INTELREALSENSE_SERIAL_NUMBER) - return make_camera_device(camera_type, serial_number=serial_number, **kwargs) + kwargs["serial_number"] = serial_number + from lerobot.common.cameras.intel import RealSenseCamera, RealSenseCameraConfig + + config = RealSenseCameraConfig(**kwargs) + return RealSenseCamera(config) else: raise ValueError(f"The camera type '{camera_type}' is not valid.") From 7ed7570b17b3d896c490a1408efff9810318560f Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Tue, 4 Mar 2025 11:42:07 +0100 Subject: [PATCH 022/190] WIP Add stretch --- .../robots/stretch3/configuration_stretch3.py | 12 +- .../common/robots/stretch3/robot_stretch3.py | 170 ++++++++---------- 2 files changed, 83 insertions(+), 99 deletions(-) diff --git a/lerobot/common/robots/stretch3/configuration_stretch3.py b/lerobot/common/robots/stretch3/configuration_stretch3.py index 8520c471..79d54670 100644 --- a/lerobot/common/robots/stretch3/configuration_stretch3.py +++ b/lerobot/common/robots/stretch3/configuration_stretch3.py @@ -1,7 +1,10 @@ from dataclasses import dataclass, field -from lerobot.common.cameras.configs import CameraConfig, IntelRealSenseCameraConfig, OpenCVCameraConfig -from lerobot.common.robots.config_abc import RobotConfig +from lerobot.common.cameras import CameraConfig +from lerobot.common.cameras.intel import RealSenseCameraConfig +from lerobot.common.cameras.opencv import OpenCVCameraConfig + +from ..config import RobotConfig @RobotConfig.register_subclass("stretch") @@ -12,6 +15,7 @@ class StretchRobotConfig(RobotConfig): # the number of motors in your follower arms. max_relative_target: int | None = None + # cameras cameras: dict[str, CameraConfig] = field( default_factory=lambda: { "navigation": OpenCVCameraConfig( @@ -21,14 +25,14 @@ class StretchRobotConfig(RobotConfig): height=720, rotation=-90, ), - "head": IntelRealSenseCameraConfig( + "head": RealSenseCameraConfig( name="Intel RealSense D435I", fps=30, width=640, height=480, rotation=90, ), - "wrist": IntelRealSenseCameraConfig( + "wrist": RealSenseCameraConfig( name="Intel RealSense D405", fps=30, width=640, diff --git a/lerobot/common/robots/stretch3/robot_stretch3.py b/lerobot/common/robots/stretch3/robot_stretch3.py index c3be2d9c..ffbd6078 100644 --- a/lerobot/common/robots/stretch3/robot_stretch3.py +++ b/lerobot/common/robots/stretch3/robot_stretch3.py @@ -15,33 +15,55 @@ # limitations under the License. import time -from dataclasses import replace +import numpy as np 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.cameras.utils import make_cameras_from_configs +from lerobot.common.datasets.utils import get_nested_item + +from ..robot import Robot from .configuration_stretch3 import StretchRobotConfig +# {lerobot_keys: stretch.api.keys} +STRETCH_MOTORS = { + "head_pan.pos": "head.head_pan.pos", + "head_tilt.pos": "head.head_tilt.pos", + "lift.pos": "lift.pos", + "arm.pos": "arm.pos", + "wrist_pitch.pos": "end_of_arm.wrist_pitch.pos", + "wrist_roll.pos": "end_of_arm.wrist_roll.pos", + "wrist_yaw.pos": "end_of_arm.wrist_yaw.pos", + "gripper.pos": "end_of_arm.stretch_gripper.pos", + "base_x.vel": "base.x_vel", + "base_y.vel": "base.y_vel", + "base_theta.vel": "base.theta_vel", +} -class StretchRobot(StretchAPI): - """Wrapper of stretch_body.robot.Robot""" - def __init__(self, config: StretchRobotConfig | None = None, **kwargs): - super().__init__() - if config is None: - self.config = StretchRobotConfig(**kwargs) - else: - # Overwrite config arguments using kwargs - self.config = replace(config, **kwargs) +class Stretch3Robot(Robot): + """[Stretch 3](https://hello-robot.com/stretch-3-product), by Hello Robot.""" + config_class = StretchRobotConfig + name = "stretch3" + + def __init__(self, config: StretchRobotConfig): + super().__init__(config) + + self.config = config self.robot_type = self.config.type - self.cameras = self.config.cameras + + self.api = StretchAPI() + self.cameras = make_cameras_from_configs(config.cameras) + self.is_connected = False - self.teleop = None self.logs = {} + self.teleop = None # TODO remove + # TODO(aliberts): test this RobotParams.set_logging_level("WARNING") RobotParams.set_logging_formatter("brief_console_formatter") @@ -49,94 +71,58 @@ class StretchRobot(StretchAPI): self.state_keys = None self.action_keys = None + @property + def state_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(STRETCH_MOTORS),), + "names": {"motors": list(STRETCH_MOTORS)}, + } + + @property + def action_feature(self) -> dict: + return self.state_feature + + @property + def camera_features(self) -> dict[str, dict]: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + cam_ft[cam_key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + def connect(self) -> None: - self.is_connected = self.startup() + self.is_connected = self.api.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 + for cam in self.cameras.values(): + cam.connect() + self.is_connected = self.is_connected and cam.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() + self.calibrate() - def run_calibration(self) -> None: - if not self.is_homed(): - self.home() + def calibrate(self) -> None: + if not self.api.is_homed(): + self.api.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() + def _get_state(self) -> dict: + status = self.api.get_status() + return {k: get_nested_item(status, v, sep=".") for k, v in STRETCH_MOTORS.items()} - if self.teleop is None: - self.teleop = GamePadTeleop(robot_instance=False) - self.teleop.startup(robot=self) + def get_observation(self) -> dict[str, np.ndarray]: + obs_dict = {} 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 dictionaries - 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() + state = self._get_state() self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t if self.state_keys is None: @@ -149,7 +135,6 @@ class StretchRobot(StretchAPI): 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 @@ -161,8 +146,7 @@ class StretchRobot(StretchAPI): return obs_dict - def send_action(self, action: torch.Tensor) -> torch.Tensor: - # TODO(aliberts): return ndarrays instead of torch.Tensors + def send_action(self, action: np.ndarray) -> np.ndarray: if not self.is_connected: raise ConnectionError() @@ -193,16 +177,12 @@ class StretchRobot(StretchAPI): self.teleop._safety_stop(robot=self) def disconnect(self) -> None: - self.stop() + self.api.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() + for cam in self.cameras.values(): + cam.disconnect() self.is_connected = False - - def __del__(self): - self.disconnect() From 06988b2135728c23776be358c36bd1923b488c62 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Tue, 4 Mar 2025 13:32:58 +0100 Subject: [PATCH 023/190] WIP stretch 3 robot & teleop --- .../robots/stretch3/configuration_stretch3.py | 4 +- .../common/robots/stretch3/robot_stretch3.py | 27 ++- lerobot/common/robots/utils.py | 4 +- .../configuration_stretch3.py | 25 +++ .../stretch3_gamepad/teleop_stretch3.py | 180 ++++++++++++++++++ 5 files changed, 220 insertions(+), 20 deletions(-) create mode 100644 lerobot/common/teleoperators/stretch3_gamepad/configuration_stretch3.py create mode 100644 lerobot/common/teleoperators/stretch3_gamepad/teleop_stretch3.py diff --git a/lerobot/common/robots/stretch3/configuration_stretch3.py b/lerobot/common/robots/stretch3/configuration_stretch3.py index 79d54670..47ddb54b 100644 --- a/lerobot/common/robots/stretch3/configuration_stretch3.py +++ b/lerobot/common/robots/stretch3/configuration_stretch3.py @@ -7,9 +7,9 @@ from lerobot.common.cameras.opencv import OpenCVCameraConfig from ..config import RobotConfig -@RobotConfig.register_subclass("stretch") +@RobotConfig.register_subclass("stretch3") @dataclass -class StretchRobotConfig(RobotConfig): +class Stretch3RobotConfig(RobotConfig): # `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. diff --git a/lerobot/common/robots/stretch3/robot_stretch3.py b/lerobot/common/robots/stretch3/robot_stretch3.py index ffbd6078..e07e3f1e 100644 --- a/lerobot/common/robots/stretch3/robot_stretch3.py +++ b/lerobot/common/robots/stretch3/robot_stretch3.py @@ -17,16 +17,16 @@ import time import numpy as np -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.cameras.utils import make_cameras_from_configs +from lerobot.common.constants import OBS_IMAGES, OBS_STATE from lerobot.common.datasets.utils import get_nested_item from ..robot import Robot -from .configuration_stretch3 import StretchRobotConfig +from .configuration_stretch3 import Stretch3RobotConfig # {lerobot_keys: stretch.api.keys} STRETCH_MOTORS = { @@ -47,10 +47,10 @@ STRETCH_MOTORS = { class Stretch3Robot(Robot): """[Stretch 3](https://hello-robot.com/stretch-3-product), by Hello Robot.""" - config_class = StretchRobotConfig + config_class = Stretch3RobotConfig name = "stretch3" - def __init__(self, config: StretchRobotConfig): + def __init__(self, config: Stretch3RobotConfig): super().__init__(config) self.config = config @@ -121,6 +121,7 @@ class Stretch3Robot(Robot): def get_observation(self) -> dict[str, np.ndarray]: obs_dict = {} + # Read Stretch state before_read_t = time.perf_counter() state = self._get_state() self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t @@ -128,21 +129,15 @@ class Stretch3Robot(Robot): if self.state_keys is None: self.state_keys = list(state) - state = torch.as_tensor(list(state.values())) + state = np.asarray(list(state.values())) + obs_dict[OBS_STATE] = state # Capture images from cameras - images = {} - for name in self.cameras: + for cam_key, cam in self.cameras.items(): before_camread_t = time.perf_counter() - images[name] = self.cameras[name].async_read() - 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 dictionaries - obs_dict = {} - obs_dict["observation.state"] = state - for name in self.cameras: - obs_dict[f"observation.images.{name}"] = images[name] + obs_dict[f"{OBS_IMAGES}.{cam_key}"] = cam.async_read() + self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] + self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t return obs_dict diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py index 8f253146..db86e6cc 100644 --- a/lerobot/common/robots/utils.py +++ b/lerobot/common/robots/utils.py @@ -46,9 +46,9 @@ def make_robot_config(robot_type: str, **kwargs) -> RobotConfig: return So100RobotConfig(**kwargs) elif robot_type == "stretch": - from .stretch3.configuration_stretch3 import StretchRobotConfig + from .stretch3.configuration_stretch3 import Stretch3RobotConfig - return StretchRobotConfig(**kwargs) + return Stretch3RobotConfig(**kwargs) elif robot_type == "lekiwi": from .lekiwi.configuration_lekiwi import LeKiwiRobotConfig diff --git a/lerobot/common/teleoperators/stretch3_gamepad/configuration_stretch3.py b/lerobot/common/teleoperators/stretch3_gamepad/configuration_stretch3.py new file mode 100644 index 00000000..507a2158 --- /dev/null +++ b/lerobot/common/teleoperators/stretch3_gamepad/configuration_stretch3.py @@ -0,0 +1,25 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import dataclass + +from ..config import TeleoperatorConfig + + +@TeleoperatorConfig.register_subclass("stretch3") +@dataclass +class Stretch3GamePadConfig(TeleoperatorConfig): + mock: bool = False diff --git a/lerobot/common/teleoperators/stretch3_gamepad/teleop_stretch3.py b/lerobot/common/teleoperators/stretch3_gamepad/teleop_stretch3.py new file mode 100644 index 00000000..adab0842 --- /dev/null +++ b/lerobot/common/teleoperators/stretch3_gamepad/teleop_stretch3.py @@ -0,0 +1,180 @@ +#!/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 + +import numpy as np +from stretch_body.gamepad_teleop import GamePadTeleop +from stretch_body.robot_params import RobotParams + +from lerobot.common.constants import OBS_IMAGES, OBS_STATE +from lerobot.common.datasets.utils import get_nested_item + +from ..teleoperator import Teleoperator +from .configuration_stretch3 import Stretch3GamePadConfig + +# {lerobot_keys: stretch.api.keys} +STRETCH_MOTORS = { + "head_pan.pos": "head.head_pan.pos", + "head_tilt.pos": "head.head_tilt.pos", + "lift.pos": "lift.pos", + "arm.pos": "arm.pos", + "wrist_pitch.pos": "end_of_arm.wrist_pitch.pos", + "wrist_roll.pos": "end_of_arm.wrist_roll.pos", + "wrist_yaw.pos": "end_of_arm.wrist_yaw.pos", + "gripper.pos": "end_of_arm.stretch_gripper.pos", + "base_x.vel": "base.x_vel", + "base_y.vel": "base.y_vel", + "base_theta.vel": "base.theta_vel", +} + + +class Stretch3GamePad(Teleoperator): + """[Stretch 3](https://hello-robot.com/stretch-3-product), by Hello Robot.""" + + config_class = Stretch3GamePadConfig + name = "stretch3" + + def __init__(self, config: Stretch3GamePadConfig): + super().__init__(config) + + self.config = config + self.robot_type = self.config.type + + self.api = GamePadTeleop(robot_instance=False) + + self.is_connected = False + self.logs = {} + + self.teleop = None # TODO remove + + # TODO(aliberts): test this + RobotParams.set_logging_level("WARNING") + RobotParams.set_logging_formatter("brief_console_formatter") + + self.state_keys = None + self.action_keys = None + + @property + def state_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(STRETCH_MOTORS),), + "names": {"motors": list(STRETCH_MOTORS)}, + } + + @property + def action_feature(self) -> dict: + return self.state_feature + + @property + def camera_features(self) -> dict[str, dict]: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + cam_ft[cam_key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + + def connect(self) -> None: + self.is_connected = self.api.startup() + if not self.is_connected: + print("Another process is already using Stretch. Try running 'stretch_free_robot_process.py'") + raise ConnectionError() + + for cam in self.cameras.values(): + cam.connect() + self.is_connected = self.is_connected and cam.is_connected + + if not self.is_connected: + print("Could not connect to the cameras, check that all cameras are plugged-in.") + raise ConnectionError() + + self.calibrate() + + def calibrate(self) -> None: + if not self.api.is_homed(): + self.api.home() + + def _get_state(self) -> dict: + status = self.api.get_status() + return {k: get_nested_item(status, v, sep=".") for k, v in STRETCH_MOTORS.items()} + + def get_observation(self) -> dict[str, np.ndarray]: + obs_dict = {} + + # Read Stretch state + 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 = np.asarray(list(state.values())) + obs_dict[OBS_STATE] = state + + # Capture images from cameras + for cam_key, cam in self.cameras.items(): + before_camread_t = time.perf_counter() + obs_dict[f"{OBS_IMAGES}.{cam_key}"] = cam.async_read() + self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] + self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t + + return obs_dict + + def send_action(self, action: np.ndarray) -> np.ndarray: + 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.api.stop() + if self.teleop is not None: + self.teleop.gamepad_controller.stop() + self.teleop.stop() + + for cam in self.cameras.values(): + cam.disconnect() + + self.is_connected = False From fd64dc84aefb007c95b814a79d5a43e1b8ab161f Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Thu, 6 Mar 2025 10:24:27 +0100 Subject: [PATCH 024/190] Move stretch3 teleop --- .../{stretch3_gamepad => stretch3}/configuration_stretch3.py | 0 .../{stretch3_gamepad => stretch3}/teleop_stretch3.py | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename lerobot/common/teleoperators/{stretch3_gamepad => stretch3}/configuration_stretch3.py (100%) rename lerobot/common/teleoperators/{stretch3_gamepad => stretch3}/teleop_stretch3.py (100%) diff --git a/lerobot/common/teleoperators/stretch3_gamepad/configuration_stretch3.py b/lerobot/common/teleoperators/stretch3/configuration_stretch3.py similarity index 100% rename from lerobot/common/teleoperators/stretch3_gamepad/configuration_stretch3.py rename to lerobot/common/teleoperators/stretch3/configuration_stretch3.py diff --git a/lerobot/common/teleoperators/stretch3_gamepad/teleop_stretch3.py b/lerobot/common/teleoperators/stretch3/teleop_stretch3.py similarity index 100% rename from lerobot/common/teleoperators/stretch3_gamepad/teleop_stretch3.py rename to lerobot/common/teleoperators/stretch3/teleop_stretch3.py From b974e5541f3ae4a55aeff1ee0e67cacc0457f41f Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Thu, 6 Mar 2025 11:46:06 +0100 Subject: [PATCH 025/190] Update stretch teleop --- .../teleoperators/stretch3/teleop_stretch3.py | 150 ++++++------------ 1 file changed, 45 insertions(+), 105 deletions(-) diff --git a/lerobot/common/teleoperators/stretch3/teleop_stretch3.py b/lerobot/common/teleoperators/stretch3/teleop_stretch3.py index adab0842..b23bd402 100644 --- a/lerobot/common/teleoperators/stretch3/teleop_stretch3.py +++ b/lerobot/common/teleoperators/stretch3/teleop_stretch3.py @@ -20,26 +20,35 @@ import numpy as np from stretch_body.gamepad_teleop import GamePadTeleop from stretch_body.robot_params import RobotParams -from lerobot.common.constants import OBS_IMAGES, OBS_STATE -from lerobot.common.datasets.utils import get_nested_item +from lerobot.common.errors import DeviceAlreadyConnectedError from ..teleoperator import Teleoperator from .configuration_stretch3 import Stretch3GamePadConfig -# {lerobot_keys: stretch.api.keys} -STRETCH_MOTORS = { - "head_pan.pos": "head.head_pan.pos", - "head_tilt.pos": "head.head_tilt.pos", - "lift.pos": "lift.pos", - "arm.pos": "arm.pos", - "wrist_pitch.pos": "end_of_arm.wrist_pitch.pos", - "wrist_roll.pos": "end_of_arm.wrist_roll.pos", - "wrist_yaw.pos": "end_of_arm.wrist_yaw.pos", - "gripper.pos": "end_of_arm.stretch_gripper.pos", - "base_x.vel": "base.x_vel", - "base_y.vel": "base.y_vel", - "base_theta.vel": "base.theta_vel", -} +# from stretch_body.gamepad_controller.GamePadController +GAMEPAD_BUTTONS = [ + "middle_led_ring_button_pressed", + "left_stick_x", + "left_stick_y", + "right_stick_x", + "right_stick_y", + "left_stick_button_pressed", + "right_stick_button_pressed", + "bottom_button_pressed", + "top_button_pressed", + "left_button_pressed", + "right_button_pressed", + "left_shoulder_button_pressed", + "right_shoulder_button_pressed", + "select_button_pressed", + "start_button_pressed", + "left_trigger_pulled", + "right_trigger_pulled", + "bottom_pad_pressed", + "top_pad_pressed", + "left_pad_pressed", + "right_pad_pressed", +] class Stretch3GamePad(Teleoperator): @@ -59,122 +68,53 @@ class Stretch3GamePad(Teleoperator): self.is_connected = False self.logs = {} - self.teleop = None # TODO remove - # TODO(aliberts): test this RobotParams.set_logging_level("WARNING") RobotParams.set_logging_formatter("brief_console_formatter") - self.state_keys = None - self.action_keys = None - @property - def state_feature(self) -> dict: + def action_feature(self) -> dict: return { "dtype": "float32", - "shape": (len(STRETCH_MOTORS),), - "names": {"motors": list(STRETCH_MOTORS)}, + "shape": (len(GAMEPAD_BUTTONS),), + "names": {"buttons": GAMEPAD_BUTTONS}, } @property - def action_feature(self) -> dict: - return self.state_feature - - @property - def camera_features(self) -> dict[str, dict]: - cam_ft = {} - for cam_key, cam in self.cameras.items(): - cam_ft[cam_key] = { - "shape": (cam.height, cam.width, cam.channels), - "names": ["height", "width", "channels"], - "info": None, - } - return cam_ft + def feedback_feature(self) -> dict: + return {} def connect(self) -> None: - self.is_connected = self.api.startup() - if not self.is_connected: - print("Another process is already using Stretch. Try running 'stretch_free_robot_process.py'") - raise ConnectionError() + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) - for cam in self.cameras.values(): - cam.connect() - self.is_connected = self.is_connected and cam.is_connected - - if not self.is_connected: - print("Could not connect to the cameras, check that all cameras are plugged-in.") - raise ConnectionError() - - self.calibrate() + self.api.startup() + self.api._update_state() # Check controller can be read & written + self.api._update_modes() + self.is_connected = True def calibrate(self) -> None: - if not self.api.is_homed(): - self.api.home() - - def _get_state(self) -> dict: - status = self.api.get_status() - return {k: get_nested_item(status, v, sep=".") for k, v in STRETCH_MOTORS.items()} - - def get_observation(self) -> dict[str, np.ndarray]: - obs_dict = {} + pass + def get_action(self) -> np.ndarray: # Read Stretch state before_read_t = time.perf_counter() - state = self._get_state() + action = self.api.gamepad_controller.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) + action = np.asarray(list(action.values())) - state = np.asarray(list(state.values())) - obs_dict[OBS_STATE] = state - - # Capture images from cameras - for cam_key, cam in self.cameras.items(): - before_camread_t = time.perf_counter() - obs_dict[f"{OBS_IMAGES}.{cam_key}"] = cam.async_read() - self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] - self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t - - return obs_dict - - def send_action(self, action: np.ndarray) -> np.ndarray: - 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 send_feedback(self, feedback: np.ndarray) -> None: + pass + 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.api.stop() - if self.teleop is not None: - self.teleop.gamepad_controller.stop() - self.teleop.stop() - - for cam in self.cameras.values(): - cam.disconnect() - self.is_connected = False From 4214b017030ce642af7836a7b3470a18a8c30566 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Thu, 6 Mar 2025 12:53:55 +0100 Subject: [PATCH 026/190] Add ViperX --- .../robots/aloha/configuration_aloha.py | 132 ---------- .../common/robots/{aloha => viperx}/README.md | 0 .../robots/viperx/configuration_viperx.py | 39 +++ lerobot/common/robots/viperx/robot_viperx.py | 241 ++++++++++++++++++ 4 files changed, 280 insertions(+), 132 deletions(-) delete mode 100644 lerobot/common/robots/aloha/configuration_aloha.py rename lerobot/common/robots/{aloha => viperx}/README.md (100%) create mode 100644 lerobot/common/robots/viperx/configuration_viperx.py create mode 100644 lerobot/common/robots/viperx/robot_viperx.py diff --git a/lerobot/common/robots/aloha/configuration_aloha.py b/lerobot/common/robots/aloha/configuration_aloha.py deleted file mode 100644 index 8efdbcc4..00000000 --- a/lerobot/common/robots/aloha/configuration_aloha.py +++ /dev/null @@ -1,132 +0,0 @@ -from dataclasses import dataclass, field - -from lerobot.common.cameras.configs import CameraConfig, IntelRealSenseCameraConfig -from lerobot.common.motors.configs import DynamixelMotorsBusConfig, MotorsBusConfig -from lerobot.common.robots.config_abc import ManipulatorRobotConfig, RobotConfig - - -@RobotConfig.register_subclass("aloha") -@dataclass -class AlohaRobotConfig(ManipulatorRobotConfig): - # Specific to Aloha, LeRobot comes with default calibration files. Assuming the motors have been - # properly assembled, no manual calibration step is expected. If you need to run manual calibration, - # simply update this path to ".cache/calibration/aloha" - calibration_dir: str = ".cache/calibration/aloha_default" - - # /!\ FOR SAFETY, READ THIS /!\ - # `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. - # For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default. - # When you feel more confident with teleoperation or running the policy, you can extend - # this safety limit and even removing it by setting it to `null`. - # Also, everything is expected to work safely out-of-the-box, but we highly advise to - # first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml), - # then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully - max_relative_target: int | None = 5 - - leader_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - # window_x - port="/dev/ttyDXL_leader_left", - motors={ - # name: (index, model) - "waist": [1, "xm430-w350"], - "shoulder": [2, "xm430-w350"], - "shoulder_shadow": [3, "xm430-w350"], - "elbow": [4, "xm430-w350"], - "elbow_shadow": [5, "xm430-w350"], - "forearm_roll": [6, "xm430-w350"], - "wrist_angle": [7, "xm430-w350"], - "wrist_rotate": [8, "xl430-w250"], - "gripper": [9, "xc430-w150"], - }, - ), - "right": DynamixelMotorsBusConfig( - # window_x - port="/dev/ttyDXL_leader_right", - motors={ - # name: (index, model) - "waist": [1, "xm430-w350"], - "shoulder": [2, "xm430-w350"], - "shoulder_shadow": [3, "xm430-w350"], - "elbow": [4, "xm430-w350"], - "elbow_shadow": [5, "xm430-w350"], - "forearm_roll": [6, "xm430-w350"], - "wrist_angle": [7, "xm430-w350"], - "wrist_rotate": [8, "xl430-w250"], - "gripper": [9, "xc430-w150"], - }, - ), - } - ) - - follower_arms: dict[str, MotorsBusConfig] = field( - default_factory=lambda: { - "left": DynamixelMotorsBusConfig( - port="/dev/ttyDXL_follower_left", - motors={ - # name: (index, model) - "waist": [1, "xm540-w270"], - "shoulder": [2, "xm540-w270"], - "shoulder_shadow": [3, "xm540-w270"], - "elbow": [4, "xm540-w270"], - "elbow_shadow": [5, "xm540-w270"], - "forearm_roll": [6, "xm540-w270"], - "wrist_angle": [7, "xm540-w270"], - "wrist_rotate": [8, "xm430-w350"], - "gripper": [9, "xm430-w350"], - }, - ), - "right": DynamixelMotorsBusConfig( - port="/dev/ttyDXL_follower_right", - motors={ - # name: (index, model) - "waist": [1, "xm540-w270"], - "shoulder": [2, "xm540-w270"], - "shoulder_shadow": [3, "xm540-w270"], - "elbow": [4, "xm540-w270"], - "elbow_shadow": [5, "xm540-w270"], - "forearm_roll": [6, "xm540-w270"], - "wrist_angle": [7, "xm540-w270"], - "wrist_rotate": [8, "xm430-w350"], - "gripper": [9, "xm430-w350"], - }, - ), - } - ) - - # Troubleshooting: If one of your IntelRealSense cameras freeze during - # data recording due to bandwidth limit, you might need to plug the camera - # on another USB hub or PCIe card. - cameras: dict[str, CameraConfig] = field( - default_factory=lambda: { - "cam_high": IntelRealSenseCameraConfig( - serial_number=128422271347, - fps=30, - width=640, - height=480, - ), - "cam_low": IntelRealSenseCameraConfig( - serial_number=130322270656, - fps=30, - width=640, - height=480, - ), - "cam_left_wrist": IntelRealSenseCameraConfig( - serial_number=218622272670, - fps=30, - width=640, - height=480, - ), - "cam_right_wrist": IntelRealSenseCameraConfig( - serial_number=130322272300, - fps=30, - width=640, - height=480, - ), - } - ) - - mock: bool = False diff --git a/lerobot/common/robots/aloha/README.md b/lerobot/common/robots/viperx/README.md similarity index 100% rename from lerobot/common/robots/aloha/README.md rename to lerobot/common/robots/viperx/README.md diff --git a/lerobot/common/robots/viperx/configuration_viperx.py b/lerobot/common/robots/viperx/configuration_viperx.py new file mode 100644 index 00000000..44256889 --- /dev/null +++ b/lerobot/common/robots/viperx/configuration_viperx.py @@ -0,0 +1,39 @@ +from dataclasses import dataclass, field + +from lerobot.common.cameras import CameraConfig + +from ..config import RobotConfig + + +@RobotConfig.register_subclass("viperx") +@dataclass +class ViperXRobotConfig(RobotConfig): + # /!\ FOR SAFETY, READ THIS /!\ + # `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. + # For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default. + # When you feel more confident with teleoperation or running the policy, you can extend + # this safety limit and even removing it by setting it to `null`. + # Also, everything is expected to work safely out-of-the-box, but we highly advise to + # first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml), + # then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully + max_relative_target: int | None = 5 + + waist: tuple = (1, "xm540-w270") + shoulder: tuple = (2, "xm540-w270") + shoulder_shadow: tuple = (3, "xm540-w270") + elbow: tuple = (4, "xm540-w270") + elbow_shadow: tuple = (5, "xm540-w270") + forearm_roll: tuple = (6, "xm540-w270") + wrist_angle: tuple = (7, "xm540-w270") + wrist_rotate: tuple = (8, "xm430-w350") + gripper: tuple = (9, "xm430-w350") + + # cameras + cameras: dict[str, CameraConfig] = field(default_factory=dict) + # Troubleshooting: If one of your IntelRealSense cameras freeze during + # data recording due to bandwidth limit, you might need to plug the camera + # on another USB hub or PCIe card. + + mock: bool = False diff --git a/lerobot/common/robots/viperx/robot_viperx.py b/lerobot/common/robots/viperx/robot_viperx.py new file mode 100644 index 00000000..4f076514 --- /dev/null +++ b/lerobot/common/robots/viperx/robot_viperx.py @@ -0,0 +1,241 @@ +"""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 + +import numpy as np + +from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.constants import OBS_IMAGES, OBS_STATE +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.dynamixel import ( + DynamixelMotorsBus, + TorqueMode, + run_arm_calibration, +) + +from ..robot import Robot +from ..utils import ensure_safe_goal_position +from .configuration_viperx import ViperXRobotConfig + + +class ViperXRobot(Robot): + """ + [ViperX](https://www.trossenrobotics.com/viperx-300) developed by Trossen Robotics + """ + + config_class = ViperXRobotConfig + name = "viperx" + + def __init__( + self, + config: ViperXRobotConfig, + ): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.arm = DynamixelMotorsBus( + port=self.config.port, + motors={ + "waist": config.waist, + "shoulder": config.shoulder, + "shoulder_shadow": config.shoulder_shadow, + "elbow": config.elbow, + "elbow_shadow": config.elbow_shadow, + "forearm_roll": config.forearm_roll, + "wrist_angle": config.wrist_angle, + "wrist_rotate": config.wrist_rotate, + "gripper": config.gripper, + }, + ) + self.cameras = make_cameras_from_configs(config.cameras) + + self.is_connected = False + self.logs = {} + + @property + def state_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def action_feature(self) -> dict: + return self.state_feature + + @property + def camera_features(self) -> dict[str, dict]: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + key = f"observation.images.{cam_key}" + cam_ft[key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + + def _set_shadow_motors(self): + """ + Set secondary/shadow ID for shoulder and elbow. These joints have two motors. + As a result, if only one of them is required to move to a certain position, + the other will follow. This is to avoid breaking the motors. + """ + shoulder_idx = self.config.shoulder[0] + self.arm.write("Secondary_ID", shoulder_idx, "shoulder_shadow") + + elbow_idx = self.config.elbow[0] + self.arm.write("Secondary_ID", elbow_idx, "elbow_shadow") + + def connect(self): + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + logging.info("Connecting arm.") + self.arm.connect() + + # We assume that at connection time, arm is in a rest position, + # and torque can be safely disabled to run calibration. + self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) + self.calibrate() + + self._set_shadow_motors() + + # Set a velocity limit of 131 as advised by Trossen Robotics + self.arm.write("Velocity_Limit", 131) + + # Use 'extended position mode' for all motors except gripper, because in joint mode the servos can't + # rotate more than 360 degrees (from 0 to 4095) And some mistake can happen while assembling the arm, + # you could end up with a servo with a position 0 or 4095 at a crucial point See [ + # https://emanual.robotis.com/docs/en/dxl/x/x_series/#operating-mode11] + all_motors_except_gripper = [name for name in self.arm.motor_names if name != "gripper"] + if len(all_motors_except_gripper) > 0: + # 4 corresponds to Extended Position on Aloha motors + self.arm.write("Operating_Mode", 4, all_motors_except_gripper) + + # Use 'position control current based' for follower gripper to be limited by the limit of the current. + # It can grasp an object without forcing too much even tho, + # it's goal position is a complete grasp (both gripper fingers are ordered to join and reach a touch). + # 5 corresponds to Current Controlled Position on Aloha gripper follower "xm430-w350" + self.arm.write("Operating_Mode", 5, "gripper") + + # Note: We can't enable torque on the leader gripper since "xc430-w150" doesn't have + # a Current Controlled Position mode. + + logging.info("Activating torque.") + self.arm.write("Torque_Enable", TorqueMode.ENABLED.value) + + # Check arm can be read + self.arm.read("Present_Position") + + # Connect the cameras + for cam in self.cameras.values(): + cam.connect() + + self.is_connected = True + + def calibrate(self): + """After calibration all motors function in human interpretable ranges. + Rotations are expressed in degrees in nominal range of [-180, 180], + and linear motions (like gripper of Aloha) in nominal range of [0, 100]. + """ + arm_calib_path = self.calibration_dir / f"{self.config.id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + # TODO(rcadene): display a warning in __init__ if calibration file not available + logging.info(f"Missing calibration file '{arm_calib_path}'") + calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "follower") + + logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") + arm_calib_path.parent.mkdir(parents=True, exist_ok=True) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + self.arm.set_calibration(calibration) + + def get_observation(self) -> dict[str, np.ndarray]: + """The returned observations do not have a batch dimension.""" + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + obs_dict = {} + + # Read arm position + before_read_t = time.perf_counter() + obs_dict[OBS_STATE] = self.arm.read("Present_Position") + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + # Capture images from cameras + for cam_key, cam in self.cameras.items(): + before_camread_t = time.perf_counter() + obs_dict[f"{OBS_IMAGES}.{cam_key}"] = cam.async_read() + self.logs[f"read_camera_{cam_key}_dt_s"] = cam.logs["delta_timestamp_s"] + self.logs[f"async_read_camera_{cam_key}_dt_s"] = time.perf_counter() - before_camread_t + + return obs_dict + + def send_action(self, action: np.ndarray) -> np.ndarray: + """Command arm to move to a target joint configuration. + + The relative action magnitude may be clipped depending on the configuration parameter + `max_relative_target`. In this case, the action sent differs from original action. + Thus, this function always returns the action actually sent. + + Args: + action (np.ndarray): array containing the goal positions for the motors. + + Raises: + RobotDeviceNotConnectedError: if robot is not connected. + + Returns: + np.ndarray: the action sent to the motors, potentially clipped. + """ + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()`." + ) + + goal_pos = action + + # Cap goal position when too far away from present position. + # /!\ Slower fps expected due to reading from the follower. + if self.config.max_relative_target is not None: + present_pos = self.arm.read("Present_Position") + goal_pos = ensure_safe_goal_position(goal_pos, present_pos, self.config.max_relative_target) + + # Send goal position to the arm + self.arm.write("Goal_Position", goal_pos.astype(np.int32)) + + return goal_pos + + def print_logs(self): + # TODO(aliberts): move robot-specific logs logic here + pass + + def disconnect(self): + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + + self.arm.disconnect() + for cam in self.cameras.values(): + cam.disconnect() + + self.is_connected = False From 5dc3c74e64c83b7b827720f4688c9a9341ad55cc Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Thu, 6 Mar 2025 21:31:35 +0100 Subject: [PATCH 027/190] Add WidowX --- .../widowx/configuration_widowx.py | 49 ++++++ .../teleoperators/widowx/teleop_widowx.py | 160 ++++++++++++++++++ 2 files changed, 209 insertions(+) create mode 100644 lerobot/common/teleoperators/widowx/configuration_widowx.py create mode 100644 lerobot/common/teleoperators/widowx/teleop_widowx.py diff --git a/lerobot/common/teleoperators/widowx/configuration_widowx.py b/lerobot/common/teleoperators/widowx/configuration_widowx.py new file mode 100644 index 00000000..133237e2 --- /dev/null +++ b/lerobot/common/teleoperators/widowx/configuration_widowx.py @@ -0,0 +1,49 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import dataclass + +from ..config import TeleoperatorConfig + + +@TeleoperatorConfig.register_subclass("widowx") +@dataclass +class WidowXTeleopConfig(TeleoperatorConfig): + port: str # Port to connect to the teloperator + mock: bool = False + + # /!\ FOR SAFETY, READ THIS /!\ + # `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. + # For Aloha, for every goal position request, motor rotations are capped at 5 degrees by default. + # When you feel more confident with teleoperation or running the policy, you can extend + # this safety limit and even removing it by setting it to `null`. + # Also, everything is expected to work safely out-of-the-box, but we highly advise to + # first try to teleoperate the grippers only (by commenting out the rest of the motors in this yaml), + # then to gradually add more motors (by uncommenting), until you can teleoperate both arms fully + max_relative_target: int | None = 5 + + # motors + waist: tuple = (1, "xm430-w350") + shoulder: tuple = (2, "xm430-w350") + shoulder_shadow: tuple = (3, "xm430-w350") + elbow: tuple = (4, "xm430-w350") + elbow_shadow: tuple = (5, "xm430-w350") + forearm_roll: tuple = (6, "xm430-w350") + wrist_angle: tuple = (7, "xm430-w350") + wrist_rotate: tuple = (8, "xl430-w250") + gripper: tuple = (9, "xc430-w150") diff --git a/lerobot/common/teleoperators/widowx/teleop_widowx.py b/lerobot/common/teleoperators/widowx/teleop_widowx.py new file mode 100644 index 00000000..c7bcc18b --- /dev/null +++ b/lerobot/common/teleoperators/widowx/teleop_widowx.py @@ -0,0 +1,160 @@ +#!/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 json +import logging +import time + +import numpy as np + +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.dynamixel import ( + DynamixelMotorsBus, + TorqueMode, + run_arm_calibration, +) + +from ..teleoperator import Teleoperator +from .configuration_widowx import WidowXTeleopConfig + + +class WidowXTeleop(Teleoperator): + """ + [WidowX](https://www.trossenrobotics.com/widowx-250) developed by Trossen Robotics + """ + + config_class = WidowXTeleopConfig + name = "widowx" + + def __init__(self, config: WidowXTeleopConfig): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.arm = DynamixelMotorsBus( + port=self.config.port, + motors={ + "waist": config.waist, + "shoulder": config.shoulder, + "shoulder_shadow": config.shoulder_shadow, + "elbow": config.elbow, + "elbow_shadow": config.elbow_shadow, + "forearm_roll": config.forearm_roll, + "wrist_angle": config.wrist_angle, + "wrist_rotate": config.wrist_rotate, + "gripper": config.gripper, + }, + ) + + self.is_connected = False + self.logs = {} + + @property + def action_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def feedback_feature(self) -> dict: + return {} + + def _set_shadow_motors(self): + """ + Set secondary/shadow ID for shoulder and elbow. These joints have two motors. + As a result, if only one of them is required to move to a certain position, + the other will follow. This is to avoid breaking the motors. + """ + shoulder_idx = self.config.shoulder[0] + self.arm.write("Secondary_ID", shoulder_idx, "shoulder_shadow") + + elbow_idx = self.config.elbow[0] + self.arm.write("Secondary_ID", elbow_idx, "elbow_shadow") + + def connect(self): + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + logging.info("Connecting arm.") + self.arm.connect() + + # We assume that at connection time, arm is in a rest position, + # and torque can be safely disabled to run calibration. + self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) + self.calibrate() + + self._set_shadow_motors() + + logging.info("Activating torque.") + self.arm.write("Torque_Enable", TorqueMode.ENABLED.value) + + # Check arm can be read + self.arm.read("Present_Position") + + # Connect the cameras + for cam in self.cameras.values(): + cam.connect() + + self.is_connected = True + + def calibrate(self) -> None: + """After calibration all motors function in human interpretable ranges. + Rotations are expressed in degrees in nominal range of [-180, 180], + and linear motions (like gripper of Aloha) in nominal range of [0, 100]. + """ + arm_calib_path = self.calibration_dir / f"{self.id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + # TODO(rcadene): display a warning in __init__ if calibration file not available + logging.info(f"Missing calibration file '{arm_calib_path}'") + calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "leader") + + logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") + arm_calib_path.parent.mkdir(parents=True, exist_ok=True) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + self.arm.set_calibration(calibration) + + def get_action(self) -> np.ndarray: + """The returned action does not have a batch dimension.""" + # Read arm position + before_read_t = time.perf_counter() + action = self.arm.read("Present_Position") + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + return action + + def send_feedback(self, feedback: np.ndarray) -> None: + # TODO(rcadene, aliberts): Implement force feedback + pass + + def disconnect(self) -> None: + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + + self.arm.disconnect() + self.is_connected = False From a065bd61aec5c5986901126dcd2878908c7127cf Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 10 Mar 2025 18:28:50 +0100 Subject: [PATCH 028/190] Add keyboard teleop --- .../common/teleoperators/keyboard/__init__.py | 4 + .../keyboard/configuration_keyboard.py | 25 ++++ .../teleoperators/keyboard/teleop_keyboard.py | 128 ++++++++++++++++++ 3 files changed, 157 insertions(+) create mode 100644 lerobot/common/teleoperators/keyboard/__init__.py create mode 100644 lerobot/common/teleoperators/keyboard/configuration_keyboard.py create mode 100644 lerobot/common/teleoperators/keyboard/teleop_keyboard.py diff --git a/lerobot/common/teleoperators/keyboard/__init__.py b/lerobot/common/teleoperators/keyboard/__init__.py new file mode 100644 index 00000000..9d27a34d --- /dev/null +++ b/lerobot/common/teleoperators/keyboard/__init__.py @@ -0,0 +1,4 @@ +from .configuration_keyboard import KeyboardTeleopConfig +from .teleop_keyboard import KeyboardTeleop + +__all__ = ["KeyboardTeleopConfig", "KeyboardTeleop"] diff --git a/lerobot/common/teleoperators/keyboard/configuration_keyboard.py b/lerobot/common/teleoperators/keyboard/configuration_keyboard.py new file mode 100644 index 00000000..91b596bf --- /dev/null +++ b/lerobot/common/teleoperators/keyboard/configuration_keyboard.py @@ -0,0 +1,25 @@ +#!/usr/bin/env python + +# Copyright 2024 The HuggingFace Inc. team. All rights reserved. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +from dataclasses import dataclass + +from ..config import TeleoperatorConfig + + +@TeleoperatorConfig.register_subclass("keyboard") +@dataclass +class KeyboardTeleopConfig(TeleoperatorConfig): + mock: bool = False diff --git a/lerobot/common/teleoperators/keyboard/teleop_keyboard.py b/lerobot/common/teleoperators/keyboard/teleop_keyboard.py new file mode 100644 index 00000000..ff85bb40 --- /dev/null +++ b/lerobot/common/teleoperators/keyboard/teleop_keyboard.py @@ -0,0 +1,128 @@ +#!/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 logging +import os +import sys +import time + +import numpy as np + +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError + +from ..teleoperator import Teleoperator +from .configuration_keyboard import KeyboardTeleopConfig + +PYNPUT_AVAILABLE = True +try: + # Only import if there's a valid X server or if we're not on a Pi + if ("DISPLAY" not in os.environ) and ("linux" in sys.platform): + logging.info("No DISPLAY set. Skipping pynput import.") + raise ImportError("pynput blocked intentionally due to no display.") + + from pynput import keyboard +except ImportError: + keyboard = None + PYNPUT_AVAILABLE = False +except Exception as e: + keyboard = None + PYNPUT_AVAILABLE = False + logging.info(f"Could not import pynput: {e}") + + +class KeyboardTeleop(Teleoperator): + """ + Teleop class to use keyboard inputs for control. + """ + + config_class = KeyboardTeleopConfig + name = "keyboard" + + def __init__(self, config: KeyboardTeleopConfig): + super().__init__(config) + self.config = config + self.robot_type = config.type + self.id = config.id + + self.pressed_keys = {} + self.listener = None + self.is_connected = False + self.logs = {} + + @property + def action_feature(self) -> dict: + return { + "dtype": "float32", + "shape": (len(self.arm),), + "names": {"motors": list(self.arm.motors)}, + } + + @property + def feedback_feature(self) -> dict: + return {} + + def connect(self) -> None: + if self.is_connected: + raise DeviceAlreadyConnectedError( + "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." + ) + + if PYNPUT_AVAILABLE: + logging.info("pynput is available - enabling local keyboard listener.") + self.listener = keyboard.Listener( + on_press=self.on_press, + on_release=self.on_release, + ) + self.listener.start() + else: + logging.info("pynput not available - skipping local keyboard listener.") + self.listener = None + + self.is_connected = True + + def calibrate(self) -> None: + pass + + def on_press(self, key): + if hasattr(key, "char"): + self.pressed_keys[key.char] = True + + def on_release(self, key): + if hasattr(key, "char"): + self.pressed_keys[key.char] = False + if key == keyboard.Key.esc: + logging.info("ESC pressed, disconnecting.") + self.disconnect() + + def get_action(self) -> np.ndarray: + before_read_t = time.perf_counter() + # pressed_keys.items is wrapped in a list to avoid any RuntimeError due to dictionary changing size + # during iteration + action = {key for key, val in list(self.pressed_keys.items()) if val} + self.logs["read_pos_dt_s"] = time.perf_counter() - before_read_t + + return action + + def send_feedback(self, feedback: np.ndarray) -> None: + pass + + def disconnect(self) -> None: + if not self.is_connected: + raise DeviceNotConnectedError( + "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." + ) + self.listener.stop() + self.is_connected = False From baf6e66c3ddace884cfe42de4ee220ecd11e9e73 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 10 Mar 2025 18:29:58 +0100 Subject: [PATCH 029/190] Add init files --- lerobot/common/teleoperators/stretch3/__init__.py | 4 ++++ lerobot/common/teleoperators/widowx/__init__.py | 4 ++++ 2 files changed, 8 insertions(+) create mode 100644 lerobot/common/teleoperators/stretch3/__init__.py create mode 100644 lerobot/common/teleoperators/widowx/__init__.py diff --git a/lerobot/common/teleoperators/stretch3/__init__.py b/lerobot/common/teleoperators/stretch3/__init__.py new file mode 100644 index 00000000..9931e5fa --- /dev/null +++ b/lerobot/common/teleoperators/stretch3/__init__.py @@ -0,0 +1,4 @@ +from .configuration_stretch3 import Stretch3GamePadConfig +from .teleop_stretch3 import Stretch3GamePad + +__all__ = ["Stretch3GamePadConfig", "Stretch3GamePad"] diff --git a/lerobot/common/teleoperators/widowx/__init__.py b/lerobot/common/teleoperators/widowx/__init__.py new file mode 100644 index 00000000..c67f0625 --- /dev/null +++ b/lerobot/common/teleoperators/widowx/__init__.py @@ -0,0 +1,4 @@ +from .configuration_widowx import WidowXTeleopConfig +from .teleop_widowx import WidowXTeleop + +__all__ = ["WidowXTeleopConfig", "WidowXTeleop"] From 1ae62c28f7e306bb2f3ce3f0fc37dccb1bd11b81 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 10 Mar 2025 18:33:28 +0100 Subject: [PATCH 030/190] Move lekiwi files --- .../robots/lekiwi/configuration_lekiwi.py | 5 +- lerobot/common/robots/lekiwi/lekiwi_remote.py | 4 +- lerobot/common/robots/lekiwi/robot_lekiwi.py | 692 ++++++++++++++++++ lerobot/common/robots/mobile_manipulator.py | 17 +- 4 files changed, 706 insertions(+), 12 deletions(-) diff --git a/lerobot/common/robots/lekiwi/configuration_lekiwi.py b/lerobot/common/robots/lekiwi/configuration_lekiwi.py index 7878841e..076dbbc2 100644 --- a/lerobot/common/robots/lekiwi/configuration_lekiwi.py +++ b/lerobot/common/robots/lekiwi/configuration_lekiwi.py @@ -1,8 +1,9 @@ from dataclasses import dataclass, field -from lerobot.common.cameras.configs import CameraConfig, OpenCVCameraConfig +from lerobot.common.cameras.configs import CameraConfig +from lerobot.common.cameras.opencv.configuration_opencv import OpenCVCameraConfig from lerobot.common.motors.configs import FeetechMotorsBusConfig, MotorsBusConfig -from lerobot.common.robots.config_abc import RobotConfig +from lerobot.common.robots.config import RobotConfig @RobotConfig.register_subclass("lekiwi") diff --git a/lerobot/common/robots/lekiwi/lekiwi_remote.py b/lerobot/common/robots/lekiwi/lekiwi_remote.py index ad720725..80b522be 100644 --- a/lerobot/common/robots/lekiwi/lekiwi_remote.py +++ b/lerobot/common/robots/lekiwi/lekiwi_remote.py @@ -47,7 +47,7 @@ def calibrate_follower_arm(motors_bus, calib_dir_str): calib_dir.mkdir(parents=True, exist_ok=True) calib_file = calib_dir / "main_follower.json" try: - from lerobot.common.motors.feetech_calibration import run_arm_manual_calibration + from lerobot.common.motors.feetech.feetech_calibration import run_arm_manual_calibration except ImportError: print("[WARNING] Calibration function not available. Skipping calibration.") return @@ -80,7 +80,7 @@ def run_lekiwi(robot_config): """ # Import helper functions and classes from lerobot.common.cameras.utils import make_cameras_from_configs - from lerobot.common.motors.feetech import FeetechMotorsBus, TorqueMode + from lerobot.common.motors.feetech.feetech import FeetechMotorsBus, TorqueMode # Initialize cameras from the robot configuration. cameras = make_cameras_from_configs(robot_config.cameras) diff --git a/lerobot/common/robots/lekiwi/robot_lekiwi.py b/lerobot/common/robots/lekiwi/robot_lekiwi.py index e69de29b..38612885 100644 --- a/lerobot/common/robots/lekiwi/robot_lekiwi.py +++ b/lerobot/common/robots/lekiwi/robot_lekiwi.py @@ -0,0 +1,692 @@ +import base64 +import json +import os +import sys +from pathlib import Path + +import cv2 +import numpy as np +import torch +import zmq + +from lerobot.common.cameras.utils import make_cameras_from_configs +from lerobot.common.errors import DeviceNotConnectedError +from lerobot.common.motors.feetech.feetech import TorqueMode +from lerobot.common.motors.feetech.feetech_calibration import run_arm_manual_calibration +from lerobot.common.motors.motors_bus import MotorsBus +from lerobot.common.motors.utils import make_motors_buses_from_configs +from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig +from lerobot.common.robots.utils import get_arm_id + +PYNPUT_AVAILABLE = True +try: + # Only import if there's a valid X server or if we're not on a Pi + if ("DISPLAY" not in os.environ) and ("linux" in sys.platform): + print("No DISPLAY set. Skipping pynput import.") + raise ImportError("pynput blocked intentionally due to no display.") + + from pynput import keyboard +except ImportError: + keyboard = None + PYNPUT_AVAILABLE = False +except Exception as e: + keyboard = None + PYNPUT_AVAILABLE = False + print(f"Could not import pynput: {e}") + + +class MobileManipulator: + """ + MobileManipulator is a class for connecting to and controlling a remote mobile manipulator robot. + The robot includes a three omniwheel mobile base and a remote follower arm. + The leader arm is connected locally (on the laptop) and its joint positions are recorded and then + forwarded to the remote follower arm (after applying a safety clamp). + In parallel, keyboard teleoperation is used to generate raw velocity commands for the wheels. + """ + + def __init__(self, config: LeKiwiRobotConfig): + """ + Expected keys in config: + - ip, port, video_port for the remote connection. + - calibration_dir, leader_arms, follower_arms, max_relative_target, etc. + """ + self.robot_type = config.type + self.config = config + self.remote_ip = config.ip + self.remote_port = config.port + self.remote_port_video = config.video_port + self.calibration_dir = Path(self.config.calibration_dir) + self.logs = {} + + self.teleop_keys = self.config.teleop_keys + + # For teleoperation, the leader arm (local) is used to record the desired arm pose. + self.leader_arms = make_motors_buses_from_configs(self.config.leader_arms) + + self.follower_arms = make_motors_buses_from_configs(self.config.follower_arms) + + self.cameras = make_cameras_from_configs(self.config.cameras) + + self.is_connected = False + + self.last_frames = {} + self.last_present_speed = {} + self.last_remote_arm_state = torch.zeros(6, dtype=torch.float32) + + # Define three speed levels and a current index + self.speed_levels = [ + {"xy": 0.1, "theta": 30}, # slow + {"xy": 0.2, "theta": 60}, # medium + {"xy": 0.3, "theta": 90}, # fast + ] + self.speed_index = 0 # Start at slow + + # ZeroMQ context and sockets. + self.context = None + self.cmd_socket = None + self.video_socket = None + + # Keyboard state for base teleoperation. + self.running = True + self.pressed_keys = { + "forward": False, + "backward": False, + "left": False, + "right": False, + "rotate_left": False, + "rotate_right": False, + } + + if PYNPUT_AVAILABLE: + print("pynput is available - enabling local keyboard listener.") + self.listener = keyboard.Listener( + on_press=self.on_press, + on_release=self.on_release, + ) + self.listener.start() + else: + print("pynput not available - skipping local keyboard listener.") + self.listener = None + + def get_motor_names(self, arms: dict[str, MotorsBus]) -> list: + return [f"{arm}_{motor}" for arm, bus in arms.items() for motor in bus.motors] + + @property + def camera_features(self) -> dict: + cam_ft = {} + for cam_key, cam in self.cameras.items(): + key = f"observation.images.{cam_key}" + cam_ft[key] = { + "shape": (cam.height, cam.width, cam.channels), + "names": ["height", "width", "channels"], + "info": None, + } + return cam_ft + + @property + def motor_features(self) -> dict: + follower_arm_names = [ + "shoulder_pan", + "shoulder_lift", + "elbow_flex", + "wrist_flex", + "wrist_roll", + "gripper", + ] + observations = ["x_mm", "y_mm", "theta"] + combined_names = follower_arm_names + observations + return { + "action": { + "dtype": "float32", + "shape": (len(combined_names),), + "names": combined_names, + }, + "observation.state": { + "dtype": "float32", + "shape": (len(combined_names),), + "names": combined_names, + }, + } + + @property + def features(self): + return {**self.motor_features, **self.camera_features} + + @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 = [] + for name in self.leader_arms: + available.append(get_arm_id(name, "leader")) + for name in self.follower_arms: + available.append(get_arm_id(name, "follower")) + return available + + def on_press(self, key): + try: + # Movement + if key.char == self.teleop_keys["forward"]: + self.pressed_keys["forward"] = True + elif key.char == self.teleop_keys["backward"]: + self.pressed_keys["backward"] = True + elif key.char == self.teleop_keys["left"]: + self.pressed_keys["left"] = True + elif key.char == self.teleop_keys["right"]: + self.pressed_keys["right"] = True + elif key.char == self.teleop_keys["rotate_left"]: + self.pressed_keys["rotate_left"] = True + elif key.char == self.teleop_keys["rotate_right"]: + self.pressed_keys["rotate_right"] = True + + # Quit teleoperation + elif key.char == self.teleop_keys["quit"]: + self.running = False + return False + + # Speed control + elif key.char == self.teleop_keys["speed_up"]: + self.speed_index = min(self.speed_index + 1, 2) + print(f"Speed index increased to {self.speed_index}") + elif key.char == self.teleop_keys["speed_down"]: + self.speed_index = max(self.speed_index - 1, 0) + print(f"Speed index decreased to {self.speed_index}") + + except AttributeError: + # e.g., if key is special like Key.esc + if key == keyboard.Key.esc: + self.running = False + return False + + def on_release(self, key): + try: + if hasattr(key, "char"): + if key.char == self.teleop_keys["forward"]: + self.pressed_keys["forward"] = False + elif key.char == self.teleop_keys["backward"]: + self.pressed_keys["backward"] = False + elif key.char == self.teleop_keys["left"]: + self.pressed_keys["left"] = False + elif key.char == self.teleop_keys["right"]: + self.pressed_keys["right"] = False + elif key.char == self.teleop_keys["rotate_left"]: + self.pressed_keys["rotate_left"] = False + elif key.char == self.teleop_keys["rotate_right"]: + self.pressed_keys["rotate_right"] = False + except AttributeError: + pass + + def connect(self): + if not self.leader_arms: + raise ValueError("MobileManipulator has no leader arm to connect.") + for name in self.leader_arms: + print(f"Connecting {name} leader arm.") + self.calibrate_leader() + + # Set up ZeroMQ sockets to communicate with the remote mobile robot. + self.context = zmq.Context() + self.cmd_socket = self.context.socket(zmq.PUSH) + connection_string = f"tcp://{self.remote_ip}:{self.remote_port}" + self.cmd_socket.connect(connection_string) + self.cmd_socket.setsockopt(zmq.CONFLATE, 1) + self.video_socket = self.context.socket(zmq.PULL) + video_connection = f"tcp://{self.remote_ip}:{self.remote_port_video}" + self.video_socket.connect(video_connection) + self.video_socket.setsockopt(zmq.CONFLATE, 1) + print( + f"[INFO] Connected to remote robot at {connection_string} and video stream at {video_connection}." + ) + self.is_connected = True + + def load_or_run_calibration_(self, name, arm, arm_type): + arm_id = get_arm_id(name, arm_type) + arm_calib_path = self.calibration_dir / f"{arm_id}.json" + + if arm_calib_path.exists(): + with open(arm_calib_path) as f: + calibration = json.load(f) + else: + print(f"Missing calibration file '{arm_calib_path}'") + 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) + with open(arm_calib_path, "w") as f: + json.dump(calibration, f) + + return calibration + + def calibrate_leader(self): + for name, arm in self.leader_arms.items(): + # Connect the bus + arm.connect() + + # Disable torque on all motors + for motor_id in arm.motors: + arm.write("Torque_Enable", TorqueMode.DISABLED.value, motor_id) + + # Now run calibration + calibration = self.load_or_run_calibration_(name, arm, "leader") + arm.set_calibration(calibration) + + def calibrate_follower(self): + for name, bus in self.follower_arms.items(): + bus.connect() + + # Disable torque on all motors + for motor_id in bus.motors: + bus.write("Torque_Enable", 0, motor_id) + + # Then filter out wheels + arm_only_dict = {k: v for k, v in bus.motors.items() if not k.startswith("wheel_")} + if not arm_only_dict: + continue + + original_motors = bus.motors + bus.motors = arm_only_dict + + calibration = self.load_or_run_calibration_(name, bus, "follower") + bus.set_calibration(calibration) + + bus.motors = original_motors + + def _get_data(self): + """ + Polls the video socket for up to 15 ms. If data arrives, decode only + the *latest* message, returning frames, speed, and arm state. If + nothing arrives for any field, use the last known values. + """ + frames = {} + present_speed = {} + remote_arm_state_tensor = torch.zeros(6, dtype=torch.float32) + + # Poll up to 15 ms + poller = zmq.Poller() + poller.register(self.video_socket, zmq.POLLIN) + socks = dict(poller.poll(15)) + if self.video_socket not in socks or socks[self.video_socket] != zmq.POLLIN: + # No new data arrived → reuse ALL old data + return (self.last_frames, self.last_present_speed, self.last_remote_arm_state) + + # Drain all messages, keep only the last + last_msg = None + while True: + try: + obs_string = self.video_socket.recv_string(zmq.NOBLOCK) + last_msg = obs_string + except zmq.Again: + break + + if not last_msg: + # No new message → also reuse old + return (self.last_frames, self.last_present_speed, self.last_remote_arm_state) + + # Decode only the final message + try: + observation = json.loads(last_msg) + + images_dict = observation.get("images", {}) + new_speed = observation.get("present_speed", {}) + new_arm_state = observation.get("follower_arm_state", None) + + # Convert images + for cam_name, image_b64 in images_dict.items(): + if image_b64: + jpg_data = base64.b64decode(image_b64) + np_arr = np.frombuffer(jpg_data, dtype=np.uint8) + frame_candidate = cv2.imdecode(np_arr, cv2.IMREAD_COLOR) + if frame_candidate is not None: + frames[cam_name] = frame_candidate + + # If remote_arm_state is None and frames is None there is no message then use the previous message + if new_arm_state is not None and frames is not None: + self.last_frames = frames + + remote_arm_state_tensor = torch.tensor(new_arm_state, dtype=torch.float32) + self.last_remote_arm_state = remote_arm_state_tensor + + present_speed = new_speed + self.last_present_speed = new_speed + else: + frames = self.last_frames + + remote_arm_state_tensor = self.last_remote_arm_state + + present_speed = self.last_present_speed + + except Exception as e: + print(f"[DEBUG] Error decoding video message: {e}") + # If decode fails, fall back to old data + return (self.last_frames, self.last_present_speed, self.last_remote_arm_state) + + return frames, present_speed, remote_arm_state_tensor + + def _process_present_speed(self, present_speed: dict) -> torch.Tensor: + state_tensor = torch.zeros(3, dtype=torch.int32) + if present_speed: + decoded = {key: MobileManipulator.raw_to_degps(value) for key, value in present_speed.items()} + if "1" in decoded: + state_tensor[0] = decoded["1"] + if "2" in decoded: + state_tensor[1] = decoded["2"] + if "3" in decoded: + state_tensor[2] = decoded["3"] + return state_tensor + + def teleop_step( + self, record_data: bool = False + ) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]: + if not self.is_connected: + raise DeviceNotConnectedError("MobileManipulator is not connected. Run `connect()` first.") + + speed_setting = self.speed_levels[self.speed_index] + xy_speed = speed_setting["xy"] # e.g. 0.1, 0.25, or 0.4 + theta_speed = speed_setting["theta"] # e.g. 30, 60, or 90 + + # Prepare to assign the position of the leader to the follower + arm_positions = [] + for name in self.leader_arms: + pos = self.leader_arms[name].read("Present_Position") + pos_tensor = torch.from_numpy(pos).float() + # Instead of pos_tensor.item(), use tolist() to convert the entire tensor to a list + arm_positions.extend(pos_tensor.tolist()) + + # (The rest of your code for generating wheel commands remains unchanged) + x_cmd = 0.0 # m/s forward/backward + y_cmd = 0.0 # m/s lateral + theta_cmd = 0.0 # deg/s rotation + if self.pressed_keys["forward"]: + x_cmd += xy_speed + if self.pressed_keys["backward"]: + x_cmd -= xy_speed + if self.pressed_keys["left"]: + y_cmd += xy_speed + if self.pressed_keys["right"]: + y_cmd -= xy_speed + if self.pressed_keys["rotate_left"]: + theta_cmd += theta_speed + if self.pressed_keys["rotate_right"]: + theta_cmd -= theta_speed + + wheel_commands = self.body_to_wheel_raw(x_cmd, y_cmd, theta_cmd) + + message = {"raw_velocity": wheel_commands, "arm_positions": arm_positions} + self.cmd_socket.send_string(json.dumps(message)) + + if not record_data: + return + + obs_dict = self.capture_observation() + + arm_state_tensor = torch.tensor(arm_positions, dtype=torch.float32) + + wheel_velocity_tuple = self.wheel_raw_to_body(wheel_commands) + wheel_velocity_mm = ( + wheel_velocity_tuple[0] * 1000.0, + wheel_velocity_tuple[1] * 1000.0, + wheel_velocity_tuple[2], + ) + wheel_tensor = torch.tensor(wheel_velocity_mm, dtype=torch.float32) + action_tensor = torch.cat([arm_state_tensor, wheel_tensor]) + action_dict = {"action": action_tensor} + + return obs_dict, action_dict + + def capture_observation(self) -> dict: + """ + Capture observations from the remote robot: current follower arm positions, + present wheel speeds (converted to body-frame velocities: x, y, theta), + and a camera frame. + """ + if not self.is_connected: + raise DeviceNotConnectedError("Not connected. Run `connect()` first.") + + frames, present_speed, remote_arm_state_tensor = self._get_data() + + body_state = self.wheel_raw_to_body(present_speed) + + body_state_mm = (body_state[0] * 1000.0, body_state[1] * 1000.0, body_state[2]) # Convert x,y to mm/s + wheel_state_tensor = torch.tensor(body_state_mm, dtype=torch.float32) + combined_state_tensor = torch.cat((remote_arm_state_tensor, wheel_state_tensor), dim=0) + + obs_dict = {"observation.state": combined_state_tensor} + + # Loop over each configured camera + for cam_name, cam in self.cameras.items(): + frame = frames.get(cam_name, None) + if frame is None: + # Create a black image using the camera's configured width, height, and channels + frame = np.zeros((cam.height, cam.width, cam.channels), dtype=np.uint8) + obs_dict[f"observation.images.{cam_name}"] = torch.from_numpy(frame) + + return obs_dict + + def send_action(self, action: torch.Tensor) -> torch.Tensor: + if not self.is_connected: + raise DeviceNotConnectedError("Not connected. Run `connect()` first.") + + # Ensure the action tensor has at least 9 elements: + # - First 6: arm positions. + # - Last 3: base commands. + if action.numel() < 9: + # Pad with zeros if there are not enough elements. + padded = torch.zeros(9, dtype=action.dtype) + padded[: action.numel()] = action + action = padded + + # Extract arm and base actions. + arm_actions = action[:6].flatten() + base_actions = action[6:].flatten() + + x_cmd_mm = base_actions[0].item() # mm/s + y_cmd_mm = base_actions[1].item() # mm/s + theta_cmd = base_actions[2].item() # deg/s + + # Convert mm/s to m/s for the kinematics calculations. + x_cmd = x_cmd_mm / 1000.0 # m/s + y_cmd = y_cmd_mm / 1000.0 # m/s + + # Compute wheel commands from body commands. + wheel_commands = self.body_to_wheel_raw(x_cmd, y_cmd, theta_cmd) + + arm_positions_list = arm_actions.tolist() + + message = {"raw_velocity": wheel_commands, "arm_positions": arm_positions_list} + self.cmd_socket.send_string(json.dumps(message)) + + return action + + def print_logs(self): + pass + + def disconnect(self): + if not self.is_connected: + raise DeviceNotConnectedError("Not connected.") + if self.cmd_socket: + stop_cmd = { + "raw_velocity": {"left_wheel": 0, "back_wheel": 0, "right_wheel": 0}, + "arm_positions": {}, + } + self.cmd_socket.send_string(json.dumps(stop_cmd)) + self.cmd_socket.close() + if self.video_socket: + self.video_socket.close() + if self.context: + self.context.term() + if PYNPUT_AVAILABLE: + self.listener.stop() + self.is_connected = False + print("[INFO] Disconnected from remote robot.") + + def __del__(self): + if getattr(self, "is_connected", False): + self.disconnect() + if PYNPUT_AVAILABLE: + self.listener.stop() + + @staticmethod + def degps_to_raw(degps: float) -> int: + steps_per_deg = 4096.0 / 360.0 + speed_in_steps = abs(degps) * steps_per_deg + speed_int = int(round(speed_in_steps)) + if speed_int > 0x7FFF: + speed_int = 0x7FFF + if degps < 0: + return speed_int | 0x8000 + else: + return speed_int & 0x7FFF + + @staticmethod + def raw_to_degps(raw_speed: int) -> float: + steps_per_deg = 4096.0 / 360.0 + magnitude = raw_speed & 0x7FFF + degps = magnitude / steps_per_deg + if raw_speed & 0x8000: + degps = -degps + return degps + + def body_to_wheel_raw( + self, + x_cmd: float, + y_cmd: float, + theta_cmd: float, + wheel_radius: float = 0.05, + base_radius: float = 0.125, + max_raw: int = 3000, + ) -> dict: + """ + Convert desired body-frame velocities into wheel raw commands. + + Parameters: + x_cmd : Linear velocity in x (m/s). + y_cmd : Linear velocity in y (m/s). + theta_cmd : Rotational velocity (deg/s). + wheel_radius: Radius of each wheel (meters). + base_radius : Distance from the center of rotation to each wheel (meters). + max_raw : Maximum allowed raw command (ticks) per wheel. + + Returns: + A dictionary with wheel raw commands: + {"left_wheel": value, "back_wheel": value, "right_wheel": value}. + + Notes: + - Internally, the method converts theta_cmd to rad/s for the kinematics. + - The raw command is computed from the wheels angular speed in deg/s + using degps_to_raw(). If any command exceeds max_raw, all commands + are scaled down proportionally. + """ + # Convert rotational velocity from deg/s to rad/s. + theta_rad = theta_cmd * (np.pi / 180.0) + # Create the body velocity vector [x, y, theta_rad]. + velocity_vector = np.array([x_cmd, y_cmd, theta_rad]) + + # Define the wheel mounting angles with a -90° offset. + angles = np.radians(np.array([240, 120, 0]) - 90) + # Build the kinematic matrix: each row maps body velocities to a wheel’s linear speed. + # The third column (base_radius) accounts for the effect of rotation. + m = np.array([[np.cos(a), np.sin(a), base_radius] for a in angles]) + + # Compute each wheel’s linear speed (m/s) and then its angular speed (rad/s). + wheel_linear_speeds = m.dot(velocity_vector) + wheel_angular_speeds = wheel_linear_speeds / wheel_radius + + # Convert wheel angular speeds from rad/s to deg/s. + wheel_degps = wheel_angular_speeds * (180.0 / np.pi) + + # Scaling + steps_per_deg = 4096.0 / 360.0 + raw_floats = [abs(degps) * steps_per_deg for degps in wheel_degps] + max_raw_computed = max(raw_floats) + if max_raw_computed > max_raw: + scale = max_raw / max_raw_computed + wheel_degps = wheel_degps * scale + + # Convert each wheel’s angular speed (deg/s) to a raw integer. + wheel_raw = [MobileManipulator.degps_to_raw(deg) for deg in wheel_degps] + + return {"left_wheel": wheel_raw[0], "back_wheel": wheel_raw[1], "right_wheel": wheel_raw[2]} + + def wheel_raw_to_body( + self, wheel_raw: dict, wheel_radius: float = 0.05, base_radius: float = 0.125 + ) -> tuple: + """ + Convert wheel raw command feedback back into body-frame velocities. + + Parameters: + wheel_raw : Dictionary with raw wheel commands (keys: "left_wheel", "back_wheel", "right_wheel"). + wheel_radius: Radius of each wheel (meters). + base_radius : Distance from the robot center to each wheel (meters). + + Returns: + A tuple (x_cmd, y_cmd, theta_cmd) where: + x_cmd : Linear velocity in x (m/s). + y_cmd : Linear velocity in y (m/s). + theta_cmd : Rotational velocity in deg/s. + """ + # Extract the raw values in order. + raw_list = [ + int(wheel_raw.get("left_wheel", 0)), + int(wheel_raw.get("back_wheel", 0)), + int(wheel_raw.get("right_wheel", 0)), + ] + + # Convert each raw command back to an angular speed in deg/s. + wheel_degps = np.array([MobileManipulator.raw_to_degps(r) for r in raw_list]) + # Convert from deg/s to rad/s. + wheel_radps = wheel_degps * (np.pi / 180.0) + # Compute each wheel’s linear speed (m/s) from its angular speed. + wheel_linear_speeds = wheel_radps * wheel_radius + + # Define the wheel mounting angles with a -90° offset. + angles = np.radians(np.array([240, 120, 0]) - 90) + m = np.array([[np.cos(a), np.sin(a), base_radius] for a in angles]) + + # Solve the inverse kinematics: body_velocity = M⁻¹ · wheel_linear_speeds. + m_inv = np.linalg.inv(m) + velocity_vector = m_inv.dot(wheel_linear_speeds) + x_cmd, y_cmd, theta_rad = velocity_vector + theta_cmd = theta_rad * (180.0 / np.pi) + return (x_cmd, y_cmd, theta_cmd) + + +class LeKiwi: + def __init__(self, motor_bus): + """ + Initializes the LeKiwi with Feetech motors bus. + """ + self.motor_bus = motor_bus + self.motor_ids = ["left_wheel", "back_wheel", "right_wheel"] + + # Initialize motors in velocity mode. + self.motor_bus.write("Lock", 0) + self.motor_bus.write("Mode", [1, 1, 1], self.motor_ids) + self.motor_bus.write("Lock", 1) + print("Motors set to velocity mode.") + + def read_velocity(self): + """ + Reads the raw speeds for all wheels. Returns a dictionary with motor names: + """ + raw_speeds = self.motor_bus.read("Present_Speed", self.motor_ids) + return { + "left_wheel": int(raw_speeds[0]), + "back_wheel": int(raw_speeds[1]), + "right_wheel": int(raw_speeds[2]), + } + + def set_velocity(self, command_speeds): + """ + Sends raw velocity commands (16-bit encoded values) directly to the motor bus. + The order of speeds must correspond to self.motor_ids. + """ + self.motor_bus.write("Goal_Speed", command_speeds, self.motor_ids) + + def stop(self): + """Stops the robot by setting all motor speeds to zero.""" + self.motor_bus.write("Goal_Speed", [0, 0, 0], self.motor_ids) + print("Motors stopped.") diff --git a/lerobot/common/robots/mobile_manipulator.py b/lerobot/common/robots/mobile_manipulator.py index 50e68838..38612885 100644 --- a/lerobot/common/robots/mobile_manipulator.py +++ b/lerobot/common/robots/mobile_manipulator.py @@ -10,12 +10,13 @@ import torch import zmq from lerobot.common.cameras.utils import make_cameras_from_configs -from lerobot.common.motors.feetech import TorqueMode -from lerobot.common.motors.feetech_calibration import run_arm_manual_calibration -from lerobot.common.motors.utils import MotorsBus, make_motors_buses_from_configs +from lerobot.common.errors import DeviceNotConnectedError +from lerobot.common.motors.feetech.feetech import TorqueMode +from lerobot.common.motors.feetech.feetech_calibration import run_arm_manual_calibration +from lerobot.common.motors.motors_bus import MotorsBus +from lerobot.common.motors.utils import make_motors_buses_from_configs from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig from lerobot.common.robots.utils import get_arm_id -from lerobot.common.utils.robot_utils import RobotDeviceNotConnectedError PYNPUT_AVAILABLE = True try: @@ -381,7 +382,7 @@ class MobileManipulator: self, record_data: bool = False ) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]: if not self.is_connected: - raise RobotDeviceNotConnectedError("MobileManipulator is not connected. Run `connect()` first.") + raise DeviceNotConnectedError("MobileManipulator is not connected. Run `connect()` first.") speed_setting = self.speed_levels[self.speed_index] xy_speed = speed_setting["xy"] # e.g. 0.1, 0.25, or 0.4 @@ -443,7 +444,7 @@ class MobileManipulator: and a camera frame. """ if not self.is_connected: - raise RobotDeviceNotConnectedError("Not connected. Run `connect()` first.") + raise DeviceNotConnectedError("Not connected. Run `connect()` first.") frames, present_speed, remote_arm_state_tensor = self._get_data() @@ -467,7 +468,7 @@ class MobileManipulator: def send_action(self, action: torch.Tensor) -> torch.Tensor: if not self.is_connected: - raise RobotDeviceNotConnectedError("Not connected. Run `connect()` first.") + raise DeviceNotConnectedError("Not connected. Run `connect()` first.") # Ensure the action tensor has at least 9 elements: # - First 6: arm positions. @@ -505,7 +506,7 @@ class MobileManipulator: def disconnect(self): if not self.is_connected: - raise RobotDeviceNotConnectedError("Not connected.") + raise DeviceNotConnectedError("Not connected.") if self.cmd_socket: stop_cmd = { "raw_velocity": {"left_wheel": 0, "back_wheel": 0, "right_wheel": 0}, From 9bd07881315ac04eaced095763f6d0c9837d2550 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Mon, 10 Mar 2025 18:34:01 +0100 Subject: [PATCH 031/190] Update paths --- .../datasets/v2/convert_dataset_v1_to_v2.py | 2 +- lerobot/common/robots/manipulator.py | 89 ++++++++++++------- 2 files changed, 59 insertions(+), 32 deletions(-) diff --git a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py index 5e0533af..6d8712e3 100644 --- a/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py +++ b/lerobot/common/datasets/v2/convert_dataset_v1_to_v2.py @@ -141,7 +141,7 @@ from lerobot.common.datasets.video_utils import ( get_image_pixel_channels, get_video_info, ) -from lerobot.common.robots.config_abc import RobotConfig +from lerobot.common.robots import RobotConfig from lerobot.common.robots.utils import make_robot_config V16 = "v1.6" diff --git a/lerobot/common/robots/manipulator.py b/lerobot/common/robots/manipulator.py index 556dc81d..69ce212e 100644 --- a/lerobot/common/robots/manipulator.py +++ b/lerobot/common/robots/manipulator.py @@ -5,39 +5,66 @@ and send orders to its motors. # calibration procedure, to make it easy for people to add their own robot. import json -import logging import time import warnings +from dataclasses import dataclass, field from pathlib import Path +from typing import Sequence import numpy as np import torch +from lerobot.common.cameras.configs import CameraConfig from lerobot.common.cameras.utils import make_cameras_from_configs -from lerobot.common.motors.utils import MotorsBus, make_motors_buses_from_configs -from lerobot.common.robots.config_abc import ManipulatorRobotConfig -from lerobot.common.robots.utils import get_arm_id -from lerobot.common.utils.robot_utils import RobotDeviceAlreadyConnectedError, RobotDeviceNotConnectedError +from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnectedError +from lerobot.common.motors.configs import MotorsBusConfig +from lerobot.common.motors.motors_bus import MotorsBus +from lerobot.common.motors.utils import make_motors_buses_from_configs +from lerobot.common.robots.config import RobotConfig +from lerobot.common.robots.utils import ensure_safe_goal_position, get_arm_id -def ensure_safe_goal_position( - goal_pos: torch.Tensor, present_pos: torch.Tensor, max_relative_target: float | list[float] -): - # Cap relative action target magnitude for safety. - diff = goal_pos - present_pos - max_relative_target = torch.tensor(max_relative_target) - safe_diff = torch.minimum(diff, max_relative_target) - safe_diff = torch.maximum(safe_diff, -max_relative_target) - safe_goal_pos = present_pos + safe_diff +@dataclass +class ManipulatorRobotConfig(RobotConfig): + leader_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) + follower_arms: dict[str, MotorsBusConfig] = field(default_factory=lambda: {}) + cameras: dict[str, CameraConfig] = field(default_factory=lambda: {}) - if not torch.allclose(goal_pos, safe_goal_pos): - logging.warning( - "Relative goal position magnitude had to be clamped to be safe.\n" - f" requested relative goal position target: {diff}\n" - f" clamped relative goal position target: {safe_diff}" - ) + # Optionally limit 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 (assumes all follower arms have the same number of + # motors). + max_relative_target: list[float] | float | None = None - return safe_goal_pos + # Optionally set the leader arm in torque mode with the gripper motor set to this angle. This makes it + # possible to squeeze the gripper and have it spring back to an open position on its own. If None, the + # gripper is not put in torque mode. + gripper_open_degree: float | None = None + + mock: bool = False + + def __post_init__(self): + if self.mock: + for arm in self.leader_arms.values(): + if not arm.mock: + arm.mock = True + for arm in self.follower_arms.values(): + if not arm.mock: + arm.mock = True + for cam in self.cameras.values(): + if not cam.mock: + cam.mock = True + + if self.max_relative_target is not None and isinstance(self.max_relative_target, Sequence): + for name in self.follower_arms: + if len(self.follower_arms[name].motors) != len(self.max_relative_target): + raise ValueError( + f"len(max_relative_target)={len(self.max_relative_target)} but the follower arm with name {name} has " + f"{len(self.follower_arms[name].motors)} motors. Please make sure that the " + f"`max_relative_target` list has as many parameters as there are motors per arm. " + "Note: This feature does not yet work with robots where different follower arms have " + "different numbers of motors." + ) class ManipulatorRobot: @@ -210,7 +237,7 @@ class ManipulatorRobot: def connect(self): if self.is_connected: - raise RobotDeviceAlreadyConnectedError( + raise DeviceAlreadyConnectedError( "ManipulatorRobot is already connected. Do not run `robot.connect()` twice." ) @@ -228,9 +255,9 @@ class ManipulatorRobot: self.leader_arms[name].connect() if self.robot_type in ["koch", "koch_bimanual", "aloha"]: - from lerobot.common.motors.dynamixel import TorqueMode + from lerobot.common.motors.dynamixel.dynamixel import TorqueMode elif self.robot_type in ["so100", "moss", "lekiwi"]: - from lerobot.common.motors.feetech import TorqueMode + from lerobot.common.motors.feetech.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. @@ -295,12 +322,12 @@ class ManipulatorRobot: print(f"Missing calibration file '{arm_calib_path}'") if self.robot_type in ["koch", "koch_bimanual", "aloha"]: - from lerobot.common.motors.dynamixel_calibration import run_arm_calibration + from lerobot.common.motors.dynamixel.dynamixel_calibration import run_arm_calibration calibration = run_arm_calibration(arm, self.robot_type, name, arm_type) elif self.robot_type in ["so100", "moss", "lekiwi"]: - from lerobot.common.motors.feetech_calibration import ( + from lerobot.common.motors.feetech.feetech_calibration import ( run_arm_manual_calibration, ) @@ -322,7 +349,7 @@ class ManipulatorRobot: def set_koch_robot_preset(self): def set_operating_mode_(arm): - from lerobot.common.motors.dynamixel import TorqueMode + from lerobot.common.motors.dynamixel.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.") @@ -432,7 +459,7 @@ class ManipulatorRobot: self, record_data=False ) -> None | tuple[dict[str, torch.Tensor], dict[str, torch.Tensor]]: if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( "ManipulatorRobot is not connected. You need to run `robot.connect()`." ) @@ -512,7 +539,7 @@ class ManipulatorRobot: def capture_observation(self): """The returned observations do not have a batch dimension.""" if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( "ManipulatorRobot is not connected. You need to run `robot.connect()`." ) @@ -558,7 +585,7 @@ class ManipulatorRobot: action: tensor containing the concatenated goal positions for the follower arms. """ if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( "ManipulatorRobot is not connected. You need to run `robot.connect()`." ) @@ -593,7 +620,7 @@ class ManipulatorRobot: def disconnect(self): if not self.is_connected: - raise RobotDeviceNotConnectedError( + raise DeviceNotConnectedError( "ManipulatorRobot is not connected. You need to run `robot.connect()` before disconnecting." ) From 2357d4acebfe57f0cb4b651a78218188cfd29212 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Wed, 12 Mar 2025 17:15:39 +0100 Subject: [PATCH 032/190] Update base classes typing --- lerobot/common/robots/robot.py | 9 +++++---- lerobot/common/teleoperators/teleoperator.py | 7 +++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/lerobot/common/robots/robot.py b/lerobot/common/robots/robot.py index 50fd9154..d08b8c32 100644 --- a/lerobot/common/robots/robot.py +++ b/lerobot/common/robots/robot.py @@ -1,12 +1,13 @@ import abc - -import numpy as np +from typing import Any from lerobot.common.constants import HF_LEROBOT_CALIBRATION, ROBOTS from .config import RobotConfig +# TODO(aliberts): action/obs typing such as Generic[ObsType, ActType] similar to gym.Env ? +# https://github.com/Farama-Foundation/Gymnasium/blob/3287c869f9a48d99454306b0d4b4ec537f0f35e3/gymnasium/core.py#L23 class Robot(abc.ABC): """The main LeRobot class for implementing robots.""" @@ -45,12 +46,12 @@ class Robot(abc.ABC): pass @abc.abstractmethod - def get_observation(self) -> dict[str, np.ndarray]: + def get_observation(self) -> dict[str, Any]: """Gets observation from the robot.""" pass @abc.abstractmethod - def send_action(self, action: np.ndarray) -> np.ndarray: + def send_action(self, action: dict[str, Any]) -> dict[str, Any]: """Sends actions to the robot.""" pass diff --git a/lerobot/common/teleoperators/teleoperator.py b/lerobot/common/teleoperators/teleoperator.py index f06b1983..2aa1d662 100644 --- a/lerobot/common/teleoperators/teleoperator.py +++ b/lerobot/common/teleoperators/teleoperator.py @@ -1,6 +1,5 @@ import abc - -import numpy as np +from typing import Any from lerobot.common.constants import HF_LEROBOT_CALIBRATION, TELEOPERATORS @@ -41,12 +40,12 @@ class Teleoperator(abc.ABC): pass @abc.abstractmethod - def get_action(self) -> np.ndarray: + def get_action(self) -> dict[str, Any]: """Gets the action to send to a teleoperator.""" pass @abc.abstractmethod - def send_feedback(self, feedback: np.ndarray) -> None: + def send_feedback(self, feedback: dict[str, Any]) -> None: """Sends feedback captured from a robot to the teleoperator.""" pass From d6f1359e69174c3d3ef537ab4c3c93b7407256f8 Mon Sep 17 00:00:00 2001 From: Simon Alibert Date: Wed, 12 Mar 2025 17:16:09 +0100 Subject: [PATCH 033/190] Remove motors from Koch config --- lerobot/common/robots/koch/configuration_koch.py | 10 ---------- lerobot/common/robots/koch/robot_koch.py | 12 ++++++------ 2 files changed, 6 insertions(+), 16 deletions(-) diff --git a/lerobot/common/robots/koch/configuration_koch.py b/lerobot/common/robots/koch/configuration_koch.py index d6ec3da5..1f465e94 100644 --- a/lerobot/common/robots/koch/configuration_koch.py +++ b/lerobot/common/robots/koch/configuration_koch.py @@ -16,15 +16,5 @@ class KochRobotConfig(RobotConfig): # the number of motors in your follower arms. max_relative_target: int | None = None - mock: bool = False - - # motors - shoulder_pan: tuple = (1, "xl430-w250") - shoulder_lift: tuple = (2, "xl430-w250") - elbow_flex: tuple = (3, "xl330-m288") - wrist_flex: tuple = (4, "xl330-m288") - wrist_roll: tuple = (5, "xl330-m288") - gripper: tuple = (6, "xl330-m288") - # cameras cameras: dict[str, CameraConfig] = field(default_factory=dict) diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py index 469953c2..9cf471f6 100644 --- a/lerobot/common/robots/koch/robot_koch.py +++ b/lerobot/common/robots/koch/robot_koch.py @@ -54,12 +54,12 @@ class KochRobot(Robot): self.arm = DynamixelMotorsBus( port=self.config.port, motors={ - "shoulder_pan": config.shoulder_pan, - "shoulder_lift": config.shoulder_lift, - "elbow_flex": config.elbow_flex, - "wrist_flex": config.wrist_flex, - "wrist_roll": config.wrist_roll, - "gripper": config.gripper, + "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"), }, ) self.cameras = make_cameras_from_configs(config.cameras) From 1f7ddc1d76862ae629fcb6c2c84f757e4e84c5f9 Mon Sep 17 00:00:00 2001 From: Simon Alibert <75076266+aliberts@users.noreply.github.com> Date: Fri, 14 Mar 2025 11:31:23 +0100 Subject: [PATCH 034/190] New Feetech calibration (#859) Co-authored-by: Pepijn Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- lerobot/common/motors/feetech/__init__.py | 9 +- lerobot/common/motors/feetech/feetech.py | 300 ++------- .../motors/feetech/feetech_calibration.py | 594 ++++++------------ lerobot/common/robots/koch/robot_koch.py | 15 +- lerobot/common/robots/lekiwi/lekiwi_remote.py | 4 +- lerobot/common/robots/lekiwi/robot_lekiwi.py | 4 +- lerobot/common/robots/manipulator.py | 95 ++- lerobot/common/robots/mobile_manipulator.py | 4 +- lerobot/common/robots/moss/robot_moss.py | 21 +- lerobot/common/robots/robot.py | 2 + lerobot/common/robots/so100/__init__.py | 6 +- .../robots/so100/configuration_so100.py | 12 +- lerobot/common/robots/so100/robot_so100.py | 45 +- lerobot/common/robots/utils.py | 4 +- lerobot/common/robots/viperx/robot_viperx.py | 15 +- .../teleoperators/keyboard/teleop_keyboard.py | 1 - .../common/teleoperators/koch/teleop_koch.py | 15 +- .../so100/configuration_so100.py | 10 - .../teleoperators/so100/teleop_so100.py | 40 +- lerobot/common/teleoperators/teleoperator.py | 2 + .../teleoperators/widowx/teleop_widowx.py | 15 +- .../calibration_visualization_so100.py | 100 +++ lerobot/scripts/configure_motor.py | 11 +- media/so100/follower_zero.webp | Bin 137504 -> 521258 bytes media/so100/leader_zero.webp | Bin 87888 -> 540388 bytes 25 files changed, 529 insertions(+), 795 deletions(-) create mode 100644 lerobot/scripts/calibration_visualization_so100.py diff --git a/lerobot/common/motors/feetech/__init__.py b/lerobot/common/motors/feetech/__init__.py index 48e0b1c8..a0c15dbf 100644 --- a/lerobot/common/motors/feetech/__init__.py +++ b/lerobot/common/motors/feetech/__init__.py @@ -1,4 +1,9 @@ from .feetech import FeetechMotorsBus, TorqueMode -from .feetech_calibration import run_arm_manual_calibration +from .feetech_calibration import apply_feetech_offsets_from_calibration, run_full_arm_calibration -__all__ = ["FeetechMotorsBus", "TorqueMode", "run_arm_manual_calibration"] +__all__ = [ + "FeetechMotorsBus", + "TorqueMode", + "apply_feetech_offsets_from_calibration", + "run_full_arm_calibration", +] diff --git a/lerobot/common/motors/feetech/feetech.py b/lerobot/common/motors/feetech/feetech.py index 4a9d2cde..8a34d1d3 100644 --- a/lerobot/common/motors/feetech/feetech.py +++ b/lerobot/common/motors/feetech/feetech.py @@ -13,8 +13,6 @@ # limitations under the License. import enum -import logging -import math import time import traceback from copy import deepcopy @@ -31,13 +29,6 @@ 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 @@ -47,7 +38,6 @@ 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) @@ -113,8 +103,6 @@ SCS_SERIES_BAUDRATE_TABLE = { } CALIBRATION_REQUIRED = ["Goal_Position", "Present_Position"] -CONVERT_UINT32_TO_INT32_REQUIRED = ["Goal_Position", "Present_Position"] - MODEL_CONTROL_TABLE = { "scs_series": SCS_SERIES_CONTROL_TABLE, @@ -136,15 +124,63 @@ 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. +def convert_ticks_to_degrees(ticks, model): + resolutions = MODEL_RESOLUTION[model] + # Convert the ticks to degrees + return ticks * (360.0 / resolutions) + + +def convert_degrees_to_ticks(degrees, model): + resolutions = MODEL_RESOLUTION[model] + # Convert degrees to motor ticks + return int(degrees * (resolutions / 360.0)) + + +def adjusted_to_homing_ticks(raw_motor_ticks: int, model: str, motorbus, motor_id: int) -> int: """ - resolutions = [MODEL_RESOLUTION[model] for model in models] - steps = degrees / 180 * np.array(resolutions) / 2 - steps = steps.astype(int) - return steps + Takes a raw reading [0..(res-1)] (e.g. 0..4095) and shifts it so that '2048' + becomes 0 in the homed coordinate system ([-2048..+2047] for 4096 resolution). + """ + resolutions = MODEL_RESOLUTION[model] + + # Shift raw ticks by half-resolution so 2048 -> 0, then wrap [0..res-1]. + ticks = (raw_motor_ticks - (resolutions // 2)) % resolutions + + # If above halfway, fold it into negative territory => [-2048..+2047]. + if ticks > (resolutions // 2): + ticks -= resolutions + + # Flip sign if drive_mode is set. + drive_mode = 0 + if motorbus.calibration is not None: + drive_mode = motorbus.calibration["drive_mode"][motor_id - 1] + + if drive_mode: + ticks *= -1 + + return ticks + + +def adjusted_to_motor_ticks(adjusted_pos: int, model: str, motorbus, motor_id: int) -> int: + """ + Inverse of adjusted_to_homing_ticks(). Takes a 'homed' position in [-2048..+2047] + and recovers the raw [0..(res-1)] ticks with 2048 as midpoint. + """ + # Flip sign if drive_mode was set. + drive_mode = 0 + if motorbus.calibration is not None: + drive_mode = motorbus.calibration["drive_mode"][motor_id - 1] + + if drive_mode: + adjusted_pos *= -1 + + resolutions = MODEL_RESOLUTION[model] + + # Shift by +half-resolution and wrap into [0..res-1]. + # This undoes the earlier shift by -half-resolution. + ticks = (adjusted_pos + (resolutions // 2)) % resolutions + + return ticks def convert_to_bytes(value, bytes, mock=False): @@ -304,8 +340,6 @@ class FeetechMotorsBus: self.group_writers = {} self.logs = {} - self.track_positions = {} - def connect(self): if self.is_connected: raise DeviceAlreadyConnectedError( @@ -402,33 +436,7 @@ class FeetechMotorsBus: 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 @@ -440,34 +448,11 @@ class FeetechMotorsBus: 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] + motor_idx, model = self.motors[name] - # 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`" - ) + # Convert raw motor ticks to homed ticks, then convert the homed ticks to degrees + values[i] = adjusted_to_homing_ticks(values[i], model, self, motor_idx) + values[i] = convert_ticks_to_degrees(values[i], model) elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR: start_pos = self.calibration["start_pos"][calib_idx] @@ -489,103 +474,6 @@ class FeetechMotorsBus: 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: @@ -596,23 +484,11 @@ class FeetechMotorsBus: 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] + motor_idx, model = self.motors[name] - # 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) - - # Subtract 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 + # Convert degrees to homed ticks, then convert the homed ticks to raw ticks + values[i] = convert_degrees_to_ticks(values[i], model) + values[i] = adjusted_to_motor_ticks(values[i], model, self, motor_idx) elif CalibrationMode[calib_mode] == CalibrationMode.LINEAR: start_pos = self.calibration["start_pos"][calib_idx] @@ -625,43 +501,6 @@ class FeetechMotorsBus: 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 occurred - 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.motors.mock_scservo_sdk as scs @@ -735,7 +574,7 @@ class FeetechMotorsBus: self.port_handler.ser.reset_output_buffer() self.port_handler.ser.reset_input_buffer() - # create new group reader + # Create new group reader self.group_readers[group_key] = scs.GroupSyncRead( self.port_handler, self.packet_handler, addr, bytes ) @@ -760,15 +599,8 @@ class FeetechMotorsBus: 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) + values = self.apply_calibration(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) diff --git a/lerobot/common/motors/feetech/feetech_calibration.py b/lerobot/common/motors/feetech/feetech_calibration.py index 778dd0b2..262a5b6e 100644 --- a/lerobot/common/motors/feetech/feetech_calibration.py +++ b/lerobot/common/motors/feetech/feetech_calibration.py @@ -11,488 +11,244 @@ # 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. - -"""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 ..motors_bus import MotorsBus from .feetech import ( CalibrationMode, + FeetechMotorsBus, TorqueMode, - convert_degrees_to_steps, ) 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 > 40: - 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""" +def disable_torque(arm: MotorsBus): 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}...") +def get_calibration_modes(arm: MotorsBus): + """Returns calibration modes for each motor (DEGREE for rotational, LINEAR for gripper).""" + return [ + CalibrationMode.LINEAR.name if name == "gripper" else CalibrationMode.DEGREE.name + for name in arm.motor_names + ] - 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) +def reset_offset(motor_id, motor_bus): + # Open the write lock, changes to EEPROM do NOT persist yet + motor_bus.write("Lock", 1) - arm.write("Torque_Enable", TorqueMode.ENABLED.value) + # Set offset to 0 + motor_name = motor_bus.motor_names[motor_id - 1] + motor_bus.write("Offset", 0, motor_names=[motor_name]) - print(f'{arm.read("Present_Position", "elbow_flex")=}') + # Close the write lock, changes to EEPROM do persist + motor_bus.write("Lock", 0) - calib = {} + # Confirm that the offset is zero by reading it back + confirmed_offset = motor_bus.read("Offset")[motor_id - 1] + print(f"Offset for motor {motor_id} reset to: {confirmed_offset}") + return confirmed_offset - 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) +def calibrate_homing_motor(motor_id, motor_bus): + reset_offset(motor_id, motor_bus) - print("Calibrate gripper") - calib["gripper"] = move_to_calibrate(arm, "gripper", invert_drive_mode=True) - time.sleep(1) + home_ticks = motor_bus.read("Present_Position")[motor_id - 1] # Read index starts at 0 + print(f"Encoder offset (present position in homing position): {home_ticks}") - print("Calibrate wrist_flex") - calib["wrist_flex"] = move_to_calibrate(arm, "wrist_flex") - calib["wrist_flex"] = apply_offset(calib["wrist_flex"], offset=80) + return home_ticks - 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) +def calibrate_linear_motor(motor_id, motor_bus): + motor_names = motor_bus.motor_names + motor_name = motor_names[motor_id - 1] - arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"] + 1024 + 512, "elbow_flex") - time.sleep(1) + reset_offset(motor_id, motor_bus) - def in_between_move_hook(): - nonlocal arm, calib - arm.write("Goal_Position", calib["elbow_flex"]["zero_pos"], "elbow_flex") + input(f"Close the {motor_name}, then press Enter...") + start_pos = motor_bus.read("Present_Position")[motor_id - 1] # Read index starts ar 0 + print(f" [Motor {motor_id}] start position recorded: {start_pos}") - 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) + input(f"Open the {motor_name} fully, then press Enter...") + end_pos = motor_bus.read("Present_Position")[motor_id - 1] # Read index starts ar 0 + print(f" [Motor {motor_id}] end position recorded: {end_pos}") - 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())) + return start_pos, end_pos - 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 - ) +def single_motor_calibration(arm: MotorsBus, motor_id: int): + """Calibrates a single motor and returns its calibration data for updating the calibration file.""" - 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) + disable_torque(arm) + print(f"\n--- Calibrating Motor {motor_id} ---") - calib_modes = [] - for name in arm.motor_names: - if name == "gripper": - calib_modes.append(CalibrationMode.LINEAR.name) - else: - calib_modes.append(CalibrationMode.DEGREE.name) + start_pos = 0 + end_pos = 0 + encoder_offset = 0 + if motor_id == 6: + start_pos, end_pos = calibrate_linear_motor(motor_id, arm) + else: + input("Move the motor to (zero) position, then press Enter...") + encoder_offset = calibrate_homing_motor(motor_id, arm) + + print(f"Calibration for motor ID:{motor_id} done.") + + # Create a calibration dictionary for the single motor 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, + "homing_offset": int(encoder_offset), + "drive_mode": 0, + "start_pos": int(start_pos), + "end_pos": int(end_pos), + "calib_mode": get_calibration_modes(arm)[motor_id - 1], + "motor_name": arm.motor_names[motor_id - 1], } - # 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.") +def run_full_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): + """ + Runs a full calibration process for all motors in a robotic arm. - if not (robot_type == "moss" and arm_type == "follower"): - raise NotImplementedError("Auto calibration only supports the follower of moss arms for now.") + This function calibrates each motor in the arm, determining encoder offsets and + start/end positions for linear and rotational motors. The calibration data is then + stored in a dictionary for later use. - print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...") + **Calibration Process:** + - The user is prompted to move the arm to its homing position before starting. + - Motors with rotational motion are calibrated using a homing method. + - Linear actuators (e.g., grippers) are calibrated separately. + - Encoder offsets, start positions, and end positions are recorded. - 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") - 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", invert_drive_mode=True) - 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) - 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, - 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: + **Example Usage:** ```python - run_arm_calibration(arm, "so100", "left", "follower") + run_full_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.") + disable_torque(arm) 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")) + print("\nMove arm to homing position (middle)") + print( + "See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="zero") + ) # TODO(pepijn): replace with new instruction homing pos (all motors in middle) in tutorial 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) + start_positions = np.zeros(len(arm.motor_indices)) + end_positions = np.zeros(len(arm.motor_indices)) + encoder_offsets = np.zeros(len(arm.motor_indices)) - # Compute homing offset so that `present_position + homing_offset ~= target_position`. - zero_pos = arm.read("Present_Position") - homing_offset = zero_target_pos - zero_pos + modes = get_calibration_modes(arm) - # 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 arbitrarily rotate clockwise from the point of view - # of the previous motor in the kinetic chain. - print("\nMove arm to rotated target position") - print("See: " + URL_TEMPLATE.format(robot=robot_type, arm=arm_type, position="rotated")) - input("Press Enter to continue...") + for i, motor_id in enumerate(arm.motor_indices): + if modes[i] == CalibrationMode.DEGREE.name: + encoder_offsets[i] = calibrate_homing_motor(motor_id, arm) + start_positions[i] = 0 + end_positions[i] = 0 - 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 + for i, motor_id in enumerate(arm.motor_indices): + if modes[i] == CalibrationMode.LINEAR.name: + start_positions[i], end_positions[i] = calibrate_linear_motor(motor_id, arm) + encoder_offsets[i] = 0 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) + print(f"\n calibration of {robot_type} {arm_name} {arm_type} done!") + + # Force drive_mode values (can be static) + drive_modes = [0, 1, 0, 0, 1, 0] 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, + "homing_offset": encoder_offsets.astype(int).tolist(), + "drive_mode": drive_modes, + "start_pos": start_positions.astype(int).tolist(), + "end_pos": end_positions.astype(int).tolist(), + "calib_mode": get_calibration_modes(arm), "motor_names": arm.motor_names, } return calib_dict + + +def run_full_auto_arm_calibration(arm: MotorsBus, robot_type: str, arm_name: str, arm_type: str): + """TODO(pepijn): Add this method later as extra + Example of usage: + ```python + run_full_auto_arm_calibration(arm, "so100", "left", "follower") + ``` + """ + print(f"\nRunning calibration of {robot_type} {arm_name} {arm_type}...") + + +def apply_feetech_offsets_from_calibration(motorsbus: FeetechMotorsBus, calibration_dict: dict): + """ + Reads 'calibration_dict' containing 'homing_offset' and 'motor_names', + then writes each motor's offset to the servo's internal Offset (0x1F) in EPROM. + + This version is modified so each homed position (originally 0) will now read + 2047, i.e. 180° away from 0 in the 4096-count circle. Offsets are permanently + stored in EEPROM, so the servo's Present_Position is hardware-shifted even + after power cycling. + + Steps: + 1) Subtract 2047 from the old offset (so 0 -> 2047). + 2) Clamp to [-2047..+2047]. + 3) Encode sign bit and magnitude into a 12-bit number. + """ + + homing_offsets = calibration_dict["homing_offset"] + motor_names = calibration_dict["motor_names"] + start_pos = calibration_dict["start_pos"] + + # Open the write lock, changes to EEPROM do NOT persist yet + motorsbus.write("Lock", 1) + + # For each motor, set the 'Offset' parameter + for m_name, old_offset in zip(motor_names, homing_offsets, strict=False): + # If bus doesn’t have a motor named m_name, skip + if m_name not in motorsbus.motors: + print(f"Warning: '{m_name}' not found in motorsbus.motors; skipping offset.") + continue + + if m_name == "gripper": + old_offset = start_pos # If gripper set the offset to the start position of the gripper + continue + + # Shift the offset so the homed position reads 2047 + new_offset = old_offset - 2047 + + # Clamp to [-2047..+2047] + if new_offset > 2047: + new_offset = 2047 + print( + f"Warning: '{new_offset}' is getting clamped because its larger then 2047; This should not happen!" + ) + elif new_offset < -2047: + new_offset = -2047 + print( + f"Warning: '{new_offset}' is getting clamped because its smaller then -2047; This should not happen!" + ) + + # Determine the direction (sign) bit and magnitude + direction_bit = 1 if new_offset < 0 else 0 + magnitude = abs(new_offset) + + # Combine sign bit (bit 11) with the magnitude (bits 0..10) + servo_offset = (direction_bit << 11) | magnitude + + # Write offset to servo + motorsbus.write("Offset", servo_offset, motor_names=m_name) + print( + f"Set offset for {m_name}: " + f"old_offset={old_offset}, new_offset={new_offset}, servo_encoded={magnitude} + direction={direction_bit}" + ) + + motorsbus.write("Lock", 0) + print("Offsets have been saved to EEPROM successfully.") diff --git a/lerobot/common/robots/koch/robot_koch.py b/lerobot/common/robots/koch/robot_koch.py index 9cf471f6..3c34bd7b 100644 --- a/lerobot/common/robots/koch/robot_koch.py +++ b/lerobot/common/robots/koch/robot_koch.py @@ -49,7 +49,6 @@ class KochRobot(Robot): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.arm = DynamixelMotorsBus( port=self.config.port, @@ -129,19 +128,17 @@ class KochRobot(Robot): Rotations are expressed in degrees in nominal range of [-180, 180], and linear motions (like gripper of Aloha) in nominal range of [0, 100]. """ - arm_calib_path = self.calibration_dir / f"{self.config.id}.json" - - if arm_calib_path.exists(): - with open(arm_calib_path) as f: + if self.calibration_fpath.exists(): + with open(self.calibration_fpath) as f: calibration = json.load(f) else: # TODO(rcadene): display a warning in __init__ if calibration file not available - logging.info(f"Missing calibration file '{arm_calib_path}'") + logging.info(f"Missing calibration file '{self.calibration_fpath}'") calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "follower") - logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") - arm_calib_path.parent.mkdir(parents=True, exist_ok=True) - with open(arm_calib_path, "w") as f: + logging.info(f"Calibration is done! Saving calibration file '{self.calibration_fpath}'") + self.calibration_fpath.parent.mkdir(parents=True, exist_ok=True) + with open(self.calibration_fpath, "w") as f: json.dump(calibration, f) self.arm.set_calibration(calibration) diff --git a/lerobot/common/robots/lekiwi/lekiwi_remote.py b/lerobot/common/robots/lekiwi/lekiwi_remote.py index 1643cd5e..1a3af5cf 100644 --- a/lerobot/common/robots/lekiwi/lekiwi_remote.py +++ b/lerobot/common/robots/lekiwi/lekiwi_remote.py @@ -61,7 +61,7 @@ def calibrate_follower_arm(motors_bus, calib_dir_str): calib_dir.mkdir(parents=True, exist_ok=True) calib_file = calib_dir / "main_follower.json" try: - from lerobot.common.motors.feetech.feetech_calibration import run_arm_manual_calibration + from lerobot.common.motors.feetech.feetech_calibration import run_full_arm_calibration except ImportError: print("[WARNING] Calibration function not available. Skipping calibration.") return @@ -72,7 +72,7 @@ def calibrate_follower_arm(motors_bus, calib_dir_str): print(f"[INFO] Loaded calibration from {calib_file}") else: print("[INFO] Calibration file not found. Running manual calibration...") - calibration = run_arm_manual_calibration(motors_bus, "lekiwi", "follower_arm", "follower") + calibration = run_full_arm_calibration(motors_bus, "lekiwi", "follower_arm", "follower") print(f"[INFO] Calibration complete. Saving to {calib_file}") with open(calib_file, "w") as f: json.dump(calibration, f) diff --git a/lerobot/common/robots/lekiwi/robot_lekiwi.py b/lerobot/common/robots/lekiwi/robot_lekiwi.py index 38612885..8f2f9037 100644 --- a/lerobot/common/robots/lekiwi/robot_lekiwi.py +++ b/lerobot/common/robots/lekiwi/robot_lekiwi.py @@ -12,7 +12,7 @@ import zmq from lerobot.common.cameras.utils import make_cameras_from_configs from lerobot.common.errors import DeviceNotConnectedError from lerobot.common.motors.feetech.feetech import TorqueMode -from lerobot.common.motors.feetech.feetech_calibration import run_arm_manual_calibration +from lerobot.common.motors.feetech.feetech_calibration import run_full_arm_calibration from lerobot.common.motors.motors_bus import MotorsBus from lerobot.common.motors.utils import make_motors_buses_from_configs from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig @@ -253,7 +253,7 @@ class MobileManipulator: calibration = json.load(f) else: print(f"Missing calibration file '{arm_calib_path}'") - calibration = run_arm_manual_calibration(arm, self.robot_type, name, arm_type) + calibration = run_full_arm_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) with open(arm_calib_path, "w") as f: diff --git a/lerobot/common/robots/manipulator.py b/lerobot/common/robots/manipulator.py index 29f56788..bafc3664 100644 --- a/lerobot/common/robots/manipulator.py +++ b/lerobot/common/robots/manipulator.py @@ -81,6 +81,73 @@ class ManipulatorRobotConfig(RobotConfig): ) +def apply_feetech_offsets_from_calibration(motorsbus, calibration_dict: dict): + """ + Reads 'calibration_dict' containing 'homing_offset' and 'motor_names', + then writes each motor's offset to the servo's internal Offset (0x1F) in EPROM. + + This version is modified so each homed position (originally 0) will now read + 2047, i.e. 180° away from 0 in the 4096-count circle. Offsets are permanently + stored in EEPROM, so the servo's Present_Position is hardware-shifted even + after power cycling. + + Steps: + 1) Subtract 2047 from the old offset (so 0 -> 2047). + 2) Clamp to [-2047..+2047]. + 3) Encode sign bit and magnitude into a 12-bit number. + """ + + homing_offsets = calibration_dict["homing_offset"] + motor_names = calibration_dict["motor_names"] + start_pos = calibration_dict["start_pos"] + + # Open the write lock, changes to EEPROM do NOT persist yet + motorsbus.write("Lock", 1) + + # For each motor, set the 'Offset' parameter + for m_name, old_offset in zip(motor_names, homing_offsets, strict=False): + # If bus doesn’t have a motor named m_name, skip + if m_name not in motorsbus.motors: + print(f"Warning: '{m_name}' not found in motorsbus.motors; skipping offset.") + continue + + if m_name == "gripper": + old_offset = start_pos # If gripper set the offset to the start position of the gripper + continue + + # Shift the offset so the homed position reads 2047 + new_offset = old_offset - 2047 + + # Clamp to [-2047..+2047] + if new_offset > 2047: + new_offset = 2047 + print( + f"Warning: '{new_offset}' is getting clamped because its larger then 2047; This should not happen!" + ) + elif new_offset < -2047: + new_offset = -2047 + print( + f"Warning: '{new_offset}' is getting clamped because its smaller then -2047; This should not happen!" + ) + + # Determine the direction (sign) bit and magnitude + direction_bit = 1 if new_offset < 0 else 0 + magnitude = abs(new_offset) + + # Combine sign bit (bit 11) with the magnitude (bits 0..10) + servo_offset = (direction_bit << 11) | magnitude + + # Write offset to servo + motorsbus.write("Offset", servo_offset, motor_names=m_name) + print( + f"Set offset for {m_name}: " + f"old_offset={old_offset}, new_offset={new_offset}, servo_encoded={magnitude} + direction={direction_bit}" + ) + + motorsbus.write("Lock", 0) + print("Offsets have been saved to EEPROM successfully.") + + class ManipulatorRobot: # TODO(rcadene): Implement force feedback """This class allows to control any manipulator robot of various number of motors. @@ -342,10 +409,10 @@ class ManipulatorRobot: elif self.robot_type in ["so100", "moss", "lekiwi"]: from lerobot.common.motors.feetech.feetech_calibration import ( - run_arm_manual_calibration, + run_full_arm_calibration, ) - calibration = run_arm_manual_calibration(arm, self.robot_type, name, arm_type) + calibration = run_full_arm_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) @@ -354,12 +421,24 @@ class ManipulatorRobot: return calibration - for name, arm in self.follower_arms.items(): - calibration = load_or_run_calibration_(name, arm, "follower") - arm.set_calibration(calibration) - for name, arm in self.leader_arms.items(): - calibration = load_or_run_calibration_(name, arm, "leader") - arm.set_calibration(calibration) + # For each follower arm + + for name, arm_bus in self.follower_arms.items(): + calibration = load_or_run_calibration_(name, arm_bus, "follower") + arm_bus.set_calibration(calibration) + + # If this is a Feetech robot, also set the servo offset into EEPROM + if self.robot_type in ["so100", "lekiwi"]: + apply_feetech_offsets_from_calibration(arm_bus, calibration) + + # For each leader arm + for name, arm_bus in self.leader_arms.items(): + calibration = load_or_run_calibration_(name, arm_bus, "leader") + arm_bus.set_calibration(calibration) + + # Optionally also set offset for leader if you want the servo offsets as well + if self.robot_type in ["so100", "lekiwi"]: + apply_feetech_offsets_from_calibration(arm_bus, calibration) def set_koch_robot_preset(self): def set_operating_mode_(arm): diff --git a/lerobot/common/robots/mobile_manipulator.py b/lerobot/common/robots/mobile_manipulator.py index 87c85245..33027791 100644 --- a/lerobot/common/robots/mobile_manipulator.py +++ b/lerobot/common/robots/mobile_manipulator.py @@ -26,7 +26,7 @@ import zmq from lerobot.common.cameras.utils import make_cameras_from_configs from lerobot.common.errors import DeviceNotConnectedError from lerobot.common.motors.feetech.feetech import TorqueMode -from lerobot.common.motors.feetech.feetech_calibration import run_arm_manual_calibration +from lerobot.common.motors.feetech.feetech_calibration import run_full_arm_calibration from lerobot.common.motors.motors_bus import MotorsBus from lerobot.common.motors.utils import make_motors_buses_from_configs from lerobot.common.robots.lekiwi.configuration_lekiwi import LeKiwiRobotConfig @@ -267,7 +267,7 @@ class MobileManipulator: calibration = json.load(f) else: print(f"Missing calibration file '{arm_calib_path}'") - calibration = run_arm_manual_calibration(arm, self.robot_type, name, arm_type) + calibration = run_full_arm_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) with open(arm_calib_path, "w") as f: diff --git a/lerobot/common/robots/moss/robot_moss.py b/lerobot/common/robots/moss/robot_moss.py index 81703135..bc6fd2b1 100644 --- a/lerobot/common/robots/moss/robot_moss.py +++ b/lerobot/common/robots/moss/robot_moss.py @@ -26,7 +26,8 @@ from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnecte from lerobot.common.motors.feetech import ( FeetechMotorsBus, TorqueMode, - run_arm_manual_calibration, + apply_feetech_offsets_from_calibration, + run_full_arm_calibration, ) from ..robot import Robot @@ -46,7 +47,6 @@ class MossRobot(Robot): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.arm = FeetechMotorsBus( port=self.config.port, @@ -133,22 +133,21 @@ class MossRobot(Robot): Rotations are expressed in degrees in nominal range of [-180, 180], and linear motions (like gripper of Aloha) in nominal range of [0, 100]. """ - arm_calib_path = self.calibration_dir / f"{self.config.id}.json" - - if arm_calib_path.exists(): - with open(arm_calib_path) as f: + if self.calibration_fpath.exists(): + with open(self.calibration_fpath) as f: calibration = json.load(f) else: # TODO(rcadene): display a warning in __init__ if calibration file not available - logging.info(f"Missing calibration file '{arm_calib_path}'") - calibration = run_arm_manual_calibration(self.arm, self.robot_type, self.name, "follower") + logging.info(f"Missing calibration file '{self.calibration_fpath}'") + calibration = run_full_arm_calibration(self.arm, self.robot_type, self.name, "follower") - logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") - arm_calib_path.parent.mkdir(parents=True, exist_ok=True) - with open(arm_calib_path, "w") as f: + logging.info(f"Calibration is done! Saving calibration file '{self.calibration_fpath}'") + self.calibration_fpath.parent.mkdir(parents=True, exist_ok=True) + with open(self.calibration_fpath, "w") as f: json.dump(calibration, f) self.arm.set_calibration(calibration) + apply_feetech_offsets_from_calibration(self.arm, calibration) def get_observation(self) -> dict[str, np.ndarray]: """The returned observations do not have a batch dimension.""" diff --git a/lerobot/common/robots/robot.py b/lerobot/common/robots/robot.py index d08b8c32..8b68c09f 100644 --- a/lerobot/common/robots/robot.py +++ b/lerobot/common/robots/robot.py @@ -17,10 +17,12 @@ class Robot(abc.ABC): def __init__(self, config: RobotConfig): self.robot_type = self.name + self.id = config.id self.calibration_dir = ( config.calibration_dir if config.calibration_dir else HF_LEROBOT_CALIBRATION / ROBOTS / self.name ) self.calibration_dir.mkdir(parents=True, exist_ok=True) + self.calibration_fpath = self.calibration_dir / f"{self.id}.json" # TODO(aliberts): create a proper Feature class for this that links with datasets @abc.abstractproperty diff --git a/lerobot/common/robots/so100/__init__.py b/lerobot/common/robots/so100/__init__.py index f3803002..81b064c4 100644 --- a/lerobot/common/robots/so100/__init__.py +++ b/lerobot/common/robots/so100/__init__.py @@ -1,4 +1,4 @@ -from .configuration_so100 import So100RobotConfig -from .robot_so100 import So100Robot +from .configuration_so100 import SO100RobotConfig +from .robot_so100 import SO100Robot -__all__ = ["So100RobotConfig", "So100Robot"] +__all__ = ["SO100RobotConfig", "SO100Robot"] diff --git a/lerobot/common/robots/so100/configuration_so100.py b/lerobot/common/robots/so100/configuration_so100.py index ac04b847..969f8060 100644 --- a/lerobot/common/robots/so100/configuration_so100.py +++ b/lerobot/common/robots/so100/configuration_so100.py @@ -7,7 +7,7 @@ from ..config import RobotConfig @RobotConfig.register_subclass("so100") @dataclass -class So100RobotConfig(RobotConfig): +class SO100RobotConfig(RobotConfig): # Port to connect to the robot port: str @@ -16,15 +16,5 @@ class So100RobotConfig(RobotConfig): # the number of motors in your follower arms. max_relative_target: int | None = None - mock: bool = False - - # motors - shoulder_pan: tuple = (1, "sts3215") - shoulder_lift: tuple = (2, "sts3215") - elbow_flex: tuple = (3, "sts3215") - wrist_flex: tuple = (4, "sts3215") - wrist_roll: tuple = (5, "sts3215") - gripper: tuple = (6, "sts3215") - # cameras cameras: dict[str, CameraConfig] = field(default_factory=dict) diff --git a/lerobot/common/robots/so100/robot_so100.py b/lerobot/common/robots/so100/robot_so100.py index 1895627e..3bef7042 100644 --- a/lerobot/common/robots/so100/robot_so100.py +++ b/lerobot/common/robots/so100/robot_so100.py @@ -26,37 +26,37 @@ from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnecte from lerobot.common.motors.feetech import ( FeetechMotorsBus, TorqueMode, - run_arm_manual_calibration, + apply_feetech_offsets_from_calibration, + run_full_arm_calibration, ) from ..robot import Robot from ..utils import ensure_safe_goal_position -from .configuration_so100 import So100RobotConfig +from .configuration_so100 import SO100RobotConfig -class So100Robot(Robot): +class SO100Robot(Robot): """ - [SO-100 Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio + [SO-100 Follower Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio """ - config_class = So100RobotConfig - name = "koch" + config_class = SO100RobotConfig + name = "so100" - def __init__(self, config: So100RobotConfig): + def __init__(self, config: SO100RobotConfig): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.arm = FeetechMotorsBus( port=self.config.port, motors={ - "shoulder_pan": config.shoulder_pan, - "shoulder_lift": config.shoulder_lift, - "elbow_flex": config.elbow_flex, - "wrist_flex": config.wrist_flex, - "wrist_roll": config.wrist_roll, - "gripper": config.gripper, + "shoulder_pan": (1, "sts3215"), + "shoulder_lift": (2, "sts3215"), + "elbow_flex": (3, "sts3215"), + "wrist_flex": (4, "sts3215"), + "wrist_roll": (5, "sts3215"), + "gripper": (6, "sts3215"), }, ) self.cameras = make_cameras_from_configs(config.cameras) @@ -133,22 +133,21 @@ class So100Robot(Robot): Rotations are expressed in degrees in nominal range of [-180, 180], and linear motions (like gripper of Aloha) in nominal range of [0, 100]. """ - arm_calib_path = self.calibration_dir / f"{self.config.id}.json" - - if arm_calib_path.exists(): - with open(arm_calib_path) as f: + if self.calibration_fpath.exists(): + with open(self.calibration_fpath) as f: calibration = json.load(f) else: # TODO(rcadene): display a warning in __init__ if calibration file not available - logging.info(f"Missing calibration file '{arm_calib_path}'") - calibration = run_arm_manual_calibration(self.arm, self.robot_type, self.name, "follower") + logging.info(f"Missing calibration file '{self.calibration_fpath}'") + calibration = run_full_arm_calibration(self.arm, self.robot_type, self.name, "follower") - logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") - arm_calib_path.parent.mkdir(parents=True, exist_ok=True) - with open(arm_calib_path, "w") as f: + logging.info(f"Calibration is done! Saving calibration file '{self.calibration_fpath}'") + self.calibration_fpath.parent.mkdir(parents=True, exist_ok=True) + with open(self.calibration_fpath, "w") as f: json.dump(calibration, f) self.arm.set_calibration(calibration) + apply_feetech_offsets_from_calibration(self.arm, calibration) def get_observation(self) -> dict[str, np.ndarray]: """The returned observations do not have a batch dimension.""" diff --git a/lerobot/common/robots/utils.py b/lerobot/common/robots/utils.py index db86e6cc..12b9dac5 100644 --- a/lerobot/common/robots/utils.py +++ b/lerobot/common/robots/utils.py @@ -42,9 +42,9 @@ def make_robot_config(robot_type: str, **kwargs) -> RobotConfig: return MossRobotConfig(**kwargs) elif robot_type == "so100": - from .so100.configuration_so100 import So100RobotConfig + from .so100.configuration_so100 import SO100RobotConfig - return So100RobotConfig(**kwargs) + return SO100RobotConfig(**kwargs) elif robot_type == "stretch": from .stretch3.configuration_stretch3 import Stretch3RobotConfig diff --git a/lerobot/common/robots/viperx/robot_viperx.py b/lerobot/common/robots/viperx/robot_viperx.py index 4f076514..058ac0ff 100644 --- a/lerobot/common/robots/viperx/robot_viperx.py +++ b/lerobot/common/robots/viperx/robot_viperx.py @@ -39,7 +39,6 @@ class ViperXRobot(Robot): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.arm = DynamixelMotorsBus( port=self.config.port, @@ -150,19 +149,17 @@ class ViperXRobot(Robot): Rotations are expressed in degrees in nominal range of [-180, 180], and linear motions (like gripper of Aloha) in nominal range of [0, 100]. """ - arm_calib_path = self.calibration_dir / f"{self.config.id}.json" - - if arm_calib_path.exists(): - with open(arm_calib_path) as f: + if self.calibration_fpath.exists(): + with open(self.calibration_fpath) as f: calibration = json.load(f) else: # TODO(rcadene): display a warning in __init__ if calibration file not available - logging.info(f"Missing calibration file '{arm_calib_path}'") + logging.info(f"Missing calibration file '{self.calibration_fpath}'") calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "follower") - logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") - arm_calib_path.parent.mkdir(parents=True, exist_ok=True) - with open(arm_calib_path, "w") as f: + logging.info(f"Calibration is done! Saving calibration file '{self.calibration_fpath}'") + self.calibration_fpath.parent.mkdir(parents=True, exist_ok=True) + with open(self.calibration_fpath, "w") as f: json.dump(calibration, f) self.arm.set_calibration(calibration) diff --git a/lerobot/common/teleoperators/keyboard/teleop_keyboard.py b/lerobot/common/teleoperators/keyboard/teleop_keyboard.py index ff85bb40..a0f0ab21 100644 --- a/lerobot/common/teleoperators/keyboard/teleop_keyboard.py +++ b/lerobot/common/teleoperators/keyboard/teleop_keyboard.py @@ -55,7 +55,6 @@ class KeyboardTeleop(Teleoperator): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.pressed_keys = {} self.listener = None diff --git a/lerobot/common/teleoperators/koch/teleop_koch.py b/lerobot/common/teleoperators/koch/teleop_koch.py index 6146d9e1..e5c3fc92 100644 --- a/lerobot/common/teleoperators/koch/teleop_koch.py +++ b/lerobot/common/teleoperators/koch/teleop_koch.py @@ -46,7 +46,6 @@ class KochTeleop(Teleoperator): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.arm = DynamixelMotorsBus( port=self.config.port, @@ -106,19 +105,17 @@ class KochTeleop(Teleoperator): Rotations are expressed in degrees in nominal range of [-180, 180], and linear motions (like gripper of Aloha) in nominal range of [0, 100]. """ - arm_calib_path = self.calibration_dir / f"{self.id}.json" - - if arm_calib_path.exists(): - with open(arm_calib_path) as f: + if self.calibration_fpath.exists(): + with open(self.calibration_fpath) as f: calibration = json.load(f) else: # TODO(rcadene): display a warning in __init__ if calibration file not available - logging.info(f"Missing calibration file '{arm_calib_path}'") + logging.info(f"Missing calibration file '{self.calibration_fpath}'") calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "leader") - logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") - arm_calib_path.parent.mkdir(parents=True, exist_ok=True) - with open(arm_calib_path, "w") as f: + logging.info(f"Calibration is done! Saving calibration file '{self.calibration_fpath}'") + self.calibration_fpath.parent.mkdir(parents=True, exist_ok=True) + with open(self.calibration_fpath, "w") as f: json.dump(calibration, f) self.arm.set_calibration(calibration) diff --git a/lerobot/common/teleoperators/so100/configuration_so100.py b/lerobot/common/teleoperators/so100/configuration_so100.py index 57a08e15..a6a807e4 100644 --- a/lerobot/common/teleoperators/so100/configuration_so100.py +++ b/lerobot/common/teleoperators/so100/configuration_so100.py @@ -24,13 +24,3 @@ from ..config import TeleoperatorConfig class SO100TeleopConfig(TeleoperatorConfig): # Port to connect to the teloperator port: str - - mock: bool = False - - # motors - shoulder_pan: tuple = (1, "sts3215") - shoulder_lift: tuple = (2, "sts3215") - elbow_flex: tuple = (3, "sts3215") - wrist_flex: tuple = (4, "sts3215") - wrist_roll: tuple = (5, "sts3215") - gripper: tuple = (6, "sts3215") diff --git a/lerobot/common/teleoperators/so100/teleop_so100.py b/lerobot/common/teleoperators/so100/teleop_so100.py index 6b953393..13c928c3 100644 --- a/lerobot/common/teleoperators/so100/teleop_so100.py +++ b/lerobot/common/teleoperators/so100/teleop_so100.py @@ -24,7 +24,8 @@ from lerobot.common.errors import DeviceAlreadyConnectedError, DeviceNotConnecte from lerobot.common.motors.feetech import ( FeetechMotorsBus, TorqueMode, - run_arm_manual_calibration, + apply_feetech_offsets_from_calibration, + run_full_arm_calibration, ) from ..teleoperator import Teleoperator @@ -33,7 +34,7 @@ from .configuration_so100 import SO100TeleopConfig class SO100Teleop(Teleoperator): """ - [SO-100 Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio + [SO-100 Leader Arm](https://github.com/TheRobotStudio/SO-ARM100) designed by TheRobotStudio """ config_class = SO100TeleopConfig @@ -43,17 +44,16 @@ class SO100Teleop(Teleoperator): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.arm = FeetechMotorsBus( port=self.config.port, motors={ - "shoulder_pan": config.shoulder_pan, - "shoulder_lift": config.shoulder_lift, - "elbow_flex": config.elbow_flex, - "wrist_flex": config.wrist_flex, - "wrist_roll": config.wrist_roll, - "gripper": config.gripper, + "shoulder_pan": (1, "sts3215"), + "shoulder_lift": (2, "sts3215"), + "elbow_flex": (3, "sts3215"), + "wrist_flex": (4, "sts3215"), + "wrist_roll": (5, "sts3215"), + "gripper": (6, "sts3215"), }, ) @@ -86,11 +86,6 @@ class SO100Teleop(Teleoperator): self.arm.write("Torque_Enable", TorqueMode.DISABLED.value) self.calibrate() - # Enable torque on the gripper and move it to 45 degrees so that we can use it as a trigger. - logging.info("Activating torque.") - self.arm.write("Torque_Enable", TorqueMode.ENABLED.value, "gripper") - self.arm.write("Goal_Position", self.config.gripper_open_degree, "gripper") - # Check arm can be read self.arm.read("Present_Position") @@ -101,22 +96,21 @@ class SO100Teleop(Teleoperator): Rotations are expressed in degrees in nominal range of [-180, 180], and linear motions (like gripper of Aloha) in nominal range of [0, 100]. """ - arm_calib_path = self.calibration_dir / f"{self.id}.json" - - if arm_calib_path.exists(): - with open(arm_calib_path) as f: + if self.calibration_fpath.exists(): + with open(self.calibration_fpath) as f: calibration = json.load(f) else: # TODO(rcadene): display a warning in __init__ if calibration file not available - logging.info(f"Missing calibration file '{arm_calib_path}'") - calibration = run_arm_manual_calibration(self.arm, self.robot_type, self.name, "leader") + logging.info(f"Missing calibration file '{self.calibration_fpath}'") + calibration = run_full_arm_calibration(self.arm, self.robot_type, self.name, "leader") - logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") - arm_calib_path.parent.mkdir(parents=True, exist_ok=True) - with open(arm_calib_path, "w") as f: + logging.info(f"Calibration is done! Saving calibration file '{self.calibration_fpath}'") + self.calibration_fpath.parent.mkdir(parents=True, exist_ok=True) + with open(self.calibration_fpath, "w") as f: json.dump(calibration, f) self.arm.set_calibration(calibration) + apply_feetech_offsets_from_calibration(self.arm, calibration) def get_action(self) -> np.ndarray: """The returned action does not have a batch dimension.""" diff --git a/lerobot/common/teleoperators/teleoperator.py b/lerobot/common/teleoperators/teleoperator.py index 2aa1d662..3b60372e 100644 --- a/lerobot/common/teleoperators/teleoperator.py +++ b/lerobot/common/teleoperators/teleoperator.py @@ -14,12 +14,14 @@ class Teleoperator(abc.ABC): name: str def __init__(self, config: TeleoperatorConfig): + self.id = config.id self.calibration_dir = ( config.calibration_dir if config.calibration_dir else HF_LEROBOT_CALIBRATION / TELEOPERATORS / self.name ) self.calibration_dir.mkdir(parents=True, exist_ok=True) + self.calibration_fpath = self.calibration_dir / f"{self.id}.json" @abc.abstractproperty def action_feature(self) -> dict: diff --git a/lerobot/common/teleoperators/widowx/teleop_widowx.py b/lerobot/common/teleoperators/widowx/teleop_widowx.py index c7bcc18b..fbb658e7 100644 --- a/lerobot/common/teleoperators/widowx/teleop_widowx.py +++ b/lerobot/common/teleoperators/widowx/teleop_widowx.py @@ -43,7 +43,6 @@ class WidowXTeleop(Teleoperator): super().__init__(config) self.config = config self.robot_type = config.type - self.id = config.id self.arm = DynamixelMotorsBus( port=self.config.port, @@ -120,19 +119,17 @@ class WidowXTeleop(Teleoperator): Rotations are expressed in degrees in nominal range of [-180, 180], and linear motions (like gripper of Aloha) in nominal range of [0, 100]. """ - arm_calib_path = self.calibration_dir / f"{self.id}.json" - - if arm_calib_path.exists(): - with open(arm_calib_path) as f: + if self.calibration_fpath.exists(): + with open(self.calibration_fpath) as f: calibration = json.load(f) else: # TODO(rcadene): display a warning in __init__ if calibration file not available - logging.info(f"Missing calibration file '{arm_calib_path}'") + logging.info(f"Missing calibration file '{self.calibration_fpath}'") calibration = run_arm_calibration(self.arm, self.robot_type, self.name, "leader") - logging.info(f"Calibration is done! Saving calibration file '{arm_calib_path}'") - arm_calib_path.parent.mkdir(parents=True, exist_ok=True) - with open(arm_calib_path, "w") as f: + logging.info(f"Calibration is done! Saving calibration file '{self.calibration_fpath}'") + self.calibration_fpath.parent.mkdir(parents=True, exist_ok=True) + with open(self.calibration_fpath, "w") as f: json.dump(calibration, f) self.arm.set_calibration(calibration) diff --git a/lerobot/scripts/calibration_visualization_so100.py b/lerobot/scripts/calibration_visualization_so100.py new file mode 100644 index 00000000..33573d8b --- /dev/null +++ b/lerobot/scripts/calibration_visualization_so100.py @@ -0,0 +1,100 @@ +""" +usage: + +```python +python lerobot/scripts/calibration_visualization_so100.py \ + --teleop.type=so100 \ + --teleop.port=/dev/tty.usbmodem58760430541 + +python lerobot/scripts/calibration_visualization_so100.py \ + --robot.type=so100 \ + --robot.port=/dev/tty.usbmodem585A0084711 +``` +""" + +import time +from dataclasses import dataclass + +import draccus + +from lerobot.common.motors.feetech.feetech import ( + adjusted_to_homing_ticks, + adjusted_to_motor_ticks, + convert_degrees_to_ticks, + convert_ticks_to_degrees, +) +from lerobot.common.robots import RobotConfig +from lerobot.common.robots.so100 import SO100Robot, SO100RobotConfig # noqa: F401 +from lerobot.common.teleoperators import TeleoperatorConfig +from lerobot.common.teleoperators.so100 import SO100Teleop, SO100TeleopConfig # noqa: F401 + + +@dataclass +class DebugFeetechConfig: + teleop: TeleoperatorConfig | None = None + robot: RobotConfig | None = None + + def __post_init__(self): + if bool(self.teleop) == bool(self.robot): + raise ValueError("Select a single device.") + + +@draccus.wrap() +def debug_feetech_positions(cfg: DebugFeetechConfig): + """ + Reads each joint's (1) raw ticks, (2) homed ticks, (3) degrees, and (4) invert-adjusted ticks. + """ + device = SO100Teleop(cfg.teleop) if cfg.teleop else SO100Robot(cfg.robot) + device.connect() + + # Disable torque on all motors so you can move them freely by hand + device.arm.write("Torque_Enable", 0, motor_names=device.arm.motor_names) + print("Torque disabled on all joints.") + + try: + print("\nPress Ctrl+C to quit.\n") + while True: + # Read *raw* positions (no calibration). + raw_positions = device.arm.read_with_motor_ids( + device.arm.motor_models, device.arm.motor_indices, data_name="Present_Position" + ) + + # Read *already-homed* positions + homed_positions = device.arm.read("Present_Position") + + for i, name in enumerate(device.arm.motor_names): + motor_idx, model = device.arm.motors[name] + + raw_ticks = raw_positions[i] # 0..4095 + homed_val = homed_positions[i] # degrees or % if linear + + # Manually compute "adjusted ticks" from raw ticks + manual_adjusted = adjusted_to_homing_ticks(raw_ticks, model, device.arm, motor_idx) + # Convert to degrees + manual_degs = convert_ticks_to_degrees(manual_adjusted, model) + + # Convert that deg back to ticks + manual_ticks = convert_degrees_to_ticks(manual_degs, model) + # Then invert them using offset & bus drive mode + inv_ticks = adjusted_to_motor_ticks(manual_ticks, model, device.arm, motor_idx) + + print( + f"{name:15s} | " + f"RAW={raw_ticks:4d} | " + f"HOMED_FROM_READ={homed_val:7.2f} | " + f"HOMED_TICKS={manual_adjusted:6d} | " + f"MANUAL_ADJ_DEG={manual_degs:7.2f} | " + f"MANUAL_ADJ_TICKS={manual_ticks:6d} | " + f"INV_TICKS={inv_ticks:4d} " + ) + print("----------------------------------------------------") + time.sleep(0.25) + except KeyboardInterrupt: + pass + finally: + print("\nExiting. Disconnecting bus...") + device.disconnect() + + +if __name__ == "__main__": + debug_feetech_positions() diff --git a/lerobot/scripts/configure_motor.py b/lerobot/scripts/configure_motor.py index 8b6cd2b0..6569db19 100644 --- a/lerobot/scripts/configure_motor.py +++ b/lerobot/scripts/configure_motor.py @@ -145,13 +145,12 @@ def configure_motor(port, brand, model, motor_idx_des, baudrate_des): # 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("Max_Angle_Limit", 4095) # default 4095 + motor_bus.write("Min_Angle_Limit", 0) # default 0 motor_bus.write("Offset", 0) - time.sleep(4) + motor_bus.write("Mode", 0) + motor_bus.write("Goal_Position", 2048) + motor_bus.write("Lock", 1) print("Offset", motor_bus.read("Offset")) except Exception as e: diff --git a/media/so100/follower_zero.webp b/media/so100/follower_zero.webp index 411a5554545d8dc4f7369e6370fdb1f9cadb11bf..3ba869902bac32b74a73ad0cdc76f30dde5866a2 100644 GIT binary patch literal 521258 zcmZ^~bChO3@F)DVd)l^b+qP}noVKTJ+qUhVwvA~|+cutezQ29|C~;}Q0002Ge>4aC-zzODs)PmlFAD(0GInyZ1OJEY9o$@0 zBt?j{v~`G}jsYP5p8pBPrmjxHN=kD7W&U^ize@gh{Ji?VWS8jwtLyTsIF2h+^0$3U zucG%KEXMyW_5Vm=%*{t?T6tf(EW8V`$%d!zw72{H)e1%>@?R1HM^-jO&U|;m;mT z^6{N_MUriuP1;N#=m{q9}A-KXE@)K$P4Fa@aovhafZW%w<4^+n^e z`?32exCQ+EY}lc3PsK9_G#bp7PgU^w;dzZpgIa^$7?GmM_CDbza#_3IuwEf!5)$(6IA zrj|as3)r<1%S7aw`y#hRkh|r?=rZk6@{Ziy8v{=E0wyHsu9G z>hSAYmF}=XQV_RTxehy(YfJ#G6)Hw|`%E23s_kkGmkN~ldPmiuOi|}=J!9KYc73*Z zSEN9dO^rVf%{h=;oy=mevY>)!XQJZ=F#C}{ZXE`WYR^aG9-pW};G_tL zBD{n6LG`>x#EOJNs7G&`3!wtTR3OrX+$R$Hk3@E|Ha_b7ju+lR>{@-}l#RSfT54DD zElF8}#F`t<3jiL@M@aK`S?N>r8+Q1>TA5D}6 zG5%bSn%F+!0cFX4;x|h#aR&4acrOK@Ye#d6b6EJ1>YckU|8Jr{LJGIRhsrjiWN3M* z*LpSB?9u{|pKeofXKG3_-o!KNIip;3NvzS9GUEgAiF1ln*m?JZQMrqVRKg@I7Q))-q$6ke_OiQ&`D64${hZ)o8LcFszW@^l)`dGz9w|{HdKNYe7E#$6kLGY?_-JMTI{>F~B=7ll64TH}ht(LM=wjFyp@S-?< zE~&f)XgB3w5tLMqWczNxBXss7KL2rRo{b18W;q;^csLy!BZ*@j_~g!Y18)2xv{)}( z91h3IKR;yMsEpyhoTQ8K_R3)|HstqnleB(uG~G;DY1|FhW)0Dj5pwoEYIEE5BMW(N1T9W?m=?A724n~S z)hZ^v-O{x$16e8Nj;tZSYvZM?7sehqK*QL2$+a?o*MW#Qc*5>&Zt;cU5T+~RBbbYd zC%^@r@X2hk#_1aBNV%3PYh{==x|}f7raQ$?DDX?L>E&h(iSGIa%rway>Ml}FIMy#l zLM``f)(40^Z=3K0B`m9d^=LSIg%!Gfyx(I7lZlo&e?ired!`A#M;~7`EA1SY^+;k7 zvL=e1NeSXJPRH=F&C#a&!Ur!IEHz3w5nvKra&}_2`2eVBCQkt+Ey-q;vRmWiTZb?! zK9Xu9alCA=7`QAmW3Z#MsQ&Z$vSG401dVduCCUn~56TSN09|pbrdDTNPd&s;hRVtl zEN*AdAmIsz5`LLxBAB@=VHTiNSPnxQGpZ>f68*&lVLZk2a}@0&dn*!ug~AMWR8%z) zsai&YecUnciQT|;a_+mgC^KeD-~YiYn%@(@89Pt`PQb2OIxUM=&WK)`bMF)!Vu%Qy83U6Ae&cV7BoFDj*D zN2BV5itr7N;JL=+_2lSn4-N1u`5pdR8VBf>bksf9;;Lhs@}wq;qM3Fa7Gd?H6_*+u zU)CP)hAA1joJ)jBB%kfrTOZ?x?YLi<`e%U}lDN>&dzZ_OV4#@DHdc@EH5Zd>X~yfh z=kSl4HnG}`)HAP5x&G8??8q5|gXwBloM1wDgg~-+HNnNoW~(ywH?b@Uj%Nz~PYPj9 zt=ku|mk&msh83Sr4W4D1I^xyYxq^;kJ#BfcbwC!ZvrcY?&s@9+1S4I~CLgHCzb9TcPTGk-mw&^fGmStj^UBSB4$34kDU5+)_aeLZ;N3wc{B%TjX|ogBOmmz>Du+TO=J6*tG32yQhS@SviNtOpR>Ex8 zB=o-vn7>Y=6A>%#S()+RB~GY6I>+4tu;c*JX&G}3%ruC8SWmObae)*Pf!VWuHSNZC z#T7GB$13fnDJ*C$vT<~Q0@W%T3Qw_Su?Xo%@EskI%gQ-)`p zhZ(1&EazUk`9qbpmkjn&1g3}=HV|Tn1snRfoK8=+GeU)50UMSOp6rL4nO}Je%ie}@ zd+}nt+Xd6Yj+3rIt!dxJ3-$C{0}VO++ki@gE zp~}!FEMA7eMq8pF@q$ntlR7|yj*rKU0tu2S8H~l3EmR|048`L3w@G&LbkGN@wIYuU zzE!AR^W#`5MBN(&5JmIBOlSbPl2$#JS$DoGNElfJoydK4>AdI@Jn$x-PE_hxkuA1< z++&c#hVfQUZ?hx9XM@|YbtM6=gAM&K7nib^#-o^W@sgo{-k6z>9 zaOx6jQTxbta}QR00SA+fRU;x=Q+UOhb;xjIy+3cN+JuPJ%3q=>0_~8gefcDb*@4X) zfQaW0)HI3=s2<_Y7~8@WBS{!dTeCenJQ;szwX_p*Zu&4jTot?8B8@2dn|ezp3Iecv zay1Wr?2haEB}<)s*x}Ks%JLw!P%#XH)-2JsS{viW+YcJT6tB3GTi_2Vobwl6h#lc` z&urN6nxI2ht?e3Q8Vx)6K(!EAjOz9gSG*Zqa`Iwgjf2OJ)%z#ky~Fer@`9TZ`{&|9 zv&mulWOcy6j^_eT>J525KiuzuYz;v!Q2u;TGe*G{b7K7AG3;}c1 z+a-&AZMJzWkxO@E+yAXHr(I9QVeg={Uy9#4RP;2j{h-&$*K0Z$7*w4UFrSF})vLTi z?DbVmMD%7?GG)n&Mn|xrwdeCB$IW20r*{o@$w3P_2$MU+T{20z$-Akr6}b@=8>jhA z1xnr#WHW|=UIiU|yp@zj`pBo=(w3Y-oL6nV=SQ>28AWkoSuQznAV1Cnw_-MvgO7Kv z17y#S?`Wf@wwSY%fd*^z4}hO3RhyqJ7BafS^NV8Js!nxy?3g*Ch87G4zoKvwX}O~A zLR@U6bBAH`B6lEt7+e~Z@Nhlj!tCm0Fx*!Phhx#*lvO0JqfKw6DZ><>B&oJb%-TVF zv5w+2*ai7pbF)0yoh_IUtyuC)d(BmrZR)-h3nw{fE)Gf2aZ=LqVO3zJK@ZwAyXxmO zns5==M-%H?DIX8@MKQ#u^Tf)#1-F5#BlFU)yt)@@coaJNElTJN(&vQEF#F^B6g9Jf0?>lhJ3$pn|=K zVM(*Bi-)~KgcK1`sIBO9BwJKfS%&J&MqkTTF}U>osk9_1AwG|wGMw-_d0Od|QHc1h z%w8T*IS&t6%ECMN>^tu z12&rC_)ySw?^soWS?r#MnK6*P66#p?Tt9)lyq7P@2j2icEA8lzP}@oR!hEB3`HLD_ zsTI>)Wd0j(=DmI==H%M#%iOVnlwK`i$fM^jo5f)Xrms#(XgNES8Q9!??4NR`4^oBV zUnfWs=DA+eufNH)CM$n;8o{j(HVJ4Ar|E0>=JvE};W58Ke;oesQHY#0USEN_M^zjC z*q6)xGKH>h;j*6lgA9Ax;#`}axWCPQ>9PxOaMx-|Gw+$BP4ZTT?1}5kP(j2PNbuyH z#_yg0orUsLDKzS2U4n!kR_#jL=>64J{kVowORR`+TnU8gJ`13{NlLRAMa3-8H0Vsq zbc@yQYI1ZWzbi&_Dy&M*I8$a-9pxR!3=~WAEevLUIKSA27;(p>+PqocbS#<^C@*qx zKKyhu%XBfwCK<|Ze0c+I_m$Q=xW4NcC9i$mE?`?*1{n9*@YuI*^uzKe^R(6bO` z@VFupPn~>WT{nczrUiN|Z`XGmrB4Wm!e5T#4}N>qXVdnwxw@3^u1tqn0#|5edM&d$ zRVaXZRLz?vi!edSw4iA-2|`qb!og|%^OI1zYU|a?cfp}sU6=<1(`%>Hc0+P!GqFAA zayu4A>%r#d{1Wuu)}!d3MN$w0r-W=(D`6PvZyx3qGzc4M?}T>(Hh4NInAS?t#Eah? z3CBO}M#>0ihl+lHi)yVLa&WX;Hd61-n?4Xz_@-;NOESu@wT$4#kv&{DkinhrK?{v} z|2&HWEo|OAHJ6g6cF-s#omB8Pg0=EmjSkm!ifa;j7ZYgtTzo*|j4P2>eaT&4%7Ci1 zyK7!-g<+?Y>!7_4W~B}x_-)h&hQP+A{w8H zr_$-|bh;cCQZ*SfR+ zF{_or_S3NZf;rA|oCp8PtF{%HMRHEK>EN3wd88)i`UnEN1g5h;18mvs8?In&k74e7 zl{UP~ofAm$xLsA`c(2dy&$fviskxtiG*I}-Snqog$Hsg&5 zKLpi?3H4cGtOcw@8-d`DK!-cdygYc$N)E^I`%m#Jg=}FKn!v+H2TEQLku8}#TIyxk z3%*JQYSkq#J14K6baM12EOLs=SCZ@cZ3LwwZF>lY5G1 z=L_S!l2eR?F-QB3JFOLd60$()Xu$gAR~D5u<+^zYw$LLCLyZ}>Gmljc3-I~@V==AV z=u^I?)|~H#o{eWdw3iVMo5~wLUG2f@H~9e3xscO-Q&3cBS+2+YC&~+Ya({A^!_f20 z=d8@kD6wr`tC#IFY{XA=IQ}peu%50j){dE0>*c|hlG`Sk16mVLh7V{svWT%0f2B;T z``liD3S#+R@-3;t2$W%khdbUa=G6Vw8UuV9hG2UQ%=5GinNwM-hmk4?dzy2wJJT>*wkQjl#hBm8FvTc6uXy*HWmRjOGbFAwDg6 zvZj#_pO2P%BH}(Dw)JObTlOV#<5Q@!>bcNk>rj>hYmp^8UCt%;L5~We?oJH>S^lqR< zRal-aNv)OR8?I?i;GLJB4{-N5dXCZbRIi!+J4XLJ+IIFWTQH<&hsn>28d3t`v(-2n zSq#Ue2D5$>KlfcT=tT|~DIBoc^H zqUt~CfN+5?OOtFSryf7@%yu7Dzd?;o{}j48=uzzD%QIR_ZMa%d&sGT_Fm7$%;EfNE zzyBV6o+DRM6$_qF5_17(Z6^XZhshFt4Bc0V)kOrxHGb09c2IetH!L<@*>Jef)X`{b zgSakGW-tYIcHIR&M$7c9FuQ*~llMPuP)E|u2Jpxk^+l?7Lg0a>hS-qNUO?P?-8Rrh zJVT&r`nWbJ*7M|u-q)%w`V5t)Zjw$A_XQZZGj@z^`L9Mzptg5)3fOA%v>Bs%pory-aTyOB+t(m7OiTXKo&L z9j`n(A-hMzL}+bFH#>=LMr}7*s&!8j3gq`993K~o&E2IS!3QQUT9=_=tc?A0jUD(ORfYP+v|b$L)A$BFAD6{`l6c_zW9oK;2N8{~Dj(c+Kwl&`XRLi6<7xS_gmbAxxY8o!QE{bVQ-l z2%2Sor9`qo_|y6)(*E93j+UznqV!N^r!e`B6Ba85Jq%*AYWMX$kt#;};bmI8b=~QL zw1aP8mHWVLJo#!EQqi@);%tyqpV)b+ng!5Dk{rrmFmKcDRN2(3bT;@iRoLy`V%)&= z;8)B$KTkQt8Q%hlS4mVhr?-=#CxKnuU0XDwtXv+_PQWrE@OD@JLnjt8{YSDlTVdBo z#L%^T)?$c+(Edh*5S>4~jXBlBWzh@D5Yo$~pZrvdHQ_~u znHd@pBFRTRPnFRhB_$}DUr45lm?x^fa-lyvoonmI%tFY(y;R7;zOlm&S?-G`Kc^6bg*utiyEKZ$GI0+ zwhKl}O2t+T7D3|jwp{#S2`0jeTfcg+*D#A2fNos!9y_4Pc9C;Cs3?`I#E4AJPSn05 zxGo7a_ZB4}Q3X;FTzlJKWPl$G5hvuws`(A)&wgg3iiA|%b)i_nvcMIq7uZmxTYDTL zF=jq(w+>K!Sw%L`}-q;ldIJ<)oe`(<4z+h|D(_Q?(;7@8TRs&v*- zfs7MPTEf69NY>0YF?zIbN8c3V%H0Eo zX3ryTHyG210}4RKjN~M!0W*FXO4rpfSszibi}D1k5Vax%qVj5OwMR7y)fJX36yO{u zDxZ3PKJ(~vGSb@_9v1V^zqPufF+|m?|TJcMH><>SEC5T9K&h5>p7g9 zrzrBnGdz^Th2g%I3tuo$KSz&m^}n>?QLznw=2k#*3YVGtSk zVWIn+fv|rbIFqU7#orG+p^E5G&U>0qv2m)e(PA%`Vk8T<`}@MDj0r$+!!~(vobB6r zIG!Q##&3)T4b3`cs?}>3(QM^u@qUlGL3lsKZikVG&R>f~8AxNBhiHNs|=W zMP-3bv!6-G2huZzVk)h;)B7tbGCa~! z9Id#UtFmsR?Vs9(P!ypsJr)}TgYlfSg4G9VJju;L7q?G>ThI;-^^T~Tqw;v*e0cle z?;VJu>fMjAK|_s<5r_UYJWFa`qiE;cg5xU?4w0|NQq>}>*e*&`$M}xGm?q+Sfjs-U z$@q&2@}yq-SLB3?V<}=U{P_hD_9aTKHQjLMt0Y*95dA@(V#OGd1KV6(Sf|~%Ji73G zf^Jr{{C0#GWf<)`tF}5@6W84-09Y_J(AtQH#~oAgeR;2_$n z^rbL?B-Pl8j#)E40OKmA4~7>h=Dzu6)SL&b!&z9mMPZ0c`t=Z|3Xw%Aj?PyAxHV)L z^0Dim85vRS*IOGUtY6ESiI8%ew-`kpGXe<>Xo1R1H%FE8;sx7%mV!EfE3+c!=Z=2u z(;6-Nw~X8(+{XW^%>&~q&_bPc{+a3@L2pGQyE3ALhgy)SWYCn0XKr4GRLXu2$4p5v z6LZZ~YSRHJ=d8(5Dmy~;5dF}1(381CXS~K%VN>Aw%LBQsBDimCtK3b(7Y)i96f5%& za7;{GMdc2CRZ}q0wyR_DT%cg&f)WIyQRIx|Ba4d<#=*;3u3q1k-6T+sX|fSL7l0k> zITxYjWSb>w(H}Kplz;U}Y})9b2hrsQ2Q4)8$kFTaqkil@lDmPjz(*0*Q_K>M^_$?$ z?WVm%(I}n|+bm`sK-dvDh2+LJ_{5cpOo}`>{0L>Z=+N-dyN)`I2g7_j>8jYdFPXnO z^sVN+o5t>=@OjupVbvx)Bzw%b!C!0yMmU}I2XQt`cO62p%7E;G`ro8?`Hv0CpC!~i z0?jj$Mn(0o_Dl!aGi9l??N3zxAYya#QOLV4B`|hxrUu;l6UO*>_pv9A^oPz>W;wKT zzCXC2_i}VWRUXR!{=Bp_r3piR*iS#Hn=s`ZmZM2*=a8DFulk4+n^->V%6)`t7>&@_W}E4@#Ir6_~G^F{qp*J@LNR8IX)lJ z0W)8%U)|fi9El7A4Joy1`dVRLP!5ra;rizw6yj%f11rv8M7@{MfEcnBsd1LXV)d=u z3@3v5m$lQ_L8=dFnL341t2U%YNN&pxTZyAnUq@-@XY^*&29;sdkinAZ^OaW88UTca zm<57ggXOR6`B8|i!Kt^V z<6ayF2hKEAlV*1p)hnfvEnZACt0&FP{i{7z7-tBGH&dKT5w9JKjv5Y7ky0Uq(2j6F zhQvTjytffyM`e;o)K$>50SqU7MY$G9Ryn6ch+V`B=hwV9+t>Lp;Nw;|=3IhjI}R?} zXD<~-yJy*<;33M|_VbmTNaNRZ4|i5`p`VI&_*gTU5OLjc-=A0ufc2jr{yXRu5N(cC zvk1y`(=gK=GILzlX&+~-t8mHj@AYRaEul zoM4v+x`ia_I$~}D>VYf@eZ@_|iRTz$%HD57bQKIJm+jFMbIt7|-8`_4pB`0W6~86d zi&dI(fkca2?abX_7RVr+;4+CL!N*`}#X~NEqCAP(CZ>KN34$QGKdHhuExf5`6*v}n zz_7dzK>U*Gm4A(ILiiy)u=BZ0-aRg=(|^nXHjJYqx6e^29Gt5M#PFb8^v(o&&MSmX zR*6-8adTx27f8tZ5Ew1z(bf;mVWepVQZ}E3xvS`EmJcLYl3q1NDRQg{vUgyUYob<# zhGWSJsmB{tbD}&}!ri9Efl^gf;`&mHs8sS9L=kRON^=C0WNTkvUqU)Xkg`8`q*QkM zDhWl^m=`3?MxTQvYXUC32}PW-@UW<=sVFEKa~u~yf=U1+WLX{_>?keh4h zjMUtY^?fL1DmIjiI+DjOCdnD9C0oet!_Rga)4;V_4A1M7Ny zEiZ<7urY5%7omNiP`DM^wgSP5TbBPRa@Q-h^S!T;M(w1i=G2WeO)U^}x(-JK1`{&wpp21wK$byrMP4J89UWwno z(?}Fq_#i~mpqm@*d2zLgZ8&L+d!%!d+@(al2zz-7ij`v7WvOwE+G9-Bh;U$eMMT@% zG&{Fs1gX;_10MZ{Z_2<^PYp6KF76B!jeW;2G)h44?I`8L%o|$Iw!{Vq9*n{A@#3VV zWga3(TTRH9dzwT4(4!r)XuIp{p43|m5lSfGcU_qd!Jiz+5fh_L1G$*j-d8W!Fun)A zBba8u>jX}t`=;cZB7p_G+EtmLZrzy_EgmRee(TdinuK;kOt-W??K;u8SWLLYO z{YL&0Y4}$83;k8$ITTPV;Ry-#)RE0jjQS`i-?cst7+hC%ma51c@80n?|Lhn6RD6tW z+~|Z)Fz%5u&yT4u!Yi-^1DCIsmZnmNC|D-^wW>W`iTO0$lsJ=QVvzIvKmPlb?Yv~i z+4?Q+`Z8BcLcA%X8LZ26tq(+pT_9QUdP<-Xs{gq{g)~BXb^dI%{?m5pllu%})Z3k9 zFgE_>BS8xVoy2GV~HCBJaMMi8e0CZERLRa0!pGPYViNF!Ov# z4z-g~<)?Li65mI6&0`&%n%I2uu7vOgo9sU*1mstBtKQV5oyjkUV$OD!?W&hrB;=_6 zjH;3s;x;Rs7l?{#{y{qEd%{kl2h)KpkDaW@AuAFT>;nbb)n&izXRh+DmsfHMRu^Kp zI-q+6G$KA8j~LkQmA{%O;Oh4DfL~z10X`wlp0hqo7K-@KK^iIe^3#;Li!E)|$kcb9 z$+&(qi)4-@GWW$%Qoh-O#yhJnNa)N)i&vfero5D_&lA%IyDPBl=GwYGx@D>#H_+pA z3@E$*13-j6yp6)3!;R93F`C#H^rTtS_ehyBte*2@hw|)8k1w8$270 z0Bh;myTReHE=&XDP#MSA{dT3O8O`#>rOF&FJ>Ykf36}V285*)e z=^DvNcqa4{R%O?g&yDW`d3d>)nKgFgM?nG2N1o#suH+^f@nQGiWM~mZGsNQlNVk-_ zx_@en8mtWZ^0EbUPQ?(sz^}dc6XLfykeBk)Mfp2fZ|8d*Pe=@zyGYEBWDUG49?i0K zW%1f_8j+pVVf4U9H9zxSbit%+86xVg0^F8QLgLGBrDTxDKDaiDYBJ1l3>oYR=ik?z zj|e}Z9|@3~)t9L>R2!At4%e-h>3{qoe9aB7*gZgPH7L3!xf4`1o`jT7*1hO@Je}P% zanFDW7d2@l>?<=+PH~xyb}&jb(U}xR$e$bPJ(=8tyr9l`-*uzoFnxec&0-;m|Jo9G zi}YbH8^3~^r8L$<(EW|o`rVQ6gPvs_fXrApQD@7mXDY3C3piZe`Pl?EGVkdCCk@)` zS`_64To@DUwICSHJI*Vdd^MCxt9Xp5AIUb2X4oELy%O)UUMASvruqce_Ia>$>B2q0 z5kxC(Zt3u#N=j*!1oF`K+CiTK44<$OZ3hL}dIqJ%@@ip7f~UWY)EunC0UojgNBOJ9 z0j@bJciwHN0Tpf9w_W>x44#ShDTWqg-2_Z#2-s;jq#XO|@j@q*XH!V0E6tgUPA&Er zjz~_bL-x&R1s;vrXx2BeVfMJ$`}G0hk$D9kzE&j}d(QQotcYkbrN+a(>V;>lb36 zzAc&(-{TK#y|3n+V)-jv566rTDM1Mnd?QA+=x%gAG8uj%#0sfVZQg!|;^c}}Y(Zur z#o5|qIkG3hL>TQpE)B9R(!l|F5~IQkl)OA1gOC68!Pm8 zf|@3}>Ru{){d)R+%rE$%gg-3W_OdaVR+`J76s%%(q4r2xqmDMDB-vEx6HB8+RTgHB&#az{%#ZeQ1s2($%$nq^WM-%JRf+rMuzn0duq}?6`=zs|1Y{tBZ|2c%;|nx z`R=kYOi@eXB-T_i$JN8hXDiX1wGML!G4l@z1sH{ko6GqdLTKxPzc*x2kJp1D zzI1%z-yEfw9EUJc;bTQ9LcUo8Okfek#9| z;$dJ%lFhVz^xZVj8>Gs^vTH;V1JMr$a0p#=W-2W2sKA^OZT#p}t@#4%7r_aM&Nh1L z<6G;05%}~hu<&Qj(+G$Na*9+H{bFa|b;bS_pWbq1KtF4SI^Y0iQFa$#5_k}y+EW)b zZA;B^?COEg4d`VvK*QuKACz4)syi6qJI19tVLHI8{7kf_M=cBf>g9WpB{e;^>C!w_ z|4no6=wH#DBN6}CCOYQF!!#LD*J0$sa?ie6RkT{k$S@yBd{hxci)}?L!2b_E5xQP8 zR_W^Frvw2V^TekhR6W6CU=8`TkvFpO!&oED5)f<6;+wQe2Wa3U|ZIqZ8!b+Q(}9GnU4q=t~21iz~WMVZ9bGs^}AF%N84uraW4 z^^H+j;rG-Z`D-t%7=>UMADWKe`ze?6C@eUmRI^8d8~w5N#-dDqVt^smp8xlzj+oP^ z(S~yZw~l`e5lUKe?zFucrmF`dS|8_H;@4to1~sW=^F8kNMdu0&7qmlFeVI^VEL9=Q9aqYw7!RZ>kafp$!4 zF+uUk*4W9GDX-UXYFrf5Wgnj}H}|OkdoxESD_PW6x!`OQC$jD#$28o0<@?VR0KNWl z$eud+H(_G%{E)p?kSo9QXS?k?5#3}jDjCpOLyzaip1{i;Jrvr!BZwE^C zCs;_$73q!tn7^PrnZc6wfaP>3gjLl63gU%xTS9N_n2|XIUa>P^4xM%;>AtB#!0D1Z zwinsDo!m}nk&s&`7YF~WPiiE()Xg4kJ2g14V=aIy6U1?!U$UORZhR-c)mEeHg%WFj z34V{0p1t(D!7t27xlG(uB^JFEDv|VUby zKWt7r#&;DwLy->e%E{8HUPg7J6fUPQV-7QcoDBbY^KIKoZ%3);MEvn|)sUtHA>mO( ziTpH8LQ98)17r#Qj2P2d+~u@>i2zSO3PN2G8+F9%sy9*z1Uf;VCsYXvl0R7kVW{y3 z0@-OOIw3I!206!?5fV15w*Z2C#%o-N!P6lsHv%oX+QDSN&K?&Ud)2I0^6J|rrrs#K6_^J^xgJ~pavaH>+l!jRJu)j6&x zBQ0*7rLEz2V&*vYphH|vs=-o)<(!=JLqk&7|7kd3g5HZN*kAqqAodKhfd<6mx&V$tz@=Evy!pG_nZL<%&F+v~Xg`_STbq3cNv-VB zaMEK6gOnvtbR)AMEtWAh>HR&uRwWrM+OrCYg5v5T>iQrnt!WSiA>F4ZTFIaiSGPBr z)QB1;4fAF&(pV3_0rlXv1i!MmDfku~;alNblEC?N#i{o%>>Y5i*;nK@QT2l!rlz5Q+UfsJ&Wvu6y3C&~iq6Q~zQHBU0L zf=Vt^5%>jt%!%&NCzxXBqVS<^EMc*an9tk|*niu|ycxFA!!XldH)dNLg4|$@Bvs-@ z%WP2!HiAFcKSEoiOlk#OhtS_W-@wuiN}DvSy#UvJdB>5ob=VV9bf%R+IgdX>N|6Zc zJBL_^&V|1ciq$Hhs3KD7Y)|oQZdxh8i3H1CvXB8!&hU;W>%dm1uK$Dr+ZaJM(=m8p}!Jy0z0aBW-4UdJ83IxG@o5cSD4PaD=IW^ei@J% zymvW;^ooi|*G3h=2n9XN*rN!9U^JX_P%^_pn3(wJc-NqfAh&BGT+dw;@GzbTZj4c;SE z1Cy`|%CxPk?0dtVC z4Ki}C_pf@c;kr}f9$LUKMUY$R zqW`G=0R~vyQ1bX)1cC7A_NAAda(-X4vvKXqv-WP!vm8d;MUtqK`3&AHi>ofJn2h2? z@YSyB&KNM>Shfe7YB0lvH28;>YaWZmJN}r+?0n+SKc6hAo1$HiK?ee1R*TV`4^5Gv zRpm47Fy7disWiJ;zQOF!vp3&RoC}-O{X@`)QKS$iFe*6^KCHC0^r=B6fBb0YR`IO^ zupLg~RK+VF|GUyc>JbIa$Yqdg93s4To4XhF9l&+T8MX=D0!*ei>xiKBH(?YUjX@6> zLsb90uu~!S1_>FT)HCVTWNC?7kqD6i<$}spY|W-1$zB)JUtKniR6Qr?CHJ0t4AiAQ zTc^91tL>1hO@9%ZZ{sgDhu8n2zW^Qnw@#ndQ=SK$AUOmxBszbHz9QfF@p46!n`o|e z>#ggDzgulnFf|Q5#G-${$zP4j8i`vP|G;wcrWHAB;NcHW11#J>KwW0_-3N= z)EeVbtF1DE`oXI=@vH}*1GD{rLd9J4`xYa{mmOx%)v*q$S<1PZ7Ak%R67SQoPHQHf zsTny;Fpi4|Tjdl|((U@?FYR7c@)(CrT9KN-sHOPh199(Z>^aD9`;-6x*MJJ%?!|0X zsKfKKW4#a6ZpKA*ZYTQ!2c%*8mgzrtpUrKVX9PK@GK*!$pd4sc_g>-O64oOb1BbKm z=}idCL{s&l#J$#S$y%cp7GxE##Y`Q=^4mUh%^Pe-mXV~S@DsYd z#?o_EG99`^qaHD*k_gNEqpKezoiKrWdH2}Z$w-%I?^zd znuvI4_?m}HY3{|y&xvVq4XPj;VVV0vk_ZlFasMvCy&PID<^42MqX555#mJ4q1}}w9 zaq+A@5kUVGh|{=vAx=TUEAS_xsE!EY$gEQqB|3vBc<$1#!=~%1FV2k6#qaqIe&cLr zru`f|(`Izv5u*cC4czp6haViyMT+B)lUVw`rh?V*_%{ajPS7GYsyMjGIn4-&(#8$9 zNPX6(hJ+Y9x*=7HdS!5fPdXWf?3Q{(-zeQ<*ZU!-rsqi;h;rl5kf z_I(*vb6*k*L?HQ+4xc~s7NBvE&;qr#_#3!VEz*&6pA$+o8L7q((=xAxgwAmqKVvxh z9UQKXgZagK@qq1CcQ29JA2Yoofaw~M{#Qx!9+D2}EaF9h4ejri2#>`R zXIU3YZ0Kyo0DYyM6jB3U)KHNKqj`Q867yp+>DD>D!}HNZw3|w>IargIj}a@(XU;@@ z>Q(-$qR2#^psJ)TuOWh;*P0qLOPqON&Sr{=rB)zH4OA?c(++-2Wa;mMmYXwyj0*y! zFo|$cnolVMMYW)}G;N+}nLS0y1@MDx%;Ofl7GOw_zK6xuP7)~5Z;hVLW)B+Ar+p^= z#K!eV3s+b~Z@OOm$-or!)jUrKNaQJXMNMTqD2;NOx&E9@(_fT^kFL0Zo`ZOR+g1ct?* z5tEs(q-OjchmA&S2B@-1Ui~#Tz6tiTx5$8-?@3&FGKZ{D5?&*xkC;P9!lJf|f!vDS zE-kTNc%e>h9`7Rkol($1GXTdJ6k>7`Q3_h&AqDox-)J|1yUZ-(*x*cty>}JI?e*7o zHN~<|zgBw?h2Ol>6?>oHU7E=S=kzd`FOl!H+yj9JmHGs3Dcf zi@}V`k(89!*fk$rINFAv4c>C1$rRWBKLAcZvAxVY6U7iIF3%mkalD1#4y!DJ-`(?bxvXSSXSQjJ1MS#a2|M1Gb0>DyL;hx zblGOhhIz@VOT>?bpGnPU8m$dHfsl6$VwHuOh??sYroaJ@ZNqPbb2J6;L$P_&$0we8 zBf#A~>ls*aLz8tnx^oXZ1%%2j*n}GgCr-#J zu>+rA6F=_l%d|%A=Fes#OBG;-l>+$e#3SxPJ!GPZoTfe(o#P@lAqQV2n%KrLj-1q` z(d0|5MyDOshz%mCZh$s4@m#Z2PCFMQu^#v)(VfdR5bMUQxc_c}}9vq+Dy|(`Goj-B&EHas^ZE!-Hq1s09K~ZUfqSO~*3e ztdC2vs3UO_4p*bv!hmd985+-^q>q}vh;zGo)$S?Fv_b|&B+4AXyR#5!@r<;U`HBn1 zL)k7n@bi5hObH89o@y-RR$g{l>cJH{wffL0Rp}y$tdj&c1T5fnRd(6P#%nBwyAcV| z9_a&3BG;3ofmM-@>3RPQJtJn3a$i@Osd&p`eB7`R^T{o7vK7oz__|=Iy zsuvw@SYBZ}(3M~(_d73_J@v@*1OVdzE>wJjKD4?P#Qe1Zn%0T4z(?wLLgeq-IcjYg zum(p+rXR)Znbi|aSq&dwFq=<&mO$MFZKLH){L|NGl5`9YOuC*f;ms`pV%7xtxc`=Q zsjp@{&ECN)JN9+30rI9m#Hx}RDP{{YE+v#_5MMQW-%DZ&U}^ffIOQOB7uRM#Dir)& zPt&6I<#GSk+@9em;lOu)MgmG*l#=kAP14<-B(JgZc($XPe6R8PJ_Ao(_4?fx3DtwU zHW@vG%hoA2LcBFQMxpQ7;nVe9nEC6#9A01Ia@wf05Wk%2KP?Xls(?d=ml%P}#I`xh zc0F&NY`Cl=PbGOc#ct{sgc=RX3(asfO=;A*TmxhaRNh(T7c|Pii_E{Th)jdyaz1!1 z#!8E7IV(yALrSfz&`Kp`(m%(WhNif{%^eL0qVvjRKy3uPwgK`0^4pdH!?Mj~Pr^3m z2)wt-A3lAKjUhJMs#ziSeXo}BDKH03yIm`apLn77g@fC{INRUrPL^99RlEl1YVKf0 z|1St|>4>ek|B-haO@|ZEf*YCK1-EH~Ek<!e8jyjp>cO!#d{5r{`E}^hTU7o4e}jKN zzU>5DF0KruF&tXn!}@f7rSh+Y+KXEza*opgEdZw-`R-&tfQgjHNH)R!8}4!;0EH3g zl26j&L21A9iLcc&(OB$zawm#=)bq8ewq3C*-8eo($YO0S>8wij$+124t?+HS(9e}V zh%q9<6VA3&`@{bZ7oy^Jf5Y6mxdX`#QCwxdFZt|@M9h6~i%CNcbsW0cP(yL86i#g` zsL<4)12y*>GW8QQg1(J=Xgv>jm4?O2&|e(Qyl(a+m`NM@SMab9-N1a#5o6ij{Xl1N zB)pJB@G>OjO8BB#f5^r?HTTQWh8hMG0HzJE5`P;=%o;CSAj)nR9LoEjxB>kc3+Y~! z!;`aQ5{1vcN63od32EM*1D9D1a(`Kc`UkS8E)yeK*8`_z@;DewKy^5M9>sX6i!CK6 z4{oR_5>1K0&q_bTsDnc~MlPd)a`!@~MHGo>XITPt+^e~w$2z|7m5=lKxPFd$gtGL| z0SfY!1_}m3ZefO)`DbWHe=(7C!jV7}$JaZdH9C*#(ml|82GZv~8f%;a)4$~5tM{=@ z9;i|(n~s79^ly{ZmtNpe{F*GU;@7|8-T6~Xvhe3_GT$^06T3TU?7{qU_v8f`LMMmj zQJ3T15CDq+Kdw5R)*)qbWk$bDbQwAXw?l+kwzow5zsx&_Pu>Sf`F4m&g->N@TVuPI z6eYbiowV|eY!E8*t=^~dhFIOF&8X{)&ru6v?!a^Omui`NhkP=)0)p z60Wdadh{a_x$G68_80k8*#+iS1|M&0?Jn{lf{Ko~=g~~^U01Gys0i!jTajyMS%c0m z#rSk-2daNC_{F_vI3m%By;c>-g6Hfnh3qs!*N->A4iGUf`yzT1MQh{&se1kNHk962 zz&qkzNygV;pi&oiGKt0fXX~)Bzg6cs>A0=}oO}|Lmi-Yy!=pk`lOX~axe^$~xX)nL zd~H5ZptnLCy{W6*VI*a&@RHO^0$%gp%cY+p#g!nOvz=fdkEo zZBvTBX^d7;nXt5p0TlB%dC{K$fBXki?m2eVFv@vYOHUZv!<-^A@McL5Z}|vDHb=}v z?7vo#QY{EP^sT+a%K|T>gn($C(wP&#t6?~pslc{pg2&-pb(Z9*Gj@m0baO9m-(Tfy zO>vsWxjO&JW+PDa)`sY~{2QhM<6szG3C>)}P1=Aq+aY$Y)uYvP*k(3iQSb>o~m3tWXTw3#tj$lpkhV77f zMM9T4%lvMYOUlXVK;9zaUd62bm4Eq9xWn!^A5$S2aCNvl89S9k`5h&=fsHjo{o)H$ zCnMoODDRHN_Xon&o6nJMj3aT1!^K*aIWxM&k6%OWEMA6OxlFWAm8AFtjQ@Do z6)_(r8$M_GX^vVBS|9bkHHq1ZE>7cNkN>xa`&!OM{{!YNvsL$Hbz-{O%>y*xp%40q;+5=>qrdc!OK2hP2|Gl!`VP=({ zn)I6CeIMl*hDpHo8KN9R_dKp>R$asvX2~sPY+_|ZojC~^a)09QrUO;T0zO-BMPTSO z$jS0OXW?~K)r>LvWC7+S!3_I@|A2oHlVHoq+N-%u#3L>KX}Fp5RW0CN)_6`z*vf!2 zeWiuDqg(QVRNhFB58=n*;<~zF$a^D=X;Cdsp6h)ld-lRe#6zSJAyU^>i+3z9pTbH4k zokFRt4PTpZiAlU`75RuOW?GTIUE*u~dDON3iV)yRI7qD<#wN$VM(1YC3Oh+w%X31>^HUjYe z3NI)4gF1XK+l~MYUhXOX$~Nj?(YZC0WIjVd4F717MWT1L@gm9rYGFwLpphb$>)`+^ zx2pLyhiE>xFT8W)L_PeIBKW}Dl+;dofJQmmwd)nrR{1llN>(6DBohxfhDaJkPH-^m z^owh%k+-n13K}q0=x5;|_7MwA!Nh|}M{S*IuYsQ2d>a}4uiYW24$nj4#a<=7_MUfFrrfzPCI5gTh_ef$K2b8;f;cFy zr=Gz@C>2pbf_UXcqJ&G?0))xU)hZ2-b7jzgt8?HY^sh2^9RW<_vR-($GE^;BXNcSr z7ARGQ;RORsol5@o$*)yYWhkmuSjgMdQhQ6UZ|R2$Dtj4=ehM3=Rl2^zzOio`eV*d` zzn)v#hF*9_inOG5SWXeQ*xPV+`oBp7$I+ba6~?zv(fC)gK<`2#N$axaCppLj5~!2! z1bt}OEHS-LllsKkQw}qH9~X3OMSGbvcYIGG$7p4u>L^>s47PzY)^Mh*74|m+*qod* zHxv5)qnwEOk_KoOh<32b8qA!!sywM}nT`BEgJ@DprT)WE9EqY<;Hk|99=)P-;V7CM z$3S$p_i~OJ!Q={^Q9*CIT9yi|35NYWvaS(pH?yit3N@jzpZk7}{iWM)$j_6*^rO^m zj3uR3)Rc41H5w~!@(cm`dC8a~YotDc18i#KrVC`!0e)M`2d2P;)h9F*{{9eizi1Pt*|h^TFE$Q1ci$^bBzN(Gwc@P=}~eE z@9N9{-BqZB{3^l+ao)Z9J@AVjlru!Q??tl0GwrmN8*|!A_m2CY zl!%2tD^QxCd+<24<^m~#p1kv*a%D$j`Edg&!9Q0RoZfzkY$z>rN#>9>oI68?jP_4( zM=rd{LNc^b%w`dZUQWscQvBG7XYnm`a=XRDnI-HqK4sAaL>|LPDE#%7WqqqpacP00 zp(BBTb%^UP0frJObyU=kR)cA++R0N9JO)*6<0N*2lL=ON12F3b9_#Xag0z7*p(JlK zMOGKNCT_2`63CRy1$2a~EB|_2%k_p*Yt4J}7_$h|zV{@@m~ZFa(m3E;{;F^OaMOMN z$PwPZ%oye{bbolAvoHUTq&lUNirjF5@(0rPARevfdv_oJCrpL67c$zmy31hqf4Wxx`@bGD4KTqPXQQsViXPVXtIK=R)t4VPAf0RT z$mAU1IQHes%~c(JR}!VrUURdGODcbJPGr(!0P!bS^bP{zmZR@@N9YmfwMn*=ByppOKbz-5yw|23FUD&ohBB-bm?l^r9K5Rf&Pk1+S5*(Y{Z* zOGmmN;~Tbx!omM#t)6K>P}xGcQGBL~jt6sor&V+FG~m~OzO?tu|C|m`plj2mV1vUk zR4or*D%PlHP=Fs1JEEj5s|61L!{38*{`dE7vF3@|FpBTd;4>swf*j-Jq>-&?@_m%F za*#|S48sdL6BjsYN`?;?s)IMl!>LXoLS#VETjM_Y>1dcQu`2adxx`TGZA7v6xOv-B z8i1avQC2L`Nt&*%Y;|EjI#zSfH1_0m-W-xL8=_x8nGNkmfCJS zG|pVrff3K)kL-jtpQOl{2^i4l9GiZEKHZAE5&lVw887?4IBB65P0Q8H&j0;z zzCH|Bi;$Pqpb=q|IVtWfki8g0^v~43#NuYL@AlX&&6M1{pHkL!9NfEJlvfMwnug4I zwd;+X3~-pvC$`i_7!oH-IwN#MFm#I(Sik^GDk{h^5+tl#1*5R_2(ln_qL{#|*3!(z zp$3xxN6R=s&dmTZo@2DzR$%cJQGXe3`TlY?dqS5`UH_W7!pblafX~G-=MrPE{cF*N zFs;O-d}-gg@?r|RQNJ+z{4rD}SKvd@cGCD*Y1ohxR$JtG0KQ+!LBmT3l>o2v z0&ii#yk3}Qd%V~8Sy`&7eX!a()P$U(jw0Q)qzGB6yx^d4&d4clw!ppoo@Qml3yeS7 zLp&{*m0ma76krxD>~+1t^D>pDr_smQ^(9?1S1|`HE2W;VYHKW{_oo2Ut;2UNv0$VJ zKg?QSL@lqu&ny`BWS$co* z*+N%OxVhLygjSLb;Lz>%7v?zNUeq{Ax;0jURHh|>{@1Y6H$#?dzfsUh+5_a_BwdXK z-zt&nNwYIRNw^FQ75Kqd8uU)+WJ$7-VU}*D%|*Rbt*w2sJzQO8l>>KmKg&sVZ$wm7 z(upRN0Edpq=@U42$t|Z>%Xa?-y+loG<8C0*cCO=liOJN1N<+7Q7aKq&Lc`OTF+-tW zD?TO6<&ju)K0Lo;Q{J9@B>5w4xERzZSJQs7ZCj2U_v^rX)Kj$Dejc=dj7ru8UU_+F zSO7bqwekq)xZ~8dA~gz^N(`zEr&EQz8i5OACkEDR9J_WzsQLUnDXbJyIJKN_CwTc7 zqVap}N{2Xc?;V{cTO`?P+FlyTM5sy} zE8KJ~l%9;XG{T#UKU#1uBf_z^)zM7ptJDVoZvl~p5p^vBIz`z!+)Mmat(B>ko};K> z>eVJhXZxm8=^+9s5y^}p*IN&ujK`WaP8lQo+1$E+yf$UIm1T73K=ixC4;HLOH`e_B?P?4MO1iyd4`tUFR9E_R$dIVO<|5<&6qYlKMU5cs(>RvJ~ z2)Pl6I2I|0eTxpFNH1&x&za-={!zs#l)+JspJl;{621eb&e(<(Xp;a-m6P0v!30iR4E&mG@19 zq2GJ3W-;wNS9FE;QOSXQxJy)^T|KQqD413c&_;PN@((9GTCoC4afbNmW~J5UJ|?Ri zI)Bez=-=AT@_=kYQ3Q>;h;!^6#Y}I3>t?B}l8YNHB-*X%Lg~+N_|3@JO&2v*wC9~A zveuwTQDJyg*FEC{p80N3mmeNLRZ4O}jsW3)O-Sqa{V0N0GgWFeBs#o+B2f8OIg#aG z?)wosMC4d@b>4VP^>u&)JZJdu44M4vD90D3J z!ULxxHey?oLv2H~W#?IFNavN;?a1nJm{tkH=oMig*nX_VQP%waoh68wH z%Ax(1uKz)YVFC2Bw9>`;e|7F_5>NX*7Pk##D054RS3B z^A+X_W6u%3^XqW8Q>J}T!dJ7v6X|vR-7Kz8m{I*TEie{6h5enr+pi~Al0*qHU~p~ijbHPR#-J{rx`Kq_w}ga2R;i3t=0Pjm6h5b zm$^wVrGNt-ZZfg|cmSvv1YDQ#OVn`s1&&Zk(<%3a9uZ0?!(H;6#0BLI?$buf_lxpIn3L$JN6=j?mfX1}Pu#(Rw=C{UYMF#B z89uz~TK`|KmfN<{OqWF>oP1@9>Oc=z5mtPW0Qv&GN*m11%IW`ug6Ud{F?e?Anja@O z3Su_AH{e)s>M=WENW;a-Ry!y_jyLrLhDF`Fc}brw_c!GP5D^srR(1^Gb&GX!R{{ z6{K!;d4l350s6*@e8&=swg=AB;<)0ATtYEW3hTM1Iim}ot`ZvGNDB32*UOlmzscZi zPT7ONm8TC6zpRQ+qF`id*o*CK{*UjAIz$44I%yhx&up`(Ngw@UX6=4Cv--q0lQx6(!^oi z-FZM{d@fw~rQPhNK~Imf)9Ic|%eGT)5>dEQQo6m$T~kq&V6m+-%IApb^Rx+NEp2b9 zzeQ>@)2l!jl?@6o;VQEyfNqeha;Q%q`~Z%lj+BL;dT($)+*)rxQ$m3QYEpt!u9uS4 z%{KkD94^E*`$OG-Ui*s>XnRzkx1Jat3)N{65a)F=^tb(TVfXt#xA~(E1V&i@cU}$Y z0A`CY18ZSDB;+wyNEfPbi#mLl8kyA?8`--tS!c3_pbfcm4X7VB z>Wut!#nSUJ*@!?HvL~6%XBj@c=54x}jxfQNe^-I>Y%%DF%-$yy(sr{8|7)Y8z%#FTGs(iqgT7apNH-9w*Qi zgYDF2)H5o+)w(s#d#Nh*;PWNw7D?l{vrNAWO6r#g5c=viJ?z?FbesOS9k)|AXw#)J znlIiK|LYGLaO_bl?<TZu3Vnw%c`@8;%;641`p=5%ftU zryzT0aC~Ep8ZX8fISKLNAN)4?x_Fn2F@vaMs4N+M^SVpq)i#YXz=yT#Og<#&*M99G z!g;XqDU+qva$@P8=@3Gl3@#2Z)590jPPA%x?o{#08L`?>6RTtIqCPtAuabCC;7*z3 zO^rS?Ei5-PqLbp9@GI&oY2=zXCj-qY_c*ynW>SL+)3SJGD41Gwyl#pMU9B@zzTP=M*A&_AoOPE$4H~WosuQg}c9gr6iKOa0qu#rr zj)iohA3%(6^}GV)3Ex=>AC4c-aH5n?+t;)Ba(^JFOe;|LtJ6rQH#7dCi~C9&ha(me z)qqv0J#D-i8QvFjR1Ik&Oh{+HOV7rA!6?e@+6!}ch~?E1uts_)$zUy`*g@5n5ni?t zmtJ4X8PR)Z6+rm1x+ov^x<=mQ*8=Kyq>LSCq1b84&pk5-o(2%MIWZJRbAiaCu$UGD_w6h$|;nlO21|_>$X&>}cd*chB ziFn9Sf74HcBEL#7@R2~MFUdqU-6Xayw0A=={B6rx<41NCVE8X_TBC6~vHz6s4p0P` zhdbq22#80u1bgR>w?s*98068e=iQaUr^dKTl-URqJr155lGiUYxP$Eon3SXSNvTg4 zmfBz(SY0Zt24i`!1zx~E?XrSW=(k8gG|7QJZ62}K#`%`d0Hpf115+;S&P_*#f|pKq zSXz6V-@f#IeR$(LIDF3g2{i|qZJ30~;W{=2$l;#YqvBcyw%)={dbXF8^J0}sD--im z_ujKzdL!)$F8}L2Y9G;bvLUl0Bz1weXmurAGl2ATosj%RmlM%>lN&_Dw^YtEG1muO zr%M{+z~k*M17UlNkIETF_BxIaMe}ZymPBtPS;+U2H6&xxTmEnA2IaeL{#q!XqT&VY zyPIC4A0Of6u!RhM*wlEEYp$Oo?Yxqw^PU3GN0fAXLovOvbLFjc4Ov&`+`qT~{msF^ z20&z%$|B14_>gskug1v+E{GJarY-(xQPuAUu5}MymZ2lBP2)^$(@m>MU!HjzjOffs03aPe08P;--8?x;J^}%ZXg`(!j~R^wdKp z6bn-XVfCDop9ra%2>oNd#yhMAl==BhTgXv#(X2iCIZCZBPvzvi|^1X&*+Bhy)}ahTrh1|{{wcTAsg zXX)rz^$J{0`mN;to<)poM zqHkh2+mZm7`5?~#?(6I9jWu~ziG{pUM%AJpWcU$Tz#=42u;r0|C~*)mR7DveZHL`w zYwov8`N=u`#F(mBK`GD~XWePrkZe6%$d~_4rq`$nh}i!=@cBFZy(C|d5!nYBpj+=& zvg-&#zr~uSyqz$emfzHg{_rIPN8E6qfli(>eQ+U!2Ppx$)G%S)6*_5tbASBG4M@A! zGN1Lb9V-aGtV5cCagNDjOv_-E?G~1I6nS9T9i1Fx@qQva3Kvf8~=G%OJ+l-TfJ-u1dyZ9MZv!rg zaYvolB0bnAQ|1z08yCLl>1FKvl%F}c0|N~I^~X%g9QGJpaVi1e<~_v7cartx_aMaM z0Qan-0a|5*OB`mRCCHQk$dCc0MM}kwJYx_4HOD^D*~O$!>2W@!!*g7^&|Qgh=6A#ePml^jwKCZQAp~TnB1J3h#sT_w zJ7jYN0~tQPGM9rTrvGQch|~#i9qIcC0Op|psb=7R5b(8@XU`2Ln8g{F7MhjRUYFj? zjRwwPfJ*7t%@0kac@@5O%4&Hqz_+3a!pUq+-f}V@fS))j&>t=Wz_M(wbv`+rW>nOu zWxRs%MHH%XC!0Zv8CKIDJiT|)&GzQyz-*Bze&z3#4HnP>FjVO3IdxsWex2$%Q?xWp zvv;?siMXDN4B(>-1be~Jl=N2#b1g#8$Q68sqyYqh?l5nNTv9BVmV|@Z2{Oj~^oc;; zN!%c2EWG-MG#Wh!rhI{DbhaV7nOR^(*f>yi!ytkfRGWR?uq#bxbnwW!dO=fWkd0O) znh94Qs3;?*mRRh#z*GECdnrk&qp{rihYjKX=e7)?9xgC=dE0U+;j^oVtS|fQsLxxMJXW7T2Q>s zjl!!tv-dh~Lm+Qy_#o=0RL~!W6xXJClADcM-5@;$qYFESE_)M;0~B#T|NR|Y)P5+p z{n04AwL?DoLP6T>0riWGi^)WVrD@0B+{}@ox6`XpVy{`EL~E;vRMP;4s`(w z)^wtbeTk1SodR5#HJP_!`cC-+I3gA}frft++|gMn^6o`8C(QVpT}xIDx8KqQl#X?E zY`y0rMI{_~$aOUBKe|lQ0hUQe>r3sSBk(t9=YiM}vW;wS{N$fj&Qj~W<6=*d>LB&&KKP|7qGFoKp{*ex zfg=ap6W?le3QAj20J!619784bsYh{>s=@ezh;TcI9euJwtZ&pKJX|e)$z;)%NXu)4 z2&Q&>LJ2DzA0ZBhq!9bHAogJ`vPz6SqAJ*USCVkGM1qdMV@xO6=yF{2 zbf(tFzxd(H0GoGimrzZ^D9}(REXHJwX}HEA^*~ot-?pC4yr`Zh;J1e0^jv$ zq0v9RZv3z^3X7l#^Q{m9kaH8q zFR=on?zMVIJXwgh81Wuz)tpD-9Z;q&M5}r>z|2@d7AZ&jr zmK}x(0_~<^sW)+)<%k2-Yx^LS`bY8Ig6Y}oC$?)FMKwem)rHh9$NNq zP8grn;%%1Rk?p`>aONb>e{j+EK3WX=@dO^tb{1O6`@4VHP?7T9$@R#g=Ft&a%BH(K zD0DCm);n!a3p+wjO81$!k4?qAyuTBU7sJv#o2W&@m~|JoPJ3n&O2K+ibv)!mx*yVfmhwjPpPp)A2?&nU(-;~KFArLh%;=9Dp zjBj4V!yJ~x>ql6orP3+snV5ISAX#L=H$I{ZY#r}l8Pag+bGQQfoZvKvU!K^U&e&I| zwxn&fykBze!GfXMF*v8AohZi-*y-&COGla^{?u;y-}}$ zadu~IO<_3;GC}K;9Q1wpzu<4?*PP7r^~djh{me5JoJB3b;g2jM2M7a6yIg+oR~bFN zP@kJ?_*PXlUy^a`C(Hl;`F_EE7foYfYYq1>$)C}m(!eUlT{9*FGPRF*u8JDLobEufX%T_ov~R$ zRKn;WVi;ikCR4q$D4O`jSNrF0CoAdMmOR=8-e#O%|0Bmdmkx6qu%O3dwYM1D@6wa9 z=E3U2{%yuEmg1;N=vGR4*g?>(JdF2fWtNj7JyRyvaYIpv%Yz2BeACg`NgdDRpgnru zrxH<#4*gjcd*^(y&IMujVkRKA;Cz063iW|~y*^9bOVUX#OAo!7vi|RYxJZeyWR)%- z#0SqI>pkuVF--kZe1I^D5?_19cmAbdv7@7`T=nUwI$eX}7Z%R8Iz%~cLpw&sI!HPU zC8L&8c+`%nc=_gXL>S0C6fk?wz*wkcZ*MeVI5sTs$DWpUf^|7g$q(O=NCHeNl2`ii zL4I~_(5zp#@pk{HpR2+ zqqMs|^Uk(j*Z)K7w-0rV%K=A_Z~g++pA@b?%ltVSul^xLp6g~tkAmc%fdy_pDzJ26 zQc6noh35rqgu8o+)a9JeAu z$(l5Y`LKVVY0C#7p#0q-!LkxN_mT0aOpu!K8oKu*llh|-vp1xo5GhnGc}UfpJ(m7J zCjs{F6L>#R1@@YG6yV2w0SAjDeDCXp3x5qM%rlAXG>lne5s@}i!9d(d#8kKHI+zZ8 z19E#?oNMwY z)1p|pcBfa~YM%KDlA4rc6Vrz<+V9Zv)Mi6M0Yew(NNAbxnRX$VEz063rv%Exq`9;c zA0vyhM;;Aur(h5wt#Ff3(~-4B1>`!7-=E{1{z=`Ee&J&3 zIoC6lTLjeb^fkU;Fw|bTQo_}g4?c#@hkr{(r7gs|CGcywhjWE^`ET~U|1#ULoIesQj zg06k;pzr+?_ScJ(?W&F`M6aH_I4lek+mEu@vqRb|+xmMyeZ&HxdZL0E8DA4V7fN)3 zMqIJ9Tr4iwCJ11R&M}c`H^~-Sq|k3o#x%&0K+5%NcH<0cH%)W@d2jr~`Fl}WuBfD5 zgJ-7E7SeWX$DC3lB0o^0@JAAiSDax-q@U&V@5c$#h@E2FBJqPtYseoB(;dzp&_?bp z6>2$tlFOJ#h1w!VhciFK*UjyB4L5&LxNH&G_c3e1>`)v0eO$4R<%82j`y!y>Rso`$ zkx>;1GH0wcFZ!jMSI@NMBY`@!x8H->8C?59r70a3dhG*j*KLhT3K&?RC>|VVFEM0B z{t-pXCA?Knw6=+P`lg0P-%qe_{60xJ+MC3d;%loG@I1Jn9bG@4Ew!@=K;U*Z9gE4P#gX1WEBWmY+UT&Po zfPi|i0M6mDa8g;QtD97a4iVeiDZ~9*iJUV@WgG+_lk=Q_BZ3R8f9-uF=x$21@T+hw z!#x2lKt-OkLvcBp+P=&HP%tiOa0?gs&utCOMx~+o= z$%EDE_deN=X!B_r@^+q)YHwScV%fLv$Ka&SCKL)-K@r;i73 z;x-Y(dMU*VMh*>HcbXm!RsHkh*xKD!r#EC@EBB~dAbV=h`AS%+o99hKrDq%0=F)%7 zrHO55WK_#AG*&S6&G^g#TS_Dk%|E-$c~gJNXGfxtup8JdV8AP-+=K|*JofvfqZYXH zPD!Gcn2CVQ7O~jyRX>YPQuRs;kBwC~V)A-b%x>nVy5+B2Ie8Tic^PkiK2k49U}CKD zs*^px{Fm?6^IL93z&d5GlXOH)$t$*RD+hV6c_`msG@KcPb_K<&GM(pC2Hk;I>&Yxm zyag;;?xhn?8abcCq8rAyIxQu4Dbs;~Ac25{>e=VAc8+QU<$E-LcPX`U(6+i2!lcro z&b9nJoN#6rXBt(ltjCkk5Q9zwN3>if+1!$+j*^la<#*JH@m7=fia!Q%2dJ|c0YNp| zpM^BxjjpTE^~)yL#MOB{9F3aKC?e97$(<=_vvCvGqzdAcpZhFn-OL3B zAk=`OO&@#}U5@%vknm?@-$obhX}qaAH)oq9UaJMcyi;H&2aypnA|H$y9?y#S*oe?9Fr$V)oPPE!o?xrX8m?XD%8Ltkg&Dy z2o_Sa_UiVYw3xrJ>gAy8s}H|A=iE5#rU?a0!gZ1U_r-~m=Den;kddElJa-j;`Op+f zR*wFHuesw84<|q7DhBv7Cws8z^*B1VG9fe&b7y^U0;y0zd#1(MVJ?96Ow;K+!y)tD zyJ-K3*(z+GXcAN8DQdv!LSdN#9Mvmel49DN$oFU8%gm~u3V{$c9f$<-Z+y76aiXWj zB7{m-y-Inm8QX7#{kNd6kTb6^1+d`29Cmn5JM!_t(Ozrd7E&OQjRFUeW)+{?f0OjN z>n<+50s=|jgS|XVDaQf`_%zO1?u<){;1(5Pbezw(t}Xp3njU8|deO##bjnX0GLKL*YgN5_1%I5K{7kPa=kh`!#onYU8oKiw5@KHMXt<+J3wrFl8$xrp`|%_2SLsD6%K04$e(fRK1XAcH=qH3=IDY!gDMP6w9I)7v*K z;UG8eS{s>LS6t7j5cSfS^yPOxg-TTG8)-ctc$a#|4g$o^ZlxbFRihlQpi+m3n@pG_o2*fX|(l1a0NIPYfWiWq|&nF%yV zzwCBP*cfv`9_!yuV}^YXOuF2j^A|H!IMng9VuGiRQ_2aXj|9%w^9nn(C4l5rom^?_ z3|nD3@}BFhr*!mF;6^n#M<#1KlACb4DyKx7O)+(V?itoV;X)BYHgrM__%0XiPt832 zW%fAlOBC%zc}}~JHVE7DKxH7|ot5|UcOS3589Fa!hyT{&ix#Tt+-n;N%bIC;Ue22J zZ$so?<5w)Zid^juJF-pEqCiNPqNF8YdP_AR^TMA7``nvf>G3vzEXWN$MRTe-s&OAs z)N;vB5Fn645?wPrh$hg*jJ93~==txg>vBmzH@U`~&k_7O+`ay!6GyXOl{=;G|01_w z_V)@y{phIOc@8Ho4W96uf2%Iml%j!d7-Xte_@c!{XBEnSE6n|%N9jBDWZ_1?k&DAp zapg70^Ss;IY|FxeSMKspKiS?pmoq}ETaPevmSR<$Yhcb##jw^pQ&|go2)m9l z*wBVO!#hL*zO!^x&VU|`|3ohmiHeUU*7i-+MT0urP^(#^kWiP&GxY!C4ymImJ4h?h zT1lIzJBOQ3ci}4vm3U+4mHMW5_Pv@WzBLkeGRti^?B@}WQt@&c0*qOxk`SNqSq?s_ zz|D}*sE8u5rrOTr{3fY^wlJ{XvL9A(A=@AM1k)<)cVkK8BA6a3P(G&VKJt2V^S-U& z^dlY8k^biHI)EeO&@hYn} z?i__V9l&Gy-_sb(@bD7vn_dK485!bew&6ACeT91Y}(+qPgsbsO-DqLFRdfg*yENV3NC<~IoyCwfdW%`7c>GJe0w zB)zC&^cBPFQjy_%DV63ziTf_E7F|o2zS^~!`nqZAC%6l@0cf<3>`m>L@Zr(%Jcw>WXYHAns$5ixQA z3MPuXmIoi9&KkKfX-y{ZrHJyFJv7f(HAa{9>aX4oOsm2E3GJhQ4K}M(3u)tXjigD) zOzb9ocQBMOOv6i+xD@i7`m%PPIbd0rQMM(!XHx4mbwMG^LY85K)=9lb#hlLaU}1Fo zCX12aNHnR~u^r^Mj>@XKq%~t(J%s;EEU1?hZgwD;zSf0IO ztR1M32&W*v=w$aYhqz%2D$^o{rR?^eDEBs2(uB3=yKktJ%Ol>oN;e4G4? z`i9xb%r1h)gZjSVNDiSnG=+NFHWh2z$8lKb5&>!Z&J^YS3x7!bvXaNAB!4a2pTMYJ z6LGfuc%$>t08Bu$zm41OKF8Y(#V{1(U5!tnaH(ATqd_A;<%6AqK>XbR52+0*?bO9) zjL;!;L0#W(x(GJy&pVyS6cV8egf_qpuI{ZM%kf@aq`gl$b%j_k3@Bn!j@(+vT`%~1 zt@Mwqt^(F89Wg=3B3UrhVf9hvA05d34XbRm-CeX2M@fYfR=j@JfQ2RZHp|@ ziUE4ztE@HoMlQ$HG3VKANP_b-9p2o!QBw9R;%eu2#yAC!=_fX&+CUH#7}!`h7yL;W zyKzQt|3v8-f9r(4(syhg*YvDO5mbWHYoN=yg`D0R6}OX3b_#g0fC|7tfcnQfm_#{Wd<&y1{PG(gqR7!Zgfkgh#-)QEDl5oV{;V-bj9vL6?0Eo9M} zJQHOgWuNYkFTmyjy2tqgL~Knqz+av-nUY7|17I8kESCWX&WlUlx`8+SRzA(?W3+oN z4`DJKgixR%@R;~JhA+`_D4MAC;x40{@sTwbZ_ zoaELjaGaDs7sowrC7FI>4^Fas@wROmjSEGNwAC}XM{w-4!^3O|hIrYbx}r1LLPtmf zo(24DMTkBTcxd)@HBBAU)>F~M|9mWGZH*xPH6N+f-Kb(d+$v?ebRg+7#q$t$iqjV3 zCxHp1u!WU-r6<@9W+Ik}#u`dg7va6qrB|4ruw)_$9FF}c@Xb)$1W}kYo`i3KKEm7V z-)@H2ULd&aHG#JkI+N7>@408Dn|05k|Ffi+kvU{Z?qc)##l4xk%) zWSfLgcJNFqY<&SR*;n)CqxyLS7TNY2S?d&&Ts3SsS43a>6-nEg{}xm+De==m^k5gv z`HO$PGj%FRoY3}wS+N)xy~a)J81pNjZNoyFP^U*6eE|k)843K-X+l4buG}?!k#@U=9kNJ8!`PF~Q`QDyYtVLsM^iQNCU}z6K`=sT z4LCL>>4}<$c>8w9I{A={_uImJZ$sGs#l*Ux#GRBvjX-&6n8?UGz8e`c&*YqUzrtg) zAW{3sS8*72A+R+m@lS@iEL@V3ZPr z)A!LZ_2PrY_t>0ULWSC%Gt=SzAOW;xQPF3~b0F6572y&9b4`%jWRT01P`J4tq* zt<4T&5bdtVpSiB1DQFk56^^HWgecCp(S0Jy)_7~~h8*>M5t~>%QbjP+{(!=^y}8NM zh*UiHhB*4$ZIwknD+uJM(>&zISP7ep3v~FbsLj5p2qENTwKhTk;!^~z{#2C#@6Lux z$nvc#Cb;^`l>OGZ2qNg{03@w6w2(f0hNo8_YTlRk+|5p^V6L$?a&(*K>JiI+&UZzU zBPzEl8(mph?@`$QKxrwoyKEE##q!4(l#8LSXQtpo$2=G^h9B8b|1|D?bR(u zdc%w>lS2}~L+Rpv#Jj#kx&bVXBvbwAtSY(dkKbjX`4q*6KLOvA51cxsG(3ekz>S#o zQwUin4wjP6phGG~zpv!sGo@S~3>W;<|5}TJtqjHp2J<)cLM!A;tCod;^ZOL>Oam?6 zkuIgc37^yM|CyXcCix3G?~!Ph85~bTe-|6iccr_Ai^jM(4s-RdhF0#>#rFy4l!qT2 zW?T@ajW3>=PsE(2c6~a~o!JVN&K`f;FAU$*>}nVms*m}0w+~NNp%h1uNd-yq$geX~ zRkQLwv7c+oiM$@@koLq1_Uj0qS@OS90h!ls|FaDNe7K9l9t}12kO$0fjtsc(+epCO zT1qQF6B~j3kJ1|PxtRK_C}kd_l+1wd4*|90pC4J=lWX-fwDU0j_D!htf&r~|VGIrT z4E8&U2xgKDR^%g@u|7HFCLEf$Yzw*ISIq@vq#+<1S$V6#&1~sBEZ<=x->R2C5702c zg<21fD`O$(Dzq9|K@?k%uhVP@uw}J$`>TdoDw1B|8$smwnh`o_FWNNGJ{F3uHpJlS zuB5J*gL}K`Ulu3i8F4}ut?~86y8M~}h50+|?^AuR2{}R(P;fk3q)x$pnAs$XjkZg+uo0tU!bkn)LTqyduQ${y+86?qd%aU$`)BbXJd zn{W4PX!eO8z~S22=a*2EUp{4Z6F*?cyIw$?TGpNl;tP4Jwm;IxZtNp*e#$}6QzIv} zX0}~qzwm*h2=ysC(eyj$6;Duku&>EkI~WNuFjpG*dRJF31B`cLu*#u>3eZ|)GfZFT z&NxV(R{wSM@E~s&dCx%;Bd!mSWFRW1a{eJ5Sk2r6QHK4$rc5Em2b|a8ap{>>lNKV& zq+2!VPumX+T|7ToG1?ZC%N_f3NOSW0S(?ug+4z~k6}ERj7^lgK{q0J-%D&k2HFSg) z2-&K*H=X)g3>+H|BhRrMx0VHInX%l?4l1Coiv_e+R3GWfSM71i|0l0qD>aOu`4BTfqquBV))Fk3Bnj-P_ zT!vyGbaqh9Z3w;3J$CF7n87150aYDbz5AB&G8sv4ym@Y6;!5}DkGZ{XI-tes*fqmi z!LU1Vpc+B!^QlIoyS$Kt`3d&ux7w;9#)&!dTEp%s{q?Y`u0Mc_P6=G}{XYHurlxO#y%wE+_ZUK$ z817%jr3-+*63Z4k&ZSDI!K4L*fHK%ujWleXB(v6>?WD%rjLJ7n7sgJO(#{RYRNL$2 z;qmZDTo)T0XlisMDat2n9-$EvZe3RBh_tTqr4?ArHV7`Y3xdC%S|4?y5!ZY0lG0c; zz6poLMFh50paAauYAqkDs?;j?dF1}l{6g90T_wfMTPpDq7EY`C=IxDOzGo~|{1u56|C_hl$ulw9-%9o50rGG744g2= zzD7f;&bgV$yl&3Qu8B-uXx7;xJqgvsI~Mc@Cai>uqC}cl^5Z`KxsMs$YAz@d4gy^Z z!dM^{p3heq)w5J-wO6Fsn&M6%&T~9-J;^xM86(iI!5AHrYLg4Z`fkmWMd`^sKW-iN zX&41@IG(|4xt#ck;*|h~%d2q(JMk`x*Kav?kuB%;GI|mORKE(#h?%l20ln0&A45sG zLz(~$nlT})^nEzwMx($vW-%S>J?b8LMxCOV#Jzb4(grMMBN@OIrL@K*%P5KXY_OQU4wAKCJ4%ljy4 zd}YIbYAUYwfNZBpmF#i|!uL(Mm?M@XY6c=9x)IKQcJxk`=z*ww>+R}j<5{GKz;Uu) z7w|6{oI}n>To73$jy9!l%4w zC})}Fac3wipK%?eTvHM@tx+{Ti^UsfwxR62HgBhxM8Rcp@u$vO62S|euoHey6BTk< zbyUMAHd)u+m57KX>H_7D4(8!h;JB%o_ha4 zxG3L~apkLIB3h5DGK9x|#nCR^2<_yLGPpaBzPv=cm{Wi9=#JlH%raB!ry!)w zfqMXVKo%6sBcL(lt#+g+y^SyY;>EDTB+;<2lKscaa$?GHuEf>sGvmw>v=F^#8A>LL~?n<37~P87k?^<0HhEz5@_tP{qpLUmN!eb9hLL`#WU6==wf^lb0x6AA@W<@-8 zlAuOG)J-%@jQDsaNv=|ds^~X1yCZyh7@UZv{TwDNx~bPP)aqg9O%IYsUx53J45A_V z1$4(1n!Zs?r-P#tv}zn`I8cOyJdUzNl* zuvSO^@6j8y=)Y35jH`?W zYQKhT{u|~|cP~*_<@hvRM{`C*)^O2=)Wmku~T5J67AQVRHds{!2B zf2g#=`w%we@R`T}v?H#^;mCDSnyGdnAkU|APxo%P8y4NA$Y|YUIiS5uL0&%ICkE0T zllhZgdoeM-hP6B?#5cbtV_OCl`9=-1ykmzN1156|A;eZ4byeX)FaJRfBffMXY8)ti zJ|ay)kYW4#$?vN;vYrbYt3Nf&GbTT#*yo?@CRy@v zK8v>bHOy3%x(%RuO->O6D~{fkDJG-rUC(1~s@J&*pUrhq3?A9jNzUismzdG{z@WW{ zmkzhC#(Atvfik(1Lz4SJaeaI)6xVTOm2g#0EADTils}u#gDTkL74jHFNuC7-JZ$XTGUom$X4ypToRh~iU{CL==dKzz)5pfBU|8HW=Sif$_l+-a_TrPB=9sUezBpiy=_u9Iq> z6-sIF-^r`L2CqPns5W&O;PAeNgaxxX3xyLVIMfX%AJL(;O|#`N-yNK}V+n2AG_a1F z5VI?xl&<`hJ@OHeFK;vz8cZ;98KYKJ979;4N$9EUab+oj~(q@?k& zRkDF@*dU($pSbd`Z}vx@68Z4prZWcCwYyh2B9;8xM&rCuj*ko9o?w*HCOS%G?CC0r{Vy z@8cTEIsf4!ZK5=Jz&KWSSr+dR0e%wPkU`?Ud1(&JmyoE5GAc)OWyJHQq3U!RofE<< z7#oDG4}b6Uc&%&{Ob#0}9AL2@UEzZbvi6YZtbW_)x@7l67*#}X5vGPz8=ts^780Qw zKyfMzX_Zkg{YC}#^Q_#W31Qc(;F0#=f@m_4#WXn=&z#*9lq^ z34NGsJca|y>A4N*$~~ofXoFXARbPAF`mYQKbC&Kma9`AV$*I^|`~DYBY>CJ09M~>; zCY6LNunsxG;=xxmJD6-hz)6JpBr#!p>}iDI6ZtHa*0yu4%;4jYdqoW#^!;w6E~_8} z%WxX(UL8|ow_mxi*1iFn0L#w(E?rXb5sT&bG!uB17@-nLs&^)*+(T1TH)8gJ-wd2Z znhMxExyLt5B3imNcH13I8ers+H|bp){kfzy1*bqg)TD=F3X+$agZMD=nGCGf8m!BS zD+)5Zh;`b;Z^&CC3^I5d=#fNL`35h4TG4IY3(^tq)cs(%+wh;w@V&iNg4(SF+MN!=1g9JTFm6Jx_bS$G{Q(pFa_)OoS!k7?RCk;d+k}!1}h?0ag_;`U9 z=>Dow%Y7VTa`i{x1*F~H#9vEKZ-ASjM1p&5Z85>~`Ij4^2%KFT29ucmijgnYYv1c{ z8w{ax{)D;*M8r+Q?Bsl(XdH}2gXkrqg~~$H_Lv>7{t^eH&1JfXH3~&vhi%BPV1+M3 zD%B3UFK&-*E>Q9QMHN>4N)xTlNDLMg3v`ZYi@&-J!@vs2K-^JSqk=fDK`w)p{wlZ^ zlduK;{{Kvz8P%GpRUFtC4J8q4A4*N74w;Dm9W!lNO30@&CrD?e--tbGOO>X~tW(aX zCOi2rWIGqD>u;CiPcmnA!Q0|~Si4EVUX+3_9VYLmA=tr5QACv*=T_^Fjm|m`AxfD0$g?srGW?Ho-e+W%6 z%pf>zrfhx9cxZ#^sWplgpIw7Rj&@jkpBauZ@K07!GC{MyOeDbpqmlBaYnVh37slNZtQM5y}}*8oI|$MLD^BD7%qESEm+wv1!WsW(p~I`Pe=NON8I2dtr?*NAX;WND1XIQ z*j7NS&1Mg=cLUpK`%LGQPTDAs4uwqIZK!KO`%Yhf%>t>v9#7n<^><65k?szn+dYC2 z<7O{sk)fjuvM@ zINGO@^jrc&c12=vEhGQQ7)BB1n54$c0WG=^}w@M-qh~2sq6k36> z`w#U19--X}BM5DPS*)aNutFPassa`j+<@K!wAK+lMZizxy#k$Q;8D-HaU?I#(5SsL zvj03_9q|;}QRbvj?ydxCQEsWP`hggkE7!jYAD^n=p=l{Scra+4DcH`ze#JdI7m3jN zIuq-*OBkt7g^WJP8Fyx@%_r_z1$AQ<)J;3|g6Tq45XUraEXG#;jj?CmFrMf1eIJh} zwcvONBd(G?46g6;h}9bk)@mT@ga#oiZL+6o1uxMM(+1YezKP=@^Wi_2Js{t;+kui^ zg&I}FZ(yZ6G>*4g^P1$Ec?^azUhkj)D^A%?a$NySS=CoAnC3i<4?IEm4KD1|i>-lR z(h=lf6sC#d%ao>;H=}DfE5#_6^v`pPCGegr>KreW3_dHrJ zpb!Gst}=res|CfC-R1h>8cNGN;{fzW{}>n!ZCgDC=h1ym3RzFN4TJGUo%CWleO2wEjn-CwPbX-iJPG=SbN5K(yaHa9c$}_B( zF%_V4d&OvcaWO7l23MlU7A6@zT02dmX}4tc$Tqw2=)Sv;o*j*Im_fqm%JW*gH}idV+xQ4C%i6(VDb^0R5TIY3>(SAgFP#EubR z0a@y__Vg)*#O2bmtos#=-$4DY7=Hzjn(Geui5iTKD`?l9TVpxy6vf%VQ&w0m8mySz zgQM=3jx5h)s--N?6RL0|7W1V!v63 zV&X4Tg%G9K!>C`gvUmJ+IiXJM2+1STQ?1ueN+=*W=0>NpU?nvwBygY{<2}=@A8z^? z5Mw^6-TUBjF|;_f{=Dj1|1*Tc??C~&uA~2nbOkr@-f`cH^tvop4DC49eAEqIl%t4a zCthyn!a$62z6v5?F=7ruK8Zx*9%<#HTEcxc^gZS?+bcRpRCQQBdf>$~)u41a8SYN+sor=$Nc|EM zJeWaeG_|oXpV^~UbLnq>_2{IzJy0PhkGT3z*sAV?Yk6xJw*)uzvgwOYtePn=mPSw% z4o$2@L!X1Uqzl%O5s$RBRF9Icej=iJ(8C+Zo&DwOKL*~*ZO$?Jy%WnAy_;qn#gT>hE291a`>T8i~7 zRv+;FQc`KOBRCa(TOPfS4Mk}kTmeKl`yFd5yOzdKlst2kkr?le$UAqkL8^ImAQ)Ag7yY!7l@{-Ccq-XAGmK)ce+fbVHOs}y?fe; z_LSueh(yg9<-f5*1a8il^V)(gaoR(Op1dXKJR|5?`qV{@`V{b`&=$f~UaCnqkdaRoCd29|cy6H)*3025>JxU!LlO|=V1UXRuYU4iCY^6omLnYGxSvqNmOk412;<*ViEcV z#HOIw9-G56UIjBzR}i040apD1ANf)LdvIRXiQU`~JjjQw+7A$$dsg05N^&)SSN-IF zG<}tkl6f%FIZD(tL%=KvWOt)~D~}4*cLl^MY7OAUT)g?yTnaDqfckz#+!5-khRDrv zTQO55BQX<6Rt&P4GwHRI*II;PVKsl5O~+@T;DK_lN$@f)s&gd*e{T$PS+~=U{dPel z(eRgaW1)|Lk1d)+1IvLvAydo4X3z{te_W!1OvTaRDeViI2q6pR##T1|sJ?)rf|JA# z8z(Z`egYG|7tBmmbp#P-dWYL4&vdm$tW+XHSLm~kvAuXO!b|y>yzn0FrcWe1t6-xr zs1P8Rybd*v5o?G4DWkz+YRw2zP+D-Ft&tO(%I(tD-V>V@yXhFhL!UG>Y}azJA|&FI zOhtm@Ilbj)Sxu(78JZSSp`(|%fCC;8Lo-rqvO)-;)}h=k-S_nn>zj(Q6Yk|e8G^_| z<)*Aa-V~??B7OwER#T&FD8W;bTfCN}jR{vS0ClhrK9-uolte#yXjW&y4P!c%7mt>i zYolpAb-_Ljn5O??tNbyc9<70?E8vAwmxtQ%`4Zp5G zWJ|qPyrnMDi4^9}Jj}V6eIZa3^a>5&s*l#nR=?!8U%A;6si8pO16ls3dDO39;eNK8ouhAOeelqzZ2k?JDkr1$sWfoo<1JRKM$Ig!X#?g`Art9esk-_R z{|L6~N!x7s>e6Ue*_FlN6i!VN+3H)%KbiK-y*`!%(BkjRpx zeq6e#&}k9Z7*DtIpLXrrZ5#RSw}U^!v^Q6JM1~_jW}q2}(MV_V{TbxfrY(wHbf32& zGDM*Lm`cIc3e?FJi%i>qoIcwxh5bA^?;2r+aY7{F0gB%haLcC}V#{!9>fnr%#S_>s zI5Y6|#Hx)~36^rG6v-|k=2yb1O?liEM{dSvx?3(U39B26pxxkWdCT8u_BZMCXt?Wd z;R4{f(O@8jR{6ck&gMKmeI8xzW>Ml}Gh0AEk3o3P=;;m6YutP$Emh0IHC{rV`aS<@DgRSp}x~ZiNgm&!`k+M5$WRt;fYIIAaw|Qe^a2v=gOUp zsH{WWJa(i)R-SCE7*Bwr4Y=11CeZ%Ns_3i^&S3j~xSx;X3`VzfG%pX?Xq{Ks)P_v_ zfst8&@ioRZzL;OoTOKAr345AjSE^U9@0~lOaV}`<<}_}!;RkKgfQAoE)3~1AVw`Q! zaZ2i6p#OC>Gz4J}<_q7vMHkwkH+k~4uXx=U7-eiJk-4o*cy3Y(ps7@~?U-W5ng!TJ zLi~eNCG`_}bO_!&rv2b-v_e4^m~f0HXkgNuH;9JKnmtTa@BkUrx@FF~ME> zs6EgtSuOfm7EU2D5uo>6SwtgoDpegt*piTeILv4*eLQD4?Fz=@Eikw}Z*a!|Yo!^d z+pOzs9r}%{xdEY3XFtuTR(j8OEU+?F7FQCk9j~1{Z zoum+X0^trdfcx%3bzyb{C&h2~yB{)5-VJFs+~K>zJq+4eqBN()#5|D{2oHYnHz~XW z_4#-`P=b7xPUlpSP5&}7zmthC_DhES1_iE+<{4(y$=B8MIvYv}R9JQp(3BzJFzH<$ zJrOZk;qs#Qvy);OiQ(dahJ9D{jBM%T3AD@Y>!1&#R&vt`K<2h z;FH<}Q+NCL;2Vn%67_~Xn|u1yX;AWr~y|sjxx;{SE8LM z#FNe21>;3=n$^Eiqnhi;uut*>rGBwra(?=haAW7a)-dB;pb%xm2FNr@X2Pk1L*4^z z!Nqf@p7r9U;}puQx`?C*wx5Onj9OG^3r;h`hNC&WxUOdWIIv@pu1=Vz371uV5XwzW zIZDqLHn}vpO!rwde6&1yw1q}F@QZ!qec_%@u${q13D>Y&ZWlF{(|_Q}d4lqC!RkFz zxI^dHO}jkOZHrV4mSfHIgK)k%cuaJ!>tx`mgjo6%MC=)l(UMr-g}-}H+;=Gz`Wy@G z`Ln@!_#dyWd`4vDNl!Lict3+>VVxK`Am$1BK`Bm`RPEv zgHlMyM>MtE#5cRi2lfOArUxuAyD+x28CJ z_r7Uh(MyJp*0^?ImWfgo)?AIoMPc)!+&1&R1bU_Mbebdy=jz$WJ(J^xHZrEZrctxVGa-O^T^Y{m3-)A;7w~fqVO;5u(Uu^z`O|`kxk^5_G^|{MZ#eF#q)xO;F(-7^Wi(#7 z(og52xRU?5tM|}04%ua;w3wq@#1;uc8S6o>>7(7P<7~roAK@zIc0C!cekATG94&_U zQ;6^t-MYkpE>wuVXYg#K;4QoV)3coXczyPKx1WH$Iik$f`ysqE+|LcLF~cc!dY6aKX-HMTngX>!>7a{<9JWB zr1OCz^c!Gp{A|BZyWr zxwpUZ%wxrz-ltWpO?0UT$-kqBU&1Igl%)8Kms(OHsUH7ogk7jWEI8bd-5N}wLOve{ z*rEnrVv6Q<_xv-svz8%fka8(^mB%rXQ2r+n2bayh2KOx_tkq1Q$xRhAqM+S_38rTaDhr| z6=zcY5_O<^HtO!Q6olhMATpp)S_^KS7lR@|0nV)^c`LNbHW=|gv#!Me-E*w`rsxjD zTkw(6_qSSWlSK$ABD^vF z&pPl!qQGx;yi^iuqd9v5HWukEDmzBqEuW_Hsy@RkJb(P2ac8=Nj^WFH0{vl~A#}+o za*?%OY4Fl|{pw(=MY6QzEk*Hyksy2yTi{X5P4Z z%1Flk#>_tsf)^dg7Mw#gSyASe$yb)e5B6>Ez*M~1(IR+Rm$=xhx8E(rle;HT*-S2;;1}#<+M#rWp`Z&) zvs@bW{zyLtH%mrt?f}wzlY$KV=6T0es_r~fSz6almamMJryy>~x3_}1VimbzU2HcE zN=c|(XUk$Zoo0~_Xfok8m`p}4nU0Vij{=?3XP~XX6LzhTCQQ<5Y|*??LcF0F>`7yk zj+$v-k=;S<9Xw{)=0B1{FT-COLAm2j+nybl6dC~uuz^A{B@Lt}wLK(#3(}`)k`Uaw zudgM~X)wQe9E{tDQ~tZ*wAGiW|rGEjG6#z0jV$kh*}sdbQV3e;#V;ij-?kM=o~sC z;YpOXU_3YYyTHE`7u6OqOW>#tYXmpZuH1C?_r0km)zS(>NBLE-_wT1BJ@dt_PYy#U zSh^ce=7rI&{5W94vB*E|O$(yg0sWqd^y|n<7Bd*N(pAsQecXI=#;d7s2R<nMnoMs=SKuWk%sn58@#&$_-jc5$Bw*OvHb){2* zMlmN~qOgOIH|st*+P4|{NlQf2bqeUuGjDvHp3zS@>)GQ%sbd3@U=lk)L!pw;bgJi3 zD_I*Q$irSdn&1=!|8VlTUyV=6R%$^==x}bi4tIKUvqdf&n#wjyGQhF$w)0yomD+Q$ z<92ta=A+s^b7ttlBMI#oh%>uC{wCj)@ceI{LO@`IZd#&iNLv|C(mNK?tTj!?q2~KY zW$Y9UVMZ&iD&dNyUrRSBwBeEqf{CS0HWVAwyhHKxmZzf2&B(fOh340*So6`pFS@$ybD2FFTicU_g{%pv&36l+r78}AcJy8 z3WLs|m!>Ztn9n8^`OX(;ym?GlPx%Bjd<;Na>@&glvz8-GgHRaAN+7(5X$LV7A_||N zVWww?G68W(8CP-LB)xI$HqJT5ca>?AYGo693zh))#)7<_n69PzXk>TgWAWtQO*&}Q zE$;My4#+Qs9+31O2fle|7 z?pyX-?bm$2Q@s0W^9CMPHAx=>G@wllIyx75iH%|P`{d8^{37|Q;3xXbXD+Sym-b|& zIV=TUj;2BLG7N1;%K2nwsjAjpurwk>9v2!#lmY(4*bBG&X6fFD87#H38JuatIH%sH zb3h=8*&(Yi(ab82WW#A*kbD*q42|W)Ye^JmwZMSldvd_LfB3m7VNEsAwOGA~wph}1 zVOU<{NW_o_1U>XRKN#F$YP*Qf`d0MpT?(jbRoR@$) z7OWw+XgSuhP|SIy2V1CLozNQD464Q2_BDk>JO9=7zHR+?wzXI9+S$DiXG=>Erpd=oPQVlbmJsU$Eq4y!-a3 zRtp+pKoasjC!3zhL2?sm_^}_?E=&4n%{WxL`B# zriVk@(m$1t1ioNyz`XfXiBviq7VG`o{YhwEX~DO{4*02EjS3A&G&YcmGva-9J##L4 z-BvI4eqpa(Lk7ldLVd=IU6b|SAgCH71>stU0@EvK)9aJca zLjS5&3{LrV4@K5R6E7n)>V}u^&I|#{69_z#Do$P+y$g8%ks4|l?}|y|D;jRk;0Cq>xwJ9K#VW@od00 z$$%gt%ZwFRJVj)b?aQ(4U9us#@j(mR3h=2sK1BJI@^ zm{IK__1}<;$lkV{642ACp7yOouHX=ZM1xnHY{M-C*^Q5YyEl>31)!#$qE1W zs=${*YjczgWbP+lk9y%9kR6=pi~d@%B8J8V1nn%(mm=6bWY261j-7TWGw=9}B7~lE zar*tFB>LI2`iZ1&B1$mOn#C?e3(iy=?|J6Tywb9#H=lwYe=ak|VqbGihj%K&Hg)F1 zt6a4F_9Z{Er02C{|4ycOGosa0Gsg^y+Oziu8n0{h>Kdu2)}kk~T3%(+aA~VGQ+5Zp zB#0fa3^!!sT@)tw_PL%4n_~f$)TKFx9_U_Ld6~*B7Negs`0pe}TPo0l0F_@B>^4;95|2mB4zB_V8Es*h z^cN5;O;K$eVWRPl&c<#+aPkW>94H#{+uUvewid8gL`E?+hX*PvOlm%Yq0UH*z zH7}dbB3v>L+y{W?UPlZI6J(Sav@swLA!z`yJ8dlphe@8*I2u`k-*^Kvny>&q`mV}( zg5D6_Mn*g#Ac;_a=T%Lh8J~46f3G@~?rdY8&XgCAKNL1PVNsRqP-u=^j!igZ^r^mr z-OVXmX&#rbGH8P>ZQIu?7u6gkRh_HqV$)Shiu?l!L6b}whqx{NVJ4>x{Ed3p1hYixW(T$ugsIOfqy(5rEi zvdBF*k`aI%y>49@)u!QoY+saa4|nBIhfeyQ-Pf%{5KtR1?2$0>X^q%H!b%ip@Nt0c zLCLEiWB9VYgpBv$VRMsF4V~3CuB;IKMiTKNy7?F74ta=Chlq9%&sXO0DEx5Ak(m?>Fuz|;+Q6fKJ zEfi$D92}k|B$qz@aH_DmVr{*X=vLUa@y`M^n&M#U*vV)=A$qV@x$foyfcS=!*O_u^ zuv_3{S1>JOXE5*xJlByB5ftrI^{uJ0gMr`^Fnvd;-E5qGM@WGH0K}eMCJBA=RITDl zAp9p+eF4DVJib+2B*+0&h(A(r2YS6Xmf_BjydL*cBJ3nWPt~?-rl^CzrfotMpYT38iTwU6Y)yU_|12WL}*gwRdYrs zdYN7j>1ANifmDArjVTgHTl`}-RpVV*BN5udyNHYKRUn!EYGk2w zJAokAfaZPBc6(cF`GAxLR5T%4Q!CC|4Y*;^;CV(hAn)WYE}`2a;gy1xm@-R$Ow z2Xb=H6aFt64^rol%7VeM3sIn_pw@%c?reP!1Wmdr7+?3SLZhVw0jAs^a*trE zA1uh=N3LUAxgwG+*vDv;$tNOmE>ev|oI^xQ`NM#xC0IUs7WU(0U7O$(E}Ch}7<1bc{1Jz&yj*Use0I z65<|Cf1qLh2#Lt!h%GOcLO`GUPvv*qTBcJ3tDn)`44id&wODD4dI?hHsv%JtX?%W~hM$KD816-5Rm}O=dica^ zFAp4i>nGj8sH0>!2gl4C8p(Vkf@!gpJe?c^o@^i_dgBfCC#peS>0${jV%JftDZ^fL zGEM(<>e?4JYObOTQ<@o=<)1eB&b04*0A_=AKLzW298h^f$3NipFh@(t!ggthF<_w^ z!?-FZJ+^#)t631#{#?PHyMI?!+Tvz+KABViB6J}&Eq}J1A7$sO{_oEZT!^}@X6mL& z)%=_d&M=&>doY)u3PpjqhK_ebLs%9G@CIiWxa^p~7k_Ct#M(Ln;haZPq3-f{ZR?h= ze6N;Em7UZ&7mNVbF|bN3;@3{Uh|(RkqM`_7JKq`!L7VCM>(Pt5r39@@qrTMZNz$PCASDzz?;~(VilAaP zq}H;TSlS#dY2-5NKSsKKZBc*=$E@~$Mwf6~XcmhniaMImwGtuhI%BfHUC*TW3x&u; zt%KY1g5wleU774e!3a1H(-iwB7$-j`vo6P&@v-<@>pX5^>vq&!DdlHXqHW!4L)2Ks z{y4&d^=lHC)1lF^&Ujj&4vuZ_%FLHe7`Bfxb-3SIJ+u_=e{P_Wn!6wM?Q{iRcLB-^ zZba2`>ITed*FZ+NUY2xhTj-J#ZlI^WrH7J0lzWj=tJSpi%SciLSN71eFC3mv<1k+2@5so{vc!FBmx!~VKMpJhPI z8?ZJCx`W}HF?>u$S2JjZMRqC`gDP6D4xZEeTWuDTmgUEm#dkc;9rNR-(EImmoh(KE zQBo|`-#p4WxZXx5o$8Y+cFQ0F$1|MfbBb{!M~S@~9=g2cz)5s}JzU_-rfIj!rU3|baTogM#J}^i4ZrRO` ze3teO|IJgvk!^!}$(3Q)sD+ik(Cu8N_E_I^L=#2Oi3zQk4jfh@d=Bil2g1qt(KrUpjS{2_w4!xH{kd%GV6eq#BbKuIf-Zm%EAPlhHtL6sAg z>-~t^-Dmg9a+CiBNouV0fbg%3n=_#;=XQgmE5bx9hIAk5sk9;#ml=|urI)iF{Z8h2 zstw9LLJ>!GWYaY!c<6xqmq8!Awxm=}oqsP^bP~H+Xeq?TcWF>YUMJT7V%-lpjr3pw zI@+-Ib=azt){WxO{pC8*$#l0EL|B2UHkd2@c8hF&Lhp5i>7xmXuC${k1yn&tMRuwA zY8$c%pU;1L#7CzR!VPAN`Wh~QQ!gapdx+?koBlZ-g&KP9?bK{tsHsOmyAysEp10Y_ zbpxj`Yk(tork?A{BS;;E?t=9vz_sO4ka6Q?ovHvC)OLdK0Ex@Ntf73Rqp*7VRt0_0 zz1c>by~s=27Xhg8cb*A$*SeKTX(&@#Fm8wh8>M>`VUhVd#Q)0>03gxQ#^pKdD%GF7 z_4;39pXN7!<%ktA1>rX2IBwl~$sxhu{FV-0qX}b7l4~rP(53QS#5xYUeJkf}=Y7#6 zXgHJ-z7j-W$-PBFZ39mK*HlKOqBCR`mw0khmtxCl9HHreb?!W2HI8_V|ADAAP6?h^ zY0xrP*}hRY&KP9TtA|Rm^`dim5Eu0y`GkzHr@m(>ey^u$99GGwB)n1BC#=6Jx%H3w zY89>PEG?-uP(zpKODhLqo1btrASrfp6&0u@7M{NeQ6$${{erSjL#A6SWlKqyA;xcv z!Vyx@qcN2keq3@*Hm2m5!O}#Zyr|7i3k;og8M$?7Ac*thvydoZoHCJ?=8nQhBLvVO zD?#}3Yfz}2&2A9)IH@yN5vW1IA^^#*b&LBv7jy$_qPDZb{c%tJoQgQ;rXdxcnY2Bidzu|D_!lBOWLq5Kz?46t}_Vat5;NFqHqE_dW1)QGbp|tr+nqxvw zV1%Yr;V=Sr`Vuq($FQ`_bTFgd#YgYvT77LU%uj@Y|8v~77|fBPeoyvOal-1)~7K3i667N6kz*tq4Z zPxgl%*#ANgak~&AHKI~;zzaKfo#qlOS+v3Q+g@B!?^52Mnpjo?;;qFkH(39eSyA47 z2~wVJdaJGSj{<9ZF{Eb!c;a% z^};P67T~IQe8I(EScSNxNONxcoeS6*hp&A}>}oE^_43$Hg-Tr1^Z<7*OoRvsT{>Kn zWu=0>T&_ud{MY4C1)#(|US0pY1l2%#cKq`kmA3g?3VZeFlqO-N6Q=}pH@jz;99pK; zP-qcGG>yY8+Tw2i;pM8Egq}qSq|BRS56lcKatt#Ic4;i1n!x&;o$r2qEDvNb zE(gal#b5OIML5c+cn<9U7GTAfRn!ERw&&nJBIW(3xgx>I)t`GJGb2o{@@=3;Sw!qa zBOpiS&ufZ$vzY~y)iSUj^<=snL(G4aY!vR_vlA%((2+rn>h#Q4n%F;uj{j+;d!HR(?Nw4x=B|@ir+a1H86jhO zP1_E1Z?Z~!`;kH3SZlz{C1Z+&_ar+~+xFNJbwvxq7YcgROCbr`e86}}Pr8C}ap^m_q&9%eTM(n3$`GpCl65T5~$ zUX?Q}d11!GDA2LSyw#qvWB8F0*=br{>t1vkjODaGOB!=nnV3rEL1O0SQf*rD^WL=$ zCg|xK><#jLhjeQ-Vkw#JHHl4a*Vnj=kGFFKQe)m>msP7u`l5ET-*69#n+sI;+f725 zGr1}bNtZg=fTvN>&tD>dW_7)v>K}&y4uKe{btXS8h6Ot|al0NkAox@9y3Q$+vrBn4 z(Tq5`mQME_i=iI=r=UyKX!+L4wadlOG^|bbLEUC=ZS&fP&bKjy2JjxD8&8S}A#r9I z$;H^w3D`%pG$abLPb~$&0wFq#M^q|8sVY@gl``MN762glS%6Ct{en>Sijh5%$!sv% zw}pGJ_2*sqX_7i*&hKtqn3uN~6&0~xGi_D?gN3x^DhTk|`BXB-UWf&7y@48r6d6jW z%s#|4LNk$GTGiR_9+N4x>pK?eUPq+bOiNLb*=(R zXel~8VRIHifxA|o69%bK967MSxBq>zVj`uGQ+HisWt*;=vGB|@cQs}ReOY~~%w-bo zy1A@>`(gU`kPJIck%%wU4{m$Zf|=blmPA9h54!d}<^S-*isu z?YmebE{0{Jq|o<|dXf%RoV81<6rvNTn5OIO)|>c$GgyM2KNr@B?ctEpxt;?pH9xIM z2$72g(Q{jPj#&y1`r!(8;TK(9*TtP>14CB*gmV+IDD_l{taT}{_@tb%kU(loCi64{+$)iEh5(|<0fYXFY#xT3 z;t$oZm_H&q@bTx@zlyox>ZI#jG?KQn;`YN!PrY$D%(z8P7OpC3xGIrdapKb_M)hYY zY3o(fk-#G6hh@=WJgXcB`tX$+H7dq>rG*oDvL=$ecWIb$4A(xSI{L~<#je<#cf>wl z>VJ0y7M59W^EKqPK^GVy` z{Af*BONhZMk3ha)^<>RbLLy}4>TSR!0k6bA7p%h+87UBL+WwP|KCSs{?FRFnpBW ztO;8msES-P&A%N7GTM8mb^87jW{AY~c0{Ct~B-V-4%|(63FW*A*u^3<#Yg zto=vrq{5CJlw9Xvl$(GET;qPB`i$XPascC&D};HDDs_L43_EJIb1XrwP}w5~6+gId z?+MzKDpkeSMEy0Y&PP8@KEj7iR%r1LAOseD4;ju?bZsEB zZ~ijJB4tLf7*;6HJ@mw&>?e^_urrP4pfx4Ze6*XN$Pqb#dEgX50wl(yyQz-bc14X+y-go=9sa`!yQJ8)`zQ3Q&nkVMfJEX_%kiGs z8?1nUGh;@G1ucLj9Sm!gNZKdo7}{6G)S*MJL0wO!^>ZBI1fel%M`#d#levQpY&zaV zRV&_^B_ELQhB)Kl3{rOsIe`&KVcH~R02msu14#x*Xf;`el!(lxaSg8=`{z-K+sT8M z0_Ra}A*CeAX77eqtt>!ma7;kyJlV>0s^VSJJvFqa3A(U=ejv|89P4n|&OuXJn#i7# zIt<;Qwk`wu;`r$x7nKUrZXDVbJ30x!K`1GM9VbQ5Tm-2V5gpQBM$un_tcum^o?tVZ z%=27KE3w#~{v+u7@s*e64|=nAa00m|jpyNDCd<7uC<~A}4XOgs_d5|nFjRR;!R9lk z^RP8=rp9Bh2RH^qGbMIHS7Qr*ET}SzlBC%*h|1k!UxFgwr?5$ZZ~uLab-=XmZXPHM z<>hK0h0_$Q$mgwIqCfo%{6G7Ma>joI5SV2b+Ov14bZY4jv-*I{IE{~GqALR@UB_*C zD8bv|mh`vjbBhRXhcp*2Jj7UXU|~Wz+Vv&=HyeS3_-aky7jgl}gh7rea-zyOfkq2dZ7ae74$wymm$y3zi!(==aO}u=;4s{$mO?XL2?0WSdVdrw z2fshsktelRu}1X8J>tG~Um!2c3g1E7z$z__$XT_wwMP|wL5J3!!6A8fSKt+i>mw-- z5196pTYFhk@;Hpo9Wsuh{ic=5rFPLj& zvq*__2{J-YM?~%dGTiNjCuyJ2cXMaXkuI+EM80foQAq?SZi{r$yLeL^-|+nE%G zDoQwtOCuFHF_=S?wiJ?YVH?vk_aCtTrEl1bNPJ!Y=Y;dqRjtfe{91s;q{TFJ0f&;- zyn;O|X9jg=cda?5I6z87It_t|Xmb-rVuEx>rM!F>kK*A<8=e=98}ma5xpqI;(HV#& z3z;QSj#1l*Vq6Y>!!s|=X2cGedhRRb+uTXIxVa_WgdgXXk`DwsffsiDKjC9?52&wq z!C3fh6|lYu^LJCWz5@6Z(rPt+c2YAPsCut)MA8R7e&U*W)(TCd6+9INpZPzs*MM4V z*a|HuShKHE&)|@0l$3$>L|}tmxvp!1(U<6Zpkz4N$|uLx#Y&8!sx3tdxi0qT=H7Kw z!AoIK#Ji`Q`BgWOYR^0_e|sLB@m_#SD?d>A!jTpqX4%DuW@1y#XF6t&%iyaw_}&O= zL5`N^M~1ev({y%u>p6Y}bE0YVNzC)%_*M?f(e zsi!UpDL>!uz367lL|v3+5@3emZw8&*m>|*pp-@tQ66N zC1}x2#GlAlvapVll{UARD|N)tB=woR=S zKIGfU29QK##T6raNtbONNATx;I0vP{?vxKK$jByG>;m&`NpML!Nt^E=$X2Ff>XhA5 zm-}GI1*wb@fGD@37DXrVvjynaN<*I9t?jWr{Ps_AOi8S$@ryBvZ)5FxlQmg#1sTn7 zP1|*w4Rphz{Fd8gp&3Yqv?LK&-DZ$bAVUdTX6~yzRMX0Ku`HSYrlV(rPMcubvw;}d zW8Yn67hhT!u^<#WF%3PKsP0KVRfTR0uN2)jtJ|6wa}T9Rn3;=8TnK_vcU`cPp(XbBn= zXyYpHWm!(@Bjsz2RG7X$H62r&FcwOBd9l0+mKl+NQr1{h9uTrTZ4Ao>o4gu(;~;kY z3-`0Jep22~CUyt7tjN-kHJU>hQ<^A2QW61gg|!N<*pNMW_|1wXvF-IYaSR9oG;br~ zkL^R(ROjVTSz_%KMR~HGP zOS%83J@+7r5H!K=vp)pCd9H6^YwigoTBo9I&rU)j%zS;MATec!MY-}k&Qiq!FXK{y zHA}8-|LvU!MCD$3it%<$AbiJj_hSBtux}UhwD^X<8gknA4-5|)Q@3158Cz+PO&`{H zJk-=d*U6kO7@Q>qCdt>BQJOKY^~o@y!Bbg$cb}YF zK9oPEStFw-mC8Ge{Pg@{f!rbi_*&u8MqQnAlT_t0vC!Sl`5iTORERccI}*B=FfV-$ zi2@EYhSWeixrcNl>53X$eQ?E9Mm-+`u|r-e`!y=lxrCUm42loj+l?5*KcGH48Sd*i4Gzf)S$c zfBcqsTn465AyOAsL#5tncv@GnmHp6U8%1wf?fI$+wbM;+eCbe7${yxs;HH2@p;KpJ z`3SGA_O$?`<(xjl;}j)>ZA$$TKJo}nF({UQCeo2I*eY}gXkNm6)MFUjR(D}4D1#7B zWyvf1^r2@};Y|Hj+%?DYO3h*dj}^3DA-~|cl7Nx3MnIV3b_SETEVXZByj7{s6D;|? zOKjKJ!9QoH?OpQ@M7YW$j=l(wh0tOkAdmoBaj~94hqX+0?)!(nXjZ7y=~j`fa`*W5 zn<(pF3uC7&2~I$dX|6&By+yN9KdDo0v0lXG{>9DD-0j6U{<8teY7c8qyk5yy(Z!59 zL1>Iyi6&e(UX^bW;D8d;>a3cEo?n zS87EfbEIANjseJ~&oFB2fa-S`fBE~Zo>0SqrCuBUgE)jWQUFZn%Ou~Ct%nsqxuwp& zk&977iu96S)feH>NE)hFXxc1fz_XJP^Xtx~ul46VP86N!ekgM&yO7OaSNCjVFH_)l zR8Dst?JCX+PZpTEqEA^a-dp0>UKpad=HI{_oKo1@Y24hUPNn?tSvj>B7A6-cy2ErV z7RioDqM$2ntY35EoyqRJj0JCnV`jS(oF zY}&@H(UDPGM0+!;E+U~NqZ%{sPgSAY$v@Ky_HgIsHHGBYKrgp`-B@hlO`~ z=|62zdmggPl3v=_rkK*1D!~_zh2`me7Y~|{&w%A9pS!$3d0a_lA^fwZ|PV*TT#jnM|EoXJ{_}Iz%)y~rtd3H z%Z$8TJse3T>G{r7?-^yt6&C11J^Lr7efF`ffW^{L)jLtHHgpM#dF)wahm`kg@NQ-|F6@?m z_eg(`+>l`K+GVRi!vk4?HQZ)0Jm_sU;5V>?!roL)wqwK%)nufcKu-hO{Z2{JT`_lm zI7sT8TD{5pE*OCu&0k*sa@0izYS8DV((0Q&%89^i_Z?TI@Ao88{D2w)~l>F{}kc|k8%eC-L zLYXnF1ee)F@XnU#cOu|cGJl-IILZT}xa352?LBX;uAL6s`wdXmx@Hv5VcA2O^=ku50CzO9M}hX4#t*bL?Mns_1I!knq=||Cjx;!^GfdpfSRjq) znLR9f-||9+;&)$I=DmeoK65;vOVivZ!A>%Lx9X{ZohGGwcQSo>)U}#ylF(UoU$W7h z#IM;Ub9rSVV+M0k;9_z92Q2x@iK|%pIG<`w@Q{CxWk2#L#HTybND$3V3K1njx1{QY z-Q>ybl_ZP>X3s1184L&N&9QA{pBoKP64#_z+b?W?RP5}zTd=B^pxODHPQe`idasuF zhN_*Lt9vP;th3EU)=w1i*h4*AVmJnj82Ot^4lCYvLQn4*2cM_6l6i z$bmdn>lXLCbr@8Aluy_bmmVN7jztIM877|r{%!ORh*IcBhFkI#kehybty7IN_k{63 zY!AS!o~&iYw)oo^?goB@EbyM?HlbQDv?+%9Zw2JPA%9k1%uI1X8i+~ZviGvIsls7Y zev107X%3?h{Y55+8<5*wph}K$i6b^y1`vvAmUQ zm11^a%n5rq)PL?mB-;`p?9!B7$BbhoR~v#RSBmisBCr;0LW;w_Ax2tM@-Pf=B&z%? zAVfu5n3>r!wi0uXy%Kc@V#u?ZWzuHw2~XH=|2Euyyrb(`B!bWtI0ct{G6FAZ+O(w_Hk zz$(xuIT@0vu_QL0foCllLiG7RV#YYf3~)Y`>huS)1?(L0_X{r9ach&73tewXmI_j> z#7&X=?u^JN4T{PJPbU8NGxtCaoX_#|S}{``I=;8YHcR4E;jBSfIN}KYoMTX(r36$f z$ABD@ZC(@8s{aQEhFMHtq4EBpo|`7ZeP)3B1!v#BOcgrkm`8SO+V{?Yth#>$&Gv(x z@{?f>GO3J*lu8eJ(~gS1Kk0HIjOpSxft*aiFZ+y%c`1a+4JVjx+!<9zb-QUfkzVRI z%B>~-6|BYp0#G}=ET2Kl5-5mjrYy6y=ysMzD7zob11K&4Yj^MkGeX+Wi(u4Z7*P{F zQj$y0-bf;80J+cqL{pPC;#x(ne8HUtl94G~Usk?tN}ut1vPZdL4}uvL>PL3M)>_6H zv}Zqcz$Fy&&&|O7;%A5sLBe0(m)8Qi7rI96zPOy+a3vhj6|e)4Bmm&YT!zd0kyB5> zOJKB2r*4G2zwss||D=YnuPL)?g_B7~fH3~boPMeFDTR^1Y(G#K-k z3=HKE5l}S8Q;;7RFU&@fW;YK^9}*ry`e7WZhx5pbm3KjMZ65dL89uz~Ttl?p;0*L-Ar04rY4iCmhA;{~*X15xnTbFY z++K^c&SF_h=5 zDjDE4w1hwW;BAuWxyDp95KT)@`&W<6IaIpwyqfCcstL?>rl>uxCEH>RuzKReeStbr zIcbOREXnkt#-P$cD7Z`ZjLKNxUxk({wNUfK?K67&s>yPMXe~T&K$7Slt*54->tXoo zP2ucyptXQKrW2rsQl#cOLHkDCLg~Vkl5>b8w&dB@$YJ>NYzSr`mxi)(2{gai(Jj5Y zX>E8W_i9N=ZgHSNfQW8wyLqp_-wH*r_U~v(EdG{&mFlNT+_<7TdU^?61nMYom2Cx= zNzwml90&N%7s|0^Fg3H_QO-@ZbDiNVcoW?|DqGb;qr~)x$@S+mW|LciEO2>0pVI4g zuatam0kb^1%~4WWFLo30k+L=3XWuoaQNQa+o)@bK8&MNm3DU2CI3}>kf|O?&7|dX> z{xw|m^v`hN0sk2h2F@7QGPSR6Wv}(Y-Q6S8jGtw#E|(ndN?5r3+fnNSQ>Uela9f@? z(181)L?7tqzci5VVCbZh8eZN4;2JFz&ccjt;|w%n?CpR;HZ;*%^@Gfb0@cj+cXj*x z)daKLR&<0zZ@Bvr!f{A4r8T;N82Z(j>wYAAvQyL#n>XBH6?=;ux;WKLRY8u7K*k># z5q%PR61aVZzDL4dczeWjsKB~~W&IJDJ91dE#YfraZ#h?$10F)TBeWIjbso7;N9cCP z_k;}5TteIBkck#XM*gbdA^VKI5Q~I2cIXv-G`>eVgorJ24t}bKoq&&utk-N3Nm^OH zRsA_ax#`;6b??juY1qicknLdM8v;2&ZoLiqQzn}5gWrBdJ*+yecF?RtH=33`zFovY zUuG!iLbEPO@}u{QJX)n%71r+gJCyWyPvRtUB566lX8Lty=THVu0wMf){JXnGM&GFhRUzEr|zXZ~nNkybxiHid#e&#$^$_ zjfxPBB@O{1#3D0--P-DK& z5fi`ojh<786>}qq>EQq~m)5>A=9I1faSfP~4k2oc_I_M|zes#?*%#~F6fFw1pyK{! zx4J_0ExY>yuTtVQTClQ9iIdqf@|G#&Kzj?~w%Gllbp#h>9&K}`S z1WBDed*iDfFdVMRv<213Q@3N~kr&S_Jvuhb(j$T$k2}BZiq0NnZKtsKPfDn3lMKkj zmJ)Gg(Bknvj`(2@_#NO^Wslsn*sDEx=t4NY1QXsHvmiw4UI8JTh^eov^dF&Z3a2U< zGCwG@`jl_Y(MONVSQcm?m86o?2ihEK0*_G|F#g2*Xo`Qx&*r6pNU!e*A${2NkJf8V zLEg3Z>3G>2Sooxp3Z#w$rF}XpiW} zKV{2;W%J~-=B>kYMo7;4pzd_dzmn5fcGnYE9Pg7BRW@Bncb<~yNXXNwQKu!OPCV!d zvhh5_$1jKvcB}{%+8K!Mv3_EUQ&q4MHh{#5(cmfZAdST6DCcKyC;-^V`IfH2)aUr( zckwQ>y?7pwV!E~-)&$I~iAN?En~YAhR9P++K&WD*$dujx*=tj@6(k*GY3E=3TTYM> zB2n~PsQhMEJeS*+y|jhwi_KTk*(zyX2>~BcEyZq2wia`gtjvN>3;)rAmoIzhJog6R zvhe#ga`|J}m~by4Q8sVbbY4CJiRB@Pq>)&JgX}BLFlyt_pQ5tsIHQK7S>{ha7t4dU z)^)f?b<^=MkFB`2_B{~EX(TtV{^S4bvB3p^G4d%Sv21CXtGgoME#3WB)-Mmky^i$W znDo2w&Hi)3YciOU>W{SlU_$h`)V44wV~i(*O&H8a!rX7JIW)e!Hb@|7gqmR!Y(fF& zoKvea4k6@)dWWuYMMr3A=WPiddHA#Oq$v!sJM8%htfvUM#E+Kb|2ecPJNDitV$ju5 z%2}G}v$cS_6qdHR0T&04V*)`Tz0bNdi`N^rJ8xzu(ZVu@bxRCn2z(&tqn~auP9>Ip zAs{}-&AQ+$xBO#8)KCtEac~zLkDN%P{<(}`J-T!--p$k|eR*jvh^QkSOgfmW!LF;G zM@q*m&o+vEcg{c<12(sB(Nt6FRhJVHgn!CNF{Li>sl(1x8g%_3nzET_i;?h~kd(|L z?dl{+Oq0}ab}X{9z|Mq>N85TQ@S`z3tgJ3IWLp6-2qON$tsQDBy)E70+wC2epg>I3 z2VxsA#@>_=i{E&uBCu*5VozJJ7pszEm)V`{{lG`u!1vWpt(C*?B3HB%L~GLH9w@!U zh~lkh5g2CGh%jB=)ItRR`sgFzU@6o&PV&_UjLi_R6c7qp|6X-1f3G0X1j*k-&f>CV z?Q2%UK+#Hi;lzh3)et_r3V*b%lZ)5^PT#)dQjN4V@`J(hQgkzJXg0t;& zQy%S6OB2*Pj`1E^n#=KOq~t=CeSbvBV#)MRjKXpR0<6(n!o@Mk!WnN_q#P$#FOSVC zEda98O=df;r0+*MsUGWeR@Pz!Vaylb`SGZ4jG;v6@Bme;c|h1r8i!&Q-rScSs>+uKz14wA#z3P zkL->tB!^ug>gAwNv1o*4P%A?^QeV=&OGpjYPP%uQ@`!LPT=pfxJx&7aYG}Fq56^UL zz^$y^BH`UenzHfxG_>x@ER@t9V&M2>r@Ddi}^N(Mqio4%rHWZ z*(R)HQ-TCnA~-?g%pc9tpAGAnTkjP2su(`$XFnppCyL|V*XX5GOm>PFx6LuGbO#o* z3lD$Fw9Sf}9*@C^U|<T@Ll3D6;4otRG}_l7KX2;*)7bsp!4~jlL1lk? zLG`Os%7$?~YsC+bnt58_k61Ng-#)_y-SdoOo(YeHStmDd%~N)3CpGbTET~}6bePzS z4%f5)zf{p9pcY<%{Ij)|g68J?DtUr=_*HkC zag|S>-qP4V)LV0{3d*Cu;@1KTE{!S3zL(Z#tg0F3RNXFa;MOG!X%Omdp|jGjJnM-2 z??loA1GYA`&nn!#L<{eTRm6qzSzD@*VZZIpUTO{EIO116ryaNge;{=CdCZ}%UlFD8 zk6PWbJb6Wx)rX_W)R4Lbhj8s0|6+oa_E8HbKEPXIhX6rO7XA-0SH`uw`)!Bt>;TWT zK_f2|!xjvZnzLvkc+U_YY`|a^rsRmFq~il6&Rvdng&+2JS>uoi#R18!S+DOy27H|j zZ*TMP?BV_B{d9WFtoRzQJaBCE8-3N)JA8)eIS#d$3D zro0t??D08aI@R{)RHyo1Q=uWm9sVz{E$yl;QVOEJWAi9DACNzSaBTPYWH^QUs&SHDdZCuq%iFy`;x9a$33^v`})8l9&{W_&2t>< z#g2^WPCiG9Y(HaS+f!T#eK0j<6xXY@(qUQvr_&3h-TZ|b*3eoFFbx^e#JNpl?7r$w zRqpj|E^p}yh0`KEYQ)Q(t;iSWDp^xj@e;-%3G)!j*|mR?iNNU$KlXjtoG1eC6@0Y$ z>YV{k-U$0|N#vnv*Ur*7-_}0`Koc~SX+rB_#+!)q8Nx4>aXU^-cbAlgDn_4mhXYIc zZbH5t)7r_mc4KzJv4<|BXm6MzMyCu!uc}Q80|Sy|Hh{%Rv!sBhT zL6=G5+=T8);NSF>d4m69T%Xb-vE8px!9D#CGUn;HcUS+XXGR4ig=Pzm-%Puf#OQli zBl_??$<59pmebwrd8(C|=#9h>K~ZB}Q&F`o(PoE5lR9>CKD_E%5(EO4tGUOmgM+?G zJyyNe4bB5SwM@L}dt@ZiI`|77qOr@|Vq{Hnb?^Uqn0ZO_tTFi%FF^jrJV+anr@x)N zq6JtqQ)H(8?n*kY-%Y&&Q*bRG{njNn7%bmr=B|1FZh9vJC@zKn+=1LqCgVn{oxN_N z=0ZRrkW!jYpaiUE(Gk;o(KTWd#Uux3q!<<5_pfH)zpbZ_`pd&%mu!lPA0%dDq?eFy zqw252WM5Cw1`q7FUN6zL;)tSj)qlVeH)sKOzN4DKhBEs$95=|^+ zDqW~<#VT}>*^Ur*k&~9XwI&Xerl0?TpeAbYro@uXp$0X^BzFhao^tN3Jq_ubO2~Y* zd;ppTHU;JUvq6{~&`O*C~U)&~$kIpw@fM7kGPIFg6dyDDTxwb{q` zCM2LgRR@xeqPKjA%>5lZ<5wz4>ikxyM3SRA=4Y^syo<#UY1EDQ+M|<4aUFDSA8B}n z0XV!{;8OMwjK=R80%O{44brfTcP=3${(I$Yb$mCGIcGOLqT`3;R&A~osjgVU1?DT2 z9YMo(W#oXBU$)%j>xI>=^?%(2Ict}8PdmyhCE4-sQpKx&BSbX&>qRdo3rGS0!_8C*)iYZo6aQ}6 zn7L+Xjt;nRfgxLz!7Qb}RJXk{WvfTIFLJY5w+A8jpWSL=bBHd@OKP+Sb~{$eu8@Ww zN-}r<{J`LC6|snXS;z$`hW!C-mE#OEtid-cH?RQi}7!^WZxMUUTQAxvssyh#VobDIyQ1DHbFP zh@Y9>JojfYt}EIf?y%8U#lZTpXYXrcttUZ(P{%?wN>VeKYQ}(o7KX?NkR5{$!yu~a zPK?!&)TU6{bch&k7#q)8<$n~p6hSWaN^Ew|1yWdXjv>C*{qkXr0_Z%6lKhEcXM^jn z5iHz@rui`qd#cXU8&M_Wx4w|{eQA5i0#N)DA=cB3B!TUq4zX%GSpH)`R*V`9Xu?_^ z82@fMCt{xZ>VlBRvcexd6ORpZ$5!4y+;rTJo!DKyvjTxd+T2AKaJ=;K`^ zqBKmQb~F}@AbG5W`8UER zykcHxx^ih68{FZsldUf`#%t^Iz=oj6f~(26Ill6Ele?R$%FV8ee^RFqpr9{(UPY9x zIc-bzM5I|%Ul7n`R$(QA#G-<44LIGvTQoq|;|^=nEIx?WH$gw9wV(WvIq=L5YOQh)uB=0cHr3*%tt)e?#!n?NLr2LwR2{ec4k)G`q!q~$OHpa7c?ol9Vx_84NC9I z)!IjO&{1h-+miF`)V{9&@VEc}TR?&|>}u3o8rf@kN`#z%OdtuvGfbuJ%aaoBfIFcx z*9jCqt(=yCm0jRJ##pZzErL^KnC$-?&Af@-Y$!JCnV;%}Z!3PKcPD2R4IW(q^k)j$C;Sob^)QV2MM-78)wp^;PB?P*TR5-s zpaAcp)ZG5s1{}F}*yF+Su}K%v$+Ojn5_t&$NBtadWN_fu;}dZC*&C{t5Z#ia-D@%J zLMzXr*Jxy>8fYGx@8km7y(FLc7@@|Ue!^jm9-&wVtD+nZBk&x$C++=}ZXX13e~qz} z5P8c&@}tI@W*3}w7}xgU{hWg&ux?S0AKrzv5emaPOdydt70oT$jaRHBpf!cGY6#e; zXK>m5;3dBgHJ|eC!LlImao61$+TfLLLCRSCjj~(5E#+3;Mm(JX~NBizOx*9@&-XwjM z8O6n(trjdB3xfDg1fH^hJN$nEG0G|NbTcXg)Wrxlp?1p@hlxM5PyT(6L&5X5x)ncV zmCmST4IsxBlFuITG$_!mGqhZ`E-^x~BUqRE`c-wnjH;R+y8CQS^Q=furh%CFi^B>H zR;O7Mg23)d;qTq7(Zj_sPQ#3w5gWBTYF>yyY|<5>^WNxOiKSA{Bsfl^K|Nx@43~ks zi5z=g22!~2{hj+gjY=ruHa$i7n7GtjuIG7wnXG2N-_pf?gi>)AHyz7HY+$!OEPnSd11(^V zJ~7ol+f!KKfLFO|48;QIPqM{f=GjiuADzmjOV1qbOC~BZa`yM|m`R+rru)}E- zc?+HGOvn=*=hla3LEOW)^zriL8Z%jbbU>C7z5{9=L#EEfzVRG#!9GZVb8;n$UNu*? zazkPBv)6(+fCIy`7`5+rGB`M{iW{pgTe6Yu>3V-}n={jWr<-Bo=iD4Tlr&dLY z0rdUfyG>2ZcZlasm+u-3^KfIeL`_Lx0zWtYAQDFMmFp|HcXYi*`0eE@A5uvH64Y?@ z>5kx?*|$C3ubNI{2!V@q#&xD`bG(W19|!z&LAyNifQ3F^JB zwc2SafHtP|j?kU@@rhR&mzbo6jRm%MTz{>b!x8*m(>2Q69~C{B1h zz?$gg2i|RvF?eE{qtHO*NnrjET>6sXQ}9|k0`tKCQ|41!npYc-ty@ z{6RSLF8COu7W{0BHJ+BAcPz}CdJm$O9s9f+FZ<0Tc|rRj>(4Hck3`yEt14QYovRXj zxFKylWbCPn&mt*StMRbWQ54cenkn9IxdoB93mvlphTMI}J_22_Yk1ML6n;)GERF6- z`3`Lz)!BN?u<>@n8dxga$-*^zpUfPk86^}$<5zw*e7lp zD(rXw>4Xgta4#(?t(WSj1y%=3vY`d!eT^a~ndeDL8D{%?_Z+`Jvc$@8EP^1!@(vIG z``xXEN2H{YR9#ZwV)EFcrI&Y%`y>!oLl=mqckc)wq*ELPE5UldNiN&$GIs;~qmh}h zvO(SRJ%XNPvbJQWMK>D&K0v|0diHf1l2pssTPWohURPW>VX+_qwxTAk+EfXa>c6y} zGTXe48zH4;^$PkTkj^-ZoEB!Ub1-)%ijb-&Atnrs(`MLJ_bu?P=~>2}U@>!ORd>8) zH}>1{lsFc_)D8nL0m@;Xn=|)i0^q;lJs+zvRIu{fldDjay#NQ$e!2emK~@ahvy`@N zybRHLqc+wA*J&&c?>dq6z0dzoAW{7iZ%6F}Agi%bMrJVj%%$a`pd@;I1bIZDXqlsL zX%aSxx(V{5zno2TyJ*8PC&Ee;bh-$yv)j(Y92vDRz@`YhwHN=JVDeSXfhO%^wGI z(qw+X0?3;}8ZqO9M?20te)sqPpKIx4(s;ophDYGhYh6H*Oy|lowKu8F0XUo!`~~jC zSas_LsB2O12GEa=wj}L7Jt0lPq4xq{o72-j!N3Cl=r(9AF$TJ=YjdNyvId2 z$@S$E>$E;f97d|(zkOgvHM#@{)7GVCknS+IXP=z7$k;!py}37qipk0Bc$MIT7Gnvs zp3n;*oc4QD0xd39ecDehW`wl4vIYvIGDL{pvX6k;brw?7``TXx1nuTKv<&BOVwqoi zSUIt-B#3L^&a|8RkvJ4^9P|K4KkUEJog zXQXO_L}{^_;tJR7KOAbNr!(39i`fu_G2%cPdtHwVP7CBO-5p4_-i z<$d|XL?%;PJYg%6Jiiz=h={JM3+PwZnN7$ipVvoVV&pEMPmJ?bY;83$HDM>=rkNx& zmJzs>9}tp>4Q3Dun8CjRNuZa-lH%Q;sw6;8s zlBUr18gnH;e@Nxpc&c4S`XSpnaDf{QwnhWSef||=3N0H3&Qq)F=&#Y;@3U9f<~Kf@ z_q#E02<^d&cuwBojnAMOV?#oJI>2GnZZP3)0E}@)He#-yuH~yNQDjXYN^qN}_h_FM zp3%HqOq9CgL>TZ=VTjku>BHFldr{f69WYIXWsq*nPp``^!(f97yT!|q`*;&%+J0(61TnIPEX=ivVD7Dkg5L9zvr8Qn$#PfVJN z?bUmQNJT(CushY;0QVil|CN)@?}!7jtN+BS-H68C%&C?jmw|-P8YlZ&|Nl~U+!Y2y z>5>;j>~Z*;V0sXK(jokN6iwgZ4x;6Vzxm_aC&DG|z3X*~$!Jmyvc>6%Q#Tbm;-*1}dV>t z*maw$%i1$UED@)^bwPhUxeor^yFm>kz*P7hB?Hb8UoMQ8`_mAGzP#c>k(_+U^;fAi zr>(UJqAm|N{Y17BnA~H^`oz9%6b{3t%h|gOo_`=$laxbwyN_3PWkh&PRXQH?oobdW zTqXVX1P~+8a73Q3+;RVc^>VI39S~Y~oNuG=>Vv+E1#L7cA6q(PzrW-? zN!X3VzqbhCFe`p~)51c?4Cz1o8ftb=I2L;JZpdyNU%~pCwJ~30M3ZVXrM5Qp%II1! zO!Hy_PG9KxiQ{7yw&DnGuDC0bS;n!f#|6%`uy>nobJU6HPa zEu~UeKEN{LZ3e>FCMM*~Kcx($To)e=bgDDUidP3sbIgzKABLg?oGV@}joPO39EC2C zxQgC~r?Y&!r2mEtBM(Y~rwX)EgXTD>KWzrCLx%X=gqCaQ6mF$h$nwA%i1aD5nYgb+%{B|$4 zaT(tb5@!*}UJ(0*!g(Iydkw|mZ$d45gKDd@cKT~7a?f|=b-ug4K(m6jv{lQ(Unhr& z)1}ayb}wizBsZ_~e${+_)$dAE^k3#Gtu{|W6tU>G)c1G_XeqgjHbT%wuO)j=mE(eD z#xLoBpyi!-8~fVL?IM)>{?Uflu}q}TcD@a%z({I;x{KyBMq*^pQeqY*Gxj70EzaR? zQeg$ecj}Z`ow&;V_I!o6CteKo|L}p`g(me}%*)u7sjxSQx(-G9)8^~SpNYNV%Khl_ z|LR%I-BSJog$>*xvU~YGnBXZoz-ss-#)LhwdENmryEBJ;MS0{`pG$>c(HFDk5jqsVN6fk%Y5 zFT^?=y6)n$F496xf(gz`b{~Krs8y}Hot1IQgUr7J{Axk!~-THb}G`;q3OZOO?|GD7) zm|Nj+VN|WKEwo#VxT!@i4-&{ISbpS3Hvw4B@fqIp?!f$G;u@m!s`zeN&lml*M4Kj- zf9~~P43n(HzlV~QPFS!y zZ%&Q~_rKU%6wK^X!X)>Omi%F0?_J-NY591Ki{N8QJ}eAd3>~@zigp8kx13ZKO0dw4 z71UDraHhwf^p1S$}XeRb~O#AY5`#=>`fhdXVi-)&|bW(_O4Tqe8rG|6EN9>6%=GAn02hD4XT+O zlGIBzDTzq`7<$-v^M~lQ;GTGc$*sYhYV3Fc6yEbAeFiSZ_w^F!aBSi)CnSJ1%T6Ne zLv^OtF7uANS;UN&TWGlJ4-6*m(YdsHm0^2CoqsoNM1B$rf3!V=sr%o+QWb@MA z^AthBg@mQ9vAw>1$;~SG-p*oGFg%T>@PcHvt&3PbsUxPTem+x6wU*3)3kGMA3>xx& zmN<+vXMWD_rs>HiepIxoCw_5z-Q!L-)Po*`BtbT0oxt=ptsN3@RD6oVyVU&Pyk}ys zkKrf%+Bl(J$aQ%X(LBv7eA{3YH7Xmp0uV!SD$-T8c;woto<5G@*ro_vShE{DAwH<> zL-lX#C<=hbO8w$`AoIAbSp37IN$(P=)qh*yL00bZe|xzL6aM={jj{Crz=F$Hfjv@O zoNr~8%@oM&biFI`+%GZw znZ|SgK%g+u?%~SW^eaWIW33nnxJhB@L)2s;#5|`q&L2e%{mAMO%^gkCWB~6PkGnS5 zk=VU%@zH5RW?`79tHe~FM1DodrL+d9wxZ(s>PkxAPLbIzL?CePM6(lIv6;sdtlX=a zBzK3a_QhI{9fxHlqj%6)Lz>GFl z2`3bpswY^8Zc&1(p=KNtpXws0RApW(jII4%ywiBKDPbMrUF9o{)MC!nVL#dRZ8BL0 z=kw7v-)+!qvF{w^}Bn1E;^KS@#Wgg|PlfB$t%UTnK zoL}M}5L+S99QdHy#4d-Ol~E--UUo=unSZ$YsmAcbEXw$;4l!7iv;9rRd6D0Jg+5X3 zvLF9M^W!NDaRG z4ej50(8KTk*+2rY-(|WsJsZZIFd!6U*+gwdhz_lC-gkQ-{T)IxzKiR$H`Zx9v#m`EzeiPdijV#;bhz-(`*#I*a)i6VHe`T6S z1_x2i<~1eYlq}f0tSq88n{>(YAGY)nI#~EHx0r3nO?r7kc z2HepGkqDhehO^OCRP>KC+qJ_UKB^>egUx7A znwo$;>VteAuh#Ynz%CB}s_jnQjGIDuIiy=57Jj6tGoM)s>#ka-YVd`MEqxYB>G;O^CDFh}2&mL_-y7k20LBnUT(BrsGq{-~@ z;yO8vjU2(yMH|VR69!_v)c~nUi~yLA*gi`?hsZJMI2FJM6!Ou5|xzI-_@A5XAsClW|qRD`;~ysG|>-aJcwf)Q^!0TY1A@~t7sVKDcx>Y)Ao zlN(~XBq8%Q;;Ddw$TRnev8{;t?RkkD4FW5reya5dJX!R{hFAfTZ+;A}@&x_kqB~fj zX)Cbz2KJRZ#k7+kW!U7|uh&v2EnAl2@?*}HK|I1G3H5c{*P*3M6A~+({qj^P z_pCSu1MwhTr@S1(kb>=U+hX>WX%!xhAxEZv!*N&t=_QJSJ21zB-4>{H={H~z%-o1e z!zp)XVgsCHpM_W~#yt;L$Xl7gI%t4ZYye>HB#ioYcUPRm6pM=3vGx`~T zZkl_pY814$;c=$iEGc>o2p?VX3GeXsXKF)VDxpQy^&pq^+G8MQ(0JO06K2@hCf$rq zQg7LqgT1xThyN1u%!CEY|E1zHipC^O4}7`Z9vjwV{NHjxjmbEI2YZG1d<_ou2g@)v zeM%Xy0Vl64(AgF-_gt17$iLV3#^JYvYsqwmiCfs=I?uUa&M(hR_Ip`B*SLrs7oR$DO!*D%tJ0Z=mf%AGSFwc8%-3@JChD-oJ z)*`^saIni->qJ96<>=GoZMr8-7Q^{07bkPDbYkG;J5Y#*i!TS$LVuQ+WD>HNjilNT zMF`ahBo!u^T1qm>?{Jgg_rcUaB~U0-zJnk`@45|x?L*)s1fRV(NvonT{if=@247rB z8n)XHOg+y3)tC& zKTEU9BU7lwnPkq3EVi(OwX7NyD=~26q}$-0+&qgJu3;AN!^{(C)U!t(jn<#BE~Lj9 zw0W_L0XcXcP#<%*MK0(gH9JHM%%v~-0aj2p6!qZ^9F-7Cl?;g7AZ)W9=H0GRo7H#z zjSN?JUw0GBXQd6$M&MjVL!s`_X)5Qh;EHK90>fK+LGS$h1ma^gJ;~nWs7`}N0+mdN z{KmkifPp`S`P>toQgC=pu&5MV)IEs-)&b49qddg)@vF8d?fL|y*fZPgm3rFFG`1T; z7jFv0rDFAHsp-P%ZN?{lXIFR)12-k6$|pFKP^eIe@FDEle#)WH_D(w6Om}<_IhJpm z2#+L_&d_6%C`qDDAOWw^t-TBAb6$<31$zhC&F?Qj>rrmE$Ag!sB0M1r-S*nutQs`M zu#qdqp9=!H*$O9-ZVa&vU(cU0FL2LJO3 zP}A1H41>e$MtSyNk=m0`^2(t$OK3JlyzXupv;c(9I-61~d2$H^5{(P?+oJTAe>jxW zvxUt;{Xd%)UV(kPJaFgwcE{XId3+`*M4M(jt0lpk7-*8*ZB{eu1y}D0D%oPOiWF&p zZzv4SR6dL4WTsle(Hli?a!JAJj~~qJvYKw*%N=kcJljl|d#-B`ZCjg=S zH!_x?4*nnc%6q|y%(D?j)21$09GNB=62g4|@{OST}-Rlq=tWj*IWjF2A8Ss*(*T&XN^&4t24NG z!N=O+q!La67DXQTlTz8oyA6?KpMN7&?SL64f{d-6{69LnF(>dNMSt$MC|6Qbbr;o~TENhn1J@Opbno^a7EJIAF2DFC?E-fPN%8pRUF1pDpklc>dXA+~~Y8{pG(h6Ir0I6raD! z5K=oKtFElvvDnl6oiD9-Z}*=Mxc@=*c~xlA1{nzKT|#G*DhnR`YJS#-6*DGBW~Vk8 zb&EE}r_7i7}W9({t(Z7?n3&&kX! zIkJ~H2|9fsd>}B+A4QFSs|XP# zd5@|2UQX)!DQ2z$Z9fFtPfRM_I}3&|zP={s(h5g8z2gvD zQ#SqLC2#!0C$*7o;fJk!t?>i zR2xqfclT?(kaIk6)05W-)stZji8=|q88TFYWj6MA3D(ueztzzz=`5tOw?8cXNyIU= zJsFf?0Z+taf%uK?_;fE;DSts2WG|}Y#U9z|gVEczQ=-T$iF zifsR^+@3s~f!$5&u?U9~sum?V0jGddjA%?o1dm7e4AHXWMFq;n0=}Q)XD+E>iaiUl z7~3`7K8G6)XD%`Lw%r^V!m~0??-#cEcRQ-C9~P7OGi3X*>3h&#a*6Qpd|9PTHYr4q z+^*9$7p*h{93f7}tbj9WQJr&C+i%e_S3`osMDh6I})=q|!m>(uB1_tRVTy|iFeP4KEw}&s{rEl-rKA^=riO|3K zXS_G)eQuN`e`4~kBQnYOyf@1bxu%ZHElc~ni)$X)zqUG<*w$x2(R6ZJ^ky#)B56w2 z>OLu=lLKeDZl;&q&8z2nf?BPEl-JAnM79+X=W$re6GY7s(#P>~Xgh`kq4kmx4h>5* zk>GTWNijD5*8Z9h4`h8?hzCI^lRPNs9;XkYKuhbF_P>E?Sh#OCM_Sr5?8^;8 zbJ%WV&S7&wQ{}c=g3?+rNJm|WivF_KfLjfFyf|6P%1H8$*3!A5&4Y|Xw@bAaTmWN| z@>I@#C+CSa_v*4kRuGHRhTXq;Ue-7~T1_t(Xs>CdL-np9ynoakitqjOCxIUwdCmw@We-^h1{8D^@WxsDC5HN5Vo-lZ+6 z$F6(Mf(8m0Ey`jo2aakbLboddFchEy=LFBJc?d`?vD0yqF0%lll9w4|f z{oUX%d~#3mGZewFq*I6vTMy)fcbLzUU8~379L3N#?|`0NHRYc;zjmQc1GVS@#?py~ zjv+bO_GJtI76`!(xE*^&G$WCft}HF@90_x+-wt(+6CwvE`UrBxPf1U6>ILZO_+&jwYpKnbw&EQhTn=j(EsO2A(@JubDC zGVZ04JJDBaa8ezx=ZqA9;D^(EB9Vi9&Eq&vRTh?qDiHPnpMU{zA`-$GVw5YRvPRx} z!U9E2RmCc*l-XCFd`diQ18}P1z2~O{WU#`2C(3ApjhY5Dc@6F;d6Xy}ZoG-bYF=#8 z%X1%Ez4aAE8@^L3?HX$=x+d><(?`VOd*~>bSEfCXrwMMit5Qx&W&Hc)uMdv`@?p1z zoo&GKJI~~5tmmj4h^ie6yZjXEBcLt2*1075BVS4ywi#O~kqTeCXf?AHw(l8%3!*f%<;%k=f$xV7`Bu2|r&E{dr|vA%Mu^w?HVP&}(8xL{Fmf*iUF%9)wFJ&Spmsd=VoiJ*LJGQvfSnL-i=KP1v_GCoWf*uS?Cva+`ysVoP$G_6V zj+^sIB0v)my21R8c2Is=vFe6{0uFrt!!!$pzNLvjuEzO9rLFjaoHTwlhjGCQwdd6@ zZ1JS1PAs2G{BRl_AcXt2MtLQ|c*4#SaKPUyBwh$;U^rV*f*oY9_WUZl4vBxM(R^D=_5i|NfWpmkdK{L%vqG)EHQhSnxH-Xe z-_i%ef1*MP@E(e2L@BJY)cU`jN=Wb;PEZGeo7S3K$sLhP5ckUNU_63E!=lVTuz$mc zy`vQ)0SxpiQ*;lXAh38IP=0*%imlTn=oL1Jy89r`T$$d$JrE|oDWrNPO@9wkh4NHy z#f-f_>WSDCE9o{mR|99X(z=@~B!VgnTYrP>1Ln)((o9rvFt(u&*v1z-Vi0OeU~IQGqw1$Ae^`6?Y-K(6C*rtgJ@VPV2YOWGJe-7f zVTT!ZFhMCbeIbu>vJZJrT3tI z5X|`X53E?g;$T>E0NOKoOq(#u1!J3h^T`))PtTQJXxS?RO|Z^LXi+D}MBLAmw!2$| zJj4K+UOB{0Lm0#eiao#-TF!hL+0L9r68|9@OoR(=yQQ`4!y{qw`Aah=PtuaeQ?+0d z<7O4_Qcz}T{hVM7wZ6bWoc#hsTl}jHcCK;ls8@e?SB%JJf)p?VufMF-lyVMb*U`^9 zPAgUA5T97MMpKRD;rO+Bw-{wmFr< zl`(HJtSYJUDNpjWXk%7rF>lY?6YQ)|k_ae7q9-Z3%D{;qv}i+IveENbCk9sJA?lII zt%fFrWbzIE{(4o4s@10msn?W1yE^*xY}WPzk{_;Xx50)b7oVftR4i#}fS7&_AZzSt z@^xp?583e^L*!Xx#_M^ET`_aHQBPQCD)?cX@*=R_&#k;q_JzJ)v+6sIOoN&S z!ZC1>?MuN3>H1Hj8^Qx%DU5Lvu31ekAvRGWL+j3nSUiD3=Suk)wXkdV;T`SrG@rM- zSFeCzLolV>SBQ*KA>b+52sJm%9cSeQlz{|i=Lfr?%SsR1#8oU+|NG{3t7F9LgFEko znbXGT|9i8115b2)E}@d9q-&6=p$D7+jD$cJg;6ZIgI`r7tkl=in@STdx&@OmFA;X8bZ?vP@pW zP+tWDn_kbY@)TBEFxw(}%nip`xcZV&rG3q-*S7>PyDWd<<|V)44BM_ox2NZK08T@XrIKax-Jq@wG6GK(&@o#Sf;K1>ny4C!^Lexv+| z#p+50r`BzGLP_RaL8$c-+^YD#QQ@&n#D1y=)@ZfznU%`kt%5`1I3c-^1)gpE%q_2Z z5|G{gXXm*fLInqCe+gLoGzL6lbGbUSkt$nd4QWY8=FTK_7~Y=4Xs7YkwdJ)*UZ_Cb z^6~h|SSqax8PQ7VB4*WgF6j>WYH>7HoPYe>z3P6KAJ9uYx>WbnRWs@(3DMGYd{(T? zPejOA^~?ZpL^cl>L^eaBa+TwwNyis(LMJu`la54K)ZYy40kS9khQu5I>^=fe>7|r+ zjEeBo(Y5y<54Xw#)!6j-etpj*4dPsWy3q#sSzP8>yFS6!O*$UWp08KYJpWXa__Lqk zr{wtcwt$6{2(NA-eWHg8-o}a=((#PF=E3{weyCTWE+ZQpr%>LnR)H!?LcpoKlU0#7 z7QGAq^!Xhvv;zcnVdV-Dg03r{PgB}1oa{%OOO@1GHrWek!f<0zA4zKG4=wJID|?5O z*-fdLdA`R*Ct9()^^Fe?M8!cYr}1%V`%iu-0IJ}OlO0aKFI!%A;^k&4$Dzp%s4L0J ztB%Bp6Lkrq5-2)qO!Bl2aW3?i@z(1>ax-wh-l03^yf77w^Bfz8ulPA;hrQV@6jB=a zh$-DqtX#mt!Y1-(^UIIzF69fz9yYhQ{Z+?SB?1x$bqC2Wnfpbpfg51-9c{+M9lZdt zJV`kp**v!X#2PS(#76n{E3UP|(9F&ul)-8)*bnk57$1Sb4f&c3H0X|eS!s+P2E-`_DVHuIU3EKdkX$%OD-%8jp7m zVccNy3}p+D3R#UN9^`c$CMeaLp`nSQE3(hYT^2PW0ptZ0a~nu=z^I>P!dzxK@S7yV9sULwnh~7`rip*vuX}- zKIUR(&L{iDU8L=^eO+KRpJf<|?CTPfBM5IgR5IP{LKnF+_EEk!`%eziXz5##hFb+- zqabbUFUp zH9po8!GNq@zvv)}%q2bwA(xwMGvjuNcz!YC2L%IVvxubW;QXr5N0r<7_s;`=d&eMVT5D!Cf;4h|WqICfS^~8c$yY*B0WD&6BP& zW#aPGXZIsr<@}a@QqsheRJR*=zC+TzFUimd{qX}#ijHJdAO3Vljzk|uRgq@*Za!nH zu*ecT11##42y7#ad9u^UDQrx#<-zSeXVW)S?x)AVg`c6{Be}%2!O1oE8L+07u=lon z4$%z6tYSN_AJ=|_7u%ra*L3{{8)DdnLwg$KYpQ4ekk_64*Wd3T_%P{~SuiRB^<)eP zD0ev|)%?A}+zt4DpE3iIfHN1IE#(tuQh&qK9KZ^S zgMpv$^_O~X?_ISa&1*>2UEX3yuIVY1%HOuG0rrlz@h-VX6Q&0XC@yuu&)2Ep2%T@m zD`RQ!ow%!sAU-@C0WFjY_pxW@$s5~tco|Wdr#v6(AJw+g;oj4qHZfje%6L^3->fV6 zytuM;HhKN~98o3dSXz?;rFQZC;EM9Tc|T>XeoO5mR*%kA?<_Qz`t@wDn^apJ z=LE>@$wKV;#M4=YzHq7WE&=$Ii$lCr7=}^74ybwo_&KfSIg}m1R9AsiL`6#*Rt780uCl-Sf%KegjN`6r>>fUkza^t=7zRn#Q@GG)n!EBW zvt|;3DL;#SrCH>D(u*-C>6xSOUM=s1``<}FA7bVTQ$bSunrPK7r4qA{mqk@orPz|3 z%{MesbA~=MBrUQdhfCY?e~P`F;sh_g+72h*n9h2wDp z(FduX)-nx!P}TARWrC%Q3xASGfQsAfA(^i6$)Q(Ic{SElke(=_eP{>Kc_om&xbRix z(qWGTvbW%t;g4{#us8Yz7Aj|d9B2yj!aMd6>u-NK%{UYx1U7cmfvd)me*TL8n4 zL0`i~=Yq#*$wHl?Ax%=~@EI_VQ%-TnDu9GsJLvh#5)lD&<0Xr>Lo)PL)ys3uZHFDG z>955sx)E*l9RotfE2W()-|gex`3YqDm%eJ^kjEZkBQy%CGjqf17J+mhdiPS^&S-zm z2Yg?vcUpJ8r!78Ml)mfh+YKLd&WVZ&S4#9}P)-slb;I4?K8yP9r}`!Fu860#I+R8T zcJg!Y9jYg;vzhXY=ca2xprUnXnZEeWMb-kR;yJ_`L8Lbw zGj&Dq{P$vSyaI;1i?uoj5#D5=7uR7wIIk4_@&5CIz>2|JKSl)_xjwG7B_qP(e-vJo zl*+3=^uqOcsL4%IoU))?Vg{Lfv;Hef=wXKC!gUrx8l~hcT}M zS6mpZZ@0pbrFs6nXms)d-to3IW*ti6iK$ z0GiV!TR_dIWq8Zz38v4t++(UyYt%I+T4uY|&8aozV#w^_vRX!~z1Y18bHlW2DSTv~ zg|L>%Rcxy&Bqn=8RH8s*4p*Ti!&D;apV|+MVX)_ABNJ;LJl27cL zLYwtEO~K6YdYIJMOJ%}jOy1$r#cDkQ!fzloz%xsQY6*naFaF?T^Se_!2{%9S{`rLx zn3!;u*@1w`NRF^7v%MZK6fZq9$%LJUQvenmRTO1}G1bres_% zN&lF^!LBUwSV13&3hq!6r_3Z;Nl_f$cMM2PZpf$X!j);@Bqm=Gf78}SWQ zXzH1x9#a*i*Jjzx)mp@TKA)A6m3aY@tR!`?eLKc^p#cC>Kev6jT()`X0@(V|7$`Ty ztx1yP8>uC6NxR^gxl z84$c1z?T{B)b=S}(}PlJq}Ih;GfvbB&OkuIiP()C-2acM0>=)gvyZ>yU3(@>EV@>0VgBPE|&@Eq3A<%tC8A3T#GP8t}$>ApfX#E@x^ znX@ki+EzHKDAwM|vdjW?Fb?#2`o^-=f0d>%6ysqNDjmUCawo>uZv$X!(YW$OT|X$S z_OHRp`jgLDV%gafGx-@Y#hwkY!ld`-XzG)*$N`%(y4Wc(y)%shpWt(}-~&t$%l z&)cX$Mb~=Fq!3S8D8mbz7%eV9I%$EH+-?USci5aHnjvEOvWTYA0{_8B`XTc6UN#ob zbU(%lNw=Mo{x1zfDZHXdLfdNYp^1yQ_v4>{-%?_*1LJ zo62Zx!#b;rt+Tw=oexHtviZLnfV7FzRN%Bc?(H=_+suAlOk+v(H<5JE!L-_KnU8-! zS;*^$`}rEmA&l6GHfM52h>A7@P(pJ!L{ayo!Q*^mDY}&26`V=M%3eVN_%*`UIgB^c zUg;3(jmT)e`;3k`0)w`fdxW3U^Qlp~#MU~`8AzA45Yv1>g{b+fgzWba({dFzcs=Y? zhSOa(2-l;B!#T0&i6vcO9jRl&e4Gte9t)55Ak z+T^EeBN5CVoD%{SpvGT4Xy3W3HO$rF02?{0o=>AB@-74+T$MHO>vfO5kJ@$ubOb0gH0av}O4U8Epdx?l&j7@m3Om?tj>}&amsmWh+y66*`(K9>(@M&rcm{j^DgSdU%TeU%<7#vxW z_?N1S64V1Zzs>8?dkM2hmY{vXA&m?)(heA-?&MkKZ0j0yerEs806N|Hb zB=7j2yG4(HRs0@>SO>MGAdHW(3v#_No;qH@tMO<*8H^dCZYI3S6*6W=P-HyGdG!!R zkItgiOK--sOdw$CMfJB(MpU{G|1BK@b1bbSZW1=`moq8hqw9Q32Rs=h2=MlhI0X93 zWO#a6vq>D*(kHRhda#QkzG--DlYM{owXVeZ4dHY3Hj~f46L%%&5MGJCM5!xrY^fAe zMvgO!UJwI??tP^xQSAsx{q>#@h16f94!wq5JmWFN=1)kd#r?Ce0KexR;Wh)v43;zJ(zf8TKM(m2-Ewc=RS`Uy z5Ol=9HdfAW@XS1%1N1^hWv@|v50gt)3WizmKLg%t_Hpcjqi_7iUANVZ0=aV;O!0$~ zZ9~E1d53kMqp>wRPY_={>x9}8Hz;lsExfH%MTMY56AQ|}sIH?Oc-wya65#?hbfv>P z&e*CJr7G_OD~f+TDk`JI-y$XiBy z2dg;#Z;zyM z7VF(7%AC6>lrYzmwNWMVJlJos#K*Oa@S^TjD+{`p@C7Q^mI8n%;lc1de^ zi4cR6Q+LO`tc`7$(hIleRYSLu;;(}lL(EcWgsL@NL~szLPrp4N{B@o33bGhn6~cznQ10Mr&O4YAOKZ-YwQ_}NR}^mEuvAJKQlRo`H_`VZ2vU?MWQeQ zgNQKRI)7oQrw!-s8LB&Nw8II|NrBibU^of(dM?e-P(}E-V4CRs@t}fZz-zk++E&SZ ze3A(%eOiG|1oO#sf*3`NNC=;T)r=@?G0S+lnUtc%m`%<`Xo7cUx$)45B^49=6A3=& zICOvp%(+5g=FawC-%;|k*eSoC97|Pv6BmJ?ut*HH?2|y#<G^X zJUE}kY2H4JC|TJ4b}4lAw|o{i*adCj&R&1lb7*ph2>#dJjos9=|7AXkxMS!_@2jNW zE-)BXGe4v}{ShidZ;I8F>OlzG<&Kklnl50PH~aA|ACgc`+H1-jjTy0RE{GEB;&3U0 z`KOOv!w&Gp{m@#eZ2jp0UcMVK z+&XK5sW;rBuOen-T1O3AkCC`9KHp5f(QB1_^u_v`L~mrd4N$b#4~EX%S|}r_(DCLa zI?7*KiUu_l8g=J|1vQ~BqpMM`?fg2sM)i_jN$^p?u9+{^`1c#tCjyEYX!pXnq50!5 z8CYWBDVfvO0iQ^tQN>?zg_zltVAa0IJlwWNN**d?{=WTz6nmov1s%81=k?jI^0!d8O5r0f@}Vi;Gla#+K+ zkPwc+=<%c=En96S_g9uiX7f~K6zZp5wFCy{Eiy;| zhIKITH;Ya3_O!WApU-$|=1={P{w?qqSiT%!gP&+tgn2iA8dIr>0Ob66Qv!(LHivN5 z*c-ut#v`bW`sg>A#rpY;TJ%y*0`hNcT8Twtg(RX^7h`{XPtzw$ym34GW&PIncb@Q2 zBhhwqEA>{AHd_<&_@p}4ngJXy4=;xxyEVm5==bHHp?#HDW^ZF9OgOUEv=gr8#Q!c&M?{@-v@p?fHSbP6sPY#m2IatSrDMr2scrg9RZKASS9_)7tt;BWnYjKj z@W@@0j3a*k{ZMc7qgi4ysYC)QDKd9uE>SvOoltmORxQD;4_CV=x4p!p;bnsq1J?z;h z05%1(nn)*$)rGlZHYr%B2%ysW%&t+)R_NodGQUu!Z~pqwyOM zThi?Iph)>e(3|JFQd>WfAJKFq`s+_>zZ=1xUElI`;hbsj5cquMWct845sxgNoK0Fe zG|5??3>{M9O0poYs`6j7NHGz23SFP=S2_A2&@a&YZYjO8Tkax%1YA9VQhqV&d)#2e z9%{oYfRNC*$SJm#8235~B@%tBy^pzJjGLC5z@ga5cnZ#D$*7*~{{2sz ziZGD5Y`Kd1#CFMb-S-H?1zB0Mc58iyupC$b4n7JqcFki}^iW8?^J4p$qKBb6VpwvOAAYrS3%fC1a6<+RC)(U2*Fo z=2#2qeEt8x)<43-bWxffpd9FPyWo+992(o}4FioVPWzv@9CKSQwbL%5 zVhM84kGYuSTRd$$V19zm?mjBgdo*0XD$>5iLWn`~Yq^+y^GW14iapO`3kD$+z)bDm z4oci+lMTbb+k`>GI+EPuY@cR>b--Zvz>`=~?k^Lje{Qo4gnVMv0C*DvSkX^Rdl#G1T*b6Q*dIdRlcBw7 zMQry~#9NN9BHaKMw*?TVQVPaZoqd@4?|%SY(_l=kW9$GsK*Ya4!YElW{W(GzifGY> zI%J}+iNMXqG)FC8deE2Rq5d&EG>wkMVN|kT%^I<}wHJzu<+8RHFGvC)L7_irhz{6K zw4Vq1RN|E9&*&18cpWz-{8uM*q7FsuVy3kE3DUl3i;Q()>ULPUwglt2h3I<_;p`WU z-ene9WCk_U1#!tBBc`Wesdzl3v^%$6ll;j)`#R!>4^<@Yg<~#+X>XGkia!9SFm(~k zHv{yX!V3}TH5lV*4%$`8B_@FMWo`yogvxfBysNhUfun{j@DX-IRQ^wEK#wIXL8KfX zfbV(y6Oq`(0U+Y7#05`en2y;TybGN=ChNVGE zJS7N;EV<>_RrpH)QF0>9G%bkHO3yBva)iWmNv^TXb+x!__&55y1<{p*1rOR1S|07K zs%65<(A0-8Ndj+QP?=C!aa%1%yVNL%`#p_sx@22xLeeUNx65BdD&$SrMn4)-3@p~p zcH;Fi$*dHKFrK+I`;9r}EGB{k1eR3%JC*K)lt>a8L=7e`G}NE@oaW0wq@SASsGT2d zi5~dMe%5(fXFYT0YwXfV*okcc1G!~SUOMAJT{W?uA#4}W?X2FeI4*2bMa}()eN%9n zjmNq7Rb@K)@&M}9i8F!8G|J*j6p~nR{B>&gIz{ zZtUIyXh~pEjx!%5B{LeG4NiN=|Mb_!Kqi1oMSgA6LFy;GB{bsx(kF8eqwz)Mm?%7M z-QNo@$XSxEyPgqiuFo3&Y7UKvJ&nPV0yepO*!;33%Z*=aH0>ZN_(EV^4;5XAR?~n$ zx57|YSwYgCZgNHsTvs4pAk{$NQ=5;~0wb#wS zKQMr<#8iMX?9=H#halS;i}4o?{Z3Y!2mWin>D3ni)UKmXJMu<9_~!`B$4%<{#BXT2 zXtj|2`g(=9DW9N^sbihxXiqs^UM*Jo>xb6&*eeg5`)s>{Fk#hpL7z}L^GuF?L$svqu>KrN^VbnM>D&`%d zt-qSk+95^bDJxrnW7MopfkToZU3EVH4riKS*j*i>?v(p@NtncRwRgj0a{!if1`m-9 zqijW|Cd$nh+Xfp)4c>8r>n4Q=#J6cbX&&6ny%#Wx!zsY=cAeRyt<4~UEJW3UBAEGJ zUd#0tZT`#@a7!4_?UF@qR zx)M1y6i55ri$~1)E}i|dd<;?SkIszmr#f+b6)okxon4+s^7Pg7T64%*wO15~@Ig*) z25XJB|FtY={kx7gC5_`dt;Y%!Ojbye5&Cv&U)$e*4JW8sVsFuwODh(YNo~%uWqH(2 z@);m+ekqZdj*duIpW`HNpNM~QbY3=jpi6?r5EZC_Pi%q`dv91vu)m?PY+6w(cYez! z3O2y$(tUG*@p9dYF2p;>e~&T*vA&iK^0ZifVjI&X6 zn4CG)uAyDYnfzMoxMwkMIdFu2=0$<>5)45pZX67BaF#300uAW#?%t zli&tKE))%mq7HAL>*I8A=@TOUF|F`Vr~=R|77Lq_kP@o8H0aI<`=B$R5stbHZrj7* zFAnxK5bFz#ML4-MT9rGEzb6MMa^xmXKoCd{ywqjj#nwQv;1NHM#lc0f-e;9bc)0?@ z`hMx{HTEjpkwq-YBm5#E!L!4DQq6+5gUx)giMxVj={80ZX5VX=%Y6YYyoE$4F*P81 zq*djUGcP*Ufj;|(0mjxe%`>;~kOmc^2e7sYG78o!yCs%bEUV;tp`<1%AmII^L5Nl8 zXTnpX>GaIu=`~@)gK#GL?Thq_4NNY+BaawQtaXPN=?~8}ZrjeQdG16Z3_g^s{VY0M ztn+FX3i-pbpoV%oVg$wU`1muA@x%kZon9zFbM$sMSETP|??@d2_dDHOXVn{Y+r5S@c zzJ=Rd7zm%Grw&UNxrt+6A&&oEHQ~b57dBN%99H`xCD%kWeJOeP7LA6q2CNS&PH0nU zBzw?&xS2I^CutxMK$nt4}uC+R*%In^WiuV0o&A%GP3 z5N2ZroW7d_C_)U{rxdtGu&3kbvGsWTG27T`lHa%+63= z%8PtDXqJ1j7Wh%qVlE@V4v|&W^@{f-#C%PYVoN$8r^y@Tu-DQAXP+wueo6?^7>2fURqn#ixbUly_!bG?J=dfyWAYueX z)K(C#w9H58knVQ4f2xd`H^dBx+0Bn>Tx#u8kA2kTwV&+aV0sOAHfVG%%z5ZuAMqdb zx#v;3F_#*F;ivYIY!z*VoRSfcx_*M2S<%$0?wg@}QN zh_f*mF#3wG7-`o4705N*aP@^xHiTrf1TMEi#R~`ob7B6&DQ7I7>@;$ki9u$(CDm=D zaP^@a=rx?_%Zt8NOQ@TNxL^Cy3eENkFGI%44fko*M0fv=D7 z`@XZ%Gw$Hb%I_d2PYZRv84mMy40Qp)mX8mu-)c1p>X@nQ7rZ3}53a|L52BD1fgQ#7 zm>o#x>(n=G@2YRZz#iO+y#VdEDjaN>9dL8f3hUR_rad(NgkG~#)fDLdm+r_)z)j!` zW^H*72OfeLh?+P+=l`JDq~U%BrR`#qU__Ern~+Rxqi$E5{gQ5jF8>gJ3YSVLao)kJrl? zVew9G?}@1WPv6lzh#`$rNj5!VT>bo#i`@$LovoIBOGANLI}inMP{HbO2A2cx@*XZ% z{&)uD54m1M|AL0=Zb1Vq^*&zGym1Ovq22e(=T`!T;T(?6t@wh8P&w(il{e z3LFi1N+^mE3yrroV4c(o@V?p>brD_@wJWt-SCcrJ+6Gw1T=IhVq;oSeMGO0(uQHj6 zK%SH^$7Ag=?G0;54G^mt4c_@TPoKua6xqBJQ{WpZOoLl?OI>iu$5HP%zz37 zy^R4yfB2IxZW#->W_zgJq-Mt$L`@F8zS{D#z(bdHo22?t?+)gig35AE;H%l>FIe;) zOJ!R|aF3sR>yNfGw`8N|{wsvT|6~47^=^>1{Y;;MMN&2H3`t4B&ajrj&)cn=aQ*TB z!Mr%ffTyX*nE+51h#baRL2!wy5*PQO3v1##nOPUlfE8A8QzL^ElYSM&3V8RT_(f*J z*(|$8l-?VIIM7Jc#~1C-P3j{$|52b*oNTxO@Dt&MeKrut$a&)lDY)n`t}}TCZNG&E zSdH3PHlZxMu?14wwTweANg+Z1k%A!ZTRK(2GQf{{c$-{7)+25$&v;-OW1lEwv1u&8 zpJ3H0xzqV|yUyR>e~R#{lDtZ96X;)?)e|0sB-J_6_^||j)!$PJd}e18yo2c@FDzh9 z2Y`V~Ka;?$)#c*QqxD~I%#_yhUj-j2L;hiZrSY};90#49JgcG8f8S}Bs>HQN(7$8{ zR`aRD0vMmQ?Zx=4*ZogMHa44xpF(V>;McGU*WG6?N9L%XKcek}`2-jT272_jdE=5U zO~9@-U=iBlT10r4J18jXioH4+Ia;~Bq<~si+_w6rL9XWc)>2vuO>gKOA^-sXF+93B5Q30N2C0vRfy6KI$Gr0Z(U1+V!L(+1uHc z*+@sh*!4Wn)i}m*l=XmSdQpW!&;8SzMP;P@_OOrdTlOVzxK9;Tyk{Pr{%u+!=8yve ztI`ifn2BB-YMT-bNz;9W7t1XOUQnLq=y_@fMa7QAh_&XvC6dSn}r|4D~M?=goAhRjV-A&sdnhEF(h2-Nm%YcHv@f z1?M6auz-Xr?*s|x@$)@7M-C9QW^5Wd37n9PwqBXTBv7OMwU>q@+;dubL6QH=?O{3{ z;7}|1Cvp>OqJbDM0T8nvx3snZ4tSaG-@643tHx-M9^_~tNjFgb)KepY2-TUw)vHG! z`g07Ja?+iS)ES@Q$WT|A^Rt!5vjF57)Ez6z%h7P_#`t zV2wN)@}wcYm0+G`9$F|V7Z^F=Q{ctoPk2F&fES(wXHv`3yCUa+cV0|xh~Kyona3AoWlQ1X*sLre)Jk7|{BWkY!sdjV;%{{D)f1CesP zPH2&ruc1z&U?aahU~DTVMVWI`U+6pxXSQhk2dVJD;JR3ED3oz>NNbx55Y%?_cNde}aX0klg6GMGN{BVLupu^b0yi)GHMk0aeha_@mFYcK+`s zAWpwt}Z7Qu^IS>gRBXhS_Nb0a1s!S|iHpJJk; zhaCJB0V^(mBGLvv&;3*$u+_n$Uu^1&QqO^( zTDV=4&>L*`S}H~AW`3q2r7v3K&n3A{Cfhx(=Ya2Yl(J`VI764p1%BdYIBU%M#1iCi z92_(XfzG{MY|KRLy<=VlPm?|m!Z^84*<%)K7Nk4=pnv`!l_~}v8NdyZ2uv9$O z&{5%#AlsX)R_l8%AbslM#|vnpJBRz;&2+yLuJUMNs4)6*9%k`&+U z)ii%ZidSe?tOIT4yo0lDs1vQOYT13Q`NseedD{n7ME|OOd$S2(zZx}K_<}khK}%p#M1HP*E}6hTMt9?P9&BL- zcI(7pTa3bddSQ+RzpD74c+f(cj0KrFrsL?AUk(S}kt`%67VGRc8UJ0{^}#m*7o-Rk z(t4tsFC`U0nC1(TPlAc?)Fg($>v}Qg?J&vyIQfh>WUc8}Jg{YsDJlQ6Fj7b4E+kK=#B~jg?$A=MeNJ3c^WY2ts=H!5Y%PW`$Ld{Il6`Cd(-ODn{1j z)I=4Cfqsaavr^Cb3|{Q8WPFHDjuwS0)xoo<%5FvkZn*4-LE4Oy0pNJ&S*Cg$VFJLE z3CTEcX@g%V(G*GQeXC~L>4j|1soh)UaEri1uziN7p_Pu6E;V&S^%=?LSEu>16mo2F z2radEeMi1L%#<#~YaPreljP%^J}Kyx@wUj{#tzGZd-r|Hft{?V&yy*r_f$0-nKgZV z6tJgU)^Fdq6;S-ABS>g%X?tm8+pus%Mn|O1hvhc{qyPW;XN9b7?CeC!X(FUT8Ff*O ztC|Alqlfq$rHFE=Uf;NxxbF#lM80|f>YsHX^14G!qnB-(`#LP(pFGc{orfY_{H`;@ z^f9j}XUl*g;!-j`Tg~1~iEqHk?EPi#+DNx}4t@#rICFa| zoXn`j%|i9*4$WDC<%Y}tR>*}18UCo*`}ngiKu6{V2W>x}oKnwZQTCGmK<_zku~e7M z?rpEfiMGi~1=s9N&i-0=f<4YK#h93Imqm=8xaYE*^dtt>&$`2_lK*~QZQINYE2IpS z0cB&ysCt6J6v=wZa)>_g-sPq@;heAbzADB4!Em$yD(F0p;2TT=fB;{nUpU=(F$nDs znxE5P$L^zM$3jvV6i~kcg}=TtxH=TYmfYtECorV&>!TBoSC zS6Jp-+5B23Qmb;0oTA3KD9gjO357nCI>+0$1%tdTrjM^k%{sTCIy+Ghf%0^90;Q|b z9!MjB*pXWG6$|}j1Zh{L1`j^jKuyFNKl)|spNHA!tlK8Fuy$(nIeC2ee;A-#!Hc@U zqc_x}vS>guN8v*2O8|)H0zgZC|6s-Tp{M3(c!6D}o)rY=y>99uc(U1dBSSkT;Y1-R z4ptT9511=6>xR*qaK9ZlL18)lfxp4!Y89`>v6Q1Cp|ryGyScKW6dOO8JmnJjtq&L% z-B**+?59=YM*#Y6vEqyY*xJ%9*Vp<+$pIu`h=a$f%V@A7fXYdB0{%9vw06%;+5U68 zTsozP{?GWeTE0~3KbtKkdlqDjLn9A?#2S5sc8Yt~3T+X$F>23Ts>uVj?nO@WMyF;% zORw5^j2nm|PnL_eD^^g01M_|qOtMmEYhDdaG|W74T<(Zb9Q6f(aKix#!FVq8IqPJF&iG>PAk@~d-ok)YHg)C-6}hdA z{PltYdTD^k&BZ`IqH=mJ-cAH=%8%kCzl3g^yRiPOH%* z8>Hb>*wh-T6D%Rbg=nXGm3+RQsa7!&bIIykw}vPjUH|zZ7sGw;3>+6H4#&8OB_v$r zAexq1H&OFMA;j@R<&Fw>6kOb=X@)bDuZbuhGmoVCf(lr+uLlgOC62N=9tE}>a3`L4 zsR5UJ5~f0E5+mYmMQb_AhCK%T9uEeOLJ~eX*(y)EZ&(ZzYkU3oYNa&&Fc0+ZH!lnlY}x%_^ksevG~`a)4!?@OmR-jfkXJ{Ttk6JO&Kz-#*vp{P zze$1nFvtQW><1Wv!9OI02N{e+qRlkTLAL3bTgSn_Ua&Y@`9o|RXrX(6Clk)QV zwV(J9;UsJ4+|JU2Q zY0XVZm08MC5~htUm$K26IOy(u2Nrxx$yZbec8(dC^k8!vY8AsO4XY|Sf1f={&p}|+ z@SGYCK|-;eJ<`X(Ms?r0j5){ScS1maP1ixyNY20x$!{i}A0qsDUh6NrzPd(l4X<_4RyOE8;^?PHodXzdfhjxm`c!~k# zQdrq}l4D-mv(6jsm$H=)Z?H!v*HdzoLFFxvNVMF&=m54E)m3()y3`T2fMR<%l7O>g zH9QyDhkobt2?cSuUmb*%K5TW*57T>E`nC!#G9l`~RZbt1cW(Ai8~HpMLwMH6SLoL) z8S3&>Q`vvvZdt6f+LoHsWhc%;4zPw$aIw`g9{Ol){|Tj~FDpZ6rhwkj7kpLTygsak zTY>y+o6*M0zCHkmo)6GM1Q~edjU8Qf&`kg%PL~sGOiyG0+-(#Kph1UGe<)2VqD)mo z)ZoXMk@yq;woPp#6NuB>ey4+W7pg=DwZT;p~9 z6mukd-mW`JFwm0LAPzxi@1ARrI ziOqUJvSdx`{gwyTdfYe0H-JO0vA|G_jyS-!G>A!fKY6j^(^V*a11EO-H=-qHjeLIR z7zoQ}r%}vX`5IYWF4(6h#fU+%GAZbdQQ!PGBT&;@1q>bl{3)ztDk`UTBv@MS0%V7b z_2`Vph;+Wut8p1DIYBxm8+jOsHx}w@dEF8MzkOcc!vNqQKi zw8Cc2I`Y;;*Ze?}RqrgZt;YZ+Q7^o!Qf(#o- zd^9tfEM!cLwCY8@h}vU~Yn)}NR=bag>wI^*BJm6t8`0VK7&Lawof1x)+bx-$+70=( z&-&3^x$1}`8qckxL|pW!!%BJH42~wbI}mxoU%Bf^Nt2LN(BW`RA68IYPyp*e3UE~) za_SaiWbXfL?M<~o<(TDOR2u=&T#D|egmmLtm@2Qhha4*4cgp1!;S$T(fCK*$7(VgGAom+1~^__K) zB+NPL6xRfgA20jv-;C!sC=?xvqJ(qUFVi?Z5WkOl93)yxDq<*=i;2VQ)gY?mgC zYJ)(`h?e?TkB|AVN@j5i&06@?PHs@2ttj;6GNmWWn6{~hWJV*;T^moe4DC`HDIK_c zPd!Q2e*FdcF@aK{{Ju{YZYhk#>dqD)xIkHOxUxRgzIAl`3oglU&74iN5h);5(> zKXZl=08~`3`~+8;FU;M{V3}xK(zq7NRsHReZ8nt{hcc@zT7h*Q?mWQ5OuG#w=oqVr z;lbPhrHLD(@<=6Mh#p>Er31A%y90RbTCXO_t4*}!aX1R0?~{I)a7$@`N!%7xP2~g(sr;sJpf2l@ zErL;_kjq`&;yLoX>l6zL$y!DF#2l7c!^^2Q6Fwd$HYBK)gg-D+mxYr{XIC5-}ifZ!~e?7CueIH$YZgrdMmIL zl>RhBf~Dz*%XX}l^BJBsK9CIZD%4{PQJ;SOwuzwXl2V|CFLGQlACw$TUPBxuC#mEN zFn`vh+p~&MXlJYSEv=+l&n?Pr1EXXvXE&^XF*oGryGHPagN4;4TZ5N`4`&(a2ALan z2a?-@h@6_m$V3i)B>xmkFSDppQ3YR)N7kt0`}qIj-3jUVv?+D$1xA@H8{<~DYS-&& z+z~os<=DWML1%^5%;*B@^edUKX&4Bf2bgzi{nbrwA)LY$uxHwmyTXYJMLZQ~Pz(NL z%?7b8qa}T+`~Ms0;Fml{@(kvSClF`2R09kXxuwnuqV)OB4;Ttk#~77=vlnVx-yHV* z?Z-QEcc(E>S{*eXd--B1W7c{y$Whw71fF{W4ktlvAmIJ^>;rq0Gt;n!SF{4&1dmJt z8hAOMMVs50e%tF+BgJ&Kcz3~5cW#{V-0c%7ElLaCu`Cb%yXwWKnjHtyGkX_8j*MmW z(7p;KvogUChG`Xq4+EZPK9sMD66T7?H==}dx5AJ{r>Tlf=D}M{N)N%;h+!N1^29orizgN+nwzyHrw$(P*^)p4M~^3iVBa0r&q5 z6n%|2ggt#Kd%P8CN@dZoS%T#1p+1RtLHq!nzSotXUuuQ(^C(kz57O|u&EL|Vf71Cs zigvQPS64oYPLz5Le;h>8x<=`w=;xfX;x6TOwsk1=pawFA%HxX`yzL%$1Ca<+GO=mq z{np|>o61bdd0U3+wI3$p+o_I>5280GBx!%H@uQi=qBhyq2kxvDL60ya_QjmWFHI`^ zbn3$@(VwKqNnfsc5jzxC_OHXoT(1e*u|{6g3)28x698qGR30xl zB-PtEv#`v*AT%IB7ii@s4#dpmD}6*huR53%c5w0<^%RreR5e4tn<~#+X>1x@ew0@9 zTZ34}X~xMr40h>vs+%ETqxIO@bs1uvaGXeIG?6P2N4ZF_Gj?9wjgb)>5-$wHhhXGt z*Mlo=(~XDlmG1 ztgjTNW3iJP*-zrWGbTh%J);}6myCYHVpDt|o${vjbT`>5?3jhB%ZR)litV88OetFl z?ln~JJJ-FpshyGrZ51H{_omrms59%%hEV!#9iZKVv}4PcJvS>IfDDNSZEIh zR#C(83qRDXR7m7@054OUV?U~6A&Siqz3B9~_?$gFne$)h$HBOZ)B6A0F>^C=06L`W zVU#M|;n6G+OT?bj(P z@B>k)4;!FRu~)d|IIwimDx`2UwT3;djP`?NIJ<1~iS|DZD?3VW*C#tY_uM1zD^yeC zH6%4PPMiE4+0l4sye6m*ao8w*I^e81X5JN;6~K7~b%nqPR=YB$Ci!O|2bxCbGfVl8 zo&lI7%-_**+b|Kl-WH9_@;UDUOBG`9q@@xk+UvVcOOnoL5eU&u&+i@$iCIVZ_4l5Y zzR+2M_CG<&SfRRLc&_u4p@(Jfhzq3MG@rZrdp-MoR5II7N1|7oG9HFuJPX96UPnsc*)-dSS`5Nh! z!kC=7@*DlBTBAXCp*g1g+RMI9F0q(7vvaKPo4#F9E)s!W`Xy}5V7DN=V8E6SnW*x) zh^Y@<;n}y0Ot;+a1A{zBKW};+jW*o)`WzhI&4d^oqM`M^5aWoDwgZR?6CZuJ*;Trqn{8{!9}spg(J@lhB>c`B&ZWQEmlYcXjS z+kX$MQ5H|u+u%b}u#epF$kS#U8q#>N6mo`6&sOmh=DbVk6|s(%;Q-7a=(2f5QEGYQ zE`}}w!!e5` zlC{2c>vCRP1FA>pJ@geSZ)4-WF*;XcHh&>yI-}My-gDL>72!%JmFS(SdzK#_oq`SI zsolQf1k_ZI&8ymT%~(Tgw=<=q2p#k^UH;%}(mPV^(wshh7*i2=S{;I}0GzJ~Zxc%D zCz|eg0NlLp0EM!K_tMu77UA49+(7r3`qj6Y%p|pSxy0GMgcQ_&eC7s4n!t{xR7AW#F(h zD#JJJ9T)FOR1Os*n=;>^i3x_y+6TTam<>7j%R1NeekKeO=mk%p=^wFBxNb(}Hm*91 z`w;Y55b15C!!?RK?clF&dSw(cX@sBe&U=SLZE4N%xxyqeC~R>eT=_Q&3Zjnagaeua zCPGt8qF&(bs$f`+c(v8AtV_$Wf5F`>waj!#-E5i)Lf72MBjTc4VR41Q3ROTB(9t?7 z2h?`Uj5Q@~eVcTUH($Es>=qyz8oU?i@i-`2Il_l>L|#6ZWsmwyCD8r znv~p!L@PH($%W4UiJ2!|!ntMj6?fSlE^gvUlC>zbKZT|)l^@m?c)O*5)XbeA7m zFYGHkpy@;W-s*?PwNb4sGvZR>#`qy_O`mYiQg8yCHL?QSJ;n6`g%+3u0RjmZM$4+Y zgf&r*YcA+^#4HK-4v*zr0Z+!|rGuyh=)v#68Sr)mV{vd2j)c_M3)ATpMvXwDF_UI3 ze$5<&$AGfR01Gg^GHP8cS!Pd*kq0@1<7Wc}-@_CnbMg=*IhNQBJ*_SL{HrBc;#4>E%=AnAK9Z|=VC!|nG_@OA((TbaMvvO@%!S-TLt8{Pz3PoO7MK%$b zHBCE)Q}1=u-#WH@#fw`Qt<-jH&HkEZJNCsy^Lr4h8e9H-$Zxwd{AJf+@nx?KsP22R z7_wfxc}Psh6EmbxqjtoXt$Jr)EWyS``Q#@%?foj4O&aOsLyFHDuK;}-K(ND(epUUD~x3QbbcGFs^d zLQ-9)@)0`4fe056oby6a18PORt}nAF#u0l_D=n(A;beVx4b0)m9LdQzT{1*pJ8y&T z4rsL)?nLT0=0nJ%%1OD)g7-5Tdu1FC*1seq)e~c{uonfUvi9h7B+Gt8S80xK8IzW8*Gfm~)X^GzxUgQm;HdA%q%p0vca`Tvt*IaQ7E= zdcjJQaudNM)5U_qVO-zmkc(XC(oa?&P?PAxWITF2TZYJ#l$$F2R|OrbKRwdar3wi; zZO~5;HHi#N538*T*;<*|e9M_C&h%3fBOWIw%{7~d$WP0$&l_?)McE*AmVT`{&0rmukM>m~THwvTZ` zp)Aa)k@9-*_MzKbA8{Vf((Y+aMUxQ-XDf{r=w@bH1ynjigK79&&2CdMd3cH$tqmgSP^yaKHfR&HDf&cz7rbDCH1-L9CY!#y6~>VQS|Hxf)6O|j z?17%)qUpOc-E<}7DtZ|54in47otAO!5-J;@@BXUphlrm@hX|-HA;uYq(Z_OCjP=Qq zyNRRr==$Y-1yI*F&zRSCAr|#{l4zFrnVQ!WK(67Relyu$;quXLI*h|lrZbJ1xV^?? z5Krf%aQrc1JN)Lj)B^JmYjp-wvviIDNJsL!&zj&HYl9g%!fI2-T&OD{X)8|ZuW>MU zCl}=LblyU!XJ_n z#J3YMTpghYIm~qeXenwLV=0O%jhxF*5@UaUI%X0d&S9{rMVy@9P(PayrEpL25f!$9_)1 zTQo_p|F$SXO782%72y^8zjBpCV!He5p2e%bAyB?}r0dFFG#r_G##vC%Qu?6pb z){zmcL`>klRwpnH1(x54_<55T$g{YH*W`xlRg#KTqyC4&uVFtY_*3|$1PMz z#|g_Vl}1NsN2KGAZ1h;7J`PnQ-63!zn)P&oI-v@%0}u|3a#_sx^!a zSC@J53g0;xT2q66udTD6L@22mZl9!O*Z2X2>j9MJ*59wi43E!UheEO)^cIMc4u5?Z z8-MU8k|+`z2e<&!2FbmeI)E9Un&*<~BI1P&2bN1g?r&fcCK}wHqFhreX?-BiEpWGh z&fPaWFN3?9Hpq|8*KvjR2!UNqn1UA?VezIPu)>haH4i&ME8Z8@pi`BNU1tB6?lax0 zUd~V+9kIzY2Co5zx*2~tq}#*h>u4JRoyUCRN9|Y6tPG^SBBm51yM}TuS88#CNQ9RJ z_NO&$VG6OH;Yh*U34w3inQT0BDtr$QG7_FaU1N0HMq%|i+YSNDMHK&Vc%`M=SOo@T zWkBUYpg`hpCC^vrxyya>fe$B_Jm&AhW$vA;BqeD1J(ieqI(h| z>d&+}O3(J~>%bd`ne61x5I8o{NWc_N-EP;l{`eL=SKSBclc0nKXwFykh2erPWiukX zfvBFkDX)&e_o^Y&3?Wg&V*NR&%Ft)L^2;qmvUYzFKQdh~o_|Bv?L!haANyjZ?W6$~ z@rZ%jBbzW=$v96_Rn`GxP+V(zG`|*?4SN>3`rg=SMl1g=U(?8JaxPjH6a%7t@zVb} zp{t+F6-RLJ?nfT`VA#jxM0JULCu2=c?V+vmpks5jpTi0d4H+4wk-N$f1$|yO;wxun zKq}hPnIf-e$TB$)`w@dbRk(ywYKquJZeZGDJ7>ONnc`gFHc^OI|KP)n8~TkxKEkca z>B8D~tQxxlL-1lo%qWeVf+LgCCqksaYap8iXEZgRYXbfuK#a~VH4oUb5-(Ex>$>97 z<{xK>HW1L1D0Z%PHClrWKj*i*i@+Jeg6}+p_eshSx)cix6HiVcV3X_iQ9_tVD7|e~ zfK00i_S5=am5Xx$6xLtub0R&>>*i-va`XamzrJg!kORg~2N8$@I}RSqsgJi zD?HArl%vcd5%`Yfa+K9$Y~lG0#XqgEh@%6>=*pFmTj>0N#af5s`vFE^FPk~&ye*A+Z zkq#q+FpBK$J;777r+b!|DPxvd$hy*e7f0|Lt1`i|3#0d%n6V{%*T|M{pw&QJ{@j+2 z(Qar&uV%BDlu3cxWm3SBzI|E#^_=diRc6D(LPw%( zse%{#qs%UEZ;D{6IiJTQeggBmFLE!bSMp!gY`>kzo=+9`&nfxl(fz5bhR1b~U6c8*Bc3^A6d0G>r&A!UFUD6K zttuN9MLQxevWD9z2hB>h6PN*IbUf8z1Z)r;p-PWOOK8rSQ2E$CSC05DREjtjifinc z%wa{TvJ1OV#Z|qk1@KIomfcRxu|wCEVA_9NhChQD6 z%yX!VMaR{UBx8}4G;fgr&33gYNQ<-N7?UJ4Ew~;<(s+Vy!F5H&67j=XNQV@p0`NKT zBhugnc(msRY%8lwUPRvx5NS}wpCFbxT9&m_=L%ny8Ri}-h`37Y-= ztLNhGAS((N-l<{=ZGPck&A+92T&C>_Ubg{AZ}>N`he<>wChx$!qu=DXhsn3?D|7$h zF%Em>E`U$GHmC!&geG#l3pv_2xAFmN5-dgpBn6nmd2)Zg&`e+|%{r6~N?|8<;b;3LWAha+R z_`sTGFW+;24Fs3cYi-C8K5tuBX|cGffZST6sfPRj_*jP%`Ibs2 z!-(x%XJC?@`4A)oGZPz~hTa6cw?SOLPL{ng_(n(mpCd`O;2Y$ES?@2%9zoK+DJB3~5-UXj7-KzK}ypu$MXcQO!q7T7t0|Jii- zM2opn_Aewi55Mq;Ld_&%+fRQuY0&3Mhb!`o8|h4UP*t+BIEqsi0?9}>vO@a3y_!1& zGBsF>DA3?qJYGVU|Co<(^${5xB$iqWB!K9Kj( z=GfKG+SXZL@k>IDiZlO<35CO`t8iIs_Xa(66gEPU&OGAGO>czVChrzL8%T;WW3T`| zK*7I<2D-|SjIYxmgm?_79&7e2vnSF~OCnkp+^tFyPYD_ z+@G3oUogop@p%hG!dl|fE(DoRtG<(liWCrQ8MV2i;qc%iV9QUb3YmHzEMjv%ik-ej z&BV+{xzjWw3EL%BTtDC9sr?+IA-xYVi&lw6Kb(Q=*?1_kzqncaDOH8&##s2F?iB@( zZfe;`b$D!!pksb(p*ta0u1&}4-~h_*iLPxN;;ssz2AmXDQu}K{<$7{g@p>1RQ%d$d zqh-XxkVXnyXD(0kx0v>TP<;dyhlaFT@=&{qC~iQeYe8j`|wBB^B&X@piG>-GIcxTrC;`qo{iBC?EIfdZP zaW<$gvd>tPh;WXR^s0ULE9yk7`R)^Q2=0kI4FdEZrG}F0E`^-nKoo^VZ8PEsivL5F zns*9hPCzbJ)Rs7+W3-Hgw7i{bEMnvd?dc+>8={n7g|CNqs(!SjpB! z*@+FTz;s*%eAq8nO_A}GEH^)ei!$rud8)ZsJPjh}{D*$MGE~tdP8+U`z|No{oh!QM z%D1S%8D4)Bj3sj*Sc*;SxCs$p--uFv5wqRsAd|^3BBHp`a{at&&Xr`5UlnDN0}rz z-uOY|5vM@sAP7}RxRGBCsNPj@`EN^a1w~FffgccF9iNXz?cyL-7$;30Tfoe!YQb!+ zY`d?Ak9qzsZu!JuEP#Aj1jc{`uC&&72xaKH#@fy7>17^SZ^MvPt0HBtN}1P8dj7un z3#wc|IeT1TCU_;0l9FUtclxKH!Y}T|!@j`JGMKv8P8`f9Fl6Xn#g$hts9@0ktyi4> z>Tr`ffSZYqY=^;p9N`{uIF$nOzmoETjyc%2!*fak2VB)F0ciW`KhV|a-NNPtHYiV- zk9nSNC1kwRO>Xc{RO8J2K>)ER)QMe`;CQRS{Gy~n?Fwp^{RT@ugEYgHYo~R!}*7EaD1R z^6H%>x$i@1A4kbgQ7|h8QajD#SBuImy-$5z2xelvcQH9I;f}7vmTE*bTD(k16nSHL zGubl$YKjnPeB;`{B5^I5lqP~;vdfE!Yg-EixRo%{qq{oKFTAHURR$g))_a+(K~vSk z@+wLTl8$0%b~BW;T74YsqtJ%eb%uuO>MxjkLG*J_VbB_)N;I_XCUi7^$(D{E_;ZF@ zL5s{)9L+q%!WE$E&l$z{guT}VrmTI1PoBnuGZnH0D*n20p&D~Agda?9Gpj-g_dYT9 zV(LEWxz8q?1U1G{u*G+Msu_mSeXfqwu$;W6?b8xv2IIuJwOeV|6b`}0N+0DE^LHd% z5gyN&jU>_I3M+6-1KQ0S%ohXzR*c_KoiN$c@SIh+ni6UivEF|tC|>ZGIwIATA_soT z2>uNz>3p#-<9aA`adBfNSuZ*e)!&kbigW(ZYo{6)rO;NTDo5$FY05l+V*^hMC}SMe z_jI5%i}~;S?fo++rR80SGrLjKITaqF(hFW|0sQ06QU0!A(fT_mX3hEh;ALkWx1#6Ld7qT z<~6egb-%g1E8o-LUBmak4hfP^muUpDCtHWo0Flg(qtYnuPMERCsw>|i&yE2>UNVc= zEnp-pqN8VoZd}PBm19>FeRU1G9Zoytkv9lY_ec*I<7aEe6&Vq~>s+7aZR~HCV%Le-V7nv_@Nr= z25OFW2jlnO99PK@^kW(#KQES4D-%K_i59ZGJ1wc9wO+_4Q7Tdo2Gpa`4mDu;tfW?s zl#zR+MsT2Swz1t0Z#wl=e;9e0E?|y~O%!Q}nXlR=RRMvHX?-IU)`MnZ$M-xV{_os<#JB6_ofA<(#| zCzo3|xbI&MY@h~qa0(ibYKxzWh6~GD7ob8i-DH4EEqd@) zs?z9BG`vcqujR6-z?((f);|>tj$bI+h1~X#Btg3_1t$1ot59sv=b73q4z{VkcMY<~ z9*!M}Px0NcZ_B@>AbWzx>;>BfemK6{>EgoZ7*7r1590b9vSFgfzJxBv#g$q@9qMio zMx)b>hFlg4~lA9o=$Ql{YoozREgn zw7EO&(*~%z#igA_zQ{8r)fZHQOv@c$|9@8#w^@$3mmZmZ+D2Oy57@*9j}pP2*~0ELTW8fe{Wi1vjJ_;ayoxiE(PyMum9m>s*D;`;NPRZg9siTn054}KR1(&!$Y??vz=VEUIBhew_V(FA4QF8>UzSPFP>9b@npOE!wYIe4a7)E5YR<|4lmTkmXumlgB$t~BdOPFb5kWhdN*F1qZ*(DI zhm_&^#P^LoZNrKkWKte*f#AqSsI_?eE|Q}O^jut0zT8p)6K;1`bXgbe(U=l}?f~@0 z(Fi6>f3k3n5uep>=1u|vW2@HQ$Gbhx^V<3pRRKU$Gvy)#ImqLzw=-(6bX zbG7^jc#KvizJ`%6ybHtFO%*tv8S3E<^=bKTC|~A^T@MOg^WQs(Dtk<}=Ax+KtRxbB zQpE_c9>Dpx?a@#rm|c+;v=LNb#<{-ofb&H+PIW0#;WTvsz0>NZ?092!EmlHA_Eg)^ ze2=ZA3my>!YQ-tXx?&q2m@degv)EfWW3(IE%Tm(0Lt~ zOWTL~fSG&^h&MO@QsBzdA2mRUX=e2tS5amO;USN@rTCuMMdVs@eSa32j6%GViQ=67aMmXOR z1L1nOC7vBsqtagK(p;x&^uk{Csq?`b^a5@#QBtvQV-y{cmE-4Y3y_7a*D`((E;@_6^? ziaI(!q+H3)09X}L`o7Xm-dJb%KcsF>KkxN7QYnmhslQX2ri;YGcZge(ceE<|8__IS z?~3CiUq$`|0}V;#rJ3hj=o%YPTRHq`OI9YlfSZKr@@C9=7oEVc=pXzu zhI4yB-$5qsh(i$g?{=jAA7`=uAx!_^Cjy9<$8En{>pR{R2BzX?lAtI*V=*@~&O~t2 z0J`=mlbmhFrp;j@CDRv|4zOlI`pXbWVS|`th0u2v-3-KE-quZ^fp8=0rfq3xY@3X# z4E2I{l<*|oP=H6)Q0e()-DzF`JoC|TsHK!(a~~JA&T~+IWSHge(3+RI449E0qZglX zGdu4BVSf}VTPK~yF)J|~G60o0Y#)#RAHp`yNa)muR)AMt1}Cmk`>`wNR`0<82iBGD zN#P3s22wSG&4DK6*}t(yE$zf;vV&8gBd-4{BQ;K7OA4vu;WHF%S}!Z_!5u`O#9BTY zavW{h$Z;nbShrmYo;W+!PL2>Q28Ec`;y6Jl+OA43w(F+zYpEGtk|X=ALH@agjqSfD z7_Df_Y-2@x2N3w@$Vz?)2Arl7iVGtIQU>-G5y191BAI#6M<~e}y7;IOns^+?2129U zgvm13s7&LsgxF2~(YVApdxU5dv}gMgS6xLRkt}8ErmMz{5n&7RSeF7jy#cg1(r(In z2y)sSW;aZi5QdPBM$PHKijlMXBr3+{dl0TV7>N+Nm$=NCt4y|3QMy}&V$@XNC8;fm zF+mIw%v>X2B3XnWJEAxS$UC!uCoLzERk?71cb&!3P-##{H+Ny?Z zZWh^na94Uww!OR1cPVv0 zmH?HowQh=E4i${V4hc3}4D9#66P@8wJ&h^Fk8^xOXdV~AJXT1Slnprmt))ztj@qt* z)W>!?w0xO@&}sk;$Z2WQf*c_kMk-H=8zTixKYyeU1`0-U7X*8ii72*t2Ukf>0OzuN zx*QnzBqI)mx8PJL+~$<+i}W}0sbD$0KG7{e_MJcKEEhXhJizhO_FRw?*d=8CD-C-Z z86f#cX`4+Wo+l?&(x<`V_~M?Z>7SiVm?9mpq%26W*$lpg$HRP_Jjv?9U=3%9;|>_^ zMyL$wNLTjB^Xr$e)>ZhrC;U7tGWb^xg<+k(mvS>Ng1n=T8q ztZ{GN;r3bt=?4*gzz7vB*Di*l3J)j?KktzOCJ6M`&z%f_AJJ?xzrqTmtZAe*zG>0s zGJL2Ht0(bI!?86Z5nXcO73F6xPa2=*zDisSmWMBAXVd)kz67zpHj5biibCXl2~;2I zk2Cr(NHuf1OULUIe>t8H+qA)3W3T^q1^6Bv&0B#8B813_Qf?7Jko0#djs)(HvT@=! zTeuHl5bpgCm&s8qH^Y14oC`0bi8#6kKLsKtdB)^j8?A*@@(x&0A$TuV?X>kzDuLp< zQu-RkKJRSHwfehSqk%Ne_H0Zf)$nZdOxni`=Yf6kuER7#^}PvZwE-vUA}`j2MLdyM zFK!}TN{rh(oIk5g#H<#JDUzQncL2zY9rltZA|hO}8iDe>c&kR^xa~%_TaEGV-E^d@u&VUg++y4K1-zGrF?A$o%=k z6IcEx?sta4?uRfnpsAO`iM&hvCpn8&x#;!P3c&5Po0LkH{?=Y=w+>lLI%9rdg0Tfy z%7|$PYU24?)BYOzeNkBaeJl2G82>Ya=Dda1qvDH~wr4euwx|W*3w$=^zpw=?#~spn zu>h;>DK@=nI6tn$uC5vAU}y_aB<9oi2E$4R-v9vq)l0IBZ1PSX<|gS)e81O*c=%lb z4Ae7>(wIXBXYi|^3vPS>03XKF4NzWIuv1(FjlwBh+5bi79eRmARbZ)#GjpaNsu4`< z!HwvQV>d~&m>we?3-m>}q740u z8G;k~^ga{Trm=(xSvRwDJq#RgqkJnbD09v}R@ zCEy#l8FP7Y5T*L1%1tOx1fqe844p!m?iX_V$4jU#9q~FQ!IZb$SxG2 zluCfCy*+qCWT||f3rx|>6)Y1RD(6>KQ$&T4j_NwA7`V>ac~ao>;%7!@e&dz-W>XNS z{rU+5f2fM|;Z`NAs|S#cXbkRu$oA6r6F#V?q#~^Gum&PZrH4<+g&9RICC?8i)L{Cc z8=foSmx_tOEWv|4*ds9Gb)$?MW#_Zm=w$DPkn=^S^+F?Nve)KPtBOqZ+Ng8Bq~@vR zgl7U^tJ{%DYVyP1F>p!7qcW-rZAcB$X^uZGYTYv#bC}qiF>G<3$EP#`Pv0#?TI*O1 z9kj^ONdA>PR)VbR&f+5!EteaW#SCOZOgj^6G9gUQc8Cf$Asq1gZ0ilczNQoNf^ks56I z!H_dKDI1+zG{R}s33Rq~9~HjWGm4KT@d&kpY%j5u;kT-RcYGPsD$GtyT4GHTl)M+X zvEEXHORo4~6@~42jmQ8%&*((zn`F*M5pR@I7}|LE*yQOY_=1fezY7uOt4`MW2_q^8|`aV`rk%4v-yJY(a*I6Nz=ple^+ z5Pk4R;OCN{eC1jX0KUyRVXU@Mc5_9f`vDx4ZEY$Ur@DdF=!~fB*vyJyB9lfRBwh?+ zdEvUe9ht655uSV~HZ-|wrqsI~Iv(Y1PIjRg(F8yJAsV9tLyt+I%`<`Wr0AZpM^D%! zm5s59q1KPaVEB?|PT19T6L6Ipy`zX&I*oR6K4h~a>o&4DUc{ueO_l-bAuJMOfaDM* zIlVeWi5+t=EG0dODUoe7Lt8?e=M69`_(U6fEn_X*tcxqqZ6thN26Yu!#)DeJ=R#*t zdP0tNLm!ga#B;kqS~?1Vnt(I}0Yg8=53Px8&=Ch<#vn$ZHAicr&D~BXNVxqW&iu;x zU23E0gpN)W(M>F?ci^;ISR2?(J+6krxch$h0{-a0dKmqkrp%vS3%Z_Cz38PJa{@Br z4hbWs(cX}L-ORw=)-b3-D>Z=BTN59Y#v2*jg%w#ttE3!x%yPipSF0f-6LiG0vG{$G z;1K(jvL2zh1$0Cl83V8yU%ddHW!&GAcBup1f_%v_dEF_60+TRw_DlDsa>lPC39-Jk zy%?PLKo{Bdi~%8cfRNw;AKxDX#QAtLh=nnY}v_S;!DW)h4F2sNU6TV!x zwn zTVlzDyst0Gmj_&g=Qbk6Rv*LV9QwU6)DQ`kkpkRz?v1e8Q_VN2iONgH@VSVjZeXJn z1;G>=dgn<~eA0av#g9m2AOpduA#4q&iV61RG@;c$NVKz6wO|wFl%^H+eLh#w_8>LT zv1DyCORBu^5$d@&qMOY3tv62T6hVgq_@HGYpstSTs7qRiT22eC&E^Ti*Xnkl z9$gt(Tgd#g2rm^ffyVc^h)=N@j}R8hW?3SV*>oU>sR{Z=oEUR6n_vWn7~a+mwmmWNe{Jps6t%M!Z8 zw(aWIp9xgxFMf?wELX5M3|;#WHN7G#HAw5zR0l8byXg1cid2ph&=eY*XAK8@N@N27ZaH>1t9uLJ=7m^Y?ujh z20r4j-TAXLp1M6Vz@etxzxFF(EuU4YePePj8qC+L=b zgu}O3h1AvYrA7scunwqZm+5??k-<(BeYYtDUMITABKx7?a(l2NllWY}X(>AG_K+Y5 zM5>Qgf;M45vISMzFf;5%^GNd!gO<14rVL=_r-7)far!7mTcN zeuCzZE{Ueypg+i`Wy)z3glhx>vm!2Hb0Ul0m^y|i9B4(SADqeSUgYZMw1Zgv-v`8y zDWtp)!LK)ggNax4O*OK8!vhCfAv}clpB{Ja6mh{ds<5A*$4dxx0 zngYIkO`xQI(JcJ6nIX%DFs+jV-Zg#pCscT@eLJTdu9>0`U|VV^CZXVehdl{+OSf`M z?t}oqD~X_-k9Ey;)`2mcAOK#5el8Q1`~Vd~0ViYpOfsjmm|u<+bz$0?R#RtDSEBJ% zs|?)cyGRwLg7GN?$}&OYBc3+^8#B)u&jxB)I{|0xa|`JTl}bC6bp9{rNMWh#KbKdh zW|3U7kfqm;MgpOs;QkHg;kLnKA+bIMc3hUjLx5`F25tUcdWka=wh)yK1Jf$JpFqz{ zYp!GZ9SPKTz4$6n+OUz1R7LKbctQxbwvXxku|TjcD_Dv~#f~6w;0#s8I)Zh*9fO>t z-Bm41Q9V^4q>%{%4aB$fpqJd&qFGHe^(I#Kj0ivW?A&nIv_SuL)5kd2p z4oZT3e5(qD6LVq z)u})k;;_?G0tdggEJGXJIwSq|ghY89C-f&Z&sfG4G&;6zgdgGY1$AN)i?l znie9+oGWCL26kPJB9lnyvEIPJr%MUG_Dmb-w*~b9%f5#8mgIfQ0cFN@s3tSvi_V|l z{W0TNS%av7Bp?JCE_)}yR^EIy83$%lkx+fw4PdXmma&iMK^9!J7a+ah5HA!a!yt+T zX=aw)Y|0eBMh~ag7sEJ!01bGNIZ8O(?BEJ8|CV z2NP)@i|wcMnPJ5CN?(?`|**j85#lE`3hLU$i^)@Wc5qylwl{$7E`;7?RK1Jx~%- z=w+*_205b|O54y_V^Xv+I|w<1?Us7$S3Z0Xt}(0-Rm)w2OrL|2u>6s=4FDVybDKc@ zFEs1!9E2#s$bJqx-WDfEKt3l)7$#^b5r&&oH{q`fmb}+^h}2QgBBm|Tp)Iv0K-Tu; z^i;xL0r09>VipomVYoMT=Afun1Swx(l}IZ*>CIpC??4UbHmj zy9&PHje+i5S*A*uy~E$TG@m@U zJqdGI+VbI6oXbAt|Etp=xRwwHOr_Lt_a|->%2OZ>^e*Jr{Q=l+^n7bO+o5=^V%f#c zT%&6CY@MtPi_@!5;1!qA$I$n`NM%pp6R_HppYTA@Avai`VZ{U{8=nd}TD23GVgc4^ zI3e20^z@TS+t60dLrzDAr9TqiCLA&}^`oX|^;ZUj;{)O>fs470zhR6694!M2QMmXN z;g~Edqt)nVz@<16xyG=8pk#g8a0VVWEV_ zE!q%t>_o)?ki?d>b_S;?3Rj1SjD}MLF}H~B$w8Gij$R%^ z+SKgwH4Q{FXJM)sb9%V9luc_)+SuX>o>`sIc4kW-pwE{A2fIw=7G8uqHQ_JOmFe8& zg2OtC@&#diLHiy@3X#mM4TOOgEu#JEcY|guiC_~#FR4OFwxcQqXbWt2$@bEzvm^Rg zaOfR)0;Kz&d)1NT?oBx-W{ss7)}*el*$DbmPtRqY5VrP@k>`Wo!hJ{W^uz&n^o9FX zVHzQ#>cI&$$w!DBMX2!BJIM(lxuCliwru)D@Z4^!KW+@&b~B_KX1+SweV0N!OKX0! z*NvYWHApBu`v@jRwiQbSf^BysR|LGJK3>Qx6xH81VY0vqGxk7SI~| z(9b2DEZt2?vTZ0BwC9;IJ_);c|F=9Lq$Ysyho(_R_k;cc=tNNgXAa6uInIS!hUz2; z>3%cE=$1U;Ae)G{F{hF+=fPU$;8->gk*uDEEn6?9^?DX(Wrmx8!MmOE+!(%!_8IE5AY;;*on!q zZvUtJuBmPkr4Hs3%fENWq`Q8@VD|c}5v+a8UU^MX)X-v70&-^){tX7=%aC3!LH3AN zX5xjuK>7K=3y^trCxL5e(%%=iXR+xnM(DGVaqdL%-Kp6wT; zyteYqEBDoBYi44YJQs1JRS^5NZF5~Qt^z5PD6S?m>&Y5 zfixyFgD`2K5($(1lwfdFWtloyxT+*f&8qTXd-5shx!5c50YCs?&j3t+o(cvBiafe& z^f2Mz6~4&InxtbYzR34*M@PDTVPK2{0F2gCxqqba3%aln2W3!fqP<(yrbrNnMNK-x zMZ4DGR7jd{7O)AZqLo3+jd?-|^j@mB3m43NVh;J(8IX~22Qc@1023%p2ajAB-8RS; zu=vuu<_rsjmBY02`Sxp)f@v&wIymrCK#rurQ_fruyTv+d2an?M%kNor9aCnpVFfsW z$GTUDZq)%VA=Q;GuzvZ`ml81HQ}GHmkQ%b$v2;Z7#uTYp^Nz0 zrQcthph{b~#(wt)u`|H!4$wzofW_WJAO~9q~Xsh0?g-NqcrSi_gszsP2 zfI(S2UQkfWF4OQDlWE)|>hg1}!t&z?Jk0GL1wo$<9Sj zsCaHzQo_781=dXEJjoY)Q`6Sh$b$kY{?CVwlVHqBc@fsUtIK{)2|F)7 zml0VCr^gn`>|WZxG=>@M9<#1YHfeYKXi5hVsiO?ZeF7FGN=9KU1>0o|W-9VYIx*^& z4pN73anQS5!urLwN41ZrhLCLe*5Xc;)Wr+niDRld=DtN=&02%6&LbIcNv#oaZdNoa zeKK*zM0OfrQHBNt-bMP(axZgozpKf;cjFPZkT$)5GjquQE1I*tj%_dWN_~}2+!W|| zX%nzXS||$ns_)En^9zsSs(qYfEz4hbu7m}sMI=IfM%nP!W9Ot}N$%o|AN|l=mm+v9 zcnqUx#BL0@Y>@ziE=cz#lJ!dwf1LYvU}&uWU)etzTV{YA34B5iz%kK;wyZZ9HW|IX z-{zhd*!jC1#Q%xH39iolZs*fzK14DYa2^^j6uniEc;n{fqka~F_u6JaMF?cH8Zu4t zUy`N)BE6svKp-dsjGi$sCX-lZmw0Wj@(JPfs(}3#J-*0T+Z}G(I~kx)kc@%?yZOi$ z&BHE{Hc`#c5tkCHZbE^xS}Xflqj*kLuM_ywrhUSo$&2sg`aUNpLccjYktTU#R)XeV zAPZ3f3mOn4A)t#d*LmSV&^xNMgX25%!+u7mpdcMeC{s!~8FK1I_p#`&YggzZJVm=E zP|TEnzn}AJ9nEPrNvlGd7CFU4Or0H z(p5K7u0d*GkIG<#jg1>&1n@23k8lB;mQlDE(I##r?N_nfu!<@J$xPuWv66wDBW~9< zEjZTR+VCTHT9(d1vnhtt^05`#*Qi@2#3O0UVT0JcMJxtKkpEa2nW>>^z6r)OtVR(Q z{SJPp33a#U*t905+n*dE(V>m1_h`V4=Jrz81SdWZF8*@szSL6G0T*2%m6FmBwB&_z zpm=hMzk#e~rxzZ^4hH|Rnn_%LduHjWMkB3Bhzw@v7Rlwj3|tUHzaEDIFc;*Z8H)M- zB_A-8l8UOl{bGK%F6qKyq;fm9nIXKSi4>|S@wHVUxL?HNh`xK8bACRAv8xCwiRW-< zzBks=x#x~vF{=tl?y`6ibF)b{b+UzF?e4@TAc@T0`NIr89mr@T3*l=AMRuIU52~^_ zf^DlHIRngWBkeJ8VdegQvxt@M*^f_Et?KfHW@5bDPob)!V;jpVJM6 zRvpgT_}4LfJ2VrMc(p%!NX&)5;E=BinYS1hAha^Ikzql0c=Q3>KQNI7}-GNS= z8S}(0%LH(5J(k}FQM6XHqz5q6+r34w0-(@|vQ5t*@#vhX4c)@$`v4AyNcVT3*6u{k z=-)%&F2VD6;|Hq_>AWt1@&?_i${mQXyyacbif^xcj2qIHX1d?iJf7Js*LF{H0lMQU zm^n3IrNFE!N3h24j?N?-;wWWUBzo{am@Ub;#dLf3Y^x&pnYGOm9UP})AsUc_K5qiY z&hjHB`ff+K0(RwaMp6FB?xoe|Uda}|8#ckFb90)`9WBCQH{I3YYR8j-W1L}D5-JgF zY43@@@oUDbbs+&)2*P-tmFrmO=5X}FUZu;$$kJ{*JoX+Fgcb7}M`oaLS*S`DLuPa( z!O9YhwWgYKX2BhmV{R=6I-QkPwJmsgj&yvACw2oH?}aIK?38p{vOD0Pv+V4Fm$;(Y z1*~)ylR5$%e12P8VunBArprW4*g_N_Sj10zQ|!83X|a9m55lhiPwd=#vZt)4r4&B{ z2EtJD_p^fV4WUZ08$%yEg2%}n!{&*enoN2ABu1{kh}4xHHlBEFKEa5~eb8{o@DZP3 z?BmgrK2M7H9Ug!&W7n&x31n#Av_ib<0IU&%7ckTTH}}H0=wYl3hu{t+0xbFf1RT^V zsy>m!!U>W3#}Nz8L0M=IX;N}=E)c=Ne6v*BmEAWbtHLGr2z{b-P49K`>3C9M|(3fRV#C zH0r6(yY`gjooZdtcW?Z}ffIIyGrK-p0BnI1Smopd+Wrq)oWo29Ffg2$p ziRCct(OQ59;B@;o;z7~RU7x5(U8o8zX(3`g;=uLdbBzaxOhCjuO+14-6hD9draoG$ zz>DM~7@!eQufp~1T2(sKFF&cgi;lRpaR~Q(ViRWEW`=Xu8j53Rp z))E#;?kKQXa(`OhNdJN40Y|{;fl$d@Z@mhI_CM+jUqKD<`G#A@g}5#-KmeE3BUNe} zNit65eJE&euqgXLN}I=~`hai8ic@f)Mj};wbdx`a_PpvoqQ~ztY=eepmB=e7^D&k0 z9lwjOclu?`y*?{{Z*LjForq)$9p>Ynsf1G1yUnv)QZ&g+XOE!$X*TTUTXnU;4Y`Kf zMIvEwR<)+Ut98B$YjJq+>9%80n<69#Oz!wO(n8aW$Pz0Jg6uWFcb%9S_CMT-S=6&5L zNr2#&CbDd&tO8u`>s|m|&OX<|fU;ZT7X}^SI8J(v4L~U?Atfz^O+u;U_8(R}!ciWd z@oE4Iy;BQyk48lp3Pz*_!-B=q5e>1ra-uS)nL;V!YQ!X28DQ6zy8+6Et{0-tTNwqs zuE@o6&dN?;s}Ts4qIT9~z0&_(^7uwF-GO-LR$O@XpDyFUNY1 z6?`@Xl7`N4aK6mndZ1`g#p?VwMMfy1zTrt*j3&s4YRS)Z(Y>Ka!aTo-r9O2MiSkyW z!bVE6i3tZy^}rSPN z@=^E}1Z&aXRA0H$4*UE>>7*PJy-^Y(&6)Pb1!5x8;orNn$n#d0f=*>K7_=M|osHap z0w4XnG%;Ual!h~%XV32;G*?|>dAb`iUW?Ff>NB-CZ9DH20iCZ6wNDbesxtWH#S{g) zp1_l$d&D&lamTYJmZ!;jOb3eRoylPe@w*LTIvQnNMmyqcN`{`4lP`kIQ3mf9_+fl%&BBXB|4uybus` zPkiZ`wWEMNVsE_5Q)HME#MTWB%wEdV&J(D#_?RK)O+CgpD*MK~F5 zQPN9}j;|D*fh1U~;&u&w?NSnf&CDC&Xq`FjP)?E?dB&6w>KKvY^WJaXDO{;eAajl1 z#*$5H zNB&-V6N#HRm?e1N^(ksek9S1N{uMb=7hvVdjG_PpJUv}`nt`YW6f#FvpWDOM;zFGS zH%wIk1wWKdxY2d6Y(;*lQdsb1Ke{E`_a{Vk#+d;7Yme->eEEigM#lyI&i$4O3}ujo zV~8LM8u+>wS1wos1(VmbFxcgq{Es34)TUqZ%yC-77>Y3kP4^od9g`zGv4Czvga1fb zfEc!EYjRyHz41Td^AHT<;WzSY-o)OC@}hJC|4!lzcQ@VU3HQKO$bGKh@@nWq_+X+= z>BckuZ);~+xW`%ZKR+>KVGMeAa7>f6SbF8i3@Y5*UIfDE&ru*sLjo$5;X+8=@smb?lJafoidCN>XK;g0MK{v4>?JRB%z>0N!e>alZj1zh96fg zFfFf@bFF8GfhRP6{52qibnixgC5_R?5R4%4GI&Aevq{WouhcDW!#h9o${$oIP5Gjj zdk`PnA%=&~6p0ZD60s~@abhkAi8*|FC+^B@|@T zHSM%QE-XnF6?#p>1Lsm@92yMqy^j7a9Sd21%nLtGn|1d-`f<8UMsMJ=vI1IB$e`WE z)4w2zh_Ue)4X5-UN_pio-IFz|5bXx{B1^e4W{OPjq?cJWBo+A*NobPFRI(d}=ut8N z#-}!KIe42vuBG!ekn~Uftf_y;c-w#m2zY5vQoYzZl#{J7OY`dbjVX#0t_(Oun>rty z!W{k2n$@b>Mk;U9e1uIpOuxxc)P`Tr5&${v!!_Sa|!kAWN>pFV4tV( z;A8ToNpzF`;GMrcWd2hIGGJm%GNU+t40k0853nwEjqmf`2YQZ<~RnO-eaYlZ#dS@SRoO{j~#x;!hlh~d!nw#S<;sD=$D!X2?qG_Kk8{> z%CHh{M|D`eo}Rbc-p@I4dnhTuy0RHSm6Y&cB|2fL_n;{ppMvFKq^gi?+XWY5WE_c*8pSmL$Ts@UI)Ad z-wy6e30_p_Hxh-r?OnlcJBGl(3h)o#45F!HSSaIo9`!3yoxOwz0)UP^#YJnPFD8LH z-oU6*34JDpNlX8=9}#d4m5@k&uZbjr7j0Y?SFd}wbi>{5V8RHI)D^eS$LqnlK7#N;RXG_RV)Q1aA481(|(Np9K?s0?9o6R-r#N zn)kCh$OUQ}BKIBn@grgQOuWD#y!{`6BjHk9qQI_BbTMs3=enlg{SeX+n1Z&>;DI!# zBy2;&5`_x{;*k;P+dkUB`Znu~b1LahpF2&KSEiPM7E+llx_qyAGQPRzHlpQ(?{naD z>hq@fks)q=YY6U2(LB-5wLgLVIO6D7Zf9=6Ag!df2~@Z?F_^%$?7lbyjMNLyp-f}v9D4! zhl0X=PBG-3Ko{1?+qGd-PJz^22Z0r_?r*&L4%X4fyNaF2k-zrdfG;pv%NuapV!4DK!!n8`T1+@@>z~ z;^30E=_R|*De*1`wYi#$VS{9wumv< zDcMrUWtwCj=OM(^$K&uunIS+04zNH0=IEV>7XH+KpyCE2NDA|O0a|9pAt1RDRsxv7 zNpz-$??U&}3FOwmGPUE7bN*vmvDw*0q5_(1*sFn!YcciS`!8Ae9Kipio(u8xsC+=> zL&n&_5WHS_&v=`_1t!3I)U>iG)q@tNEB2+9v`Tud)y7uawZcH8+yYdySOW(9Ds7gS z?`i9jI13nxdMDne{@~$p&PEr4MF4!P6cM0*$vcd3gaJggSLSc*DJ(Pr4M4}-@D1i3 zg=9sj1peUY;RD2vZk^JSl(1OC zI)bt~NPz7PIeacOl6FWqqcq18r;KO4J0MJ%>JDd{D4EJvYGt0cN-zZ88v}aK z@7eDps+n}5`_#F={|ygE+ZS8+>ozQi-`y-z6tBFPTl=7Sqfy}ntR;Z#lu~e{*+o!a zQ%jiqzi$Bqvx$gC0putdvC0XxXiGPJ+BMi#9R$f-qPi6$Ko#tTOPD$(YORa`%e4r7 zup9&>uI#5)14-FB_pSGuaH6b?AzUCONpR;^2KTCe;))g<7Pkv@l zJF1K?a&gnQ^(rxiA=u5105@(nH|l2;`$(m4R;Mg{16snD!{zbyF?MmA&RG#KBkG57 z+vgxYufq%exdrUkuK*d4VA5;)lx6fph=w_HGLNN+1I#SO^^S%7mltZ=?z{tDQ+Cqi z69B;pJwo!9eCvx~!8J&z!ITuxYucIM(h+$T5#cK4!|K|73A9NA$)NqcNH5Lr^mchL zOzQn4cJ+kza*h`j2^9ggP8T-lVzk!kPn&K%Gk=4qXn8%TUntwKU%0%59(2Z!kNg3S zEq18}qe`+iM=-lkps6;>fUAH7;4Vn=g^Rfxe8In$#JmXJgYZy}0;HSj;zFT=)ntTB z<>G}n_;4^a!Q>X)VI5xDbo^tYkpM^j6M_Vm{hHBiI1+@e|2sB34!ISmbnY^~(XDa-zu3T|7bHs&~Bsg=5MGVb~SA2DtzzY|`OgFYk=fHKmK;u8{$Cm)X|` z2?4>_?@av391dLHsay^@AENA!#!5iVb*jmFiEbT~;fcE1+D*Q(QBxF@;1vET> zQhGn? z>ZIyaB_uP`B~xL8lZW(0Qg=WjUNEY*)?{HTS3i7Nns_ z)1eB4R>~F^SBFAk&zZj)XF(K1OPDbAkgKl|Wq6w;1mopF6%5$9))&ht zp;m(s?$$7}(ionghw8~8uKPH0_ZAyRsF?o{$&ixX==8BJIlDgQqI>qE+B(1M`zorJ z)?q*r0n(AZVU6feZ(h$#zG(`-??b)n2l@vbwV9d3XLb>&uG}z^0Ca_mDt}W6pt$SZ zgbFN4-E2x*(v})KV(I4|$gRiTlfctvbEtcO!x#&XsMhx0=>Y!)m$o*$nL9Uo03X#M z{-%Y5_9FezXeO3WV38_asKXSFT@-rVFoV_>t(8lhv6LTM3@jB_eV(t3D1s8JV}rc9 zK`eIWJw7%Ok!G=P*qTh9S0b2d`}sr z_rWp3o+t)}J!}sNm2Oz60 zxBzcOz_#N&K_$TOBB9$~Or8kA^x6d-D=zT>42C$CtS6&8*MI;6<7+h&nn=s`6e@wT zVFXUzLafe04wU0lXUcIVZz_|F8xV7s8LdcQ=ckD<`NCa#{#uCd4n(9)KV8(wEGvNu z00ipEadp5DoB-e&A^#9Gm2p3nm{2Ny0Oow>a>j;_51{TErGPpLwu1Z4U0|hZn1&uM zknAIk!d1V}119b))!>#c5`-uC?n%wWX^M4`uhS4caZ{boq2kXIFUTR-I55Mei-3zP-(l60I1<6?nW>V%uvbVjwa$-T=Mb}&EK5wLOiR|M`cpI!#f{#0xW zWXyj(wGs|HwG;sCk#97rPG|Bbh-2AGMu07)ApWo>=QCUG37@Nqc^>gw;v(=SS4yMd zpc7JXtNfu(3abWz6g)Maz!&0&Jte!;r*_O1W|7yGR$I z`*&4vO~cco%y?iuR7m<7lxbpL24-6w3tUm*(vC2$?EXj;QXXHPRvfb1X_RuTIXOhk z3U|K!6tiKy;yQ*IOk6G{#+rc^0UzxU-Tnbr*$qb8J6#NZdixBP<(PdnUuEMt-+FCk zh=i?e-omFdsW;qisj0eZW4_e7Me7y~8p|t(d;Ptlk6YN5EbEM2N0aLBcaeC!$NIr?#9EmfenFp>;VRbCOMS)p& zOt4N*SItjz{DA@zVt}gU@Q^+X+xteX%@V+h8OjP)o_j;#xX52HaL&#Zlyv5ALY<&c zz*-`4H{eo?(EL0EkU#T{lmMXGIXESNyS9Bl2!_RfEx30-t;oK8KdZ;pdi0wLCR ztjE&^svP&nY=ERE_eck*)kLDGtRdAw{Ziozbi#|;N;txFRQ{Q`r8{7eSNrGH(=xfN zrgwCbZf;O0Bf76%-}T-5s+kQI&!Gi|()o?>ikF%d_KS=W+wzc@rF?r80v4+VM&0B0@wus%gfBA+=EQJ1?W33+!0{7%LwU z>D{^Fd2k zh7BtF_nHL5J3@;lTV@8Za~9uCjjeV4^G@sAV~c*32w&n_NPCJqROnO{h0qXFU*GzX zvYEly3D*E7qrZ1CU-aKK&Ds&rv2l=Sjvwd=ZUjJZ-rLWWs~xV}X;W{4rRx$8J4xmj z9iE$Pg5ZHRM%o*`vEZE=6AbH&k%_Yj26LkX_;+;eLrpyPaMm>is*dicW|<<{6;V_s z<7sFX>$*1DRS59Y2e!Ua96|Cd=A1>R<{rsw10zhhjhFY~V9JndG}^sEK;G+LhEg~8 zE8R7$JUV`CJ%a!z{r?llKGrO|;!3h)S~nLJ_^855a|r622RhYxfA4wqGNlQ^nusJy zEaH^5O!QFDA0*;tYots<@mso=enlmEIq0j>??g+`N`FcS%Xl0{8%cR?0Yn z;VQP_wQ%yT^m;FXKV_*VQ>+i3kb=nb3~w!&u(PG27RiGGc2L&ZBpU+sYueQ2>jB~Q z#qK*Ox6_C&WmqKTbR4V!pJ5HnJHp1Vgnk4z@Bs^9^vNs&z+re>*UQw;GGx#aYTR~Yj3FBcllfbrN68id7*tnga(hy@foI(=LD3Qj>L!G&>y zjf%2#6WimMj3!jcWY?w_osk>he=xwnL790%q$;t9VS~JhS+s-N9xp9Wk+-5(I*Jq< z)#bKe&^I!xjpnc)OKPo++rwt+JIyYOcyvhz^dr)g(;%@A3}MXd&N+L3;^YFLD)v+t z3cSi%+tp<7Dr)a|7N4}J?^1y>A6&#zOflEd8QE_oZ#I2DM@06mGS9lyuWS9z$O z-DN4iSDFW}8OSjsawE>k5V9i!$)YEUIx!6| zHc2~&63=ACrL~7HfoV$r5cr`+@=jltB}oNlMeZN9>M(;8e(vfQ@*x21qHmPMlS^xY zL~a^$4-;lkf#rUy&vM8NZ^LDNuth5~(iZ$^+&fOBR~^03|LcQ#d`6}md97Ckk)M&x zo1}gY^0rerfjYsuD_YwGXdW3p_Gt;00)k#3OY!i z_^nkys1-kpp_T4CH; z3lIW4eofp>eQNm@eJ9XNL@Q@8hr7Omw=IsD+yx*G2cfGA3L4ul9ZQJqpedbHeK^}b zz$O$nmeV~%|2|rgt`QMmG{AwqO6$Z0Vp+~i+!D^E;RguC-m&v?{DA*j^#pDxzK#ZS z8Bd%nkx~;;7$$4S4df))tp_)jGaU-m99L2_r3Hm~2-Is{HmzNbBj4>Pf)WC|IIj9I z=|AZWPz{p=EJL0q$X-i;L0Z*8-4xfuGGtc~iZxZVY=4i=t>#Ay4j@_nOZ~<1_l1f# z>}5Xlkz?R7qiD0okX>8oT1ZCnR?@P7*a#zQ)&E9r0Y+(p-5fShp1eS#rc@D6h&9w$ z;5cw}!qtu_l`^a%yAovb9>%zfb_!p-KBnHI6ujM2!Ze56W#fkn0d52B%93lF0=pB1 za&qxYB(pZ}N>D#w%uR=uE)P4kC^q3vXf5vua4YL-();B>^~1Fv;&kMjKW>eq-Z$Zt z5{-ax{&nkLVsARk7G zE=cJ`hoZ-S3UhvVfH3l8oOD)1aV~@7eYctvlH@ufJ@}74;u};?W5OKq5 z>L_l6wgW%Ascr`)f`ZK>87Q#_tie!0heEj(iP*bp8fswX88S%A z`t1jj!u}q&(w3JC#$FUdVDN!B3B#9gq3&Jf_r+<_EJCOJo@2+iFY9|Vzc}lbycvHt zap-F?`yFCpS~;i?TEugK-r|j#Q(&Bch2M~2V$2L0oW{WRJz4`VM7nlpuqmg(M-P(9P_@da zq)ry!=os!*v8f??+h*_t?TRH^R(6l{Iogp1=GWkRM%?vilicFk8~laKfi({)P?_jT zKyLs5D~2_3#!W*o*h|O-TMqC%s?6RpMo_`W&a&IlVSOOP3?BJJg_UHUBFq_;`=NwV z)H)DdaJSh2vG`|I$UwKBnr=;C|WU=Cj0& z0Y%_7>ff`-nXZkma%Env!ubt=6RwRyZ%^yyq9ABVJPT+-Akg!xnCm?GkZCC~x85wF z+Gk`9XM-)Srq!7O!Y`avu|Tv;hhXEF5BzUjqX5#qM5U4V;5_IazYD>wC#%lCZ^bgo zAH8ar+AOxZ8mSpnfEDj-o3|$jVMt{l+V-bpK$mOTys#{xtL0<{W=f&D5A@0JgEd7E zxcQw&QzUZn;41`Uv+@jHD$3B~j9R4%^BkoMZk{sHS=W{y z{Z~;KINoGvfV2pZMc$GU8r5SjV*9?7155&eakv65TO^YhD>tpa6^{b5$TJQ&L5O)U z>5>a;vG;k|IroxZs0Kxs2W?G(x(ed6Nd@Uec{VfalaVrHpq=^8G3*knE7^U5md4a~ z;|u#ghe77*q{F$xwjrR+D{IEmyM-taw4y%r>=^;yC*6rf4~mfWj9%lPg2@}3&edSY zIkTV52Ql_bdk3=4Yl8hQg5t>yX6ksPO6v?%!?g#8$a5y1q8kK{zM#rAZG^_-{H}nziN;56l zO$XI32fT`cWDY8vo?Vpw1uX#-{u!>y|O*{yoeMRNKHvnyd&zhW+PiV=}qs8q?!#Onu|0 zDkWa}+ej}n<>+915Wg3z;;m)0W`5LP)iI@J<yFSEx`mKT<#h*lmiz*uXrb? zRHx_F6+>#c-#t8)U==b)O5vgayy^JKHima#4O>Y87Vn)v<6tJ@>FLml4-wH|reBD| z>f+uQB^CFBKumuiV3XA;wou-{E2J}^(0b4{*>C^eZI?lB5N`Wkhm`>TtI~@+@vP+$ zZcxoq^eqv>t3Z>zF{I&|J)pV9fQ zuSIW5dl^5#8i|qd1uak&ehZZMMrLF8&La~F1X%h~LK)O6&&hWMp24NFtUJyS|ECR5 zB~K{O6fjEKT3`_FVXkFx=4}QTcqH=BI{ET;%4g(ioreb0Yi0xS8S?61?g@OAic0Pt zgw}y?9vj4LKJY=>+JH$n988n_=sZBu8E@^c*5|woumD=~@Hi%Mkx1)dvlVbjdK?I5 z3{u~Z1O=kuIkmg4q4Rb&FD`=mpmyD?nl{q$7`9Wae1aO|QsX=*oLxwRUH!H@yb;Ev$50E9a3kuU6N zeQiL3(eSraoIEkW$t>Wc6i-~OL}){R-alurRh^fZvxpxCiERsvHR-4iR&r;X8o+No zKm}Ko?NKDMo%P9mZQ}PBAw-ZO2`>jNVkwF^V#XEnfG;%wsB5Ugr+rZ9UiV9mf1NRy zKj!jSe)1GDv3mTfDiVz3Dk-NfgfuS_Ybw+rkHjJ9{RuNHnP5|mmgu&1Am8l>Abo)S zUyK5N-gEJUCj~Wq%8rc^X75zDi{%mM|q%Eoko|NTvXS9RguJuYB^qmWSk4$i^~0oY$|qnn8pR=@TN` zEg2Ol9(O9woz8Qtji#ne94NSUuJhx*WXKl&9li1q3M-FM+9EJBVgTHFOQXsK$Et)L@axQ4kYy^9yCGU1yxK z&nVH#{sZ7PD#5#Z!KnP=J=e&@H&q|8<`bh2y2bB?Ob`q8patV(6%N8@a(eXEsQgokv-&rePI)TX6(|HZw)eKifY&t z&z<_Y=td_+R7PPjGFLrS#8e54Ki;GTNSF@i)|L%fzyaZBnR*RYK400{KF@A0xd zmfpNWY9(PHrTcL24n^@G5rV&dfX;^7-e^-ppF0NLoqY8ebU>jwndad8>eE_Au7;^n zh&ZR{9LVdZi~Z_;j4mi>1VXy++x}ap+O{pRn;vbRF6YRT^r+eToBHayjC7u8~ z&~gaVcix-ap|?#ea*`M~EKAHfxWCgO#8;8x@vMDzVijc%(z-!5OJ6!~FgDgBX5}gK z4?&A&jq+4$E0!=-@eL6H&jE`l=-9y;*_AfTsWkzaNk6w^qp9|cy48V52IEtjB!_Ke z{5+8Xj@i#DIVrUdm(E%gv|gQw9yX?8iE8qbMiv`mJeSPJJ$>+t^wKKPdcu2 zh(I13hzR2V%!E+X-rjBYH%z~qyI(ovOTOuf0aY(qqD3XwhL`4Ho=@TbP}tnl6O+Vr zQrT||(H7R%P-o+Oh54r-Eg^J0;kJK{4xS;GhPPAN#0eabG9R4hzL+tXV;G}e9&`4RVW~Lg5~(~!Z0~O*|TzP z)Y8yt@u85(E1F?^%m@KHAYQi(gGwkY!v^3*g9wgxPqu;zalk$ys4Br8?Q}W?dc61q zyW)zH{;lWDohjT8y!)!E4tp}9i@e~kFRgWOI!c1k@Zrr* z0#6+M%Y7!BI&&a{Ru?aqpTIF-b>`ENq^Gt;a0!zJ<_el+H7EFxdm_>sPS|Atyu1YU z7AS^NZV{1@we~d9*t_)iy+EPsKG@MZ(R3i=Q%sd?I@%wy$H5uBbUbuOes%W}Ch|gO z{_H)vm4jpGk@7)Wc^?B5EQcZW)&JSQ|DhkHPl{8qP+H{^d;XXPHc3f8BwnHbsz5mR z2p7i*1CbiYdXY&tVnd%7Rp04JK{<)ul1@D%7+_<{4!^C6rdRLo%WptD}P4h4V_ zOCW}oN13Q0ysfTf>;#tJ++Na)|0!&nL9!)BuA~ogUZndk@zQFYsCamfS8}>W2JR30znmrE zLz;lhY0V}T1fQ^IjZlKpTo_sz~(m4K9mA#)4i0e(Wz}|W;nFb4Kv61piz%? zij|35#-cO`-2+N0FW|qqZxz_euP+`S8aM}M3IDqZAoug03Ak6@PO66RzlQtQu%Z2C z{6*@yiiG<-5FDw9b-sp^egQG}k4A6{BTRHF@)Pk#NuQ1T-mO^ihTE zUddT`5>?qXFWj-Fv_xet(<4+Eas7a3-R)_+ z`^vH{t+9}Hu0oR+8Bx9Fvih`FQ=3meI7{5QB)!_umX&*)(3sHex(iM?pQDf&KJ$CW z348;9*DhoVL)n&EI&eLb#JuC!@s~SlDie?~r-Z+86~NUjif0>|2Zoqus0PQ`7dWg25_ThAF4jF6wuY29-;K zEn(yvXqnx*5T>h+_#q>R@L6bJY!_bn>4fVfxW5szuSfACPT0lWVbHa3k8_*_NmwI< zNSM=u!}bX-_4uHy+pOe1p#;N057W;DI^lcElM*)<^YrIAz5FQ8%ipWzAy{J z{cckAXaP)(7s&Btw#+HGBvk6fbm2W4pnkgTh$W1xUi}I)JRq?_#LG#993AbPYZZ1mR>0}yuV#m3#V5yB0xhY6f>}eoi!`_#Ka**wADAS3hG4blYO- zbOVAloIIL#mD}_#SA->zl_;?cQj`7~S-6#xY9R&-E_UEvQ|K|L3OPs60qn1`n3Q*7 z>_Q%#aB92_7^0AEx%Egl#9WogQhFfHp5f+D6nr5-uB&=U5P1$`346*KNpXR;M`8hU z0s_4MA{dV(D8S>@*HFq&qZhdP<+Pg>0_sAq+eW(t#a)_ep%efsk$lQFVtK0J()x&c^-bJxp3VrZRg89a z8F}-ld+k)Vyt&1((VM$jo5fqXW#&8^R6a!UVhsY%Y@6a=q(D}de@?k`sIT4Jl z5AZ>Yg*r6g)AbgIv&Y+LQFVkKcT#iINpQKFSaut_0=Q}#%+AG8k>s{yb%Qfa6=*1APN>x+#Yr|*4n3#A!D6`jLu? zLpBruzV-1o#pQ$i7$u>AQeTzFu?H~PJHPV45FGxzJB74{0=H)+1D{HTJRc3FCqkI{ zX^d`KbWD+ytfAo@P7l970VD!RERS_7Ms)($xPPe?HP2WJpyj~`pdw%D`iUpay$zv+rw<@K`&Et6`vabSYu~i3Gs>Iyi0GxohwZnKX z{R!e&t6?;t9!6g>%zN-F6BBv^y-&_*o|TMQ93$+-c${00Vob#1>zS>iSKVj?TLAd< zuqm`JQje@PZ)nXG0Daf)O}IgvI;E6Yf&mF^`+Iz0Q9lzM4Iz(f1M9DgR~~qXZ`G*V z{lv(jt(Q4Fesdt8DFv_}6726@Y0ex8V%FzC?xZwx=}h3S##++er=xm^!=V^ESPNPX zYnONNdXgHI3cun6#}reXaDw=1fs=$au`H8Gq)o{B8cCGydZYSTTeVr!*8%^h6-J-Y z=8vg4^s1u7y?^8>a?j&Ir=k?O7#M(?s!4*@I*}gq(1M-$oh^GKB{7-; z`D>8?8k&5aHru)ai0#VBjh>ZA&i;oD@3zt`(26wXE;rmNWn1CS+3;V9g{GuaHp zan64{Mc`u9>)5vbr+f->bzz;^F=9j)({xxo5q5_|~)-1v_Bw31=;UauaJv zC2E~onJ{X$GKinS7FKa#=WbLx$YitViod1F3}a{05c@$JN$tENAhOt-b$7E!ZWBUh z8lp4mC=3s((4FO5(lD~eTen`Fd(;^u>;es&3$x<}6p=+9c>;#_S!7+oww#&B^}r`q%g!=LfG{;znuIF}eL#xuD_d;Z35h^dAP+@g51K}_&_fZ^ zy%WX5sZfyO)0FM#36~T`+Rl@Pv=zkErw_BwOEaNl0p5O8&ST-+4-_TmwO`Nia2w8m~9ok-H;5S9Y{z=`UdPVvb5$419HFaFKA zt4rocLoe`hgN8IVUrBf2)kUK9ejjBu-bk`hoipSy10gpzO#Kotz+FcNttIY*onfla z&GY!l|4}r34I5Hes1-mE12S(}N0baWT2$ehwPkexrDMLRT)DH)n^$^(SNl*azLb-j zjc#dLRKI;NX+zN4L<{%~Zx{4raU8~GFaGx8Oj_Pz$FQ_3S!9V!0&OFJ?b3Ef2IJ?X z;NucQwVx>T8RY;-U>t1!y^5;Z<4%<^nVYG}iG$2={CAjJOcS~J&o4l&ZGQm?DR8$& zAY$kfF>ZGvTQeax;R6W5B_odCtkx{U7+w4&%mk&&W$^VUIY8uZ*&Y`HqOw;~EbBzO zfDNAW6VW_?80E|_t`I8-Aw>IN00rpDiCO{}8446q!!;OxJw-)-@b{`k8=`gWu0_BC zAXexJ+BFB^g)F*bOAbVroqcrjB0)^`k7zvs7;q^GlV~*vWZbA0w9yjyriV!Hb#uxN0BzmSZcuSy!s3|d`2lIZZVD}V! zscB5lCZqi>Dk6L^pbi)Op(mOs7#s6xTJW&Ba?XtkYXxrcT)499*?K_{M_g#6naFgk z8lUZA5eaIYikU`>^M#;WcN8AxwS|Eev7ShaKAR^C28t!GLBzPpA8midabiuglWO5^ z4@Y1my^IoQ2sW^1bqZ{$qzyPvSVpY>7EpOJd*3W}3_J;fim)!e@vjg7ZAv2avGhKP z%LBdsao@xmx{@1O>|kY<)I#aEC3EPdQ>Wl&WRAYtGK(~}h$w-+ELdsJFrN_kZ16&c zwQ-kdE!Xg63Z=hwU`{7SA>h{MB$M3K&qr(4ScAc{vH;bUXB=Q}dQ1kGRK*4Gyc2Pp z-K!UQ9au0L3x@{~)fs-@A$Xuo&vfAlnEWElc^r|(UPSJUpDu$(M^))zOhaC8R(*m4 zNx4PmD}hwWIsRBcrEHkrIy@NE|GTb7DsVekAl4C3aIUr2B}7<(zA@hc&;z9j1nxNc zlRs9Z6hetvpV%^ArH8wTvkh}`jjkv-UO^k_8*5ExXJGOlv)Z7FZ&$2UUXcLD{+;QEs8=zD}-g6HbX|a)7Dk= z=eMr%wPAM^(tBB)KAB)8a+)ehUY=Iyc!XU2DJv=wXcZT`1TV4OLZwK%7!WnaK(T>v zuH8T|J=2if(aW$qjfJjvE4h$~w}NJQMx%~?qG%YKh8ZxXYu(`J##Vd#LtMBH*+A9) zw_A$(vQm8%98#uO0-z+ovlH!$ivs@2PA0!9%s7WpbRzr-cLIek2xJxW-p^*RlsgcM z^^reS$Bo^Z%rC0321qPNR3B;?8;s@Ye0Hwtlr<;#x}nV=D-PpijYhhM_6V0rGED-z zlsDOZtO%79Q&K0BD&kq4+e-iNEgxw!v#~7>8Kjti)wST#daNL}_)7svI>+^)10&YB z1kI_uW!Y1YN_T?s3pN6BVOX-_)^uitqHnk0G>w_COh)1lAmA8QZQp*RWzA&aI%Tma zQ@3J|%cga~V*-U+;=Z~iXvQT;@``n8<|mE{z3>2PuuH*WKR`x8R5xS4xI5sVBk#&q z_cU>_l3*E&ZrukjLt+gk{9UX$B3i2qt*f6QM7zHneE$X(@$eTd_yj)|w@eSf@2>SV zpmeP*h;bz>tsRhGzV~Hw6^h?x)Nbd5em4P9Bx#FKmV)kxsA|H{&fLsO&3V_P-ej3@ zeP2EoJqY5IoSc!Gpuwpt zYoANCfEQvgWc~WoPZ~Vo>e$%~FEV&KS?cMCs;TpI)Mv!SAu?^Pzw_ZMZ>BAywKkSgTflrQ0dlj#U3L<5I~LV)8*aIuEGzCmzhUUm76>> z8at@8Qg6$S?>)z{^JzeqZSVs6dvAp#j*p7#=gNlItDFaf{1iRPO0Boz=ZTWCgIX`j3I<1y#JqxjhA^cBnlKP~35Bsn&YBjiV~ zSjdosg`AdD&4BOd0`i*lhoQQ<4uEukB5#24oyV&YFl)y_q&_Jxe+$vMS=e$LwCOlQkidfeoOH6CkOZ?3y~Pt0WI^Uy(kxAYMSeV{jr$1R9$aE< zA5(y;?TO0o-%^mv6sIEzW~%Z;gv@|hwyFi5dC+b}?&_PWLh(pI`SS1sDjQ{M9}@8} z{}1RAvnW17K+?JJhveNUd(S?I2Ozs^I`efp;&sf7gq2VJzV!KHEG(Cw$ZGk)k;8ls zjeaKNX{T`zFVIKvGLiLQL^#M0zHCRM&!;M!y2rr<-@a4sn+{CPKH~p zkmcRDwxnYA`T7(-_dW1&E&{aYySPOpxAxdKP~%a#Qq9Ojq~eKcj_rX2E;`X`=gF5o!7#8u^GL)TQk1ucvd>x6}OimGJGz zcZ!Z&TKt8F`FBt|yyTOZ>@avXf7uT?YuDX4I{P+DV*U+V=ZCJHek&~LP?iZ$E%Rne z(QyFP^(zOwpOKDKNd{edT%S6=c>$C;+kD)AKjem&3yRUpz@!Fh^aheFRdhGo!@Z)V zt}RqhBw*u5bw+BYK(&$ssenIdJ`7_#pJw5IO8pKuEygQCw~nQfc9;?T;A$_SiQvg8 zxXKJXog|Q8r-QGfd=Sw9Xn)Q#r73B zG@7xsN94h@pr(2+JMqfQlUDaJ^p@(LgHiO%jDy|bu$6?eDLMnzw8%8NjFo~gqT?i0 zumV_}+?lCZFIB^=E%#qM~T>I@neKRx!C1*-!vm zbRLN2{t%im7%M_5PG$ljKIvao{WVLB+Lb~e=)hk5`JAFyMZ%GElxi^;L#8t4V#oy) zf9ITX&%V}xXNWMAaz=J~l`Vi@2;=udEtV21z1`wWcPMtw;V``$cpz06n6l6(U;w0% zL+5b7z zACO0m{dy)J%^AbJzF1;ZgZ5ys z*#Y+QKIuVxDP2te>ZJC7qcV^a+EHgcZAMwr% z>bZav!l(7J?Uy&ArE>x8Xgbvqp&5j(ACAY9fV*gS^VqDjRW^&We!7vfWt2bC89td49R;t2W5+2+x2LHyCAtNS~$jo z?3mlYfB*pZ^q*HkG1sQ$zeBY>imhLDLKOtua!x z@>q~@=(PYG=*z2G6nY2!<3C#dem}WRK#GwhQ{O}TDVX#gPPp5BsMD_rrF1=#SB+otjNe! zQFb|&^Xlt)G?5{!x{$PqW*P_A%&f~rsvi?ql3?C}dCg#5kRG`Oo z!>W7Qqf|(^f0a+W`xqRdWcU{Nr@lreA(8IIwTIrUBwYnSEB-8@!E3<`a&@bD);+wB&`N+#({gFH)Nsf9kptwltA0dji9wGCTCm!;M$J2US4``2m)G$w?B zSzDokV2vNv`6tT?XFeC_*(H%`c8bx0g=&2W!Xj$_FMw*+*!tJRvvo9QVJ7JAy4?j( zG{-NiO_57J7QRoRSPCeEO6a-KYbwsmHQp9ED7vj%q z8Qs@;B~>O2+$S=9tGpnge0VfB81u-HlP7^Q0!1Aj3L9;kZK1iD_{TxZQGYUp+84ET zCT_T3A+)@1Z+82SIMQ}Ni;N#;A$Wm;dHHe8uWf4nUpWQT62SV!XD<{Hf+cFxppqnB zIf499si86Fh3iBT1jmF=jVT}u70YYt@N-e57-t;rB3>gw@e|D;3s$xOP_u{rE)Je3 z_A`|l@e3i{eUC-#JVzUE5i}|LX?z<9Wi{a6VSm%XM7jaTO-Zr;|GMSnS`vAS#&Jcr zMLVZ|pdH;5Aylw6Lt3TJco=W5+cWEuTBTer_p-I0EmFhu$t58w9Wea9%kKc4gYSzJhy=1}ptW0H~}*6IUy!gKucNu|Op!V83X zPn%Ey%@!#53Z!-H26RMHP2uO)D}?=nN(F7WRlaT2H#V_j?P(509}VeA@(>TLQPO(} z5*zM9AqNSsT44tySaBqE$ntLmWQ#K*c45DXo*G1`bY~@Q56Rg*T;*3>d>@hQjvbK z>v0lUi=7=qM+po*?FcJ(V5|2O2YNJ?iJ2In{_eLgAN7}Aqp$cT>85cP`O_g!hnyJs z;%2my9_Q(*LoFT&V6@|X?nZ5+zLoMpJojez3AuB*GgQiK)YEe#HXp74ZtzS&_D2Q^ z5CIn)yJ#}}b`?ie1qy&@fI9x}5#R|pR5|o9lE>sO+%$FJ33PVbQ$=U=O(BD=a55qG zs91$)?+rUf{X`=geg0tgY}&*ZRO!T}E&tjeE|yW*5mQb-SGtYE8IDJ9S_itaPN7*wlC+hep0FBE7t%Y%Xv8TrfFtPMjZCYGJ#xG=Z= zzm9cdtQa&=neo~|Z9|pm#O!PYHu;uf4^LdAE|IA|*tvhjr_ahEr#Yfj=!*!EMLq&3 z*Btnex%cFJT&q+S*Btyrd<36?W8#qpxktJjYZ{J*uJkE1Uk1CFQj(KixpilRB4CAG zr2SQt)CUmpIwzA7(X0&Mo$&9 zGGw=_DpI|?4i_#N?eTYwhjKhFwX4YSOcrWQ>8MX9C*^wvO1X2dqD<>b0K~y>KL`M* zTMqN|TAlxeJP(<*;rQPUOm-85<{Pb9Y-G-88T*&C~ zIfe@JP|+tdh0;(&D_@%oMV%|5U~~S}PxnT@#GZ3P3)%zWf05#>KPwOEj-5u5;KW;6 zNJbwM6D1LGBXUU>4}V|%wJIzAKH^H@EKiB;hmAFycC{TwRf`{$KSM-1$vEuODoT%4 zZZ~%Oo$>e~Heo5duU;6UQ(lF8KJqzCG63-{=>HGM6SxnOt`lmKel+`dEb&OKGqB&H zBc6VkzMU!=L^G-}hS4GP=Z!)2{hv?!7Q%%551A;DOWU)-mpqwW4J&ih+2wdOk2PC4`@d2n=$nv< z`t=S)8fbF)>6)LdQ`f!dp(^TnyN`Bh+YZ<#&$QC*g@kSWJCB(nZG^vmN!XP z;6e8n)^3h%8u35D1TCTL@T_D8X-ud~??h!%8vqBi6tFfciqiE>b9q}`5g~@@OL}gi z0GT%?`F@`+YSc~~ic|j!x-2iI|CVXuXYx@C#N9Ocbo@bljB613x<(^l?tAxe3I`j> zHTEFbZQaN-DcDOsyS_p6PiUf4b=OX^BdZ?1NxPgYEsta84Go9tqv1sB-zL$`QAPI)6Zc8J0lKAO+u3o9678-H(W`u9~2xQ<`Cr181eDN_u!Rdd8?p z7{j#2gg`}j!$ngHIkwRzrg5w!N?>}9Ljd7uVVj>-kU)Ue=n+C{?CL@G@NcWlX+jIo zKZFFHBHd*R)lT{$bB4e%mrJ;DfhAIEzMHIWP##h{=MAOR^9*hw(0Y_j&E_jVyU#zd zBUtw7k(r1?7-3Ri1$$j(^;ck^N#}k8xOxc5;0Ni2))3?owVc*6p5)EQsxP%QUN?U253#XR+fk`uVr%s96RCrI>7x;fOOP=va-EE zeCQa6n~SB#a=KhNo>7)y*KKNWgUuq30p_5pD$2kZdx?-`HpvWyk5U z_t=@Q5GLOvhZuafW)T3=##WFbSlOpjtAqjylK59>M^$e7{N6~5iJa8rj^~vb(q*d} z>DitC=wnxeX;rNJAT?c@Azp={^b%&sL`dQ7lLk55=nqxi?s>s%@D@Voh66$~fPydq zN`2qoDvt+Bp=Gj@fi@3$_-H$(bQzFjAZ-J4zwwFgm?7^o8<=3uDgXK&dz*~V`e@wu z1jyr-dZShN0G{d_8Fp1NsN;TZb$xdSB0_`f=+ka+X(R#{5Lc|NMiQEY^P?hzd9*`m#1J#bc zrxgg-HGt1(^*5vf5QRDfz8DI4B$_>D{p;Lo_Da{z6LjgCPln3P`>Oj6z$5_{E7DZ? z8=2tnAw);`q%$3roaW_155vo#C1rf3IM z`Mq=+`!>BH{i-6Sg}a+@-C{k|T_;j{P@0eV9~{>$(qEdR@L*3BOo*|C(qKW{@shM< zRXPSw66}XPzzwXvB_Z#6y9YudM9hEMLc1S~)*+%nW#Q!%cwJmhco~XLp`w#=y z27NdggB@IoJuJYVp0_T@@vEI{-QNt1Y%##H>01R$T06>~wRWV%P!%vt_*L>3mo{h` z48&2euEf@*wFf=olB`_Ees?x+i8zv`mP{NA>k8#Oc2OAf9XeD+62jqC=8k&n_doOl zN>D%m00EX8^V=m7F!2BcfK~ti75aq;Mvx+w#QRRoIk@Z+w9-CYwEO@(kc2QjIlNT# zAE8-fG98hWL+TyrV?Z+g46gniMW9LnA9;ZSy%^?d8*KWwUkLa|<#PeUhmqY=!XCux zAIV4gpQo0RMcr~U#U{P~&><=FEu6(X!<_Fb%2s6M@{w6M_P8oS4X%-3Sp5+BJIvBd%yW92{elMF}zp`nlr zpE#{!t>Pp5A^08{=sx)`Mp`8E@#OJO5&E114D6_<(sdwlPUsS?;wV?;8U2;tmN(dH zHlWLnO)evP{@M0Qj#CtPoMJlj_HGKz8B@TceqPQ0%lxK3JU(eXwo4>>D~&R{_)@XO zvf;Au>%%K#ewn@~1=^WhGYM&QErJ#0yQdStqxy)fesLPKN-m7fo=i}igg)Y^TQLjT+>32J z1*R3ua<_Ktm3P>Y;jC@ccS6+mD#!! z5uH@Ey6-)L)xyA@p@pJ!hJX8M$loxXuKoYj80(p{f$41z5gG-h-Is*|S)6jFbE=-W zc6;6tO+iCa=l`yFyG5{fY!^?@B8$ZKBe%4xhv+%}Col&lV;%=v?a%lIlxmjk2i3~S zD>PYm;KZf|YAoQV|Ij)s*I|PvQPjnL2>}>g1}PJcQ+$`;FkA8FcL+oT8A_8bwFqh} z{lSHdA4F`G^gCbUk5@ODf4p{+U}UC@a`@pBi_wq(S|6d{iH@0 zbGSg^`a3cdOz7VWgp~jQ;UF@1g{LcMQ$gZKNJZ~kRS+taE>l^Kr*3l!c+$f+xyx%w zD*Z{m()9n4NPe`g03+?g@0o)|r~%{wu0R{|prSGyK(?qyDwgLY*q5u01`=tFse-r( z*cJ;{IR{6Fwmb~;O>!r@+Y#^xP{z^)Nb)OZS-C?b$xfZnD7!&9Dq-xd*o^P_Q4}nYzf)T^mohJTR7I8Vh!{?74T;6>t+O7(F()?Mk_RO;*4Aw}61}*ruz$OU8rj zKl$~`6`Z1E@k2ESFBtPMZ$)}%!zdU^43L>b&iLYp zB{m>_IV49ha}fM8F9~=r+wV4{$()v?wY^Ey6w|?X14x`2CUfm5WH7x$F$L=dz)(o; z5_VzlNd#imI18sPHZ~PghiSA1%3JDL8Zv4b{qmqeWFOHjw%&%rm}1K}Fh7n=1I08$ zQ~4UrUI7Cc`uwFnYqkC71h@7o$1jM1bPmgB??9?XFaooD2cPWMSVn`=%lc3M)YOut znySkCeYy=l-p;bcCa+%an5gg`{8-!&=rJEM4z!G0*3ewHv+I7d3eLcOtvGp9hk>|; z6i?`?l=Fkc(kcBDT@b4T%5q`R!dXrZ;1B-`_xdr-*~4ds|2@^4zJg9tMsvbqHW)Su zE%g!IhzEgR;^e)gn560Q@AePJF{s~Qt3@QFciook+&sW_VnYq>Get)f?2n+urm>bd&Q4`)EeI4I&$5=cA;~PZD;GZ({gmy0+L?f z3ti|JW}eID;z8^R#unk)$uO6@08Wx$$M$E3K$47UD6F&2L)`uLpLO=yHl;JfN0fIu z$W}(?Qz1dG(}U^Fk2-MMIcNKvx$}dp)r{TStY4?pxRCtuR6j$$0po144q}wrcj+oP z2#~QdhrB;!O$kKe;`6ZW0a*5b&iH)_r-Clb21!!{168@4jgMQ2fK zhMUjsn1^@H$qJkMU~UL=2GivMm_iOl08Ps#HNDJzu-ox8mw|YJD0~rN{1(7MIrkA0 zIfa;>H4JJCTUjHeuuM(HPlxbB0WfT&xT0ecStyaCoJ$gXFHao^ZLF+o_72d2&17%` zHTS@RRes-vyI{D?MZC_i4iHA%4n^;AMi(nh;S4Hw(aqjGVKc|>l;Z|+hHnI4)<6(i z8RWNfi1vHwZ`LNj5Vw?xk)%a#NQ~=vY=%&m81TrXNHhYRzk0co!k^*Vp;8QS*p(GC z$^Z+Uhpm+eCNx210@(_q?7RL|lwzH}gHE2+g)n4ktTr;r`g5RBNa~NYe@Fsd6q1(Y zJQ+!Xrk$03>Sc{LcV}+Aq}X$)Iq;$@-0mW3#&cjWoLk3&>kUu3fA###0_0wBNTE1v zy3xnHAqU@lyVv$2SdtL{!R6~~4h?-@ySHatQhE;RUpIL9%{NFxD|bytYagpJ@~Oif zEKsE+3L^+MdA>KNON&Z^Q&x5KG;rgDK}QP!Ca1(PeKQ{QqW2e$682pXy&aMn-vbj+ z=uk@0bWLmp*(S_W$2Voj5%B`l6|6vB&2}lU8bPagQ=r1S)-)C>DL z6m95ey|}D?UWlw#_vyoDzo7j{8xgd6Pcc=APAcKB4fG>K47b9 z#bs0-Nv^=MCy}e&Tg(IeZ-&v98qj83$S0ha<^GC?8G8Kx<3#uAB>U6-B9#k{^tNvP@Z7sL*#uJJ9Rpw3^ZoJ=wX|cnI z*7J~GCW(bLI>rh#_tb$q(u8HnypDKe#cH?)6u_Nf5qQ4V(pm9%3Zfg&d;Gu z;L#U*F(Z$&1~wW1({9`aDFe5`UpFQWo>M-U4LXuWitZ|gg6Of!DKw`YX#fG6;L@aGJks$4T{udy%3ZzT4Pjo_gTE>$UvV>;= z{+w-g;h3||9|@DhJ7wd74ocNyu4cG3H< z5Wnc9Ba~DI|6}IUs8b#D$Dawka*n5QWHF6&?I2=%1OzdxS*!l-jXU2&MA1aN@8qi4 z^y6!7A5kU(FkCR7NW-Cs5T!2w{esIPp<7AiV@n5Dn^7E)#S0Z5f$x4IJ0m5g$;tJ< ziu8f(2nRtz$u^$akJD<$(E!S;OAaNAbOa~9$OX5hF%;N92u?h=;0zCpLvPDwU;OD_ zwK;FW`Dqa;^Q(?YBZWos8o)4ULU7H^lrkm`e{3A@E-p%S-!Mj=;Dy!4Cw-C-W0wy6 zi!>=k(SLjSV_ZS#tsv`Jx_~C%1#H}(hK!@UHKY!`j5!ru@=<_!Je$hL1f(S{o!>8s zNscr|DTbC(05*y#j^#%ee4r+-3GRrE`%$=W(wL!K%|wozB^xj&1UUGpqpXOtx$-&uAH5lw+>vC6{6G{p^2ARmCo5p>zjfuB|8=DQl z<-*p=C9B2#aHoRRl%olrrl2zTn)%qp^PbpOGsXcb<0upqccBL+Z_f+Do@gIO)$d(y z=%qFy<&_-vqe->T-fNx&fE_AG^E26~KcB6#YLaE1Ek%b4W@e+42zX9-9C|17nC+(l zP&t0uUEO}#4Ql13)q+uzx60QmP6zK|koq=i3mIYc)Hy)y?XPe8>q z4Zb={y1-tc=&W=hmit0ZEKON@d(UV#qLp#vVE@ zV|9C`py)gfIi?SH7aarv9|WF3w@!zt{2(E9-lHk#9IbZFtq2jeytu(jT4a}1QiSo; z(EU&+N5ory#wh21|K8*}BS8;9=(=??-~dsOKE3x+@{BMRt~p&%sw6+*iCvrRL>=X2 zM;!Ecu0^<+=*9EJ5REO65=R|z8dMb?87s!zu9x}2`t^IIVnQLbuyRuM08j;hNgVKL zJ~5w_p+m5+XsiSB)anC~$d(5hCXaxIt`V{6Ale#(30Z>M5N6^HfX%X}%Lc*uo82+L z0lmaUowR%`J&-tYM;(A!9SBj_`F$j%pojibGSbhbN)(du6URIPZ$j2$ceJ zPu^exxTU*={yPUH_iZu&rXRNo*o-8on^gWFr6}khoCvt`Bx}#O#vr?$Myd4!8|Ny9 zR>VX3wE;?R1RfPmoew@$@@IR&QT^)p(y~;4*IwkrCmU$eoUDx*Fcoe$D>rL6H(;ja zu#PiLgtQmjmzBu;N0>DLBQ8c9tF8XZF4p?SiV9ff>bqQHBaiZ8Ph4vd z0#~#7Uv&ql-phq7PAgMqGx`Jq?6rF7v-}kSxCkurfMKJbYT7=ufB+wxiom&1riRGX zjcxvkMI(S%9zEI7bx3|B^ya@AG5+yJQGE^jdkxG6IhR}Cu~COR<8>jXI80CHy2di@ z7&vQC(tpsyW)@~!kXyYh2V(FN3T(uGU-gjo(D?TNb_gRZHxOZblOig9G9PZKmXdMX znsTb>41;3wGMdf`_y&EW9uCuIB!Ho`5)1UJ3Ltk4A88vFGl>_z=lbdHWT}yk;NRlPA@9^ zuc*FDikzbE9iXky=}qZEdwmY$anpMQTSH&95Z$;wU&HcczzX7|_I ztHXyXgXG>0()kCdfC*HfKAq7SHJa}G3n3CM9oSQZT2}4?^lP8r5b#^dm@2z2u)(0> zmr2i5MkMYSmgsv#c4mh0oTpDo91)goDONV;%;xDO%QGo=NbDgVxX?7hUOXaU>M>{s zMY;J=AhmI--qZ@{^TLk???a<6rfrX)P3*)j{k@>^((#(0+Cxg`pg_3i}DmFD>2oBmvoasG+Y%l(p%jJMskKXdNUKV!}zA3bxqPpR3R!YqFb|6mYDH-kHA{Yl4^)ZoSJ?R`@3Vh)4dRhtF23y zMkt_?zZcp-acMEp49ocLexji5;@S=8aV|9o?DOR&ir&W#Nly3@Fxoym8 z$7KIes0)_#RA5b7J+u=B!HAy;!b;Mooj;GZK?6=aSKsC<+(b3!H8~WcR?Z7hBUP#4 z;B+hWC}f#s^sIF-X)F{W>_Ovs@p&mYqscahy0V~K!%5}=PtG+7LQ2nvIaZI=c+v~I zQ8FM%l-;>W^J9jI@rq)MJil%lf7BSlaDQ)YWjtYUuc*OKkI7L3U#55P_((k1-?03`4$C6}F?qE?v#5DRimM*yk>2~+22Dso+S67*D6Vj7v21*a*$ z3?tPXx;=B?$o6t6`!!+?*4;C}ZLp*V3MPm0sMPI)mV*$08a3-irXYCsX4c)9pr!o*F>?THAnqLgT7LZxkNzvtSik}M8(O)9H@NQ zfF7{0#%-#ddh^WAJWXA$3te@q!%+k@I%@08(PYxLvf zm^-))d*=klNpjBo2XfwVK75}#UDhFB18Z7ygK)=I<2M7Gd30^6F>0^vwVWCVgLEvr zYp0pWur=e|quV^mt;yKpeTrApNX!7@0u8tCZ27`)fzJ%1Vzm^4>wp3n#pD1UVZDR! zfsO%7IB52Y3az>9a;b?7(7dha9~$pk!15FvyJQYtud|MBmKp0#{QSSimwxUMok?J( z7uz#D`IUq8CJzWI5!`Hj{4cvaA%P3yDj;V@KWA3zLYJDCSe{P!fgO()- zvhrz&u6{WRS^&B5 zzMuMq{{%MVcv*w40bgEqy5I^E7SdExiFRpkhhe4{Zau-VcSR%kt>E7a66Qc^zE$Dj zDOu{04z8JXOi~ucHN}Qz`5dP)v;c?RUv}=N@_rr6!Lf!0MV*l#*^g z-)i5G9(7#rM%vp-A}wSDzkaAv`kuMqA z(~!-;K^nLjTZ`oW4V(>4a@Rws4x(d%tj?(-ld7~<8;!NAjx7Z|3r_toW(lo$Mo_&j z!7#XK0I|PqB$=>(o_*9~ynl~ge9PN&c)XmsM@v4fx#F6!9r7NUZml3FsD7NmDuqFy zVZpxU6V9>wkWd%yes$WPVemJ7+PTFU?7xI1>)H0fuJF+JJHviSqibix9dEXGRb437 z48;4CIH$K+Yot&e?FAEhV(X>Wer~i1C$Yd^c-tme3*_GnvMS$r)hUF@5LyaXKlo$&<&U#DJvNDuGiZRoE)%^B>r--UyuiTSW76?MRn{gsac4yE$$VabZ;(@Lgu2P5s& zHxy>eY^Z0mJ%452*`L=Ppjlq;6}ck^YB&+{8Tq-wtnODurm)iu5!14ojd1^`4Fx(A zfX=Cxhsx{|Nvl$iNGBEMx_22&0#ozWDC294Du-Y=-78*yTuI)=i)0AufsIfIw#DcG z005-yr006#tI5+0s#+)&cKX!HvH)sJY9%)T5t{lHgxL^DlP;0e_9*DjWDhYLwHWr# zy_p~y6yI!bfxSiXWAFnbmP6m+ET*;2%{Htx&g`SiM8$!iC46cas^DHud!8pU?HWt_ zuPUBm?;8%>tTf*vhEZ)AB*5GqU<^uhBZttI**f6GfGNf6^*_heiUVq#(s6avdek7_ zQ)&zW{Du1t&`PKS*<&Df0cd}zAWd!cNiy&f`;Sd~<{Xef3J#ennu!h*73M)dw|2E8 zY}?<}iNAxQ-=mk0;Su~`3Rx{*7_Omg;!?&lbwA#*Foj0et6IhmBBZM$_O;ev8Jb7w|B$I7z z=@gwfymma_2{<(D#pA)ki2&a^oKjM&t*!7rsQ?(FwKCTResCKY1Zmbm6GhYTRUPu$ z5)Vr(Xp-`$AwXMRW}o$p5bO1{g1<*9MsE`dOk;1`Xk*r2VR)B}iHZ zb!owPh^5^bd#;LPr@Uy?NkK*`)`I~T zuv?P_c`MefmQy82V7eock)K_asJH31dBeviC!R#;v&QSLA-2qwxqWz;fFN?)94JQ_ zBT6Dkf(;Zo-J8+^TYs?K@9-}#z|XQqWRn?)lR-pDV2 zJ`KEHL=ya=Nx=-O6lR)g7Hkym8?Yo-TZOu7FA}fhao!xfR!q8fzhnL>M-Y)bKs6 z#N{2CNm_R3XGR2@0M`yfUP`#vR5p99K(pELP>lCH8Raz-Hma!=zKvFP@v&b5{2|(N z>x`a%?Rm0N9Vt?mEK|=DyWXOpsEqfL@M3+W2fQ>rdDYD;Zw`C{^E4ennrBw2_7HRm zRykEAr}7yp?S#^*wYrm{p&G+qWD_qUeh+ZZVo^@XcX5IU$;+R^O}{3)PNQo+#3&n* zNKxO$6MY>|gE|0=j~j8BMA)3^!!~Cl&XEWQw={~Oua7n2C!UE7?2ELSFu8yF_jz~} zY{9x+z5!u>ucwU(iE|?Xi!>e9g2-U)VGd}}MiW7pxPdLxuw1o~fPjJ~B`cyqV~|;a z)G^T_tI69gYyiKOV_Ub-Qw+!ev@nyXoLIOMg#IIf@yv=lgyk<1ALkeG#>}#y|)cPLFK@@hf+LxA@!Ins1&m z?<$eOMP{hrk@(j8rkk3de zW~H0AgE5d*SWB&WjiZU?$+NOdj2vpapE4Hj8tWKs`2j!=E>HPIQXTab;80fozYuv* zR*ha(07WZsHtAJ+S^h%4+g`9FG7GY?y-khubpk3CfaqtQxq2L zJ_+fRELtplA`a?_=+nxc=*SX3N>ij?(}$hP52o!#;|r=XF^S=;YHza9Vkg;3ry$*I zec`@Y7K;lG1WYfg+yptNJXln%X~GV(IymW}^cLI@c*6y3Jrt#*Ir9mc&{z*G^8f1* zuiB(b#94Pz^N9oAVE_?DfOD6S`|DTo`V!NJkUa7_30rS8F}P{@sc+riaY1{a%=Ii> z6aYq!#jnxzOVvt946+HCYQfDNeu0g+j2GAWjnR9CcH;{a6%jlGh-6@cR*MZC9c6R7 z|8Gh?Mm>`>W#v?|#Is>%`CsRZyy<(|V;*c0h~ln*__xSGWJ%T3BE*I;cFguK>)6~~ zw&vM5IZY<$lV`yNC;LYuVF%r__-`}-5wO^aw>%HMP#Rd}&c0}BLH$g#IQtS{cz4tr zs?L(73_%$BZVqP~*7=tr2{|29f$}w^vGvz84J{SrJP-g|mGlXBpI(INiHX2bC~~Lg zJSjeVO;*b(C4ba>UbDUx+UVBL{l;|u^CEX@*@jjA)% zKv3;=i>PYIpQ$sVovoHo-m`j{f`bi({9MWjBbv0K?)SovVK1_2HEyN4#K&W zv_^7rfe^imB`ksc2pm-7pxUDIxKSoVx5ZP3vgo*YwvptNqi)+};+Gh3H>ZH?u3MD$ zyyt5+g03-+;GJ$Etix2nwj*jfCXrr#f`Ne9po9DT0FzC=p8ps+Zh84Z$q2>QfI0z3 zRS3oQp_qxG*8+&!ir%)D6dkcxO)Q@h0^5^kj)WidfiY>^dym*`*iejOqdKZ`A|E=C z?_m@)ql?Mz+nKQt=gxn|%Z1UcWB~lOc`%R%#tk637X=kj5C|l?a05^9`D)By$$tcf zt5M-5=K%-j}Ne7z_y!(EBFTVjkED;e_x&B5QxRva7BCK zYzElSt>}R81gaLL0<;B42Ew2#95~PY!=^S~0jxj+%M!(_y$!s_aLB+#?0LP5Jojb4 zY+3ME`Gr+Dcaig1l^1x!?y7cQge({egrNtcNk)~~>7NdJf~oZNYj8ky$O0wV>n`TR z${W(S36nPC?gnB+-i9DkBKeQK()QF1S?q7~4bl49-~>)HM$${g$gV=xBcI$${H4oT1=bv;2LE7^_j` zy&$qS zY7=0;{T8{M7Xath!pM1<<={l!{lu>veM}9+k0b36h3$(DRCGt^L$MsqRD-@;_y%cp z{el!;6(6vt+3s!~x$f_Xu_{2P)@nsU08ak7?*B^|&aw&;`cl5B-VzZ+;qE4pf$KY% zM3WNj1W+oiT}{@Hrs@#<=UP6F*7ds6`0dsm=!T}w-E`;2u4;y~BM7181J)mc6URX5 zw+RGp@cRlXfTO#D;cOr4rC!0)>Kgy*5++ecmFaEvZIUN0N%Wg69ed3eX3eOFY(IsQ z<6ufU*}2YBU0CY8$&w--%JA5ik?u&(RPpY_$N3W|QsdHz0hEYZnU*smb5g$$l>p7- z@?QMeHghi7K2+LfAE82NM5uAOIhIHd$7irEmQ4U5x(!h#-Ncc(M6J-eRD6 z|B<%~&bn>qOaoHehk{S4TIpFGOv9+669(3RD;;x$r9UK^Ys_HOhmlyuX4)8ZLVzH6 zigqH{8|LUPolBGn?TfK+oHa{|nQv@qwdenjkV?gE!?O8ZcxVW2nLBvWbQKTUD`dPM zpnA>4loS8P8Fu}6=bUTF_-WwboeW8MGaClbc*elJ3@%f8|0_jPI%HBSWM(ogmegP) zv5B?wy`}AQSyC`?B2{h(^6EX?`Tpy#_amfq8#%83A+rUb>gQzK)ywqdmbpLx02e_x zOw5}QtuFl4TMtnYORV(|;HX6ZsKU4Z;^Z`=+s=RmBU}Qt$A&UMq88{&&=Od)p`vU@ zg=(yQoNs7-A&GkkQpY0RI^n(1^U~6A^r16)5WlE2PW5{470XP<*z!*CLB-n!wel64 zhlaYfCnsw6uH48k0KLD_Q$*4pbAQ42rorNnFHTc1=te z>jk0H4_tQCnIky@sP1=iUnYCJ9rdy8MRG1t4qpDIsZ=1!@W)vYngZRKvnO%@r#Z^H8 zWqttGe=N%PTY+^nt9)uMYi#UAQf(iR=F3=3catcL2zq0;{TC}Gor0LHUuRDX!JJ&H zE9Hf1$eN$TPm^RMg7N>T88sBY@>Lvh(gu;6TB`UO{bF8GcAu{_lRhWGQ;%6kJPG`5BDEF#o%8;-LD`&%4{S$mNTM`AfN~QAaM*Z)gw)3(ea~L%V2=d z2sYZ5fT+6Blvnv7oTWb5du&BdP!-Do5J3&AGSN|K{sswtIRi)InSN1tZK3jN%am>K&=Tf3U8Z=GB z%|t933u-^A6~-I!_dhv^H68|UV!C|eHqf8 z6&d8}fYgAdz*8-_1Bjwa_EFP<|L2e8=^-zRM?m|gdu#+Pm4G~brYZ(MdL>7?cxeeg2n^Onw(pzgX=-=0OSEC zn4Fx&BOrHqjR^ean?L{n004T~;im8dQiNI9n^u_e<4+UkPar2%AVXiS_6)!4PlQnG zILQHmU2d}QUK3l*1q%;IdM0~06xH$y=z;vg9o=F&?gn@#m6o2PxyeyWcGrKv=KOkIbQ58cm=h4X_wp#`K*0)Oy8NJw;Tnc5jhNC5+iHuLSpn>fKkB{HFuIJ~uf zOXim>GZ|U_e|KimuYvrsahJQordW!eMKu_$R(MBk1BOCtr7L={)K|+LRD{SW$Ib6H zjmj(`Po_l=P8w328N|NKiK;5V_mq-k-&ha_j3P*4P-+tzB_(vX@YizWNAi#CsKQ-$(6DIMrh3ykS1?0pXXHHxbP>EU-D}$U< z8B9~^{Eqj8p-s^&6d#`sf%fX)Ld!rP56xQ=nHu9)l+gW?uU*FPnll@#b2)o(#1^j~ zo`gQbvTxERm<&*E%iJTkFnB_exK2O}Q_=30lJaco;odZjX^;9ELv^GXyo@W?{Nk&{ zFfh#!;0aYVH8Qtk@5pc_>s;%nq%_`%!&bRmi!KmaohbD6?j4D!6o&Ud1I@e*#CZOJ zuTtnU>aqGdUnduY>ov-4G)GMZYx-tnFoq%}ZNh(HZxGs*&*nmLd#FLxGfKcEM!u&y z25?6hOm@EKUUUYJy(MUQQu7ZWzQ-RDUbME}BR~N+qUM8?gjleFLqajWCaw&|$xfs2_02S2z3% zylp)#w4CwKe8Ms1Y_N1|q+UcU{&x0N-wJf^j--%L8kD0RAa?4!+FSjB#BzbE=#c>O zAPR;zWMvaFt0PeJuX0tnX+VVJwXiC@eJ-z8MUrM`Wq!*hA~KJ3w&NlNsa^Lp|A7bc9ssY^?+@ z!WC~esEsYKFB`PVsMfoe`EEZwsHqe}k^&2$M8#_=!*n172H%+8NiMAXP@ccdh~8Et zM~-{)Jdx)h5$^0S!?R|B%CF2nCuB>CZm52%3C^m*`$)_Q-A}`;0nmE#>)T}>RK+yX zM->>c@cWz{rXRRK8?Z(3+>&!iD)yVv?FPSxLYa}{|6;d!Cjx3`fC%k=bW7WRO_>-0 zzW^&jVF7c#>ehq&8%0K$KSx}AmyyZ?fjU_iVY&s?X@S9IfmvN?a?cKt{CD5XBQ>h* zLxyHy5>s8gD=FYu2n^L^?b60XMSj~mf$K|SVL0uvqzs?|3c@J6+yBskNgG|ErTiUp z-iIUmVM8Gc!3#{!h+odH(?Pq=6F!qflJZ6Y%|akUCz539_ICS4kC+KWknJbA85h-F zmt6bQ6Z8Dufy%nYlw;>Wo?`&qf}q6Y4OAyL+3HtnTp2{^cn$H1EV*#?fQBl&gxXPo+io=MY!v}Vc&zafK0(2G&IVQuS2cKkpJJs`JHOmBc z`l;}8!MCf7S$j|DAR&6S8J^IL(x={S7I}|Qx~Q*>NAR%q`md1c#XFvqncQMNJ8S(J zIwZ^ug+x5eHAb2p{#0kFf9aS#Y;VMN_gu3U_5-zHJYP&#UW^QCRMm6HPu&ayX?^D6`U5};%gt>C^GM0WVkF) z8j5WCYZa51k~+A~zb(+<1k?{D$O1SijxI9qeM~!YirTQ^c~@W{IbTT| zNRV=w+}6%<#TDQSG+Jco=D$ZPd(??N3lCgo1;g)rwfl4O$0KD3j($Ggv@FwAdBb}Pw!~hgJ zGajTT8>+pcO(q;%yVSmsT9kDyAxBQ+zp=L{|KhP>;@@(tCm5^DEC1 z5nMSpGIYzrFdzTO=^my_A#LKDzI{-dRAUPFK3Z%1m-O?KX=MOZoowL}WX|J^Fj)?I2-~w-DB1X^vsM@9HBS1j8S_o>&6=fB-nTUWj%IzOt;9 z%>S$6J36)ojrhbqov&H=csoWgLupcR{j-vv8mVz*s3Zqx67ss+2e@|ZXTr(=2HCrG z#(%R^!^w??+j6FG1?mw5001grr$Maig7Q&=gq9JKglQqeMV?kng*D3caDZA{E<$jj zA2)_22%`sgJ={_XYZ2Vl)O9D(h|qquQ#N65#M7YAdoy>WSXr!(Mq2Y<3XDj(I+a~vpp3xzL+k|DN=@3Os0N1ALToa!EHc6kI z!3pI|6D4C$C`WdM<4)Y)PV@^frzm>8o`LLi&k3*4-=Gh>x3$}g&J;V-_R36#sj9b2 z!St1Vqi9m|cg8ct$jW&G>FJ~s?7j^e{Gu;L&Iqoqp`>2Fh*(ysa3T1xvRBi7f9SRm z1z$1xtu2ctqnPP}m0Z9Z8H;z8H>aTxz!%DL@XN~B!<;w#JfTMfn9TjD?53y+&W;lyabihgFW)oH8Xr7(uB)4A)#Ncnwv87>Pw; zbB>|-6ZIjlVAMy#A*Yz2ig%5BYbp9iWoNDnkTtnQtvYgl^wYdd?EYuNMy;X&{&lM} z4x%!V;@Hz97ifo&yFZt;isJn695i*Mu&{xvlHdv)@qG=z9EgR`ldPrAh8=IT5E{#% zSk514onZDgjxa$&9J-J5TOOcO2ROJj(hD8vq|{t9S$Ip`d!4hxrtK5XK}*zriTCySaF;mC-d-D}y&Gz41Z5db|v z!oPsO04gZn3et6U92KKA=0T>NNDRwZ*-cw2T(4t`{t9krfO(lARj3RN{`#e4%JN3z z=?y%1QlZO+-PY`OH0y#>LwE(m23bs2HGYpbNgmQ0R!5>f3fOr`<9hnN+e!xB6xGJyd>JZV*-g2Q&Z~oWKB;Z~^sG zv;Zw&YGB(#QQc)vtvuy}O}z*+Q-V=BJ6W~2*EzLA)y`-dM?_z+h83U<+AJG;DYvlm z(lz1%2gbovV3Z{;HDutd3-H8+=?o-ant-tDBld$;YF_j}5HU@e%ea~)BUqjQ0SbyN zz&;QY+%ip402hn0W?IC(cf=a*P67r?C4fK*jR$h2cc77*iLVS3`O(aXy6*SiA|>xaI?6~Y?K};Z*a}^ynms}%yg+fFyjsCZXbx4SxbPug7$#lV z*^CGN!J1{FD&)TI_SV1$TGXP$#7Ax!Xd^w-%| z!_4qLRs*kWUW$791B{6bh0b9uXhL-wWIMvXT&Cl@YxF0>B$@p5fD3|df?lBU-+a{^ zF})vmV?3=1gOtdFK{!_KK{aYSp#)}L`QbG!wB{}t+5)CH&xSjuN*I*!9N;b}+j&hI zhKZZXQmfo2nZ-oH{FiRo4eD~T5>w)})jk}5>Kt%rUQoZTz2dgvmlj2dBN!HGW;Cj4 zeQ51bH+UGWGp3pm1?^0XUo=%1;hIaJST4M%szrtta4Gj_8Hd&H$5I{>NNTw^r+)RB z#nVhn0{rVo(&DmHer0+v1MeI)r{sb4`doe;Y-Rx@NPGs_`H}j^7Wv9*G6t6|vhga0 z`j?2!&7Z1Rkb}|Q6K^JN9qQ~UtS&fT2>`S#GQz50>N1z-Wd^b@R1${?_adic5yKfz zS4^|c?8F{A0J?t=!*DxtE*SiHide}qU_bzE#r52>Nk$17Jb%G*O7bU55dOkaBc%lE zsOjmSre&G zLM!Iqk<4Vr)OJu5@oNB8lHggx(zW#S;4%@6ao1X8fEOf|j5tbH9LoaBhelJhDJN;T z>Q+N7P~sC1BmoVzDVbqly&79BPA+#U!%Bq%4IDj_is%F6kqeeycc7I-F9Wj0Zt^*= z8y0x;04idi-V_7HG_M-jD#&bwUnXiQBc(bPi|cS`g(O<1%3VY{ADUn7{F=)C@N3_o zF@`a-c%)n0mWk*SLeYR3TtNDG=^mMH>z^1ivaTy3gvouy3bXE7d_>f&pn|i#`$hZ! zAZ*(?TDSlLa(s|2zyJUMPOD{TEK4x*6NRi2Yqc|UdE1K5?nO%=lL~_I;!65}6j+mK z0paH4$7fx$ooUT#`2zR$|3&|jf7`V292H-a26E3}KV^y$eCA$Degve52 z=+uF|_=#>C@)XdT+a)|;a{6C`aGoq2Z(*_b_7ixaVKsFh4g<*C{H&edn6Z*Sa)>+3 zwH^wRDVAeuS?a%^`S;J9r^(w>OvU)f`lJqy`L~5rtgX42e19(XQT_mWFK}O1tmJVO ztJA6hh9R{8TuR)Q^-i{6e$#>%+es4>#F^yPuDswKF9{#1^QG2}AtrEdg|ul6u^0zV z!yZ@p(JRU6t6`fe)OdPH0T(zaKI{K#20a4Y5%LcN?@3br5~?S>Yo*ZyW(9;WXt=#% z;$o{vUMijIY01eUK7yxZ6vR>P=l}5VtSA07GZZD^iX2TM2sQXkM7bYZU4G!buc~^$ zhb1Y%9xbK?DvsB}MP@4j2&~#VCh;;XC~khU<{9FUgQb#VnT;M53{kqQ;aGWa&9Tyq z@yNe3UJ6x?sZ|dZb>_^x1#z@Yc^p2SPM2~-hE|!PYE@QsM8V zRBF>}vRWx@l-QPDg{M|vh(!bPWj?U5y}PrrcC-x(@>$fA17UT5uJRsAh^2k4vq%Z+ za*)Z%&nNQO_ed&qahBTx-U7;f%#*L?Yj9$J^6J%xeg^O7Q;0QTS_@@JG>lg7wF8>z zS@9|RfiI{t61v9-Wj|=5Ffq-ASvXJE?Sgz`7-)nACC3iOy>T8qADD4i6oj#x0Zw~m zrRyvA*9)R{KE}$CRQLGK=1wrztSUSRB#r`rkUAKF`{2u^53j0#<)KY7-g?AjMI0fh zv9VF;@Thvvxq=XJVq;i7c+&&l6tSb@G$eqeF&SCIs(DZaV9IOzU9Z=rtgapyBTtl8 zyYJXHr?HyiXsjW`1>iqwUdiW3b{-L%&fflsw_8s`2gfcZ+HOosnRdA&hwM0Td9(gQ zqkENS@CkCBx>K~ky|{aUjwCpf{m0qp@th#v#VlXnkqE%|{Ogs1YXCEp;thgSGz^|{ zT5LVPdY5_RQC)^r|I762c(a@DcxbPER6|z_m{U$Ruc}<$;~nO5g*{ z*>oPhi#fA28fANpFVBq$g z80Ql2wjXI=Ix~$&(X`r!ADlLb8YugU`RhUssy&u&p{=r`4#Q}Z!hF;;D^tERKlw(0 z0w^VN?@Xpj-6T`%j>|g$D)E~WxE{UC{X`Qb&!CD#a#i(5o-xQC6xR>Yv~df8lLFQ4 zo)h@8gz>cDSgDoJ<(DbU%7N7nn9NM7h7C$JHfsc>3mQjGF-7$+17y+!Any+aSL>4H zZJ8zj0uF6PtU{N>oFXq=$f$AWT0D1f^P?~(ISqC=>xLU)iITAO8XgndtvGs&#RRD@ zxBw_&b@P~QF$zT37)k)b-MY}Ls<>_g*34MHcFR7s^twM|?LXT5dm z0xB!{(?Dje2tN^O5seDj=3Pb#&FYfTRSctGBA?4AeFYSGq;)$1=^&HTdR-D5AcwhtFrkBiq^8R;Vwm<(nMlV+TyI#y*0IFBi&{=x3i29y3h;!dDHWM+Yri$fR zM!(%vJ7SRVM5H{~sicpV%|%cb8V@GCYV>dn(Rpp@d>j|qLqHjcbLzFv$(F<$ztNM= zUrpie`4AGJ;d2SYbVU!cj`MkQ%{S-0Ev#mk`^i&^_u|JVWu!Yyk_1$aPx`R%1?DLCu{bpCL$4+q5Oi7cznN0`|6cbtU{dR$ zck#gWQ!@vRRFzm%%=+`)v)8XsuLkj@Z~=0E4G?P@l9je$F(ZoJvpuqGx*5E7EMoqN zRokU$K(20+l$S6FDLArx%br$Q6}>EzUN|W9M05KNlwG9H%67w>p;|bcs%pR{w3iTm zFnv9%S3zQOzq{og%Fp=XuLPM1EfP(@yS1oMAX>kF+$z)^15qQlH0-B!X%XVhfYgt6 z`EbAc7Nb=p>XBEqOg6?r(|hKepy)K@hs*maBqa=@wXG*$>Nq{`IVKTd!Rg(bjl-LQ zAK#u36qBIAKA#V^+#t&66C?iF{ISmP-p$>~`gknaOP?=t4$zOp=iAkZ+9060uJJ4nBExSnZFpN*tNl^_9N5 z9xRvI*3iGj6gqoPUo7Q9LD*qW>(xU=ms{a>^cs_h9S$HUJ{GWVsy7$C&&~AAf&x$C zo4N3z>3uI#`^y$x$F8H*BHrPLBlfR#(_O?zmBn{BkC0`;w>cj-_{o&$$Nc&>U(cMr zvGY?#a1I6v>SMAowNRyv7_{f@OLPu~PqRQfRrszeDla|HTtnnQ_pWXY)#_KW%&nYbc^3z)zqv54+Um;fp7tR;2Ws0X3Ei6cmmyn!K|`qcw) zZd8arP_D@t7tHVi5>@x=zK@((U8Kdq*J&N$Hk;)kWRhy1l-iYIxPw&!vgs#RvIp~s z?aT7m5v*IwlD2?Azn~Gdue5S_LFvUb|FRpP3&HbPF+wbC&gCvOIdXrgRW(D>cUIb) z)G`BZNMLAQ;m}|J0i&W}2;&On2AJls(%|h-GFC^El(vdokj7NPVqOd4c_1mzKx%>| zJDt=(e2o(v9>UiXNnYX}2NX_t#SGTRDyv!_Zd=Xad&mb*P3d@gSz-wpPiskW%-?gg zxZ=3w(~f9*bEQZqv)haPeVGBED9GyMb$j5kFd8~ZR{ZaKot*+fNf{k}uuxmkR!9`3+78U(!ds;fd^ErGDs?84!7z$Ph zMOR=SxXR_%A^vfXg(V6NTea74`Bn2#R=3b3Z*Kn`ZT}SDt?opU#Z2=I)xQ}z*4V1bqaO9$Q>I$I!5RnR zy~OTMs!0Qi#-*OlpAG^I&>Et6RK_3SZ;gJz$r_TChF)o$HlEAJ%H z;+axyfQ_T|695*uAWk-d3ihA^P*Ex9gVpM*6cdSb#-_MLSi-Ik8ca-rR7$+olcuX_ zHkc<_PWjVIBhmd$0eJ;|!)@JALO|DgP}#s3uN}%~Eb#&Lp^pkKP1_K~htK`oa}0TP~P?WA*{^A+uSiW%*XFbRi1d7gl~iv}_AyCY~#~W-MGCXDQ;d%+5N!hTMCP z{NVBRb8PcvZt36c1kD=a5F7j&Zl=Ewf$!b+A=gQc~-8#u7p5l`#EvUTYu8>3R6 z_W+fuT6{*184B(1jT=@<`=7FLvv*!YJ5pbyx%W39eq;p@>=+&~Zx919;f@i2kOSU| zzy{A`O2L6P!Fce(l0CgX7bmR+=JE98GbQ!!-;2YVI+?Omj6tA>#D2iS{kEg8hV7~;s!A3&5mC(53L6g(3s6~tRznd zjX{;ku74=u6>gV-H<=7U9b9i(Dbup5Au4uXmY#sWV2~VX_81ZEj7)R=<-y+!^WZ#` zX&AS7F=R5MY-%F2vvACoIYTey&V}Yk(O?y*|FDtN#v|Mp>)L_se)JmEov3OHcL@9r z6`z;^Y5ygovw3F4seBMTnhNN-t+;yJqhmB~l`jw_&$!cj#dmQ!I#t@pZD5 z69F?p!OqaY&E55cx_+~wdCgYOk3X_D6&I9Gv!tr6OmJBPdn7J8)KS7?G`)&Re}k@O zY4*Bw!KP9s2FE_3p^ZNu+Q0Uo#=+Sz60|-f3o5;Q`aVk0kKheomGH6bNd_?n5ZXo_ z!c8r4S>g;HYdt0*&*NPQWu2##ZGEE$$D``Xe}OWQ#oMi@-)7Q0wClQ^v8;on7(GC0 ztYmVVWo=;CK+`1hhuIxOq*dy0FJEc`oI4_D1VwnlBT!mh^TKIWhCCYn;&iw@V1Nsb zNC#zGA_@w$k|0DJoBdMh>X7QiOpHNPghA!_N;M>@yZ`|W=LaHW4d|U)Sn+*fBa2k* z=i`Q`JgiHMAH)v}15+M=ibT#a(JWlXLms=hsP(m1pOI4%HTHh3$gZfnaB6?iDsgc~ z*WtW$^J%;w2dhTDVyw#ooxbz;5bybKvF70>$Jx*D=FDwsblxHTIWhX zip&op6fW?Lcrk`-n|mNIfB@@wV>6+A891Mb9#x^Y6i8=$0BfbJ$|<=jznot-n-1bX z+?gmm7Na$V{gQzAE7hZZh`gk6kCOF>pGRv$96S}thX7USF334CY4H6Ui1BBx6pq%> zrdvHPAXX9QBQV*0vc!5nZbl!3Q?%u{JGp_s(d!WW1@r4Q#F$!$t4tpn|21PyW6PY^m5@ zn%Ib>ZEzvEMC`<8?Wl-x$@?sw@B?MRBHJzaI@>GUG}yv81)X#AdE^`pk3}Y*T)cM2 z(YeP7ekow~Az9;3w7FvM!4Mm-z_^T@Cx^`^y$=y@>rA{55qCw_}9gosLx>|Pskn`CWbqEd|K!H>s&DICJdt%3O`nV@aU@OGgsWy*#NP+7sUvj1N z3y>@0e&C=KhY@jM10Bq@C`hwsRv9;wcww(w6v~9Pl=63lY(ZEY95@Av&dwL2`)CL~ zySysc^h6}vu+e)M7>|DQk78E|aBQ#ga+Z{|bM}>{y8NVe@Ykbt`74bgW}q#IYntxj%(+SgP?>*0Vl z?2pKnysaq+A9l8Yu!u2ksAbrwbCtW1AHDN0nb0^oFW3-eFUj?xIQVkVVLzJYKga+E z;D^kIk-@?W>^00s3HzjZoFTH2uTfZ3z1p^b-0Hp#Ju9h`ddD6;VC`ZB#m*;~4g`X+ zgxy-eqP+EAIw?%>kuNX~$hd1CmI{l7NyTQkv_gY1X8nMCW3OWdYgJsIeL4os$s3Q5 z)pB`JL+9SjU6BUwsR-bT+PcG7`4!U!mmglJ>)b1p0$tV#$paVM(4-J1(Eyin*62J{ z2M}OF%;Jot`jYy@U z^5pVc7mEWT%i!Pf@iuC4qcdp~4|;m;vU2W?ljBbsmZ(2{+pZIeJ?#Yx?qXjrYJl)1 zZs~RUkMr}dn8PLxmjDg?4O8oVON0oavIpdbQUE4^J>uM?0Hq3+k?A;5#hb$8k8B2yFh$lv5Q7lKEBI&y_WI)r`aYd zQ&wzcQIvBCy}3n8@gRuPoY-hI=4>uLuZ+?#OU^(3^WDP@%&5_fDXp~^yMikLu0wUn z_{~d$YuUG#uVlH11sj`6>rf+C$t?B!;UusU^CHYw)?9igkdUd{O(sJs-POLX!lc02nZon+T;X*sT@dM{bwet^rMu>x=Y4c|wZ1?!36!Yv> zby!u8DN@N4>h)|aHPGh7S%bkxO5A0EeGB~TDpx;e&o6)``CLyMjV;nAiXbX9?r^SL zGyPj~{lKFk6$AQ1)hW&vYo5Y2D1N8x+JUqSh!b7Mq)?hbf!$L=SMMuV8XqC{LSE!q z$NmW|xX*=)7hl(o%rzAdPFgw#e`gI#2SERdv8wR!Y4xm98a5g)aD`JwnIo|iyz@um zK*S;ny)cskn`Ab=OxI(8hRLu5M36dY90_!DIPEH6-f$udk{kLASF$^`1DfROPQXqV zxvrR}+$7`ZHbA_aHWV>b53g@>d?~N#FoUh(&Gv!oF}r>`jJbH5j4QR=w~b;I{Y#t3 zJk*l#6Gi=)TOv~!SLyi9d&L6`a(Le{9iG#E%R4r zGWHSs0#2{JS2;+r)&sJ{hdydr7`L;7A#Mi3<93cZg}f}_KWPXKAGKFubm--&p>(a% z!8NNSz78R?aUP%9SDT@`Z^SCxDa)T95ZOJPo(6g75XQ#Nt_Z>A;jhh%0Rtz*vzr=T zj+cQid1=jvp(4;l-HHC`rn2`beglC~rb&T?B3!MN!&IE&GNE{pk38FO0-T^6jD0t` z$3yW4cueEiKQ7*@cP{a`IWV`(;0~m`8b^P0!DGUA*;U+Q+#VLL|-A{tW&@}1kaXpuuiY9OL5Ppx%! z*=c|3*ykJq-p3o38Z!_+F<~yc{jYJdup`u-$2&mGPDLIGc9j+Ck_58Nz+o;~IZ;{X z$R&eb2{()wq4rJIi^JTU?sG7dXBQkOAWdie$j7EC<;ds|Av7L_U*XPUZW|Mh78(3; zi>0xf$3q1HUN%d!p!TlF$o|wvBb?$i%TY1;hg?-^!!N4x>3QH=+vxauF!-cCmOa*{9LDbieZ3hbwutAK7pKh!+olXPOq`}YZM;OcVJ$N%{c6IzqpFvkFJy>U7Hlb?R_HPzbDEH0-A z1jo;eOGi84T*vv~)`DB9z@U7sc~z=bz14u4yUAnC=z97CW|57^t)Altl5k=TgL~=_ zrD-efBwqsnVX;Yy1|F9MG79w5kusl~tH3PE!pex&5d{NcMno7g0S5!P1f?I<8#6DQ zFc&ibN9Q-jAhdiBZRtBC&Jim(C8j#R%`^igA+Q5T`e*Clh}EL@JDIF1p}IZ2O(4v; zC6qm;DPZ$N$Q2dSa5UTt-AyFh>td*zbY0CHNPxn;MJ|6wEqIfapI<%&zE4}l;3N={ zxB7LRA<`SC=vf| zq?HY!aGZ}@L;qaT6HizD!iesW;B9SpoeV)lMo;I66slt4%zPWf1E#AX_?fjVzJ|5b zOFm&EMPksQ=sc*m)D^uYqOpUf+_Af$@jvR|X_t;coE3ai>iC`;<7tkD4U2aB=nEIk zW>^r#Rse1-@kV`5p}Ms$KZI1JMNX1pTOJm`#YXCEiw{r8iKRtn#Y=12fU_7y+4`sdr_EGQJmymK{ zu>7CS?*nI$CiW*Sdd7|#-J{(#KzI-b5l?Ny6puzn6srs5Pw6m|iFdz}kfxI>i8JRVyQ8iRC%IUo1JbGd7N> zRjoyqF!%E_{3Na<_#L?){KWi7_V$>(LD%}*J=PrH+^k6D+;NsbSu^pDA-%Iso(a>c zJgDANeO_5E=ZEZ=OPt&wYmYIm$=Fim%h~o$VVLS4+=Gg5%>L+}B^_1$%mL;xJ1FE4 zEF8}dXANFyy|ZI@JdT29b2Uysjjh|OpYU3#tcR!;N8@MU?PA9TE>TqI&Dj)S?m#-D zkK@_Ca3!vVQ@FGy*!FE6o=MXk5})Xz4B)TBTu~ZNDH?hu5Sl6UdVL2T1gEr`Iz^N* zWUU0W1!`}svJ{U4k~^k=?~nkL!%p3wMKJDDd1W7br=M)+O&-DX{Zv{#u^QGZg;+fF8k5b#!kA4ce6@?(WYbKr1K|ExU zp0_CchjmwiN*|(SUwnaoy$v7W;&642PRk{{E%rzh0<7bo0e~P7G6^vpo_l65-6g>$ z8dyujI`xn`wW2Jkx@rR;(U1=Hc$cQDlbTxkmoFJ&R9(z4!YKgE>LZb3v~s|H+za09!|>^3C=~bApr!S03c5!s zAQ3JU-}UY_UqhbC0y=*ZoMY5iiF?TlsiL5@1M(ywTksbLW*?I%I1iSb84b;9b|ntp z5i&_~auj8&pm+_m;pssb9112wt4+ti=n&qNK5o#;h_16i0jikz(eQtLbgfip4Ocmi zWv(W#0nch+dCN;HRg2p#F(^kU^2?9SDPq~d_$RgxR-VhFa-!t(xwp zMv2*0zaNBZa}c?sWQ5+Px5VUlS>6t&w?>zlSHo_D>HLch!vW;ra@+T7b%^XPa$gUQ zzXC4Co@7DM8PH?uS{MietX4r$JuEo$VO#1k8V-%vb)RFyamZ~c$FKzP(HAUy~q!QK@sAx>jcl)Nse(8Qoh;Pk}cnzqA@74uf3B{)m zU02FRDRt_>u)8l@bcN3&4&%+J4)#c+&AX{(yw#|t;7#EDD_PtCcc$!BZdf9T6?_*U ze`r8YlM6E6;%g`F8EvLvo~HNdxsMFYcabO@i6@I^gxGkzXl(3L>{h)=K)h4ZGVkar zpT&^*NP&eu2uMG#_LE}_rbx-~TW`WqV%o6J;We-lL^S?pdtY+zT(Pi;`0CxEIhV2k zi>4}(tbcZxb_&`!GkHQ2tAsPT?*Z7PQC}Cl7K;+4>|1+>T$)1^e|A$nHa!o^eznZz z#1$X^U{>Nd{+-;_EYkI_1Ymq>`MYrnAUlZQEw*^BkV_KL>n zI703+*pjhvnSM0>-}0n#ivpt!2<5$4dFE%^Ker zlkO_PIS}2=dyD?!9{qhGOk98h;uc$k&&pF=jA#FUzy)8UMH)*bOu6gY%*6Bkx0o={ z*t9XcZIg2`@o^P^?FWnvm_A#A3YYP9PTrZiQKA}rUlJTYrT4<&OxL-dNktNy98pyu z_=$pn+N5(f8{dlPh@3fym%UlzwGe|9#ZBwTR9FjsbU|pG7-tH79Xi7vI)L{eTZG$4 zR`d|=?qb*w_I(Oq?AZb|{cl*Qaah2b1q5@RwmdY`+TB-Ftk1vl$Ot9zMOp-QBKIGz zP;C&|C?o)gM?QRDqw)8;wIyX6)QpF2b^POwJiQ7`J7w0=iR-}WP$maI9LnF(|9{Zw z&K+@-FG3}RfjA^wvZ(2f9WnQD!IKs4!A3}5S!DAj*6oH^EUZUw#Jku9o{hp1mTR*a zYLyic`*PN?-zM+YE3Y*I<%#%oNkhHvQo6XP6~Yc{+{1yXct2vZ+8`L-0v3h0rMjLf zm&`v2vIa}>^f<4!7KlY3+z6C_X7)kt``6VWfdUOX14pULVc2h+9Q07Z%mxYS3>ml9 z;=6*F0$RmXtzCB1w554fWqj=YDi_n*4Sqpko9cQ-V-jvMDrXYu1HLkB=L(WwA4HgB zkRFq!9rTr-w}nq3Tr8HMnd0s5!Or)o#2|y8L$bmh(v)Ks$8l9%5`P51~k4U7W6b5sZq_qe$$!5;gsRPWqK(|-Km!*OE%(HbpfFD-q4>t zai|D^U_RoL_Nf%P?vE4C;P^hraYxKJW+D}~cZvH_lkBcvDY*>Ss5TDY1fDFqBb10r<+9b?I5q`DKi`l=GHg2ON&$= zx2Qawe{H0MLWK8evex%C)Xm3@dnnKxk(VOG7d0hbye}7McAj#VGW<9Ddtt>RM%nYg zNK@mce{7A6^%i&1L5Tu%d|t9{L>gBKs?b2H?yFmNe#N>mgq4#OPCj-? zBHgRrY$l?cQ-{H_#uH^;Ehl|to8aY?9hbA7k}KT}S< z`hd}0Zdju%w~N86Pg!LU>_d$wug3^JtW+1;*V%>t{blf8uij?rm}6nnAv38sQgpFF z78@22%cS8g5=GnJ=CT|F`t$JB{A5?~0#7V(X%H?(w6K`W`RNGlSn?1ELSo>I_5I}f zx58EqxUNd(f+{{ZrvUnsiUAoxnQz=L1$Qw34%_~YiMuPL>2i<1ye(kb952ZX3)%`9 zfO)_{r2rd%0efX%qG6|UhdB)Vzmag#*Z6+UjOvNMPUTofdP-c(UZ>T-F>kZR5ik`3 zsfPC=I6X?k!|f8|pFbDBP)>>%I|@N*zAcmunq%`&TQs1UrV=pMxF1tChp4daK0Iq> zgVt9-Ft^4(XbRgyz&YL!ACt@Cvw($At&Z3?C+ZP%~&ZhcbJXW;8ut8?aqc1+SW0yYT3zyt!rsa`=Lh))WwQH;MxQ zB+x6StCuwYR%<7xscrUn?;6J#>zTw^L(I|apbL=ne#59eS!R4uRLho`^hh~tBRYsc z)+fih`g4&(O$U^dr2Jw{Ao9Hq_}%d5aYRf$yvsnJVv-^e+D4)%%h(hR#7_iIFv#yP zCf(P3rwPB1Xw*snW$0-e>!WdEix#1&ssFz;RDfCsY;G_0P)V=afTiBi1CfQ@5&Q^9 zpXl>-5Of9RBzhTbNF^*Rf_sb*IcItH@AA5HSuYM# zZz=3JsB0MC?Y(fC1$nc+nPLU^uGS>}BzP13(%$ z-7e=qPinx$cqF`6tX4Kv$@OZAIYGV7$AEJx!X^MppieWKaf)BOh$e`%j&t?99_qLe zTun}j&(*Jw%RYY9T&={}K}848oUX^C3;L?QoutMxUJnD&(qk3~)E9+#xq?FWv;n9! zfjHATOX7+O-Uo>COBF>_zlOkin&X7hMg?Y9O_~EoWJw){rA@?LPkI}Uz3(di`0d`( zt@n=R1M!-uQXUZTl7whu55eT2z0})A`_VndA|z8AK^$t-PvVL#z2`Npx=K=f#`F z0Eik@cTT;=_}Z8_N9D#bD)D;Pl4$(Y*LMg4U3H{*=WPVn)r~oj$r)}1Y1<^14``6l z19$$Pg+HLkz%_CfcZ$K4{;}B#%-rceQneb8Jc+b5q$k;V;}0v%=czlFVH@_o=+KDm zUReOM?oM+oHW&Xa9@JifjaT?yCW;$p>^CIM7pb5==&v;J({h$Bx z>6it7^PXuUk^+09lsJC$J&ETfYZHJ&0d#9^dpwd5-SU{vxwpF(lvEAX`d%gJ2bCkW zQD|BC>5^is6&2QrhSc66XlZ7daP5+bVRuJWB=7&dDE*ShdOP-+?(ij}v@@H$ne} z?5o%1_efzy;j;}E=Sx7soOP&*;ABx!6d+MxnP8~zJF98W3Br7uDuBeSmR3?pPT6gC zz;Za^fadc%dY5`i`G>$i9~WhGtgDToZF*%?=Gu4tj9@eo0A#BoNghY(zh(KJVm+H{nMw4LXw8auJ`@?*y1lIw)r)Zn(h~83RHzlf7Kn-4 z@cqu9%AaS4SeIhd;#rNG>r+yS00&H^a5*?ap;*M4D&I}!o!=*V=9V%mdn?|FnBvNI zy6n2F9VJ86h#;$V=e*hT7I|7}v(hGmB5=ziBY;8(8;xksPJhPhF2BRp10nCMR}Du= zVtL1Mq!6+_=Q{(X{}I*6_ewpA^wTS&U*?1pT9fV{o}k*Vh+p{hv3}$Zd1F<*$lqno z+6SFd`}b~vajJ}z{5vL)LH#Jr=}f~0C2;$eog}EfgZyvmU=^-U)B~8^hdFvHr5l6U zqYOQ)RQNP4gH7NW8SoJn{95JVtFu=Q89A!ibizF~?jZ_O@_!6=JkEr;X;RX;A3tXs zsmw+hRL+MP)+Iv+KUmet&=xxrcJhY9LoEfy&s^Um6nEOI{hGgiY_pB48B^Vtm# z*UVRC8n6TzDNuAhgc_A_(Rc9GqAdg#WQtOq@!rJGQ;dZ?lLcgU;v`+_55E-bM$Yqi z)Drn#chzZ-NKB9$8eg}4vd3%cgqBKZqb zC_0(4A>c&=5H-IAXE^RSwMi|#{DQ$qbSbX=y8rw67HT{Bpz_E`*qN;Gl1=2(ut_9( z$|R_pS(fuo-`EfjA%(TD`k|h;2K6ZFyyDE&4%j~e5M1fKfWiLwSz;_- zgwx~@+#Ky)aDrs6$`0+hcyoJ;M1-kN^=?(*k_%R9IY)I<4Jt zRj(lb;XV>;n}tY0T+ahAArKxCN3UMFY8T(^(wz-LD;{UW01lDRLob2QrfxQY)vr4a z-74a=U#o*}Zq1PT;hq>MYm4SUda~!I_v;NgnR*?DSOm09~cY-(vN+8pagNm_(%9SX+uJzKz*@d(>AxFQ8|SN+jJ#vmn|R-XoBM!jHMl^=ts$Ud1~oUK(S zfJX0U*&krQvP>4qDKxRu#k+_d^{pbcZlHGY)`AlRZG>qqcocZwv4G=qJv`r{BkbNI zCuTFP6!|8mM^nAZrebtCLMKm13Ax+pnlDK=(TF@L!fkJ+A94#OiTiVTa;B2XJR4rT zqX&PzgsEjr9wGbQ;w7I43;j4>!|4+aa3DZkoCSgeF1Z8MP(OWBt!uaaZ5l`db^5 z%WW;78As`?32Q!`+~+^N_g=8FpZC`OF%G=1TJz5Jd}eUqyK#AibWfl1?8K3PJpQjF z01p#4MHgy1b2yBJN5N=EJQ|*mbDfMvbl~f)XTDVrS0hrXTiVHGG$wC-v9^``0fZHd zg~9kcSWS>rmj9UEf6|T#$53D=KNtNhB$BuWt$rZwA(R?LC*s@Z6%VBShYm>uIn z)~c-VdhF0_VN=-6QKe15{ZOq(N7FnOQ;W@2mOd}M($Kwwt>WmR%5+@c!RRschCl*- z_`4xUAYQLz9q09qL?Wgh$t7~(K9gIhy+Up)Ngq;Hn0?N&ol-G4V+lBKfGrh)f$Q*< zNC#u9Vq~|mJDzmxLYep$YirWZ&%UNKM95`Sq zK=%SS9R!336cTZ|C!DWgn7d6y0pg|6dL04-{H8;w4W)!tVAq=ZN+%w2oLyB7;aLt8 zF853Gywa>6IihT4v)-fUp69;TAOQ9XBA;BbtEV6ONFhxv^zsUL$A=>sNpBRg580km zoaI*AY-Cdv`k29a*OGX#WxmHQ@i#`<4VP)EnvqCwZg+=Xgi=OPMCMocWcj(v%6Y_f z_8g^BrjOF2ig@5aTFK0T9|%rrP6+Do#oXBRmn5)5MXrXygV?}v>WwR1ymU||X?Ud_ zIC<{4;;nWt9DWUaI23@BU|!K9YHY?lUa+vtcMdZEH?58-LnZRTj-3Y%TVIq`7fl#j zbDyRK)nc(WX;7M$=+q$jT~lAcvjaVROP0w8g_M7jYTq!1W!4fdW1a}^)HvG7eg4>~ zgJi>EK_zH>;D*ybXFdyuU(*Ny1R7<<$R}xVQML3aO5~|Kf;%Rcti_m6bxQ`T{4VpM z34#CG7olgyLM?n|BdbcAMjfCy#fr!bzT_flC;^46K2!tZlN4g)v+ag@z1Nzj8}O1? z!QG5&M6a!e5^mb29qCxtAB39b^5Z~D$&AI8C7_S$J9dJCkgL;Q|M=z1wdt|bT(t|J z;5jAwW^jXPOJrM2ZmQ-+7D|5+vM%ZhM9%qrUKF`@h{X%G>?)Nmi(BxzH#Sr@?eQ69S7CM_7WW*FHksHx zW}!~CMk|5T^3VS*lc7YlbGNdJ=3s9+%b_!7o4ndNC%vKo$)Q`&AT$+vuM%?Te6X*# z5BouvD4S6Rvvc@F-LEMt5h!y)3|@*5T=Y_1v(XO}4{x_xs92KPsbi0{np@;xOV2a( z53ms8+9x(XnyDtl0DqR9Z3RiXtfv@*5tk#Y)GMNfGxVqU<-~aPhc|+R_v+7DR>CfX zK13L>z9t&p66XG_W}R(Cq^w%@;YT6B-o>8ddI7becWiBel~O!;Wd_nVDhTZ;6dwB0 zDk)?eShdVlk zSp6qe>X6%Icc>x!-Ia?DP+~rZ&W}Rs{6ozlJe$W%w3UDaU?WK1FdMzwQb9op#QvBE z$++wfIu48X9leX08*=PC(XONVsN}Y_-1;k|nO~sBFy=N!?TBgXok@0LZAWi{)yE`V zXNJKQHnAH4$0fVA(d^H2kJgugKBU!`pJA!`Bpdvu!S<@2_M&RnzskqvcXq_V*XDKO z9P263WU|(YY{P*)N5jen`O5n|qIY_O$=@*IHvm|sjeP8o?v#G{S9^WOL3QM^s=z#S z66I@_HUbL45gBq_sx2b_&$OWX3%tS;A!zuIb5-X~HKk{>+T)_C%(S89#T%OUvNU^T zF4oQ26Ps5@)XX%7C#t9{dMSMddR$xXiivV-p2*YSKC(9WaQi`V{^6Wam&4xcLrT<= z8AvhW!IH<9WF9&yR;~KRZ`a>C_w|ACvnvH_|p_B zbvOItQ=By_0fzw-(_TDauAAGTtz9*kVSx>LH+AiA`aRh;rcZQv^`RxzKVdr2e;C(C z64}veQX1f|u<%V($_hcW_KpX!^@_1P-8PW4{~PWfv7f`FIgsON+POLcul}%fOr3O- z#C|j6xod`0n`3lKDeE%Sf0JVFj;RTNds;{*duw!@Wi$Ptj&VRO`b0*jrcljh92%mU zjU|6|NW3K5)t%BuW+m4{3Pgm{g*KjDdhI^B)22!6!wtAennDzkw%PI5fwez!ZMO>r z&YRX%LJ}$w2S)N#TO zShiNvRL)5J=Cd8tFTNXAOkxDukLr;AX<@XQc)?O*!asHXZu6B&de;xlh%oL_Wm1QH zFOxXs4B96xLV4*$1!6M7rG-BFs+XG-2*UDddtzzvHF`XFT)X z+0+~!QLnPvRk3=)$_c?I)Jd%{<43pW#*HNFU#)*6dexiMjnyh)nYgmP7E%t%K&HW> zyhG$Okzl}REV|5}=0n;27svx_3A|@AucNYlq_*mO?h=2u0$q%z{@>p$-Mq+gy+;vz zV?bX701pLG80-`zFB)kC}sJ-IthnJe((E+P+C#~jyFu*F9)0i zLjmMIe0A(}xs3l~?D5L2@&l#xqM7^dv>$4E7IbuBUNlJoyP|3L^?&NP(=r&LAK2>8 z2?A%Fg99A#PQF$aukg4|7%;mxopi=|+P$)*6@8j^Dcd;*^*}A~ie|L`rN(8f#$$ES zpOcyzBVi3dPJNJx6i=Q2KS0300ITqeB`F)y5-*r$JwD}Np6bIafT8f|&vxK@i|46b zy(*4oTmH|_ipD^L5L=`h!$HU!?_~jkcd$=J)A4~ysgl@J0_&L&x%3t5i|Cr)tB|*l zVau?%klUGD(_`(SNzz*?`7iCEFJsUW{8zeiQMHUsqAEg)xtln+zE7+L3o-d17VsVO z^GAOM;l{U^Tm*qOTq*RajR2~P@a`s8-oh})tPWq+aD4fDC^lybI2H-Tk#YZCJg`UB zlBe)5B{M{6(T}D=d%&3>te>>Jdf_Q>Gw3W~jwEmR9HYZQRN@SutMNLIEO_$9xPdME zYu)T`on`wVT)~CSWsFaQEFQN#w^`<>Icc8u;>39#*S8waGOuYH9(VFp3v6PK4$fip z=$C%-9Py*1d<+-JnG7mKX4j{$EyTAo zFYsI*Ed$HEYj&mzgJYLPJH9{cQGwm2nQtWc$^DlUE4n0^GZdrK&pJ$BzpN4=1iqvc zfM~d#UIs;7+DV*OL{=gv4}P_!9kD)&F!ZdDXqkFgSOG|`EdwSM{1@q(rBV0kf?8XH zcd9ibx&ec@l)+0%Mpi{hMukuC*o1(nD z1a>AUf0<@q7|O20{Skb4IYp>Ms*B;AmvezRXClh|B?55vzktzsxogAti60S}kM@`V zD#&h5$k!xHo;FvWR|oOg20KwJ#$az(eGsV{$?461lnhRNi27#=6MildXbhx5y2-<@ z#xT@&*z+jXK?Ct?4_2;T8lP*VeojiCv}V9l*U`~m#FQFP8opnt;F9J%psbWA_G%L^ z;VDrHyLZ=lg`;m0Hv^eJoC9kLC0G~u&r0uMPA)0mx2mKF6cVnKV*9#d!zTuIUk4<1 z>Q9HJ=7m?K!fD)!`}~fd%jRl&H{imY=uNH0ymso#F$F0jpkMyfIxKA(9YeRbZ1)$GXaxYAMNAkKi#f5e3993*){4l%)2!RhCLh>B_F-goNCaR) zJpbxlE$!|U1G&8p6pr$&8;;B1#dv(K3ag!^k-LBQFKmE$pLYQ0)d-eDq`{{wH&$HK z{T;Du4M4F;)Qfl!1sZpw5Dax*NQ!1kN~WO7#vQ%pbt%=`5GL1nnT%V zI)pK1rv=ArH>tjtu7ry0t%1}yO})&vnx}>mj{lK)!EB4F8yoZP7llI>796$#8Q;`O zLKbz<*3@#xk9ZpW(cJT-B&xC)@qtlxZcZB!h=cCu?r0J)+z<1>N?dX@r z`E1|sfxs`QDI*1+HyPCkFbYBGrw|2?qO^{JlO!}eRSdZ4`scX|0m^+Ma%6R@VRQq$ zP2=c)5}YA@UYC*_3v_=B^L-QXjat^g;e!N2TR>TJ*D=VXdC8vEsV6_E%OanU?+KfY zAzaUb()Vh$atlul&)hCU+_$&lS?iiykjd>`GMbNC@o?C*!!v|umDVG;7u}Yo2nnte#QZ53{2q0cV@9Q9qhy)Et#$SzG6o4v#IX1*(qXT zM6ubQdizzVl~rqhX^_r%a~unhy66KLk!}Iu=<6)6OBOXSpVV^pMZf5f7hP_d&pQ^) zFL1AbufG8s5LZ! zt;Bs8#t{SB^H>hj7RvhNQh-r)h*eQvUrN{<7h1$JVFh@1txmUF#Zv2)H5Abl#lliT z>W2VjE0u%qH1Vzi2S zkT%(ED^$`#VWmo-Lfce?(U->s_TV97_H!c&1@^z}p8tK8vJlM1(s301J)6-fdO-2r zNPenoxlOqG2=bw+%uQquaBU~&|K4DJkHcv-Fh-#jC4HB>d>2!$ae#Z8NqK)R8f2s> z4y9={u@Dkj7<2U-NOu<>pV`GmbrVDEQlPl^Mm0-PUpUcEQQ{q~%lbG5B!BYXBb(um zRml;XEfz_GTQ>G;-Pm)7scHySezNMNb#d#kCKK82K^Es+_UHpdgyFUq{Ihr1VaKeb z3Kvfo=`SJj0?Q1!-b$h)pGDL!HLTw=iMGjP^7(Kc{(gYapY$L`ga=%GVO!~F#~Y)Z zGaO#iE{L&>1kP>zkwIzl`pX*4Ye~UjKb&m#16Oqr?Wg@^;jbJxV@u#7oFt99Ws!Ic ztyT)jG^R!5z#*TU^}d)s%1t>YYCog+{2{q_`8#nBJy(o3iJYODmzo6GT6c#v4vq&X zMLT&(>&kgW773HgK>VEmPbx1eRl3KOrf!FgPey#t&S6*p6vn2+GDUhdNM32e1UE!P z3PUb(UX}4l28y+VWPg0Cw?IeEbBL>4SY_!GRMrf)9^Cya{}zz-%0O|0;(YkS+||>Q zD1Xa!@x~5#Hq#6^jP{8_wMIMgY=3R&I)2~19-jM)md=@y1M6m?9bE|55Hfwfrw`QD z>2RERWZWeOh||+J2&|mm!pl=~rsM?ZIrNwwtwYuf?l+gMrkdWc3MTJynuk`&U@ZDHqa>CLiHumm4^#^Y>t^h%0c zRTMV`O7Wkm(^GiH`limOgTHcAc!9lRwT)~&uwal+ zdXKcEW!-mRa_8mw%bOIx;@&xKck5vr%_H{6VXUR(R3-Af3HV*vvZN&L03(<(+_jDpypBEaZ|d?!{IwIY>`*B zh?OZ4Hm%AlmF2BeSiP}9s(g|?veMO+Fvylr2KgDkkOzW00@bS zgraK(N2L3hQSaqm5o-LquNtgl#YyuN8=;_&Yoj7v)M{&BkXAL|t>c1}Pl3zJ*Y}%@c_;7J;TFi)fTr$&e&yBcB z{0?xR$x&)ln6A#5Vbot$I!+Qoh`*K`zNa-InshRpF1Jn!+6!#bj@c*UIDJeMaIYg(`BxjggPurB%Mh$D`fc#{xXG#|+>+RLPLOV{Il zJFh<5tMJydX1%vB*G1OZnE`eLI?-8*#R8L(#fS6TQu@hBLItvZJ33@F$wZU5aT_WD z9o0dL=34|5Vh!IdelcTObByUJ2pJ^pt4Hsmb|>~ZEo);06r>{L*NQ;i=qhs2k#=7f zIjxUPq?~RtcT<`%)T-f)%JAtdVdq~_TN9%90hmzb$}{ve-F@@ODRPs=WiNvDK1z>? zJKnf|DE7na3NatGisF8~_Cp^=0YL+eJc7I`lTj5fN9avDyk7i2Z7Po+-ijeW2ps;= zgPhfhRGwH7MP|VtFaQ7n;`k^41&`GLHSNT&lsLP~UG!SxVhaARFFTwQo&@6ztiDy{ zSWqACi;FJpY82HR)X=Tk7*FMi{?F?H$FX^-ek@~0l4sa(?7byz^3F~LeOw}&O`1mq z{;ko;iJ#<6G{EHKXs&*FH-ihl6y990I@8UU0yo&@=lkd)%%G#IJ`b@i;CD*7`)?9R zq<(@zw44FeO2G|I3j8oLT<-_oaXe417 zH#kEnmZwWlQ&da<-9Z}+L^9Ld$c!_=#W<)ghpi~A?iYrX?~_1{L>=fRGszu0|J*nH zP3F7_39G|`W;vQQR8DtQ{t~? z$Xf^>Po&@p09BX@`SUi)YY}}2n-x$`UgCPLJ_Ah+PEmOcXPmwJP?n^tBYBO! zHsD-Va}+WCNsz?!Tf7|V9J1DO*q@4Vg5JjQy9aD`uBPUw1FAWxSeDao6?;X&;~9`> zlBpcNye>oX4LJh`l)y&RJunTy#Mujk_<;V-(5xJT#6x z_VD>(L~fOn0o-RrV3M{Ea%8z<)KSwLrm=@VGw~+}GN#OD*3a_E>gDQRK>S`6T9M0$ zuU6Ro%#r|Ao(qn*8xJ5Oz&DmDgjmXc8`@lk4S{@$HJ&>uDAQ2g`EB}kIfcP zKOVsmnABYSzy$=zJntpO3`5Xv`!D%4SyfJMK4AX&Y>GznSY&yk3qLG&(>#gDsQ zX~w$O_C7C+6fUfthD=Id>s|gYNRWQMB|a6+^@_m}u`7QI0Q}sq%eHYt5oj=Wfv6!B z5;sbHYPPo~fvE9>{QZ_YJh@H^L5m+9CsPc@aZ9x&06{-o;vG4CQQ5+1A(9 z@y`N(kPCo#XAfI%T(!xmUHAI_nczQre5^brIH5Ur`)mKw8O4~KUA1T3y;%v$s>G;y zf1sA2L2@AWMiY`uMV(s@B(FtQpCA2|v+Xa#(=Eh#G=0(awPX42_dY|bH^sh0N>jCVLih964cvZo=gOxl7Qno+$J{Qs<<+C=8b6%I4mBS{#aU{5~6i%MQeNI%afJbxYTz6rd?5T=TZLH_cf z8I+_zPBE1tSOu2oEPxL_>%s}p0c8hVd}I}gc&xxq?!vWG#DAvGG=g>w-V%JR4V|`) zws`>NtreTZH1+^9>L${DtpqV&v6p2q5m{so_$=}dtr$|znW+v#HaDVin!8T`YJdRc z000B!lURaGvC6bT05a;WA9`3A@%nCB<*CrULXu{}o0mq>ylfr7~-)o26CXA1OUk1s??ac)Cx1@U}VaD&wR;qK#Q< z6*$iKCN%%L_A6-ef6eZSwYn3M^>$DlPTO1?Ya{EnVrC-MH`^zl4~s8@oyY_48CE63$nfPAYN9kqe)z5iusDL`Bd{e_;nufC(ApD;wb8yS86S=7 zmbq8=a;_lSoGM6b1DNSFR8FSYN+QP1vYM5_zH-eh>?Ne4vV*E2tQ*pA zrK>at5OgPiX+RI-jsbK0njok5GgZ-UJA*6xdtV7K)-_4#fNmbv3@(r?g(2C5O;+Br zA(I8z4F^gyVQhgIp;BL02^1)B#lN6cQ;rE2xkb+uG5VW4m1E~U2SLJ&lj6u(4nff< zl@}8JV(5s(CkE?7EJ~)O7nXGGt)3=(N3)F<HH9+;KSfx-3t?As9AzKyfLV(hnd*SzEOay>&a5L-cV+D6eqnwbryTR|{T$s9KCwI^Q zq8({QnLr=wv%sQR5_!J=m;`*T4-PC4qE`of?@aJ#-=ZyeB46wBtO=Z8sYbjhNXPBY zs+pe1Lf+J1G6D9`XGVTzQTqOyW1??P4I7Oe{4YqDUQM6i%LIUcI1+$|3&Yn_v3f|* zLN&$$JYl3?$gt|KFi`g`@&LL`bNL+obbr_1cnMgqoXKmu_EOd!*(2k+aLIf1&72D2-29%HPEju_ z%K2-e&)|L&Xt=}TYHirgc&mWRh7lk7g#8v^PjS(N6Tj6#cpGN~xHaaDu+DEsa+M3g zi}&Z>BY}P5Axl|bOB6QR7!Zm}jByrhThHk$ikr2PvZbF3=-uumoF1O>4ej*<7Dj^> z#`7YN0=~i=^CfaiNQDg5h$3UnslM_1P8DQ;X1daf3QTN^O%y`c2jiDP2?QG`W=&4$@c zP3CztC`xadGE(C)nh0zKBas!v3L;IhFS+iPi+i6gUV(&)uTaiojwP0*>vZQZvNd8E zCGYlSM^W>Bh0qw~gv`M1Uu6iOtV=I)v{9^dBCK?lNZwg|mR`tABwtz56XYA`&^4O( zaL_roF2Xo<(t?Zgmk#H=pz)YeYwYuWRqiE*r+tQiR_ADe6#>1o3Fdc7)f}}n(q&xP z;c<7qlew`tTHRvm(G7u=_F-K(UJNfv4K(2t_Q2=J5GtDx<7>H)T761SM00)A)Kohp# z(T~69tj5rn)6&% zs+D-{T!M+{rZwS{muSZ?`xJs>du3fOdUbkkE_?t@`=|z4vXHkc>fZs4V>8bhI zkdm@0)W``W$|Z}p2`s;o$%9;o>f9TG>A~<4Rv;AMMjU-2=--l#!po;Wb;OhZaZZc= zo)R)yXDJ+bug|_#%NJ;%BohFbcDgVg#(3 z9{SWx{K)Ww+9(pMhIjE8pY@ps5gH>UM-ptu-k8oRFeY|-LXy2u5)VrnE_dj-)OmI( z-rTj%(QliVBx&A548GkB&Kw|?`^OCl34k9Y6*$bX-6)j`Pu$W8(sQr|8w4gbxOnxi14$RFqK8ddJDr5G#izHt(ag3wGrN2k zG##|!B=uNEjiW%v)durf%u2A65r9vl0Cm=)u_p47gWh6Cg1aBSQraHum7<#l5L~CW zrS#zqcy(H=mbnjlI>kUBuP$uFZ3(rMIpK{V7G9Ks}({W?Surs(4dOuQ*HI0wGVT8q(-%mLe@ump^Xq?=!<9o*g zZtxZj+xz_P2X6{ci91#AuYfVvRwJYB>yEM52DtCtxAoJ6i8~Z*s#I zcsy6C$or3X0C)X1dFR~2|El#ACs6*nq20}6OKoV? z;Pb7of(9u|@wMMHBn`I^eMM_p&=zKcs7S8$KET>5uJG#V25yQkAoOronE(+3JeG8H zC)p#j4A~Mg7drlew=B5ll42Z99*+ZSexim?t}eh;_o8ECO@>uMoGyL#2^5mgxr`G_ zbzNUM-+LxzmN1Us#j9!oI*ax~t+&o}(PuQ8RGvKKhE}q=bW%m}Rz&B_K&Tr~j4*%z zkvj&g(LVNpLPF>cNJ*1GDWYfyqaM^FWbG&k| zKn$^7Fd3v$2FiWgjH=Vk$|X(`7f3h!Yz*3O~H&p0@ZtR6t~J;7RRZ` zZku`TxOck1#q_1p9(^ZM=R!KoZzheS|L2rU36{^mvv?KT@BM#bE?K)~9sFPiLK9^< zpeF)io?5|kv7G-)iTN`uryweMnG6E`%`K9e;~>rYwNsI)pTa{rhk8}t;U5Opog4fk zV%gZI!q7n-aBjWag5srSIPw8~$Fvg7ol$SIQFHK!N{AHfe(-X<$rkL&*UUXNo8h#Q z{w>9AMw;pd!o$o_!IhJ2|zu82IUH624jfcvt^-I%NO09j&~qjZTmj`n0fMb ze3r?PQGK=v{k0h$-< z$^hJ^E#vSl3Y{oGYmKQ0-7qr=6ge&IB1FyHt1^3cu-x5+I@}$HSm4_p=3EL|JLzRj z2^qfm=3^#-?^qc=;SE2a+=*U30RONn6z1p{PV#xmZI_XeZ`y(=3(9aU-hQq^v$@sj zywkKDJE72o5HwkToV{hUM|MLsK)~;aXoRD0(58lJ6~*pX%#`9Tr*E&bcodT9qsCd(-1Hb zhi2H$DeoQ&f4PmZgy2+@GIQfh6)~_ zUH5hTe#Xw4wN}ltu!*FTw%^m~bY!I~?uac({{QpDXpiMQ1sP&hV-aHquJUgr4f(Hnfy zm^L7vx;0gZ;kVQqZB3ls5z8X5w0OB#oR&HfAoive5L4PH{Zsnn_|AY|R9kkO6zLR` zgizKcC)&R^g0kqlB}RVqky+EWcEmI@nL|pW#*IFXXh4K>U6Fcp+L3+hBx5uUciF?ZVogDtHQTjm_;3K;O7 zM?ILlqcJ0NH(09jBMW`XS8Y_Sn`SglwO+I2iKEE$X=pB1dYd#H0VWv6%j;@}_3Dp& zF&L%dqFykSB(c?N48UZ|qRs4c<`hB1@efzLf5}j9qjt29K;gFz+F7*M`*An#gl2Vp zMX)PSq{@;ob!z2fCDm)(yJb)H!d%*$r@%7LG92g-=7&TYknIoB#?e1^H(sbozwHcF zh(+I#p&^<|UNba}QJhQ;drF}C!O^W6-HDG?^JrnvJP5*L0WqCIrIH5T61kxe#y>`U zlmU{lX$L3=1OkdN&0}M#@ve4O-%lF|PZbxh4Yg`}$03cft;LB1XCkP9fTx;9^(mS) z(`$!ubdSAHzRmcftW6tzG!d_tFjDk}(5j36Ckg=D#_NKyNU6%g)^QGz2o`$u&DInm zP$^a%4cLDPI|jMiQtX3RpeA-;Q;8WLma@5VVoufZ#{LHZ+MVNc&8h?Hitf=)pGu%y ziE)K`{5Xk=d{U9gp=Sm6!oPL>6qc(xLzjl~r%=|7YMOJCLC8Lw{u|05&#WYhmXPIVBNcV;MOHvL08Qy1%dL<5 zKSdpcNUk{Pp7}iIay_w0R;mMS7_zM_K(L3SWo1nAV1{a*R@a1i(yz7*3calJ6(O`* zX>(_*VyY??i=L`2$QS5k2sRm$o(p^srH#(~62iq4UVh60UTAx*bT z#^VFrzW(UT^L0uiN{F}dNQuqA2{&D_ryx|)cg>D3}Pc)9uOrGEJQq0 zTJ0j`f~Bw#W}q?=moN?K(ftEO5!qVHiP0+M;bAWv6EPAqnx^XclC1z2yafl+bo*pG zU5{su>Y(y>;}<}`^V|^)S$F3i8U>B!S0gBzjkEGEj)02N$9v4*h441!JZln%i2!dq zi#(X|&~7nZ9Gmo2ahf=NIZEaEuw^kk$ls6@IOyjDAA-gkb1|TcOt*LewgE+ngn_O~ z%kr`GSVN6mg~H$sxM2G;sDUrdL{F~iUI7zFy<&OKnCt9)Pr$E!{%pix7d+5Hl;Qyj zR=9*gwCpL#P|07AngU@Zjew?YaDIaGLE^YT`*uI^h;j6$Rtw{0$BLv2CnC1EjSwT6 zEH*>=4UvAZAGG?RYs06S&`f{#zY3L(U^2%r_0vq(!H3mXOmYN0;G`f72-z~kRE#s) zx7rMv}3X z*e>fXW{bW8R`)j1-&Q3B2}Hb{Jf|39p>1vOE!H0!L{Mh|{e~kGsjZe!N?n$sr|ZSQ zl)7G;@i_rBsRcdW4J!fFUBhhRn@xbO38h()0O^S_ z%{`Q7!7DS{zySVzOz@G@n09U5*ClC$9X05VjVfr`|1utKSjhDP#r=dcY^&M|K{H%b z_IR~}z{utstFV5lX9D(>-G;-6O*Qbip3Wl;`(MOXA}tw_IpBi<3<`>Zr9d?>&Vu*_ zV~>)ph>xfh(_W^n@etVHuO(gbuPGsHuDya~a#*=cmyq+N=H#$1{URuG=C$>?zyqjfkP9+ zMy_WlN*sR!Wfe{f4Bpn}1Xn3LLAw~?(Lex5NVU$V##(&v9~eL%LJ0ML?5~Ub3G;|b zko6BxHZ!b_rK2**{s*^#pw#j5qI1TF_G%F2)mzBb zx-hi3y+1_9toE5)NlDo7*U)$P(FbCK=I6lR<*sK}TKj_v^7e$4{K2UKYNY3{EqwQU zQ~T0_yDM@2a2B@3tHBb#To~!#@U*7Ji*`vSr&_hQnl`5_4NGg={_aPSRB?i+br&g6 z0AL!mp_7<-MY&0tWRax@2n{_xb+rm*d2}S6KJPLz zBu81LeD^$gwBd~E+aUQ^#xaZWK-+EVl$o0c>w8L@BP|3)nHA*`>AQImH&>}{Bim2m zf3MMzr_M=MR^JYO|H+-pZ?OI$KIkIVI29m?e@#O&4-i&j-IF6wRJDJjzDjdFtNy1CIlg*gYDmVWq z^XOY?O-{F_304WL^G;Cxj-*hM)tGMEX|pZ+%E>(mlAS>n_V9C)1(oyNu4!1E zKnT1{?ji9kuz0Sv&zaSo7|;n~1gm?>bkwXq#uJK}#oeImlBYNRW)*M2h=jfeZ+@bo zSThuTgQNR^@FC>3>KHB^?NX4_apQ-hKHl971=fCOjmD}xxyADPBK`EsNF<|GoEx;= zt7kJN{@W@i)V~4GR#BsSg+L^h*;P@3QN>1T%}wUfa^(rQLPB_Bcax%f3N(r^pBLJ& z!Jm6l5v_)RF+MMeRSH=T9S^A=tFX%>dC?xiTYEI}@x zM(MrX2LiTvZkW;1tK~Kwglf<2Ju2i5)$RJu0~bGADb!r;7t`ztXZ@nC;=p&Knd{ax z(~-G5s7RxLL2BS|bd;($^QawZU!CMd6)fjzCCyOA1ayk^E?psX-Sci}Cg01Yy$$;4$|LM>YEX?L43I-+^Sv}|;B- z2R`Z!NEH4jjqYtsR|t3Ed?Z}1N9%!T$DDhvi+feN3U+$-;9H4c)OkoehLMR80DK)n zUoduET%d|-b>S@!5xG~z7L?Ctr;E{Y|{^;-`$XXS?>e*QHpyL%}LnR9$LCVh zeWiD41F_|$9pI7hPfg;5Z!%BTl#jbXxqf(v8nii2Vuvb*1aW46c0kkGrN++B5N6ji z@MD0k10NI;D)#Xb8HZ3F!L%qKIZ3{eh~B6DCdEhQK$C(L6PqQbg&K`ll6qkxd#3T7 z%qCva*E8~p6Ksl}0agG|IXCbi3Jx+6#?cS}AW~x0g@6&-0vjM9by8w$fHge+t&$Z# zAPHOoMo_F0qU{m8M!HlpiL-Tha(s0JGa{twO{u&hTuCx_ZXnKU4s7&?3{_65Zx;H}i2| z(J=hsM!j!Q8L{*67D@Ny@?2cnXXF0UXSJN2Zsy3`Dew?S+4iLvG<*8@LM)jW7qU9UdL27S); zdZvz-7C}BMS)W7nq*SiL>|sUoz?*#yi{fQmjQqlbd%uBFVB6Y*C^0cdyR~pV2kFG- za$E*oKgHZ=%`~uq+Xuj1JZ(I95*kvA1Cu<4e-r5UeCoAnZE{UY${B9`E6`l&5`zXn z1Px2_zJvaH&}WX2gb5*Jk`ODbC72ZDWxNr?F6z)-kJGhcyZ-@OVo=>o@4q zUR3{EyI^&T96ddczT*#C20$z4s*F|Bmr6lguxlS5^kODvk+J7dBeJZNPgtxbPVd6= zXKm~;kv`yWPnExj?M)w0eZ=Dd&^h^rf9==D=`Y|;NJz+N-Q}HGn+MWYY$)ITJ|L<} zGe+cE_v)g)&ExMtyG3PoSQ;o)N+Jesf z&Cfl(#0PF;^x^o?Rng#-e?5=tTHuSg0V}Qi{&R%m8g%0u8isBmB-v=D@*v2)>A@vy;+yoEtVG#|X}9(pEpr6{72c zI#UCit@eaCfOk0tnw*^jmy!jH<~TFVZB-2aL2@v|{SFI=6{Mg=HD?v#agC%$;N(ch z$Q3BKrQfmuVsQ=FdTU$*G2_as6BoV|KJGg+UJP=p@;)@mpS8Wa>T>FpYrCrKZvilULi z&~;$os%fEQ3<{1Z16=Wp3T(QxrB#30ow${V0o;EXt`Vq(NAAc!@NN<+coEfaM z8b-{F0^*dB-zR)uxidmM`Cnx{jV_%^Q)UpI;$6_93qkXw?vp`E%=&wI<(r1%hGw-U zL+iQ{=KjD%5eB$3hAX_Rj}kWUt~C53XT;zEO}fJvA*Jc$MMZv}4_1L%4nZT}Wd8o8 zbA(x~W;$$lF%I=%Ku^J>-{YIU@66lUhQn(%htJDZF5lHyz9CpPb1I82X@UJSuR(UJ z^y=jNh2ki4Y{ps+{cJ`;@gdfOO&QEa_XjeM7_IfxH^(B(>mh`G{s&YQg(&_c4pSzi z72dTw7EYmrXmUc)#-CaApgh?qz`axmcAG1qBnogFfK)z}nu8<10%jY$kPVX;4=vd! zi);<;x3i=^ex!YN0|H8@*#o}aq@If_tBiG(*oTF5&5M!^erDP=>+(<87P2wbgB$RN z;2@Glh-Wd#Gd@Hn#&l-2C=*N08P}cUCgyDd-e2^oR#zPZE17O-lNNdRZitT^zrL-u zT3#U&nmX&B;=pScsG=uJ?6GGBcLv&oQODBCqk=a3t9IN!sOVe(z%BQ z)@%%gAd%;X>7UXb3xk0B-$Q>`_PT zPRk#MbZZJiFf9NOTV%7(@_n5}fXBNIy-~@AePWbw-Lm12(9_blH*f;G7yIxH20&L4H*Q3rFkK1*?a!3F2Gng*^T2;=RJ^ z-FPD9cl|3xk@>PxpUhYC_|Aus^uku|wMmg>2%8|(+6}QD@%2ZcLM8n_X^bCJU8X(spKrINzrbgDTNP!s<0R~TgQS<1-{fU zN1dk+ClZ(4itvr!oJ*(_QXDo-87^RExe_Y(q`LHFd4^Yz_v!K%3S$~h$1i}Pss0@S z@Qyib@cVM21yg%2Eo1FF9|C{%LyzcI7?a!YKFQ932z_c6E(1FM95CLsAb#n3G#6+5G3#C4Y;DDfzFfu(M4i5W6ZI9Cz! zk|Cg#=H8j-OzjSzHM^BgWffGxUKvqN2v)^^S5EGK;j{6(Cpt=G@@ir`k}(q3w~NT{=aaVaEl%Q#5LzYPsO>x0O~2Tt39OYm18a(iSwVVXR4LP+o0r*5fe&O6d1SAhy;KG&)$u0%BfcEfIx|xIEe}f8LdNQQ2dLrNI$0Rfo1$5~!zTbEJ)<~zxHf#i{T3-4gSn}E z??4gl$VpuoS`|W1NFEKVn^GvUdaoKe4Mx!Km8Tv;+k{u$eQyT)$@6Bqr?s@wsUGW5 z!ggopX#h1ZI%O!CL~T~=eDP^T=VZ97{m10grud&cSg8Bn}qzg?+8knR(gbVA+R8ESL8I6iRl4wTrWk*^=1`T?=oUIP`4nkQxm?J7BXbq_1=9VmR)@4bMg+kCwTCy^I!S4 z%rF21mae!c<^aYBh>__7KYO;}n@lkfDnGVS4Bk?J?PmGa_qVz!`l5Hw5;7Bn!*AQYB)N zQ`YVq>T`rnD;2252FF+PegQU-+56&@ylXBWWFh;8-=d zSf1$`F)?}XXoE8e6^V5$!$w*lp){jy{H+gvta_@SHxy-ggnXFq2XTU~x9iymxW!QWVHZ8LBM&Y(FogNXe#D~i|rFVS9TujET5C2AE`+jEER?~amz zizZ#am9mSo>yh*z?9j_bWZC80kH5v`e^(3P@~CSLaY9$~6(s<)*wUY3EOZ@&sAE6k zHwBksQ5q+E;y~CtZG-;45wBsOyV?ogjkeq?;gwRF-0AdV;&;8o9J0cz@OG#)_=^Iv5obWv_DNmCKAs0s zBKPR8gmV$$ISW1(reNGqH(+|`(OZAmSGa1(&uR~!P{3MO_|HE?6S)f**3$GZt6@GM z#JdR@q>VU#c42mHC(l z(!w;PnYv6FK;UVf=6tsUPhXFS?1YgtM0q8q;bbGzsMbg?@Y$6cCbxD3XE^=1;b(4H ze1M~@i6W!l&55@0e_T#Q-ih6-H|H5Hpf$zHLyn)WIfDevdgjW>AzO*Jd@xUsK zs`T8CH~`$qDh_GUH{I0hUDQ;L#I2y3Qm4zIZ_au%vBH^#56cI^%cunJB~--FkA}pS zBW~{9diqQBi{-`nLHZ3dY4PMx&i}Gyni@@g-4@5V^ukZaWep)Lf=3TdXr^$Go#z!5 zx%|tGRZ>N>&AD-ed(A6RXuANk-kSWVGxIFtsMlmZzua44EvEPBx_U3mQ$k)0^LD&oo7tpzTqh>coO+fhSVCszT(o}sB;TAa&;sQtduPe zRk?G;;x*Qm?H*y`Oj~{og{USm)EDUCQ-i~{l;r2Hf!GdmBxodCRrrOncd{`4@l}Yk zK@N68#&{_mALoZr^HGlfR3vx1#*qWm#H?y{ezepn*VE_z5mOlTzbyoeA zL1kbvMKexk7zX*RlgV@%d>Rb^yk%(mRJ3SJhYPKQqrwv=&%N@p1~bvoV-aK|T@-B4 zPSLKVw3meY?g^3Kqdhj8fU9$BY%+&zx~G&D7#GEiZra1&pO7sA=@`JILMCo?_SXM~R-Hyt#3TKX3M;Qh`AtfNtT11Y08!|OowEcl5Z8RDIUqU6Wlu%{i=SH5XFWMa+#VPYSpH5Jk44WTsUi^cS~B?D&X&= z^M2N28$Pk2N{d4VT+qe6sX)kCGOlfm5GiVf?K++0fb+KbDaM+QNu*HwUBsHT3nPzjC6QZ2k%wW+Zu3L?2y;w_qqvI=W5+=0~G zML^FkrWJoW%Gj}H1pqW(kKCwY6qJayxbbB0u?10{^{+ud;(oH{V#0og_cnf>qpHAr zSS-))aHX}$|HI)`1e8X){{bGz^)3Bhrc6Q&-Pq6rN(go9cP{-=Xc$O~DxOPuq9r~X z#_cNVu|_$>O3yEAm1(#0dZ=O~+B7TD7B0$~DY9F!BuO&LNx_;N%GpRk_7S5KYPjVw z0i9wuKuDvt#jTSWX_DnubQbu%-$IWA*EBJ^XWrD~0x1rrvc~pW?Du1z^@##i%t=u^;Lp1qUBRK*Y2=qp)j7o8#3%2+q}CFBn671Fm7TdG+H5q4+Es3^o^|Kn7# zWNGt<-$mIL1ha~A5uoYMsLa<2ndg%b*^}d<`s)4Tx>s-sy53D&V=<-mPvd^HmV6#T zDeqN2L432y77}-l<+>6*(1HX2+&G0px^|&tk)%7jCIT~&s22<=xhB1+O`~iVGq;VK zEx9Q>H$@2b-^jB!J3}uwv6!j{ER1;)afj_luW5U3J#hCkhwCCBV_-x+Jhp+_gxI z+2QUXpuJ|~Ob7jhrmUxOF`9BE_-YNk7t)2m$5!PQp~?lbpeX_2Zv_|+yX%wr00X%F zr=&KKPnjp!l76+e^l*1K{u~Yx8H8RM?qGpGGT!Eh;uia#W(oW?T*AAZ%W<@_bU>`X zvX4^OG(VU=W}a@*$OR47aGPL|DgtM&fwrb86c-K>3^Mf2s^A}OfNNm^nLP}QR6-8g z#QF-@fneCu7W<-~P)qnJZ<7s=$9B*-@67OJu43fx%8V?477viGJ7G#U>Ut-wBt|~# zujH#+48urMw!lsHUM46Gh8GE7&);9F+9ehZ+DKz+G6Pxt`*Q=g^UU>Ujkwp8!mQQU zZC-_4-a}uj{JVptCtMUnV-D<>5L8E0_MQbPj7b-a2{U}CCz@_^T5`J-iH6p=w+{_J z5=4T^j^$hc7P4u%7Q9alCe|&c7@ir>T6JqLWfkrPd8pg~b93N9-8;ii7C9S%x*EsA zbuwb!QTw=9+OT1jb6j+t^jLiG%)wpuI;z8l^8cb?&-?~ErMPvVBsfg=*E?8QlN$p; zk390u&A(zM#z!KG>ZxQAfsV~+&A&sd%3Lxk)X26b0l!R`EJiikuaKlx1OGiPyW*s) ze|xOZOfhTw=U151oDc*w_kXBi<2bF-xr?-=_P7Q+Viq4i(D@^Dpk!SaP(+0?)K{nA>r9@UVuZCN8NqvufLvp%LhQC#z=iPWdz!20Qkj^&yt=sA$J73%}_OESgeS`33q z)mbT$qz*z;JKAD&7zXBG3NOOy3bPwOUfL8Rk0{*MS`p?{DfqCWKB-D_?@}X?bR)bGB0mF2}M1N$6pb43PQ!G zDp9SDBH`AG?t5Q}kA0X4!#ev$urJL%UwNB2V4vUU>33@uiI;8cHb{|@EJ(Zt9ZtHI zxL*VNt_B=h`~+d7c%$o}`V#(5mhqITtZ9&sb(=Uc8?=Ed!?F7)a5~Gju&D)9D-@W6 zvwH2Ge_hoVDS#kdVvib+i;U016rcd4eiER1h&d^El5?VsBbvhzSo9hjwUCT>N*3i< z;4!85OqsHFSM8hx%0k5~&6~tQN53*@^pXv_fxSTIsLjUXq;*Iol*7kbAl)emv#%YupQf6n9yu=%a#ReSX2i#AvG5Lz~MsWy?a znD9}Z2{;nOu}54XGc73Q3Bko;_CPjQo(=<#%q?{XR5)h9vMU3j9gSI?9oRDjnL4kW z20z(Zz7o|Adf-id^-8LjDLONe@I7fJn1+ujhQhJ`b-oF95>CNH+ddgE9##9YH8{ig zhJ{APB5_|ulD^Ud*lFEeU^+0dwW<(2eum`3TvIlwxnVGn+rRKsk1u7ei6G9|+WeF* zV2$hrGAetH+zSR;pTg@L93f+R2-2huvj8n7uh~yar=C+vLtZ-u8=wjFsRk|3WHzO1 z4#Ic56|<8lN9nqJ1O*!onAfjOi9F#ggWc%5W=4_M$)WPxAb7cTg8A)dN!+1~l_j{O zF>!rC7~c~)Cqt~QUQ~2sd=_9%kll{_8iXS>D@8SwiugdGT@NK>zyJV}B6(b+>k?6SoPz^(D;Tcm_cc;GKPu0eZfc*5CDo0}(IpDgD{wTx->L#zmPr$e> zjWdDpkHGCksy$iC-K3HtarY>nHWIdo_eX%T(TgDe?2l z>pY?}WjFwq2Ifl$PovhGuKX|UB$ap|&@y6lcs=2odyExE9t$C>`N3=w4imX3d9jNDdO!nu5=2E;p8zB)2cja0lLvwT z00Bf0w^6&al7GK!O$Z#)nLQb+aW?^H5<}OIy!HvuEV*c&R6gGMM|zvVsbE*cD9+ir zCVpFemxhn&6T0}MYEF7gxk|;pZ7a1idvB!yHI%r%`&&K7b0O*oKfZPuhJH=p5l>Z8 zD;Qz6EAEMIMIMhZpRQt~ks|T?d4p_`a$$-0=}4-%#(9-Mq5NzAsgRlZ-(#0|Y+s~r z{-TsH5y$FE-8_6q_Q_OL8{^f$s+k04#MO3;n%ls*rS)IeJV zdb($7j2rmnv8C4X4Y!t5jp|sKLe!LCGt}i!S6shSZ}omG2y?Mf8dR3P=*2M2ZX>^i z+fV;~S!Q2ZX@2udgelEPJ)S%%>v=@cS5r}WSp*{0py}7Di2x`dyDzA91Bb1fXLMQw z^5E41fMQ9<8@R1EmCB3@BO$#3$yPT=t4alYk+DloOofmn3e+ zCs6;LJvX4^<8I`=K$>b}WuD{8nd0_B9kFpdGOR#Qo!lokLi0}1AkP0JFUj66;xUK( zHC5Kpgn>h+d?5?`v!!NEh}@W8?mf23#rw|QNqe257#kU@{xm(T_v+e?!jz-A2=^Lg ztgs+2ff*NMBB#O^ztF6HelP6gC2r~~JF`hj{Z>Ya!f}-{d3N3@$Fd-!VkPwT2aYQt zfr1m!g{tMalMSRg=$~-oo8W+MF5>`gA#Rg#gH<$s10g{1U8oI|*a50~--b|=05$xv zEfigY+4n|Eodv3G0?QT8oMC8>HfkpH05t8+eh(icbZt_CDBt!KL`4kSmb~581|?om zJT%6_`A%w{I57k+((JC9q<<9zT&uF46%FuS#M$sB;R?8dERJ+*^`(b*aLvDR^QNpi z%io#aUvF@bD&N6y_=7{W+Nen|$gBxpi_Vtd=m_-#Z0_a%Z z-?aHn;I#MHqYY)7FuZcJ;C4)(0gB;gsC~aP)Mhk@h`X1NO+||2u=Q%u!4TO*#D63L zGAoHu(fO_%4R<4X%_su@r%H%m;1MyhY{A^1dK<#zL6+Dv%jSk*Jv!7gFXy+eQOF_>pN#&UH=I zjCEKZWRb;ZfcuyO)#JCof!>U{LK-Tn!Fz9t1~8vT_Z}5s7{aYtXZpDoq;lt_<}2qI zIgpWs0#=+8b4O#04Sw}|!CLsE|0hN3ze<-8wtfrG)G9{IQZ2slo>3)^={tD`hOG^# zB-thjO>AS(=x~`?$eD%7s7*U+$OttyI zc)Yb2-|^S@kvtjGX&e|0E;ZD=H6~Z~HIe zsidEBY#s+nFw_g!;JoNIdPzV+f=}2WLu@U?QIFqYWLDW`UKVFa5N0=NptD~w|*Cd>K{&YgP<)d-A@BZNRv(ig- zGb$&KbA`bTYH7nqP#vBvR{@&~J9z{bd~A{N=}G6S?jp!luiWUyLF7N@1-Y>T5H7m= znMH@P;*F|lhm5(Z@u4EhjCNU7O*(}T{JMyP1eJ~4n^ausHWhG65J*gW30{hiBs=hH z34obwl+v#*?a(ajjhw-|aYaFapC!CToCH!=X;kIv4C{p6sMR$rY=W6VkKMBU0bQkL!j;g!;$_I_;Y4heNOaE?yk*89v9;*R96FDkOHC zQ4B6$TPkgY-XWuNqn#N3 z7H_my(&36OWhQ3F`gDbZjMv0qOxo2rDP7bl`>&#Mkn+g2)AqLwQXD${zkm1t=l}o! z0EL1!f%4B6FnqA%jy%zAaU5c)#}C9TIu)oCHx-a!p57?Gd0S^NL3U%y9^9LKWRQOx z3S39bzl4<-IQqSYSuq=nE+ORLAvaEf8i)>L1->I#h*|BtS`32qihV6Q{+b$sl4;gT z3QUTuv8LxMxVP^!by1`}ympGSj1Mo8!VRcc=HK>#`N!uu6#fvtB? zqb?-r|6IitsS4Nwr2~HH&}igG6iICa6#pgZ!$!8xw=bSb=qfa7&>B@E>rkhc_6Crl zJBz-3zfCX5w=-X|)I3RzFlg%I|Mc_`urYqP&H{hEQ)ykB*gC~5F%+_ezbe#sf*tuO z-yJC$^`odRfZSyg#1p@+NoAd3){l0xFhk)(y>@s)3#-%Xq-6zMm;r#i6U_(iNl?uC z$9TTm=v&X9yRW4xqtVp==7Z_KG>u~UMdDI=h3=GAvMn$1xrUbBNj46=pffbWQKQSX zqUQXxl#$NW3`s!CxO;mzh+T0w2O88NG+#o7O$GKk5C?yF#vvi=2g2{wh|e*(+7Lk^ky=uo+VBna3cN!J#@?;J3giB=lg+v1=Zi33kKK z=|dQ9sBOp&9c>SbbFPHoyT^k;33%?oRZ7@RYlL9dgzHs<=@d8Kd2iW&YOUQiZ1SNQ zknl}~e0{~XOBaqMjl(L2CJmLf+tY_1qkv0x5Kx_OjoKXhH>auJX*=tS1$si=_sq43 z*Cv^B%v+o+S;f%}&YD{IxWBJPio4GE+@K@Gc<70Q%8LY~ZQOx{^h8{^U~e2*k{E)& z?`c$W_QP+du0=7{N~Y>TNAjmF-|K9yBvpc!3QGYL`i;IR{XMOT!kDbRFhdM`l;ESi zfq0SchM=RTLHK>Lj+9R$1CsuFOt+wqOLC83*Qx#wq=l`1vdmHYGXAmBIJ(%WJ zRm08gBt!gzygKm7c#hlU~ymZUXdJ*L0mIv3_XIyiFM;4m7O1Pg9iqv=*FA zA`dESasns?C#ZMy=lhlP0Ry0za?kd7x`AIoQW-&;Mt0c*J(`(01g+E<8R!WVV+k;A zgs~+3NpiRT9Y!g-5d}%M4q3#ftrW{z|IdQ=TW@1rK(|Gv zMHr%XTrk{#qnn5gtxm(YZL5NVx|?dfbA`dDRc!j=tZkAQsuO2{@x_j@THFZ<-R$x> zM0+MLlh1yoVicg7ZqO`H4h~Se|ZA##n|8Oed4g2_{8eBMd@ z!UcrVVJm5ll>QBVTOS;vFa%R(zx4;`pqu<-C3*u*TmU`u2%GBvZ2?WjO9v-_H4D-~ z$bw7I)E4${qN1|@$cY$$M-J3@%S-4fWA`CDQBXQ(rMDk@&~(%x^_#?Lce##TJu$?u z*1wimgX9-;D||DXI_7oT(qZ}>`aLVfV@IE(h_)yQJ>6oU2ZrFR1>dOg;lpBe>r4Lk z@sk@J0phkGbe(0c)^em7;j0S4Nukh{hHVBGP{0k#rW89 z9YjNlc-_x~MU%q^Wdn{nQG{Kdggrz(X9e$-3+4d_D5VCWES zW9~g=LeK0C56X7`jXypA70M6EdsGaeMZQX<8OemCUzxehJQdyec8iirstbb#7C+cv z6;|&#Z2a>9R^0e_Xjd2nq`0P!u~=qFg!V}&z2BA&UueX0UE{eDnAVve&&EMV2vKVb zs{jB_Vp(IHBK`p+1Dm;fN;Lozar%%@E&s2)0IM-yqzo$(FUmJa*4YglxGhtsV0-ApsTK$iZA~QJ+7-woOoQA;kXY5zpRT+WKM=578MwGzMXw%`9tWs+9 zRZFpHsR%uF+U+5EQCvu?qF|(f1FqgzV-}~IX1zsSz2HvL!xL~vzVX*P59n-tBgzX@ z8xA`%%t0e?h7C8GKpNm`Ur;Ng`-U#o+TD>{vR>!I*E(gQhVSw7o4=oCCk6|M)OJ_y zt0l-g2LaeV+|#x2bHN-j5w~^bOtGW8E3q|w9MT8JT6Qb->UZ}$JufOhwtWZmDFe=J zLfpTuALBNeoSFe75;e1yCF0~q-$Lb<<=0q$v zN(R}dv!tDjUfUZ+v61NbE&p%ogg@6fp`hONYi^ga!_HPk?sdE3Gks(S0J3F)` z$kLpIR7rlzH~_8yj^LyNEv&c=J+eQA5L_U1q?Is z69QY{?X$SE#-ZNAtGnErxPakuuqWPbCQlX#@_`Ax(oE_-NZe?^&1(SA7{Gb1XvXyP zW*<6*Ku@HtZ5y9mTDFOsqce$s&T1(RB;o-Yv=W{T-48ln{zvxU?*<30loCXd&ixwO zdt-yWG9GHh$^VklHydWvXvVqotyIrmm9?L(Q%7eTp+MR-JqbT5Ha}5JArH)l_d3|( zC}}4NY8N$9_MJ_+25oOm43SSM8R+>FqEj@yFNoqC7}h9G?sg{d+a2~j@xEilHzl_v zU9c|h8a}&(;pMlmE5Vg7L!q2uRRxO64R3){a^2e=p`U_6et)&f)F*kYwO;9b*(ci5 z;+voBf*P%H(^BeWEW~_V6mT(7{c}6Xj@{oE67UB z%JP2PsF0H-XL!*U4HuX2-hUpjYMtLp|E10jM+@=tB;rw@Dx?0-1_+<+h?q~*Q!c)fr!atIUt z;$uife%NZE&$*UW4G#4PddOk(a|y~pv$KjgkJZTYwS+@M#c;{^DZ6_v@}h)}qZOfX z;Orypl3mvj?#tBsiY1;%E!Q;5!@{?rKZkW9ZmFCR93H;>Kc|?`GviMA>riSAZ~z51 zkm>TXkMfz>TXZ(-jc{kev-bxz=oXE*2Pau=NKOYNY_9DNjEj0UsO4G9oam#b_~9$T zP?Nf_oyQUUP+Zz>hYOc~_^!!R%B6pm$-)1#?dNpEEV211wGMg%~gzU-|gHjXogS9LPF3c74&% zVqnE2Di9~gue^6|5cjJKH4J^)lqQU6zzrlG-SYfQtHWu|k0_a4{uJ=;@slyY?1g=t zF&kDp{F!t+>L$^>6NQcK3F&QK6M~UviLwn_QgH6(xi!&Ala+%3mDVqoU9ab>e5>#-Je(^XTGc zj>U5!STO{&xWnrcLP&9NrecSZoRUQQ<4KS2gbMssnBN=ZMo5Q)jzRsfyCk=XqMU%C zu$=mPHj!_kyk34&H+%%HN)TsDPIAvQ5MiNyFG9JNE%D&}>*(lWc(f)=Uew#f^Xzj! zofs*#SnrJUr^wKmV2WW&rc!F_^9jr3hoJ;@{@*+3dGj$(g{=PvNwxwK2R{?voyO)# zfx(m-?2Q^4MO-p-bE>q=2L26EN!~92A9vgGIV%Mkb0)>9Jl2HA-Dh*vsNP^)o|J5m z5=@EP*c7E(9!6JDk>xxny2jvUU~A_1=**04GiW#7o~-Ma(i^v}Z|PcY#|CXGL&6tR z9@H+N=)WfJmOBg}SZqXm0|D>LTx#As{uIz)T1aF`%4y^eLDo{RiUjOWw3%Hk^)B z9`SV=jz2QxRsHSkSyVMg34)V^+)NxW)dn)((^+g^cd8&qsBoEbS3a=ifZU{blw=Lj zF(&OJkEA(Od6=TD3hKGl!5qQuP#WGEHvIM$Tdo42A7c_TtD$Z^F8Zn69P}obsHv{P z+@Nc3Yt<5H^gI9nVZ!+ccRVJWfrAruyb{gB=sB~JP((p;G6I}}D>|c$?gB&yo~8c0 zn}#V=D-%ZMu|NyEI6sqUL}9#Gt#Flz*XC%0Y5A91Bus{cIuLYdxI^RZ z(8;s;S{+9A|M51y$1h7}C7B!s%(b}1LAK|9{6d?D3Lg2Pv62?gX60d7J%FI+i!BHwn1Kt6R)1OP>gIGVa%j(_)Hv-^Gn|;V%*<4T<%1;} zctG+o>zoQdH%|!8KxXco+_`$I^rS=i1W=CQH zm?Yf*kPRyiH{fpFgWPs(s=`|cC2r#ry95nE78)brIMoe%1S=;tpceFu+h+VaZ>}oX znAc}Zav4^k1u@}*hZGwG0ygGwLa@t{)qjL)pg78P0;w$9qhRy?rh|S3dKDhylm#H{ zEYbZM^b5~3z>wuv8&P)nGQ;<|wgvO^7N{f43DxM&w7oVn>LZVJ@Y$l$eik?uc*f1x zlB>CC918n?FryH+Wo+27=4QU|r!GXGhU2P@S%F0WCEULa{xHDmN*xchM5JOW`?~Uo z=^TS7rI*z%?R^e?+Gyw4$q&3>Y2T!0|KQFNI=gEA(R_aVIqv^;Db$9Cpk4iRpkV87 zKgAJOV2>6?DGE!8tMNhdXycdcjpd@T`+Ft%^*U3jri2EFe`;@&&vaYKbq09r4BZ5Zgbo<k>;zFx*RaDjD(wWtJ>Vq)xQ@B``kdt^E# zGA=h3fzje04-!qvzRtnhR-f(3ML07N+}m8TyZ5|PkGLNG?Mol958>krM8x2ZGvQpH2Qejr;g5hP0MFj?z^F4>dPbC4E9Apqq%`v&j^MJ{69)mXslz=;`s#56 zb@+dgXuZ&z?W5=Sbk9KGU?&Rl_Lq5ETfu3JRzy>nr~n-aPoshZ{-V|>}92RhxMcQ=~HCMGZ$1)h-^WBOI`yJ91y zJ*u610?JWmosd}ru63}R&G1(;L{5;Ru^rb!;Wy=`-;x7eS|>0zy0*Oi=>)wJ|}w_yQ!E#Kq1Oj?~X8Q!<8qOI{d>wG%@jCA#99x?aWsO z`(Z$2nvZDKF@|dLnuYu+w{k~N8wm&~uz-*H=q=0{!KU{*`3rr9Q4d*J2ZY6}#5Mc5 z+^Q$;s{5qtOaG8wi@*RKbG*jFkE;gTi{U1)ts6ptj+QePHMjxk{6Y6B85B^fxk!3* z25_EmWpVUYO#GT4hZ3Jcm{>1Jjw}&GiLVsG-oozB+6b=|)pY*fzi2Cjb5~5OBrAZX zRgb7*=IdZ&902&JD!a8a>qJveS4tdti1lmlU(7YJ>5aUzN_L6tVp5)SuxgEl{lfD( z%&S~Ol=3SSI7PHN{K6>i7U*K^On|vS*&GsJ@f_5vgQ`# zB4O2gZwsIRfIK<-bK}+GJ^(H@6^_ld^c`k5N&2pgl{}zRpq2bH2~QjCgAGtU4|T}Y zq|>%Fp-rguMTl|!GX9r8?3X5&LdZCl_4f%W$9LI`T+sxW{1Mg%t$#*wAqXIT@+Lqj zc;I`U;&4^FNEBQL&ghli)bLEp?*H)+B7}9mZJZjLOD6p|~d`Og6{V6tlBK$7{hOFUpn+9xSy7(+>>oX{pjDq{2| z#MidUD3ug}NYmsQ^NQL+*)dk#xvy=hL_I`!1afWkOWvhnAvmcjCD@>06+kB=>IRWK zR&aVqCqFs1`+Lc|kUG_x8eYF5ohp8CT%`99cdJ3kkbfxRjB>@4J*YnCzt(Wf?pu65 zBthpAggXLrP!B$WD5W{;N{|A@sc}PB5hPSdWJ6%-ubS9bh%Zwgh^Yy+z3Sg`rTnHP z<}Gy*x0g__{H%v^%Ll1W9@^|?vhowvCof&xMkZI?GfK@bAdCeD|H4l<8#y$un;4R3w8UeNeNl``!z&?9yIR z8pj=HXP&9Vi5161AUZv=1I%+d%o^CB;q)7l5$h!re^q|_9{D!tvc6m>ka_Nb9b_RJdS9WcX zzg;-DSZ+bu(3*xk(`65j6=ASv9I_2^#Y9ps*t!>M#70gb*A$QNEwwRXkVp+cYkYcUq4wk!Z9i}NBBbAgzMY_ zYz%#K4xfXwLB(_sf{l(KW2ZHMndPFr?rud-BG$=5Jp3lCN3%VQ3ye8vi6|=Uc~!2w$GEKte57A6TlA zb|^h{s<)ueX~G60O3I1|wPPI@87b#BEjEpM2iGGOIqw zW?#a&V|>ga!1b`S0W!OMoA7EB7~=8PH)9_GVY{(dsK?{$J{9vpw^)Z6SHAcc%jn{_ z1Ey3r3@VqyOzuy~h^8q^SJ&(jI_DFMb8>)MG{)Zg>N-7*4J72=VJ=vj zAhhv~hvFA6ak4zW0%p2$eckhFw%T)4+dARfC2Kv53RU!)iLMp6yC?RRCvhS<5_|;d zO*)VtuY+{8mU;7pEQ^6)u4~0i=!kub5+nTzlVTShyJMyQI1jm(tq2hqN<*Le`me$E zL`CpkXHirIbH+3iN~6h@nJ6k^4?IWk-6W53j#UdCLKYipQIlCB?Lys0d8kkWjAwOQ zTMXAgT~HscYoB*=ZMRrMHxb__!6_to3;4E&L&Ll$ zu+E1x)*CF{7Y{Gz@v!b{RwyNY2|D#Prr)gHIYn-+esw^QDFE;TQ7XUoV$gRoL=#Mm zqEcd-Ctm_Iv>o5dwbwl=N~CY6%7>N;^_npzM_l9Z)P?^>)pmb6mXL{#H+mbBp|sW6 zFN3XzV2-dEBe|{6FJ$34!;iqEXNX3MX2hpj(_8OY@)4ctQ-u#a7F+4olIteA*eFvs ze;Xue-G2`5hH!kb&nEsoctqfh^YRhhSzj=J4=yjzOM`NNMX40X8NfWlh#(mNhs}+b zg0PL^VtapI5l0&S01IT1O>s>mWM-re?oYhC{(^|VL%D2U=7nBqv{Se@EZ6D%5(Req zV-M~Jn0T;qR3$Ute-OzE8yVbD%>s2BVpW--T0K$2AT`StdFN3YIy{8+#rCLsAs7GB zORl^4-#BH_mY(|U9jDsX?vpV~k`7-o#B`?oTA?1KR3=T>V$xe$YdLyD^==_+|^;`%Q zbd0gHck4kx{O70ljaFDXJ0~3-`bs0b4V?R3pa}GOZ%3r)f}%)VITd3Hb=$#S%{(wI zccc|?PZRekB_jH)8suY)Cdvt2Tp8~NRM-i|(|!t8EL*Zd(qRJYeMQu>GN$Jd&lY9f7I`^s@ zw{jR=i3@*#=#+YlNSQ@?IMuMHP08@NMLarMJ}IrL-_WouI6wfmO}$q zbs8@o$ua<#)%l^tRd2#<)ja=7{4Ajrzk<`=TD@8lQulm~tJ}JoYr~~_@Z65^AZi{T zgs3*GmDUgWPq1G4MIhex93snco=V^1#Yfz_5K-9U*OEGYWqSCIuBsRYSwU5aAUG|E zw0v59dxibdIP~?7Qz)8K%azLtWNh~> z7Yj+4eJ>h;T`l6s-Y;7Pi+t{{z1IS zs%SGwNSRfc#{FEWsj+?R06DgFXafS8B;Sn6OanM}LA;)%P!fbd;p66c=Mnhtx^_(HMEcepjQh)r8yd|);7*+C%}cL)~)nKg%ln) z(7-aG(WC4>Ts+E^hf8a&ZwZ5XO3*Syn7sVu14)Xxe7qrBryJR5f$7P=)*l#u7L-3PMcIS1efKa$PcT{HQ(04U+rW!#@w6x0c;hu|Wd^irWx=vV8sK^y z<)Rn*tA;dAclZQHDvS%`K}8pMqn?QN;L1^sT{C}rP~OBIF@>Lqs|TL@6ww`HCx{Si|%e)jCo%{Y_K?l6dHpHrF+Qls~latKvMAj z`!0Vj1-bH{1n}c#zeKMiQG_s=er~xra$*5DupF>ihisX~>d)d^d=_|-UWIT?Jz;yd zA94$Jz?r&h$I0PV$K(Gm9#$13P##(Xdj8CSRR8{FV?=RDi7m zUzUL}3OJST0YhSoh#p*UVrg&3+$%4L!Di&0E8%AZ+#$S+1A_+m8U0S+n-V1~IiIgu zQ!(Ch0{Le!YOB_;yDKCc^%mtsT?#h;TU}b6wc-$L63J5o1qbtm;5D=;{rr)Jl-uU; z(t~_GR7`>HM@{+b#-%9Jt~S*rutBFPcDtlFfC)`M6AFLvuR$vk0JSegExrL)vzYk~C0VJsS&P;y0 zgov34o7cU;~a)zUxF~V+`_=z#X!$`AQ2ZorTv0;fsJ6xkD9Q zJulAdjtJ`WL|be9gSSSh`^Ra5QVUes<|+Sb#>^7Lz(v_rG{H_)X&GuUYgjTqLsPri zW;nSw)uTcrz!7?eIVE{D(eq3qx6wsT0P9D^OF$7~5P5KqK~tS670E4801ia?sUaN7 zA%;jsi5pOT2w6sOhX91Q$xh@yLSU3L7+OiZ*O03K)5gQPDX4}g{kFR%vWd+LK6pi& zLnR7VU%=6l4Oyn|*_31JI+7|@5B2>O+&466>I8kpssm`i0d7oZ^V9C|IhJJg zAuSS=ft7n$VnBy!awLxkPt3i7M{NV|kDEgS%s?@r6r)eHS2Vbgx-|9j6J4(t?pJ=Q zeU$N2cAygT6%1 zW0Chf#C4TDf@lYVJOITk48$)`4X1OlYua2EcuXrus%ukhk&UTy08AEyEZ5}Hzf(dK zbDTcV><-+giBle%RT(!z**JF!LVx&3R^D@rdOW|WguO+|4AcQT&*BT24dFr7>n2deFE$aiL1~2k)Oiiho%irI%x^TmSkRo| z{pBf`9o482M|^;gT{E%6#vSY@{d`M>&~C(UAt1;F$LATk<` zDz-T6z#}5BS<~3x#r)Aw7J}*u<3dGT?{u=cr=4*S@Uoar>W2o&#+|pGTH{n}wO+@f z3R31TcFs9~oIp=Ebao%*Y_0u|wAVEm<8Dh1i-_vxwt+B(CKh=G2dz}qhPSK`mHC4^ zd6{jEUtY*m@+%R80!kqf!c}gt zD81jNmD(@eWMz#pFC)pd#56fd zA)!_A2^9gjeP9-;f0rKENP}2IeZiS1z+n`xMC=y8^k!o-p^e}8DPXo#e4Sj}lesQ& z?ZR>Ho26w5bF6!`NOBw{jUog{;G@H@?(ByDKixmO(RjNex^ogqpMX`7?}$Er8bd&d zT%Jj>9v6Q(By|dp7Th%Ikc80-R|WP-`n3$?d2)t!hhNMs zfI%{pAL66TMr8m{)6{5$Sel=QaI8U*5igsRF9{;7EN_!>JHUz9*ZRskV@9@n^mZ@_S~^Nd&cVTu1-_J;(R2C&$=Nk+yX zo(|E*!2qUehJbn{HHi~UC0!k@=U#qbL!vMRR%Dn>0m-aY}=j?h(+VJpX3mn%Ygw)X~@ z+e;43!~EHI-dgt98XY#@5BOFaWxKCaqSl^s95smr(a1tS5GV*RX7Iu=)i$k12v33x zt>Zfi4lx}(C@TN(F$<_9VQYuZ*g#2I)&*P+7&kDt2=d9|)%*h1o4MB|HPaEFC zdBMIHX!b0>Sto>LKBQd1*0l^Euh*OCZ-N?zoOmy0msmo$B)^bbAlXk2ab{W6HiJp2 zxg6~SE?4b>7A`%atn?rB%`15NAdG(*=&pl zS173yQB!ST{289=T;E4vPY(=NFwNbzkY7MN0}^J;oe0g>A2h!S1NaEzX0nfCkf#EW zW-D_5QO2kZ=8eh*B2k#<{VDd5N%@gVJ62H9t`hX3j%>}boBOQqZU#LtP4U$Of)Y>FbpB6aR42sP0gaX+$_iOs%9hH(?9w3)B zY*3H?vy#qjA#L|N96*# zI2A6uD&Ez~0orK^BV`PimDJ*ONv=41ZmLezjaxUyLTG~5(ROOLwFgc#VM0#rzbh(+ zT2Y9P6<0;xOM-^f*{)Z0cUy**v^^)6*zcnsEDRF2CPGDeaGpv~>G@%j&uD;#Q{6-U zYVmLqrvLFHP+1TlSvh=jho-oNPShJ;nkyCcOYmHjP6JrNFBjD4w0Au!9UErKj1-Dtn8eo{3f_2T>Up?(R8U~JuU=IOqY-Y==p#dBw z`}y~PK|f5i>Pq^^3K+9TN!9SH9yy^8ROYAU%XbmKIA2xn0W>g$vy@d~u=)Kft4Vui z>c^wxi@p?RMty0D*j9vl`X!S)FY73!0+@2_%6l)L~}y|=zPZjOd#yzHW=R_;K715%l$kT5MvB$Md@t63@We}=IZ zZwyUL|E}x9%mTcR&#)GnC3^JIX?%)imO8&^E2NG0S-a!`aFkz5kQKlp&O9UrwMhlwOk%Y;~c+s z;#nQp@r}#@$chkQCFRL`?#j0aF1Yn>POT(*vjZ%(&%wW%&~j6lIdfy47(bSVGaL{k zgl#5CHKTpNWY<&yvE{c_|H;dE-&zRPoqq3BDd03D*;r9*S3q6)7erWKAbqKpt-a>S zDs@Li{Fwhsp0B;u2L!vMO`N~k3pUy`zG9%|V0gPL2)sh`SrzrArOw~iFl4pDz(v({ zKGkO_VO{ZR)679Q?*(xNaie{?mi@N|KP^g3(op`S!FpPER0ve$u8PJ-lDiPsGkwp61M6k4hDx%RZw%v z^n#_QOTYzc+ifwDB?of&I1zQqOx7I9__bwU!(Q>21~CCZkVC>qn|L1XGbMm_bzM+6 zcB_|g3D05eRm6PsP;pDki#mECO*7w#DKvD z8B9RnQMIDy6xwGlfmpyFkAeikq5v<0CB=4L zY?dmA0YZR>7x4&rZ-c{5!R6D*E5dV|RPG{zCn3})4XHkd)o@YONdW-;IbA2{{#u!E zG-l75=ynrdHK{s2j?0tnY~b^N&=pw?p4^UC)Sox75=3bR zd$bwMIJRM%giU9*Iqtq4$_+5hYjd~!&~pY?RK=X(pZo|Mjz|}hZ6hk8WDR~nknOx5 zhYr6;?(9J&T06da%TY$>8hyx9)$HkCzhnmOj-S!QsT5Q^^kU&zKs~L(T4~5}wT96g z2b^T55}1dZ$i63yoWe+no`EMgq0$v#Y5f*^5!0yY5E7802XUfkugr}pgm?^V-W;4` zFJaQEl*fS3dOCC}w}>auLQ@*rw#KB+zuN*BJoI;0!ot2feo@Ghy`dmXI;#ASnOMSK zH>cNtDfoDN-20oqq>oCGwyI$1Gtor&))ic1zKncFFAYqQ zqBa1)&d>aBka{|PNl(e=>q(Q0$_o$swMc+|Q)aT&oiHwjd34-TU$#u{WwtMB{QU!Zs~A=V!p0c>bn41Yd5a+I0Ed{F)o=CS=PUF^>J_ z*$oek{HW$4RpLUlLVZ7QXIdhRY|IeqTcH&iM~2wMiy=sa0(OBl8}#EbFRg+YB9v=- zk;^c%6+B|uqZ{@X2Y&Qif?rv~uh0LIjAt;S?|>S>ja2b3^$@+)c(FS)e#cQ_gh5EV zg6HcCNVw*G(h2b{K>Uqie`1cCt|G$2VG=A^mCVwWK>k<^L|Hz(b(*N+FF^X+sB$2N zA-X1(a)xDd+_3OsGuqxhSdZXepak-Y2Z!3&UmztIpR&O>qS2bbPURjr8LS&1`Mj(r zL=y(9bDS;y`dhwkylR9;rFUeU0|ERCrw~AKLuC(rrk|x5%zS{Qh{l5yYy>jjRxhBv%F_avt%&D!DII{G= zPCpnB3Pc&gYSi<#LXOn!*+r)aJgT>k+32xa@!1z&q{PG5POO^lk0_w~zDiX=c`?oE zHKim%cU7~d(KEa@Xnk5NFPbSLPt=JbAoo@ZgT=>mF=JErgv6A6%aDbaUN8+k(U4c& zlzuGrx*tuktdE0xo;lQVauz@YIt2t)7iC=H22y`JbzF{U!45H$F^ z$N|zB9-lP&w*nnyw|(ebnq8uAzx&Y|v?390Uupwo`hs&{N-MF$m1rW@@RRiuqeieN zHMehNV*=Uq{!D#zHuWaa}1m0Z=0-Ydvda&LB#QZsMRD2{~e{>U4 zOZR`{NvMCY``-us$Jg}SSDFYdtmP`5{wEY^0-rjVJ5hJlwr58(I3e-uy!eViH#U6M zCwWdi=415pTJ}uOyBPeNnKa{b`fGBuX1-5Ua^?HORX0*tZCyfbgC`3x1iYfJFd=4= zTfaD&((=D8s?Hy%3t0l8m5Xm2W0&kTJf;+o8OJd%8R72An@dn$l!bC*?|$37FzG9`5^i}%qfzo^%xu^_ztA-j1%)_V`nhlXuQMCLkl8c|WIN}QfX6F57vL@=N>Q0&@i!PoGpT$NH ziAW?SS&+anxz=Te@U%;OOe_E@z6R5Mds{JV6_&1z^5D-a_2WOWAhzZgo4_2W*8#1~ z&_-}hcwX%FP*pY~mn08J9GMgH{Rd>|gZCu<+L>;J$w}_=3&0t%NY+JNFY;_&NWe;r z%%+EO4nYLhX9D)(IcN`*%$o?m1c&@97SzN^tUUVP@h?}HuS!P)tnQMm*6Z?Eg)SkJ zx5Q8Kh*KvS%SLKUpr@Rwc(+ zr)jFeu9TiZkQAHiBM4msgEkJ~Yvmz&lf=;QttZ4gJlu{X91w5ZhVv``8uV;zR~mxh z{^!6F-j$yCVX97(YtIZ+NkI>X|GrC=+=O#2?UYDnjfpEKK1muMJj7#rBQ=)Ooz_bYTZ2H=R`uR1`djudGBjlzh@T%&8^X_ zji+;91g4x(6>%MqdhU=m2V5sF0!{qp2eghJyyP|JxnUr$oW^wntJUpDH#tDbPo@8g z4e{Jm;Q})iF)A=emSbp;h&hYs^z-n8AT*@ExFJ!3DWTBE>8QNlC3D-+5u5)pi@##P zZV>v!P(adYOzOVNAu;cHzaR=&FA%;n$^j`J0yT3)4dqdtY>}A%Y`c<&@-zGRjtD4} z;WeX@vTzC6&y?-5%q0SVpKOgcd^NogL3u{2qvAGrBlgi> zn%n|Hw+W>{6F)rmb3X(@3v&3tX>#8A@FEZnc$iqtr|Yi(n@T;#SD_@oYs%dZQYag& zRKJ0h`vz_myviXVW=KO7D1GMXUEe;r#+a4@jw}s0+*ni39GZT~kpCk#uv^t8-8!F~ zgN-l-uadCIs69;+rUD3e4R-iC!VsgWIYft5Cr@6ZBPN3KsHM&;TU3plo$C;BL;uYq z<#VPHTH7)*L`1~=;DP82luWQR@)9q+WhUv|^Z&A1fic(ROt*Dl>f1L{Ox{YHtxw#f zz3Y~5C(rjh6cc{!5G{GA<~0YJm)XQ&9`v2LV!uzy)3m6>2DGO%jijBNv~HbylRm1t zzDbvp|BfbLbk{9@4heyJqJsbNC|173+ljh)Xj7_oMH{*T7n`iOTYNy?@&MbkiKd(r zfZ*&#*O;4!x;H!ewE4Y-1pb0HTZDsA=KEo|Jq96@at1)o)gA$VOM+y!^KPAMJ&1a; zY)%K6a&f98e}^gs$WdZ7Z5;*c&{k%Ysp%7IX0Cke-$cH?dBxvNCnsDsqfMrg3P>q= zmN%TcO@<)X4d~Q5VNRUbM(>u^Y?#Z8l5 zBKUO58G92mJv$p!1LUMX!{TcMo)j4&;?MF#K;C3S&{ob!E&|qW{E&~_fpy4W<4;P< zfGDm@X4IkpAMoo%y;SdNlp*dYmorW>obHy(zhw({uPh#El@`+Q7Sz zkfRUbkT9$T`XZL^eS0E`O zS=QV>b=V$>N^~Y6&GU>uwuZiFq&ZF~w$jrMRir0#Kok73hTc@d_n2-2ofdb^J{L51 zbEr&W1CZU-7L_2+aM;nwHIHNi1{N$Dg!N3(ZZz3496cIK${9O2C(P&UQ{{0idVteS zq7K6b>6oJwBY${ZndC2S}^34v+yGe$flvS_aXb z@df${555Y8-_PcreR44oPTh|*1H;x|HMNH59KRD<$yfCW^G zK$QT_6mSgR8p41VL6XQ7nvd{2xC5s^f{si;iQWAwZ3AYsbqn^(yiHzt#Q#)=JV)AQV~F>O})R8Xh$h2aDZ z&!J^ljt&oZb>;RtwL69}79-o_a189S61MFfTN!7(72C}~Fc4Y2hxJ08+4_yv7Q4;3 zNx!XgorW;=V6PKx>d1hEuH-I5`pq+$)KQE2w35jv|6@GiV9=;n-Q)49d_@OYFG5#U z;cIcqV0o;H4spv0Wq9n7K#bm-g%0PZa7yl~n5I1Mq@6j=dnhvMH`ka*d9%0~VxEHO zDG-4QC(an=K{Tb^ch`gxv{b$!Q2@a2ZxPJdThl}$(}uGr8mRoDXiILGR5M%gamZRg z>TvOBgG6ZDxM)*0FAHm^!bUWm_j%6#|L_5R8P5t3Q;jzlP=C0la<1KuYd*;Zxz#D&p?@05;CCr zP+F>(=pe`42TwpLHV!as=csaqh?+_qSow&%GLv;5zW%F#ggV89MP}3m7FsVPf|24v zkPg#@$?B@ThLAfweod(^TbnACU`XzdMl5rBE;BjVZf`iv8wZ+XK$`NLMT&dfsh3a70a zUgGNiW<7r2g$6S2Nr==qE4O4T^m*IZW`^F(>i=$wTlgMui|;MlS&maAQOqk<;xtve zZJP(DbXW_AN6X>zS9=!qsO;76Yq0ZM$~r6SDbQ>fJjJ7)I{n-$YVya&EqV20Z;sHG zr??)Max$QSK?~`y5~vnM6G1pAz*tCs!5BU704gnsvkc>JG3pD zMZA=M2#OoZa#W@JLlbl^aKMDJT`+P#^fMqD{6jP~jrZQA%E#NsFcpT?-t%``W^GXf zZ(l5ZF2Vv{z+ro|6QvHOysg(;YFDt}qK31o@GO*Pz${i~xy_UZ@ z8RS{v`I~9am~T>hJXhH-W10|ek0_aX0U4-}4(DK(_-g1RL)q>&c=hLZJ88x_@rexJ z@C~O`de+Y~qGGN<0OO9CWUY)Xcu?x~otNh_^IagiB_QIBS~0n}d9JFyQtf3%rHyLA zz@cIV(yioN=3-nz{=Dgh34Z#kBatTOwW;a@<&R5oG~PA-l5J;J=kda%c8j{(x1+V_ z4M}~DX~T)*j`CQa5`kp%#;LXcn83>2zzG@;_^8tI1&@L;KGVMR7c?tIB$-_l1ZPWol^8!ps&U|8tQRhLRD@#19xJ`lulffs!&}5u zkUNN)8-fFUW-~^jsXWn+ltqyAN)JC4O zp~&;E>H9i_ZYGI)^$4jPFcNKXP5l=jr&}V(=aoKj^y_%?mADZVx{ zL@wmvkuA<`vJDN3L0F;@Oj|M# z_JlNn@-|$YJ%1jz6L}C~nB}r7L%3%z4}u0-Ke}PTlMBGhx8dZy^KA@Uz;Br3ZJtv~ z6dHb2_5(Zxy8#I>iF;0q&iyb~G~(9W2QF{y_?z6SRP%TQg6+OoUh^?da<0c&#gPsVXPEmziJ;%tz#qHW)&)qb{Fs? zpTiRD9L^Hp6}5?rGZQ>5AWL&i^rr>#Kd}B@eHwq=5Q%?2D``90GjT97CZ)2H4}y{r zz5SZ4ysoeYZpi0Tib!L5U>u~6p%g=OU#r(+_OlM5z`u^AB2EN3_Hj|X{}yJD=5n#o zrNi7E11SHA@Bt=aN$JjSH})*W@vURuI#XPfR5Z8@XPZJ;k;b@`Bxg;PNdPwa@eY}W z-Suw1X@+CRxlQ(H)O$etI6U5Vr0T!b#@T=0#HWdCGzSxI?b7O6_2manh>_^k**hY9 zQ{SNfE7%U5eD;XeeS&zpc`K`N)>3algysrkTx_H50jL1R%*ja?()Ax9_KC{x+hsfpc@eLw^ZBJ}hwT+yY8C*^B}xzWw1j1ji{-YCjcQO3W2! zu#$}W6dSO#;oC6snjVG+;i@g^F|t2kGL#SAPou%YkJWfPy%vs9Bg zgeB? zvKgoDr(jdkfS=2ZPvDuzfC$k<<64wxH_7RaDo1OhXJj%9k?R?=l}Zx?jfDjWomAtT zx&kFHfIP~}Gh=)RzaQ3rTN1J3boPEh;D@ZmvOKzPg2>#4BBT#mifFTVXq+on1Ut>+ zwz+`tKF3@2hJ(d1Ot4Lb8ist`rGxL>bPH@st&M$augJ(D91D4r_EKHvwd~DEZrqHt zu+w$;5|eK29P%c4N&Z1n1=7NPUlKTcVO`!3sY831ws4{_9rd7X;s3ehuGbN!1Ot*r z_RG%$!6mLR{>K;i4J94_fB7VLhxlK|jIJsug~_rp;=tn0e(Orvcl6s1I=HU?=cxLr zHq3_hvA(SMYwPIyz-Of*bA@qxLpy+a`u)&7xxCY=!n=7Rbblx9?62`5H}1)W^b0^DwEc;apirPq`1Uq!vhw#OR?ns_1u_Pjv*<8wad%-Pa7NdofxBeTp_JX_h2?fy-I( zk0J-Gg0MD%+pbiaN(5JhJ0{{F?2`QaX{L8duCUJ<4S{|B`wi%sRk+dDJ@sUM4%84g zP<#W%ER%CtR!i`kq{+en%K&xh!^1p-^f~2~ZQrSvm@y;F{ZY~()=f3)umK=lJ|}9x zEWskszsoLFqnQ^b_d14+2Y(LbvPRU2G6pCzu$}pBX4O?2(Y>*-C&)E%aW6@u_kuw6 zVYG8RkRpUo9afhJ!EQeYYY0SVrgEm!hl?eovU&lkt;el2C68S<}b~pUKm&r2EnU$(72M1X>M= zF!$Xwd4;2VaOkvTa%ry=BF42!_|;55dP?El z_)}=JQuM|B6~gddMhmIE_r3~m6SNKtoP2$On#@PlQOZf~`#ICdRT3|uFe%z5453N~ zW6c~dY=G)=Vky%M#4k!J#UA&m!`K@`pBmuZHg5t30|(q#6h%W7QS9xE1D=VVR%{DL z`eylYEh7|Tdj4-w;P`*OtX4Wij(9zKtCL2~fQ<)l5`hp$s4F*PNqt1~UWny1_U;(Q zYD6ECJ&l$SFP0?pxh@Ii)H)G8TkT(Qo73tR&j=sLNUV?P3!ygPtB%Pi_F@P4BA?j4 zb(_j>n=4Y#1n62f4nsKeD{3O;=`d6$;KrZV$lsyfj|etzdK-q{wM4}l9R7fP|G!Q=TnG&TG# z*C^2B9>kT1e;h~_pl1qmfN8yTwYr53KxezkVQ1LP?7Ea(Q9g|_fV9^(zMw}zo68~h z_DV)|V)lx$VE^tGqi2WRR4bUBuiPysej zzz`2Z8N;MWQjzB+5GbFrLGmAxk{EXbXwgK4K zXNLSFbHVLi7xh2FnP|E(V=+c$|8bySFqwf=dDuOq7L0HHNt=#}y>b|VTFs^Wa#&4} zNZ7DB#ZVOEuPOyavs~eGa|>X6G8xh^ZC2l>qkxh_y#tX zD1}SO5gyJ|;gWvB;6-v+%*j+o8?&XD6mg)VA}aW%f2P1q@IaqOFaq0!t7O}AV&;H6 zT5xMkC?VdqW0>}gUk@TcQLT+&o)`Z5={QthY;r9y9{-%B{9Y=|g4a^ePn0q#k@ROj zgcR!Ce>XMAj0RNTB*DFlu-)M&s3Eu=5E*5!N!e{vdqK!5i3k0SK$#kcu)4hrc#Jp8uy-x6d*C_e?HbDi!kuO zpHyw+-2R*8*Xqrh5aREk)>SDBWhL6@ERO8Z)9 z(~G?4^XLewzNB#5Bal3>+%0_Jzrhe47>yY{Q!?Ht^(hO5wW%OHwcN?izi4Go9WFq* z3qqd24~m}glI=MfWV9YYK#koOBKnhj7DeFW@-=fuJrE+`*mk%ZbiNl~1r@98vLt`N znW!eM(WRqg6q7yXDVhoC*kqD1uZJQUDFv_FkcYp;+9c>Y-Z#UE4JU#KmL+(<>+KPh z{NNa9Tcm)FzJzMO#7@)!qf9ON4-?mjqNyZU?`QOLvYa=~CQQ^oOQDIvXkU;8YjS>@ zM*->xh%KZ&=6tV!gE7TTLVT2ZIpA$>l4Fr+aoA#NAU- zAaf;Nm1tYhWzGf%=A!#(sio|Zq!r58B4NzR=5;mmvr-X=DUTxd#qPb+vE{;h4+{At z-<^Drp1%!NOY+?EISU)jDtY1@>aGht&rg&#c?C|F7xqZWK8sf6Xq5V$cy{R<;#Z-M8b6fUC$1g(Ah~u2+gjNs#N_aWc2uU}|B!10VfzF(E1@V!XVHfvdRR z(OaR}WyVFaVjwf`0L99Mc-al@AW1iPg7 z9muFx3+Mx9hNRyS+&xpz^0pnwZ-1KYY^-Vjr{Nh}+icZ0a3JodKY8e%m2u3olly8H zzSUE?ZI-VH8mj|V=&yj~LVwZ~dC~jbyi2u2Ug8`pycUgm`Y31{&1ze!_?9;~tk(DS zY_J9>!PrKrxw?R?t7~W%Qq)5<`OE~_rs#+!b_M9xsC$G;_BW(ETS<$o-Ae{lmQS${ zE}EX6O0SevBkZI)mRrM9m2^to+k~JdY^=LI8SZ$baq|M2^jDW|Vz!e|;K%&gYmz6C#7Dhw%<$>nWXFN!}aU$lY5pkzm?!zG$tx6Q})+CZfG&#f+$&Ey(E>CVy zzcZgri^CrolC#0NZ*GO5kj!`ByUWIiP$!lwCJzJ55C7WiM0 zJ5{BQj4r*U^l2po>F;0wmhY(XU05Z)z$)jm;5OcR>f!1&9Jy03qwusBJcv_gcaP zN?@(mtyaceq^;ZqY$6!3AkN3LqayEJ%3Zh8AVtMDHJ+2*m?{aSS6&_z_B@d(RvSVv za$e)rIE%0C^YW1(9!GI&o3m)3o@iRbOS@X|sJ9A37V58)RSM!=xn3qqs^Qa-s|-2} zb*ZIv9*YJB?AwpIUEBzb$UL{Z=n4(^9ww z8U*9JSM5O$%9b!eJBX~I8Kd)OK!y9c zW77BMDNVg-e(6gEbt_ldxJjW!12`a$*Kq$4U@m#{GOLP(eZDv3?C7cuv^X8aS^KMq z)l`zN{_AY7pqf-gV7jgDmDPgeKClH67l^|%S`0C*7SrVZcSiKC@wzz&rExTKt!22K z6}Ou_kBU4{?C;>V%y08`aSCc$-z}h=RjDY+Jy)0}wU*X6@Pbv?Gq~|a)aM&?i3{5zTnU52*Ep4=ozSEbi;afb}U!}uNJ=AtZ=3a3NhT5&!@WXHAQUtFQi_rNGN zU+QDy`)cfbr>adr_PyB<0%r(AOljiFjW&FXz|01c<1_a^IWZTwj#OeJfREg<9JA&U zIhp%<6Sae~KJ6y_q>I?IF2Ju(EfJ>g_bQ;3eL3)vw!W{J>dxN~a_d`@=bUY_L)StIvTA(ew zYBhKX;HM3V%{Tt(XVOx}PmaY|@kr=BB)Mo)*eI>1tBagiQW6)9O_myha#*of*N0(c& zL?9U;qh^hS7BwQ$rM2D^OYn^)acgcsMQeor1KmDt*e@2F!Pi#+(JeI1rz*DNsuM_l zX7gdLRb!uTJG%pMHB1|OEaZLYBuY1I-FI={s?7fz{BmFbXP&QK2k>1w&dCT0BeYn4 zNotf(E(`S$HW2Kujtqhh{8r8TBUHT7qhbUT!W#+KoWJP3_JBPIgXl8UyRJ;99%ZB} z3URZXG+XS+rdcOz;h=^Ew$_4x0Z&%5zeTAVb71}{Oe0Q?7o&fia>FV%9JIA$pXuQH z!ka0mrk|_q6}pXXR6GeGrY?YoriYj4@RhC7`wdZHUcRpxsMT-^Y)aHo7 z8bomZ0L~c@aaj*X`XNk9wUsr}c{RCnI!_=MPNY{PWQUmW;0CjaHyj%KkA^p8@fg4z z#H``Tyj*RLpHHxea8yZQ4(hG}U!#}&(k99_+_(Wg-OYG7%TsX2(dfem2cxg1cz^J} zWOwHpM#C{ZFIBZveBhM98-?`G)Ace)N;n9{PK!o0n#4qYyU&Q5q?6QA{akKRYs#a< zGE{f*MZX*EurnESrz0q$n5~+`YQYHq_gl0Llg$QKCi&D@jisN+zc7HEQV%DW+}GqF!Dt&lr5g+(fkxl&rRj z*1|gU+1Ar_0d^uijlCK!N=BpyapAP2e;kJd@G>MgMqnf>3#HJ~7a@pJv z)-~huq)~Hb06pRohb@JEj+2VQmy*eHsykl!!I|wZSQv)$&F${8Y*dmML~s!cw|{G? znVG-o<9R40($=U2bgelVblvJxQvGpCi1qvZxE?awR7M>kcUFYE!N;+D;U24i!~Chd ztVo@HcdEuWzEq|VisPo1jP~X1NeTL4hpNSEcX>UiJAN}lDtGA)&aJcES8(wV#;cEc z@OzbTHD(`G0!{eM49*>;E$qR;w{MsMC`w~%q~S?j(Ha#|U^`ajmbA==5)9-WX&0$j z$Lqe0Z{1t+@>F}>)m)-53_BCHhK3C$fO&^JC)nl^@rE)^gurmr<>EER*K7x2Fh+lL zJ_W=Pxl+4t0YXQHUD=e$=dtzYcf?P~In)81`n2KDl@dQB!iaUd@THIN@l|)0CATr{sbWaR9}1*W1o)x8G`(n|=yE1r zi?g5SIcptmE!%HJSjZ71lNjm@oTk3U1%wxP&u$~xnZ98bE%$Go z8kEH|H;TtcOnAd&#PPF1@$4bU!jHhWe|be|p}JmxbdIi~mZ+~bm%Yti?S;@{fG0Iv zeOTn~N&_)UaY`ouk%V|>m0uO^{0_wE{o!aI;^zXL7j>RBY;0M zH05>xG!1jj1P+K~)9(?=sk-`NCgg3=NEx0dZO!vSyRAvtR`-&lH^X7OOmEEKkXX_`=3BEoCN4Td>zfOf z!2jK=JJ%1dgtTTeupyObnsYBDf_lU9UU!a;O4C%w8<6(_3PuY%)!#1jRJCt%GHRpb zJD{m|1gJ;PP#0~()rwr+RTWJ#IgyvpQD^21NUyOm`9vzT#_^8M6Oz}TIHY!_mQlf-9rqgmDB3-kX2EUXGWCJFDizIg+hQWno#?8(GMayG??!;=Po zP@Uo&Q1K*AML%6aQrf$%QSIOUa04JVgfJEXAv+!WjR)++AZvQW3WA!jF2m(&npxm^ zbO8X&n^aH9Lt7UNy>etzT%Fg|r2tU99hXFhGi4h!%GaX{oU^DZ%Y0g_sb+li4SwBN z$lH_Dt30Uk8JDEzEPMJAtN9R>T|Z5sIIB#MgJ7Syum387UCg!}69|;S~J5H$ak5%r62zvow=*LoGe8;g40tT#+ZEIeiTX@dp+Ce2n~>01VSKRGtY+B#_YS z4|mD5&U7*%iGvIHwFn4gfoHQZexq@=zUdhcj8{&&r102Rf|QxR{;|w)SpF)iZdP41 z=7t>JM=rxXE`V|TG7r#`Um-tS&&XXgIF_H z%S_BOY|<=zr#x5imR0y9S{JW+036?7)}{CJbkw~KV#HzDmLca|7*O+qN$E$h!V>;pJ&1^_1!5}?4 z3q#@d0^LM3_Uy|<=*e$$+?GnCG)Hx-jvqj82`u#O%|q#b zw-7QnTHE&>L&K^?J!K&Z518?utL|JTGD_`53-liD#WsJ6nK9EY7`m!t_1q2jc&VR< z*Zx4ION3qlV>cL!mw}Zic{Tp$#CmkLWKLU6h>?K=VWrpPdWd{MyCfl~spJz!N=XQt zlu;%Ivg|X&3*NAkqH8OZL+X6mzDo_TTSSDUX?-OxI=q#F z$Z@mv%x&L79oW~|{((o|%aL30^|F~8vCNaTV{7u!n-`X6)Zs@bXv->`JchAP>jY@o z`0W1uqL|Pg%R9>?hAZCH(A3J4jh&@=&(A43xr#KwPr-07O@dXmS{8@EOPUP zX%3NE(mTY(Z;J~MwAmQ&r58yKP$cL^&6RFzfamYnF_81G)#E=0`ZZifoFn1TiqZsF zKW-?UK-|hdZ)tFte-Uxxl`a)63)CHW%Gs`dz%SgHU9G%|rrofld4Sav(MyD76M zCDK_lTs#)U=^hqV#&*;TL3qk;prRJGLelVFZ2e^BWEoT+G9&U>@7`XP z+PkG<*g?;j5pUYF(H2J+zON$OUOz@{1v~}O4jBc|p8LI_riw`IPH@SKt*oHGS#j7d z9S5P7Nh>_viof+F9 z=*rNHQTTKUYZEm}%MBX%w?j56$xemwhcz37a>rEvp=Jaf9w6g+&DL-sv&h0C*WcR1 zas-WuMjPr;3z=nVM}`x>!&I7#1F>eYx#Za7o90Xg@}h?Rt{u*jD%q43JDdo|F(?)4 z9p%q#5_{t!xgM))wLJV|pP`!Jq0CNrS7M%?KGx}jFM$8$*T0;TCg}7_ZcMIQxVx+)tK@wzq*%9_ z*5I5)6oTwSRK-PjBnf&9BFn3*zrEq5xmF=gU^AQdy+rDN0Dh(g`s73z`os`=olNLMwyG4>+sBW-Gr}3J{W68=NWao+idR+%J!#!te&pmM+{t;ifOWh;eKKz3 zR%26Hws@Id8dVYdRc#`}XO2FGY*7r~gh;+Vd+;1&Zgbiy0OvjLWp^RoMjRVXU))Bs z4D_40uNhhLGgVM9oEC`$3l=vx?@Z`8`Fd}OPRwAy3kWzmwv5c#ol(q6N$+wa{v{Pa6zCX)BCazI zgu5?C`D1UnMWjgZzGQwRIz=>TVj$#f;z9L2=GQ!sh5U=Q4zs`VRB6kds%(@B1>YpU zy5PU-!QQ=L*%Y~5XfQNu3AL&fFvysiPRwfJJa%D%Szpp6>GBbnWvA;3C0pE`mTZ0n z)m7a+yuDxI9mWmK)Am%)yJ7cI-kALI7T4fQMC*%Iv@u;D4v?u2H(}cCun}Q zSFUAui=%kDiJ@xWgITe?qBm}Z8_4XNWoz6X&kTn;UH=UK3YGii!q@dn4w$-p+Pad^ zc?qw82|z@_Ulyz`KyWxElR0okBkjn$^Xb27&^AEMN;wR`QnhPZ0YsGrb)vtSxd4e7 zDu8U%Q?SAjn}5`+b)Y*6oVp|$`0?d)tMz*%g9J0_*4%m>Z?FAja*AMl7=8QH8>H)X zO$t*_O(2;bYS}kyc&~g9I*Wnx;U&AB8tUh&TU^ERyYYBnG}WX^j!=1W0(VI=np)vS zeN7$aGGihm(sxWJ_7TkeQ%{6V0NFj~n8NpDNjxTNnRh%<4bm0?ADL`Ua4X0q>uax*@EII?Fv z(^yA&qkwC{);+irAY_cF9gKJjuuFTV;uk;HRQV)(4KijbWWAdSa&Bl6av^DwV@CWb zhwO~pC4ARPKAV&hT%NmWP1JQm0@jt8%oY1LHPGGraNFs^DHdH+4MSV*M^JF+QhAHy z)KC?yY?95WFRktmO3PGVjQGH&3SVO;gGblgfw6gV)mDc$ZOUgO@*rI*O{BAz82=`u1Jr*DNuE9hc3gmEzgxcJya8+tkp0)6^+=@<@%@6{Vu0_Imqyg6x80#&P_XBmk#qv~LX+j3E_Oo#dBfi|Gc6`ZM=!p9-s)jcY|%}oOT=&K1PbMf>_iF*pp z#-eb#X)M{j$iT+-IM1+Xvmc!n*ZTU%4FL?R6aCP`C1)MVWR&N86PATt`%VrDWjXxV zwHRkcTgE6Z78o6NJ)l{tiZ$81#HBu08Q5rXt8jIa-*<4GU$00^8%6c-OSV7H zLI%?NLdz^EQdE{^z#NzWTyjt5^%Fr_genAY8pkfMzLBVCYpQ52yVMEg1QG}I77 z&kqips;QtDzGo#EmR{1}55@unIw$9hM9_Vd8dS05=Qch?TDnq_H!IBXsfVbKZeojn z6#QpsyXpG`vm2lycmV?r!PUyDB-8ddW|Je}g}Z8vC082f z5$4pX3GoF$L7%Vy>Z>qS&#C4>31eY~O9SbI+nv2d6pX8N#srSxvY{d{W-VpS1@OK} zr9-t=jy{>A`=m4r?LMu*xAh3H$&Q9^p!#bW32eLW38*Kys{CPd-)|uCZs1+9(y12zhhgq-f< zN_Ij>J$53z|H|fU)c2DFfm31^hbfaCojRvEkXgMGWpej;ZHFwg*t#w77#p7`AImsq z3E6Clw)XWPxIEuSss`_!URPx*mCT<tg^Y@>D0HT!=71 zZCWIOFe};JE&k}P9YU{oFV$y<91$h0P3+J`8w3~A2f>W$7AqKX#1o%0ru-)L{J}#5Uj5Gtqu|5vEp7fsTomdhs+z^<@(~Sp>b^Ox z%%zdqze5+~LIJg7pvi^+JDW-5KVgg z*63R*Px`ggP;3o76J?urdgIB)k9uaKM>A@lWcin%8%8c27niHf3JM0=W>fhyKE~Ld zwLy5DXd%CJ`pJVm5};rLO%S(;Aw5;%BEw>ouv^?gfK*UlS#qnP_-Ciji$YxQt6h}p z1-rul2S-5`;x8irvPVV&zbanw(`{!EHqZo;EcLFd)VC*S zzCTkauSAL6qh|mITemFy+mEDMg16L+43Bh#>-r}U%brcKHtZ%4Sj_Db-ft!bBZyx) zY7M9z+HM;WPSUqdU0!olnESkHi*QUsh6NED81I>&hQ z!?>@XQ;dqra}CF#`jzPN=hM5}VAp_fKhm@Z*a?Cdq=9lN3Ck+IVxuwy z5?|1AR|-P*9C)N}dd-w^uKz#u3MS#uXjC;jkiy8B-Vugws>Gn~pg(UoZPbk*7nmUw|mcVFh?e&e8-v& za~JYRSRp*4%M_l*t?Nf%EZa$*1p)iU$Nr5Z?p?H=ufaxkO6ATq9{S^ueGF_y?~Ryr zv1z)J-Hyn^}g`keQXJDGeHpkyIzJ^FtTu6P2^7b26+50`{5bVI5y;DKJ zxu@ln!T&`eayuz+P`p}_j0x(-iyW#B)js$UNbaBEW3!i5IJ9vqus{Y|1?;YCyu~7ETbAO zJmlc&QYXIARIRK4@Vg`5@gpBl`&{yfCasd=Ko%b^E2It69eqbb6$%+hkt2xx2v0}C z<5BMN`TfL4j4~>WJ3O$yR4RV9>i1Az*IN$c(fkq*?9zfH(XeJ)VT44^#MId!6MC_! z?g3SzplahEP@vmyJ#Tcw7!&XW5}f^gvXOc&ZlU{K2#YAehW|b5;FI%pxt|tfP>7(c z%!g!-+)zD6g#Fg{Yz-2QIQX41+P`D}MrYTKvF5OYOdg#*93$1eM*Ls7=}A# zKYwgjh?|F|LU395gsQ}&_WsH$#wV-dClWqKDmdIx8>$dDozp+4I#%N)%AzR~ej@E> zd!P&au(eX~76OEzjjSMlcEA zC?JGjB>VsdK_NY4OO1S0ti@UEgK(vFHS#Ib83o)bT!&{C@S08>$&hct)|y{(s4xw? z)VzcbSiY63Eql)mE}~2MYc~rX#*$Kkou$!NGgyaPchH z!Uzv1mj2ApLnda=BUe-umgxKM#Ge>GyNnN|2(Z}xtUy;5p1~-$-Lp;iOFVsH48d>` z)@r035iWiXiF@HMl9&T&+cPFcM5!*edQ}0dIZo~{4*HHEHA~F7_lFABN;K09LDdr>nvly20C%(CU$Dr^6v=*vj_ij zbJOsSrT-xjPqfuh=kR{EitE3{4{TXDfavRIbP}bF?~@U<>m6qYa~(*~gcYN~3CwGP zL&}Qi-XgO)wQ%>a$CI~;|2Bp}zRxYO0#IVn?7T~Ay@+pmjE{uS=0_KanO@Akp$>_A z{!VVuL>k2$zo*)X^<=RWpu=a0oaO?Nc2c?L7rGbN-|Kzzvzbjq`s;mKmVyr>df|G; z(Y*uZT@d|Ob%Fgjw4*q(65_~LA1v^JoG$ZaR$^cL?fYZ%+kdJ7zm=}xpU@VztiZS0UH|Qy; zJeX?euu96{y3v@D*}YmC9l7Tt#yYX3!wVmH{dkcjCk{LH!)gFVB@W_51#6jI7dD88 zW-wrms|^gkq1&%u*!x2VkP4nKv*r!f)`51MYl~05C;@P)L(bYqJTpJ;aMY;R+KtNp zQGS|Fokq8H)g(fC{9s)KDlO{gin(260Lp<3&(mrf*M1yHoRMt16M+u2=ty{6nP<^h zc+*%Z>%g(OEfFJMn+g9YK1c|9N%o4>Wa%6GuobjGl7AqqmFdk&Fr z(VL#*Sv?{*MV8tjV$t)n?#@ny_ePrcs#)yHCT=`9UNYDitg1|`Ym>7MiD|?P?FD}> z5I{|jGe{lg=Qj3_{h<2>UDG8a_SKTCDNQrVvJ3PgBYUyGzHNzQd7D#Q(RI>~)*GV9 zFIYB@_{l-1thX(8^kv-^rw;o+_d}W}sUjNB#jk-;AYNMW)y@;Bk42tSvcP3)BmH9G zNJ5UGwf0M&LLu?BokKg(N0&%yvWM0x%Zw+mzhz`X+3fmt?&d0#r}EWBBD46+7#xLG zNMq1AX{&+%e-RztRY_<`&(+0c!s8HY${#jg!-T+EpWv>inTasIPk@Cq_#?B$TwnfT z8soaT3( zA5(YjALY+t?M>wzKD&*jykzae_|I3tNf@n9NMHIHdXazSy1C;XbL=JOCt4EaK_=7A zAry1LvfVW>G#cUAs9$5;?Zf%#B7i=Q@ep$PQ}a0-+#JPZ_sg@l%>6(?Mn|!LG+FGS zE%#1smPg zUnM`)F=X|hByim{5xEy+H?HL;T|mXoWAMX_8slb)l@!_gkO+IRJ{jAMMVbc`Td~t3 z6d<@I8iy^kkxpW)1o=O}0AhQ0rpIo*N*=TmRm-2F#C-*XCGXJZ8pJ^hAr`1MRm@U| zn`L~YX71_K(vH_}0XsVgeIkWc9J}2!M`)G(R|CWADju9m%J)2dL*`%1U|*E z9iqwhqzS+&)M{0fQsNBp1X^TjCuqKWx-F?(mt6ZR%hPkS=aAt>!d`u9jRVFd@3ff@Qjkq_@j4F6OFnje7X*MWKd| zeyoR%)e`=Zl&6g5Id~<+$XWLQ=_tQ1)@r_N$)Ia}yL!n987l@GhN4B4v5b!Y*aYno zglLI!x$mq>yLE2SL-bt<{I-T58h^g(=K2lB_*>55i=+WDG7I8{wWlI!RHFEe_bgFz z;jmmQ1o~#GEnIJbeiicYdLkv&(OieB(3ho;O~OBdf%A%1nm3asZhjNGG0U;ivkC!0J5+elXs*l53B zud3yPfxLc=lCbTL%suaI5K#U)uqa`uYbM2{Ho0wsfFkvbo$B#t1Brst)S1jq&aA6V zPYI%~LxrK`#ssd^08Y_$Edq_>^&mywXK9UJ((6Vzl%gtYZEEDni`e66$=vWd1pWXo zK=%6V*5sEevD;f|{+PMpE9eAsls*PFqa~k!H#?*=Q9VLv@A&_(*Yj-hXv<#4k;#zW7|J zT2}6T+FKIlVIh%mQuxZ`cV=^)=EO{~u>U^c2fck-=zwG9SNP`@f6oU6q#%rTz(v$9+>ddZ{jn=~F+$<>%*+{Jv2O>3>a`Far|e!6I| z1yqaVvDb%=BYdBBfESV4inWav!)u)9nNw+PN5?N-Y6vwl;u$|ZUcRogT~cTJHvjux z87=1>4+@C3#98+|OWZFMQrE-5SXyED_J0!cs7||^=5pn|>)DXNWg{O3N`4{pllUoj zSP(VNl2kQ4TN3``CPFg7i~glSvg-=KXGt^ZN>{(bcq#wRKc@`hzFP86r{GME;AO6T!c9)5de19cf;c@=bis-)dCqzps3OaA)a@b61D zYb62w$O4Zo2q1Hb%v3`-*Ht5`@sO83=$M-T-hv=KLBPFx%!p;TnI7bLCrG)x9fknm z7KwRD**6>t5JUh12l9wuyJ#{#C{H+~U}u%E38lz}c44z3oEgefbbME)oQd$Bdq5p` zMhBo;&(et^VVofUDWZ+f_Mq4$)?c=b79mxD%~+d^D@hGB zGP&m3M#!;_fGC|0oE98>G|Qf?izYJ25aU!PFpP8N9qkP%GcT7&A zCM!9o$X;1$<)9HJ2TpBmi7KcZ+?S$pvB|asQ1wNya=`yDE$pf0MFL*)qVmTlP$;f& zGKe^p%;;KrDk_q|ol=JJ;u+89pqu5NQul_56r6uwm4Z2wSCf~ldO{I3ahljSxw5+M z;S9bHTLIck(^}p6V8u?bpLDA^pw7VEiMfq~!t`{};NYSRn~eRjrsI)O&YJ^MC2I6= zHFEIQvr1&3yp3O@CyBDoS9>r*Ng$@!kVkeIiseAgN7W`yl;>DhTrVPfr>CpVp@`^9 z0x)?|vU{pS7G7!%A%MTmnBwCxiBi_|Q7#9A2&5=_1(ntWt3|g8kABgOZH9VY|N6LM zPM$MG686zb89qS*7;r0kyw_j;8u~DPbu#sap;5Uh@4DRF+);9gvOV}Xc^4W1`Q|R- zjvCUMQzlIZ{Auj=5sD({c+Z7~rbyefXx;y5Yap6!c7f|^o1nK75`9I%jAJ71=|EPe;xLTS2z zqJCF$G(jI9?!uvn)O;k{b=_&xBdx?+*IDgwCigI_7ROgR^2wqRFe6J@&&yFp`q5?X(dCnsuJ2rySN+^42M^wF$b- z_+jew$BZg|Uij;iAC*UzGeK%|AD^H$irJ8GPLGz^Ixem9)C?Ulk}|mZyV=3c5UX>0 zv2=i)@}+BB+R0P5h7Zv9aGZUmcMM{HmA6d!MOK^tFo=SB+*Dorm{Z50VVBH?{VEb% zFc38FP#{-}Ie3+2I80O)Oh_WoAUkZ_IhXgI$;JK~x8}hA#aXcGH|%~3dpWsM*m^Mh zXXehHHtnLB?SyRpHNKWHq}Iy|v-;J#K^lUvp;IHo6jcr}(*)+2Re}9tYEJww7tzM1 zF?6d7HMPJ|7!D(RnKIFcePHQ;d+R4^gM>~nf^%(=)^>JfQ#mcRRtna3T;;)4T08nn zx)|OhnKYO@pM6)cAq;}+7$bEKC3`OUTCqSsd2T|+;M}gd>svuqE~SM>w*tii3kwHi zvBI@#&R+4=9cP!-3wVE?i93hHbGA~+uv)Lg!hb2n6)-OOF~6-srmUO2Zq>G%ukxo8 z6i0VMEX?<@hGJ=pR@1^a`1o{yJh#+0NDAiPbC~hJ_@nk525Vk1CZV(Mb`o*J=FX9} zrqq)D+M|&gb$x*A*!%oEQ@hqdm&w@|38WaMl4GJ0d9fbK{MC15BgK?~Z@WlXV&0pS3t{|-R46q(+=e{frJr-R+7MuQR{ur?Q#PA+|M*!CN33ZJMAq@u$vLdsoD(tj$)&`XUKHTnLU*taKrWnsHn#cn%om#-vMvpb+pu2JvDsoi_Vf2=#5H249Rnp~AOfAa zuFtrI5}bnvb9swqjr&!G2t}`&U9EqTm!YPTjbQ_$d-=z>o=njuHJh8Q5PU(AGh16Z z^{8hqc|Q!vf_JcSt5+_aIgBXMoR0^U4LnxS_bRcds#_FTz|wJBE(VzKrd1B-D$T7C z{Q>=!fn?6E>m#i zMDuBj{zYF-Hj7(uSJ@>tIrm+a4Gt-Tc$<()sW>sWdM9lF{7q zH3~wLOZX5m;j$N-Y~wXcH7s^moq>$QtZR$+Fu%ZX$-q5>^L4Yt4p0y&1%zR{1o8_) zCSKWt;ntU1;8GCOX>GnvHv$*$IujfnBVQ;UW^P;)W2-n`{`DxDORnO!GUV*WW|1Z2 zA-G*0M6)irQx2-%^2{xh<>g8bCT8&nx%1Sw%AUQ_giRcSnZNZqdgihhom@};mr$D| z0e;SqCV-PI_y98%>xEW*7eN1LVq+L%HrZnuwV2Xp)y6~4~d z)cYMlFBa{7hs?n$+WswGc}e}nY%ln5mX`DBV1&26tFefCfV@#_NV0}PybA9D)ndP4g3G%s61I68p!KYE|^_AI@)G&Qp+?|{1NjqI);Ie#*? z1}bcMq>V1F3{WiR4)cp@pg<)G5n#NksW|Z_t64*#% zr5}Wpdq+4>0QM~5={zC;FVI`Nm8~tUCdFku$63pYzG4Q){ zD5ztx({vGjJ*fQU0turEQMJyKBn>gx7|6_mvg2Uf`;%_?Np!1(SFB3AM?cmJLu)#l zZ0lO3N6>;iZ%m}N^#xVsz1B_^rq0#a?9h{>z5ZMq8`&~iW>aw)G5($ER{!z;QLO}~ zpZHt6n0Se4<8KIBI_!nqK}JI+2FihHZ>+R&^mS)FN}({4ZG_gH*rG;-%4Lwq<23qM zg=QNEDr3G&g-@{i0U&XPOumAurZ%doS?Z~5s;ogd{wAoNnQ042gk(7mF#JQSU zH|+n##uZC6dmv7TZq<^;UF*`UcLn}^@?E+ylFSXk$TT}nn} zWEy(3Y~x{P6nX|2`0G$WV?Ff_=XkxYKB9=zv2^#F-Iq=wUa+eNwq0^Fw<7Sm0YY~2N{{Vc(P=1~Qj-K&z`NDtCNCFY z9A;Oo4a+)CHod~~UEG;3rbR!`8Udk_7KDS3uQl4MQx2=6QIQ6^Z@tA|rPach=h~0y z8?X3$*POS)mk#9t^-8W_kcgf?@K(O}42(H~nyfV_D=7xltj=P|uK)XAN*;vVa2vzg za`}@MS$W~jyw`vw4=t4yXGwx52R>jV`kGm==M0W6l5(%0$bW!x%4h;Tj#(Oc5#Jo& zeq8oVv#W|6gQ_R86`ValgV@*oRgHr1-FSdFFMfyPAZs+ zfBSU0-WAg+s~TgBGG(cLebO8sUpjs9{nH)Pctl7_zHlMo11fsoR5yMB4zkuUVmbQA>6_GuZc%9s;nTs~Z+c25*5uZNUF<|*$pHBZM zS$Gasm9$&+k6Is`O?sw^dy9%n6=Ed)p*UbOdllBv&+C`q*Dwf33a?WKwS{$iQ3mvw zXh}b)D7@3b*p{G@wrbg>`$FfuLL4UTfLqO_NEpMm6)$+O zc8{cOu(>Qr_SYZ@Di_@OHms%{5<(vSX`+eI9I$$55+z4ZtiZ_$CWXS=!whiAB-N4z z>xke$dl^QLh^utH_tWh+#<>E-QH37<4bd@20?|o)_S`&BXqMC<6+wz^4Tr0bbL>0 zR24Idnj<=Va}aCGHvt*93^+d0FZV7ZIZ(eDf560-PY5|sYPz-w{lEA)XInVGPr
+&bm`%T>Jkjli!22%G~a|5J2fy|RLrO8mO)qyRwstP0h@%~ zGb^{Xg-`LoLV=F!$!euZoYgKA5DP+RaoBQni>t~c<4FZ)1!yg0t<{p0#LAo1DUfsKv1+ho!7C==@0D2>MtGy_|XGHGpXDT8gA81oW8S7Fhm1l4TqdQQXkH-+>F2iy~ zu)MUqu-tM~E*PWTI`3)l-WbqA9bzqpWd&IiFT#!c&B(|8%AZV2Mcvk%#h%lIkuM1yET>U{O8hCBl~>dCo-}$>nB8P>>=*c!N{PA~_b% zTlg0EK#Ap5QjA*nc5d-#)bwj)!sf*uQ_$u}rQ^A_Wpv;-pOJru8 z(51sV6>cb=cX+6e7L0_Cq#8=bywiY7;Y$yYNP!u1zT#Y(;Z3n2Y#9=tD;e?CXo~>yqiz$=*Qe=fg4`Dz3ulP++ zjG{2`lIvI;)FSYiL>3KIO7ZE)`Wa$h3r4&;SEKQiWjUx5m83%wVNpG#YVTKF2RH*< z9P^-^JoC$LRK_L>`Cx@sl&~7C9&c~PZ*&_^9_c=s5&5HQUo^RRF;Mj1JQpB@X`Y)z z=G4spJ7Qk`w6vc<@V5fs9CLLR%>)B390eU$GeORc(Y5X$%6=em8VI3+oAjyC=9Z+G zs%ury>9P)kt3w=HHUH1(LhpGc$YcfT3e@$v)dT3{eu`VPicdpO*A54-Q#>=ckr>}Y zSP>^TWrcU;aRJv$#3MsiU%?|os;IfJkEi?1uwAj?rwdJd%C2b?JZAuGRf@#(Kx6!6!`5&q=LxE}E#gTB4Wk=(8 zlqBsW4?)x|Wn9vH7%!Xqj{Cd*^y%@BZIfAsFhB7V?HDI3Bn_{6s9n)RHGAI{sVOx~ zqPZEc6KPTVcpO7{O`bs+%LH}R<%~7KfKgy>n>=A7{`~?|7KSc{;$~;bll$U9l(nU^ z43zZQtq%CQu)&L#a1X**G2rKx%@?V2=_ckyEG2zH6vIAU(7L!SV_f@ok-*a2IW zmx=6InL?QQ8XHHI!u=WCFS?8QHO(hdbT*uhA!gz0wEgMiw@FGRbiv&>3)@@lR$^h~ z8eA~kYx3qysX(Gwc3I_&&@>%=1Oud2U*#*c0%@)ku}0NPITFYRNd~~c#%i1&F!+Kr zJ?C4bb=sC@XKy4AoWw-{MEq-*teyG=E)JtOk=fK5^YZrjgMf>A|EeXf%i_zlo?Cnu ztn07k<;1!Ja=bDD!-Y_Jc)J z*6a0Ah{*do!-AAD=@#=ZYdqZ9V=fFF_VGE(T(joLw$P|mZoq_nAr3HInvuWl{7i-Z zvM%Xae*L}(Li!BF+}5U2s4Xls2*b9$eG)OHI{42L)^!uX379T*b#oH@_?t>7Vdbnang9+P+c zZV9++&+4iHy$|E7=L#dx;MBoifpD1v)$r$@X*=avFQ*Jx)Nl}SPBn3lRUTh)_sV~r z&fK*E^w!^P%esJlx}YMRRR7S#%FZy%Tg=C`2=D7JT)JNU19u0aV)Td~7_(J>&40Ql zp5PkTk+_c!`@yj8*l6j3)MS%Z6|zh~iMpV1!&$C{VY6G5fA+c}YnL56ZhHBhB@HTFV%D^1Lo88 z#nRfS1bS1|z@cQu^^P5QsfEnvKVcDeY2xU?5Akpq#BU*xke=etWH(Qomo*$#R#)HM zwtgeo(4f?Dbb9ksvCm}LM{{NQUsNK3jA_O;j!3n&z$?h6+c*#YUB4&Vnoti(^%y5E z&huUz>p*EAeaS1GZ;pg4q5>Sbqm6hO6BhEU=A!uKT)+7o$f!*(m#Jp2UeIKgh11_# z4EV88k)K~ah}IaV@ioGWfDzsm_SiNqLFBi*F1A@&fj*+cRxe{mX%0AUM2DN=0M9z| zh^2HrW}nc%MEVJA9>FQmb~$=?wWy-{n>Pnr&D8n0wteW_0^ZrOBtEg!jr1b;pRdli zLa&p)F9MF`Ej=U-mUV2tLcBCVSbecvBDX4EiCr;oUA*f%O2zcyEsCwl&9_Iu>%(UM zV;1kw`|c;IYk-Qr+s`Jx$%LXK(zd|CyT9$k4`|I#cO4sTIPf| z2jUP9p>y<6Cl;02J4sl0AP4J_006DavGAx5*}3xZTNF*Hwb^plu9!aJ;X}0%IWdGHzOSTAS(^rJaE174 zZ#A=lcfVKA!>#g}A#DG(xC{}KMv}`myV_kTzW^4ijT`3N-=;MDF_yO<>dJ_V=Wky2 z$yK?rJYNmJJ2)}V8%lX08MIiivQ2(&&X*OgookoE(eBTBQec!@#3?{c!vNmrfW4Cf zlETOXAe-KJ%NMO_&(sY_QqwNTmym0=p^5FS zmrbM+-I-T6RJGi|ziIxDZP#t(QoC(`E?Y5waJXqMAcbe$9x+~$-+Do?lU9Ztf}JqEqF1AG8zDL*h&r?{v(b9yR+=7RPGMbx$uAb6v z2$R5>5t$Uw@n&^@UhkWp7ldN_MM-h6!I48Pfue8IE&QgIfi0LQMqk>QThcWYFm~Om zC}rB_NX6hUqQD9xE*(ip4)KGz>Vhm|%JP?%R!qSXOiD@k6rC{QQ&ppKl{Q-0P6}i_ zd0Y8F{K9jVf!V`_FBky3LCw={!g|3F(lafCa|kuZkMfr#XmoM0eo$*Un$BibDtgt> z)OqsXMe5)`pz$Kpi7f)ZdN5_V$Ic)asQl}f-b_c=md)Qyry*E}K?A&kottl5H&0L6 z?o_XXqWI*OjI)H+t`UBRpBad$KW|Z;3`aT~^w8jQ6M~_CqT8v{lr&lRJHv~*eyCTk zV7cj#FZe_8fK6qQi3=NCTrS+hMxc>oixKNk6gF$r6??>BX348e3wov3uvtuPpWsfD zqpX1MVz(VpY`O^1H;^tluXbt(mNrJt-O<09OiIyct2((2e#$UTm2O%15uEzjb$`9< z9*R?Xn(L$1Kw6-aK$Kz-4JxSqST36|Y8#F{ zVW?i)7uA2kqnUyze5%`v);14#4BuBd!L5zMlXN^Jeu_oUgo8T_2z9aL4kD`xN3|q4 zb-=SNRNka@+>JxZSg7;QU|#$k4LSMaC1}@{92LBuVt*b#dMyB9W9US-$AX=B)_|<}A@26X`E6`&8DP7tZ#@F$ySfO~uF&kD<#eugFHsn}LjZ#T z#%|>`OF@W21e&v=3?0lZl!y=(W#85Zh326N_z$_ zy3^QjGjZ{?Ich;Q%K!hrvy>a|KIVGx3-T3~BREp7RsQ~hC z4&+nRs}v=kc0#77Vyk$c!W~`dLO-l1FYU2(sgm2~nq)^V|cY zeXEH~VV}yeV40ud0>-}sBXWQXRT9n;8uwu=`Cvj?-1pSQOo3npcEVEbPl2Ml5t;;B zP>!~ZOkStoF_FB|4In)VLq#NZPK&yh_7zf6xfL}U}6RnY|)Q=5ZE8hZ~I*z?prc#vnbi423yA3evGdrWQ zn~2aDl z0B=&>5;>C4#qk+gBZ;aL;IkMj#z|XD*5_dO+1?Bxg1*lS&q{c``zmshH>gY9 zT-1(NLo`8|8eZa46w38IZe9FQJ> z$p|Y6VgWsLX~smw@F2q$Xee^Kk;2P#9=S^2h6K~8kY+IO*(gfC7lYCRV-tIIp|}iLC72=##6I*Lj;xA<91|DM z88h{;K^#&=+|Od66zl`4r%k%;TC7n?wJw$Qqdu*psI{Gi`X>;k< zkcEF#R~p^uciL>2NowywR!ZmVw?>84p<(sMR*Ub4Yr@SC;yppEuZ~Ir z9CnnuVUW;CybB!J%ARb24JThVQHOADRp}X#CGohFWR6&Xw35JV0TVW`U)MGl$huyC z3;L{6OfLfwS_X4eQ5ic50!NSH&6$ZoT=a2920&@9RhmSSZ=yoh&hLCB9iF4E38701xN)P8Ek#l4S|Vd;C7M0TN0vL#PqKB2lxP{mE+!gZAX z;56YFFS+RpSugSBc5E>d&_)4i?@2^U=xlalY!J>!41`E%6F^6#L@d zHp$;1I+7rv^Sh`|1gcBTp#8oaE(9?*C3y9B1+n5=GtQ|3y9F{KQ?hfI{Wczo4PlBv zrFuxKy?-IBf?Vk+5KeGAEkiAgz%==9=kHHuPbOqOk{~g?+(?#vTJ!v!gEGDGu z5h*hF?k@biw6#A6Su*i24^@=D3K(IF_nY$Wys#D^f@8vTJH(~s+y}}fH39m^iAV#? zBa-Rg;z>8~wcH|eW&~YO8EsX?Qy)ry@p`^P{wlmN*iGEau*FD&gy(W_i$9zZ{=qAt zaguuCDq2e>kirfc1mNC9gTiGX@AL}4cY>-y7+&KU2&@ia-}q|=cO@ue3ErGBHf<~f zaBC(RVq10YL??Vnv3+E-9(@Y|Kb!C!1$@fkjp~CXmE%Kh);$07Ks~;M{R)WL# z>{|rqfpShqy0QdQ4Kn!1Q9x_5vq#R1on*v57HLTpz3FR7{P71q%N8CrJ6zroUlR4A z-sqLZ)cm1f9~g8&y0Q~roa|=jANx;S*HX&rE)ED5Ld5i_CcUOd6bKlqr*vP&USM{Q^Hkt@yLt0CAojs_q=bkgd}^+ z$HEprN>xU_PrhDWnI%ACTz)HFrm~ZjXoeDf9N+2C$Goo^W88u+VxQttn^xAuce494 zs|WDbT>=1m2nix5vx<~6gV|N9@mu_tkQxX@UcTsFwbBBhvjKr?;|bq+-;uJ1Z9w-y zU&TtG^Xa5Db|Qy9L_}i60@pSyjqpX^l+!Gv1EagCzZwZa&=s8Q^&lbE2@d};OnV>& z`rjINvxN3KS^AA?LS&WC_IZ!1!+7RA7vuy~)1}QykCNK2>+u6*p@VMr?76^vWz{}) zil{Zusf=F;{wwh%HT34p1y}&n>^kG(BRydbIDsQdz#~S-x#XXP24aBDH}$XAV63Om zfmha=OKvoHi58bjG>yN^N=avc*woIV!g7{7#a!yn3u5N?asxqhBN%teSJrX^$=*k3 zY-tfkP+7Hjm?K@31N^R${E>y~c~v>F<_M5%J_?BekQvz4xPmrp`PA`Mh`4ljgE`Vz zK|V;R1jck&a5o3hF+xi5jEeOPB38?-n96;0Y{o@BANsyMEmh=Ej|YY$>~Dr5;7Dp* zxI1?jXtV^eL}EZM9R#^Lj=NN+YeQK&#EytrnK-Piv?5)%Eeim5UHHeOOz#LJeJ=iM zcv!#KR{ZS#%sSseG+X%_>uC^qUVBy{*TtS>nOMfbYn|+ z?F`rJ{&&#ZCBz=Y3=9vBuApR2+yV6)a5Oy5v&H3aTmi

PXYU&C$G+Eupghci|`m zV>V>^jKNd822nEl;6Cil>Z&bWw1x^z5j7fggA)3&$9N+BEy#yT-*q3T=2sFUvY>;5 zjT}GC?Pr2mVpqVjab=;cZcIzUoD*GIyxOlzS^qpUtQ&FvUqGBxP#LkjrEZ((_Q@aUX8sv zpK+i^3la~7_*r4P{cJmGw^=`JEH7py!X!(Cmjlw9k##R8XwzA)|1=2W{O|t^Xlx>`!AGv(^&8?{=kFOhF-j z!nT6^YzbG9OPapB%uNbJn~Kyw^U5HL+!4SQ1ec%Vaqhf(BU)-{`--C2w5-&g zBu{@M4Qi@5h=bHXf_m&A_C~NDO)iCdq`VakcBL?EPqa6ibs?NT6pABHIwu$XrMET& z{BE0|9bI@oaG9kPvdlJc!W-HwyfY>eDTdE-d#_+Q-i8;E#o-L8F6{s(K-j+!Ic*jl zW>aA#=R(;#*6Q?aM-Rj@5T{h-mds%)4d(j73KzXk6s7E`mbkZrHMpMynD?N3Dpwm{ zyqqRjEOX(xxDa>{dZSr5kH9ZsU6>RsIw#+Smf-!07_n}JL9<%J4tR=AB1k~ijx8T0 zk`q-{ISjdw9MTgaR-3&=^kZ@(Gc>ACBE=?@%a3o$%}h{4AcZ22=sreM_z7L|Dfb0U zBLUACQWao$6*wPWi5FKKP{;STILEQHp-R-1s71faj>+!9Jk$l2ukN)Jl$@p6pU!2{ zg1(O>-q1EN0_Z)vlswZwP6;WfW;&qck>npDC+2CT;TXQzAAFOxD+NByzMI>MY_}iE)V@WNcfYtW7iDl z&hoTu*u(vl|0bn!Z<3Tx404lfQ3#nUXVqzu-4!InpTCLJGa#SQFYy1+kW{PM7gnZ! zG!_X%psK#h$1}xhE{nZIL^>XgJyh)|p9zm>J81%t)7>QYtFtFpI>wzX1OO8S_)-`K z@85tn9xCtqFLG|W+Wc!HWvuLS%i*_!`htVXDqYV*@LS>h{Zu}>W7g<@2>#ScD`$^_ zEi#N7U}F|xmgQq7Qcy1n%{1Y!H#D;+DO;l z65a}N<+e?sKrf)TP&;xUo<3;TT-E7YLfDbU(9r*9_5|`6m#>L=fT#I6)(xNx=IiGB zEjg*H!<)5Q2hAtP3Hb%`>E*Jey~`d@yVc!Xw8WcOyn0#jDgsM}Ug4Kt-14WOW z?U|qHD2Bd1EU&L!JH`dKKb=v948$6%;YUCc^y2&4izRdwY2 zy9`sE-q$tfcLW=Wk*D2?LTX~lh1p}%+4SRPGO;q%-CQSI_2p^;sZ=0tkuIT?H+ZHQ z9y^TgnDwN^Y0TYihA#hLk*+?8=UhbKmm$7}p3j-oj7-UApJp#eQFx!9pH^=tBTag~ z1%sp?4Szj$M^zOncd5#Ic*sZTpcmivtcNU*FoJhJnDYOACz~JXmWH8RNq!)5&@BKd zmtR+sHCDR80C`4FRwQE*W&w8Kt43k0S=@T&25~Yi7z`#vhsHyGBf02t#kLzwQ3GaeuNMknm?n&FAi5kKgGEls$?9&cP2?=)qYC522s62suC}8J@W(q< zwhA<1^d_&d&ZDAMd<=tRxrCYUguf546(Q|NTG$|Q=$3#ZlNPw0P>d}ttS=F?mn0YP zuiXvjoIZ7~qY27R@b#GHBXJK64c3PFH+aHUQ=!)am0pm_OX%C>*<6r9^A5h$Y&^7; zQ}-{$&_@oeDo^+DrJABW$V~GNy(5t^u~9|@=m#d^VKF6f=4GDHsJ;W_rLJ3!mB1EH zXOa>=!ei-f#1UG-FR|B?!%H-x;R=^C2D2!fVjz}uU$B?md4GZP+dv&2-D8TSQf^(= z4m!(?EMy}YM|i(5C~bu^dR#sHt5|_Xb4DP*o1{^CkdI%dR-WeteWa*l+r-Uo`AhW zd_%G8I|ZRhO=#u5sG~1HeXN&*GnoL@C!tbIqG<trOqwSrgqMV{%jDOzXa^_pTyfpBaRuH*->Y&XC zhqILT=-I|#QeGiTx}C5MlFqt92fc8^(j>aYLS*p*{io}rKAC3lXLf+1y^8`3>Sv28 zN;<_J1|&vD%*75-!e!m1wXoq&GaQ~P7N^OwDw^r$9}Y3-a5>Dq8V^~%M@x+e`v%g5 zoPCF!6xOb6ta7rT>SOUJ#pwf?g9h6x@VXs&V!ZPjN3|-C+Bn(;xOhn#B4{Kl#G6VF zSCCAKRLrweWm0)}io(8vm+sFGa%M?g-T)L|gyRm$zNG??`)dmt)f(q6zFW*2NIee4 zZ!2KRzT{p!`?V5KI4?SK=x*zJlJxHzxOM*BuR+KTpKaIBv+bBX9P>VSjx0y-*@O`J z-+?zzJ4*s6JFd%?0l@jBR0aF)ogG^J_dHikxuqaoZlyLm>HqmXBs?0|(W2GX; z8IRyP_>=***bCNX$AHGT&}+nDwmBJJ)BeJPh*d;FOFB*@V>8nEJ&kU1xF2pg;QQ6s+OrgA?cR=ax~9Sz{7wm?`nIe zGh!EUL_ujrru|3QF?H=cMh^4(L27^nu27b*pf$q?{{5pajT&4^&Ik*gj8OyujSztQ zRY{Ypg9QD5nvadVYH?y$x0XFXhpu|<)kxxogC=E7ZSDlfHBk2RshS}U=mP6~B%0i#V zW|leB89@vJT4eNzR6ky?c>WQt6zF>0o-NqqjkXAjM|e$uRElND6YIN-_@_#r?|)5-fW z?XKh2*}`v5N^6NJA>aWAw>9{xg>v(aP;hV1bg&x}vB1?t&(PhSf3LU|lDMUhEm3rh zV=nCcX2pQoj0Hqwts>BYNUDaT zHAU!l0z0Qryqr{OXcBH9+QhThqd2-mN7VyNKD0P^X5WcQ5S zxk6@Lwh0az#P7&w_Q0Sd>;F~zmenV~$?0%BU!AP;rChMd2uo5B(cv-tO{agCXjfft zNp8t0X_!i$PwMz?C{aC;{sL9fW=1n{Gfht4<0a!Ordn}vUgXR64c#PP<2N8(oB?x1 z{f}tkvbF2ZJYtGa309RNN$j7|`C_GA;rH>9Rkn?ntBb=+k_o<5#jmp%RKh}35b#nN zcyv!k;4o|a^v4@0yp=4tXzgg`z0qNUg6p%I5Q-^n25c|&b~tM^-9)-a zXQL6iaAzbB2SP;=3gylm`RO?A!&CNLlD8_#r&Wf2)51WM*i!XAI%>Dstuzjp;iNYbP`-sGCjhsANjgrmA|8QY>>j^<+ zR&OrxUoT#%45E24g`qlgxMl4@?^IUDS=c(e&KT&qmUj3LanrbhtI$vf=M2yP$yf+3 z2<1x)WQnjg=Pdp#N_hAWXm7=K5uOmeI^_C9pkH^1_Dyouwoo2`jB%(TtjqOs+X@MZ z@?Le09w!Nh6};@J2A9j{Mxv6y{wQIVud&MT!%SQy@Wl(0al`KT9R zK=aONUF(s#de4O>E11yJj7=xJtHK0uWI2=(ZW7lHvC0{7nR_+7&879W@>R z*H)7Az%PAXH95>CG>rdKKJ-r1-@h33965+s{4bSn24X_?K_U`aMwR1JF~)wHwlpZd zH?8ND6Px3WLdoIO*vyH>ze@W=4T1|pi;RYR8vZjg694b$nEekA*d!3x>PD?j-I2Q- zKqsDiIe){s1BPlpUlwV6HlvMJ`H;$p6<|GI@fYmt4#VSp^Ifk#_1%WmL8pnP3}PB= z^PS*zh3QN%wJDqlOis~q7#$%UBygh!QI>`Sl|mL7H$9{NT3EKsc>(}VSxdx`5JN%A zEurCx2OW(&0Vng>b+ocfilc@p1hC}KeY z5PKu2X9xL(dl>hOafs-t8sk$*r_-nmRvCME0ZQ3fhKxyb_TdM-jY+G<9Ni5$_$8c_ zEe?R-D&rYAPH9Yk=!Q-6sC*)2#Fp55e+x%-NJwM_&H4pLu!s!QgUIpth8#2LilD=n zJW?_C*TN{enF_;i_!OFX&?IV*G)?=p9+dAM8!1YJ5gvGui ztD!NRF#dm&TMRWhigRc8E`jpGpa~?wqG7L-DSA~t{@UAUS7OEwua2pQ@}us@O}nmO zrw$e@iBJrd2O42u=TPkVWP@TS9g_St;q1RDMNw;=DRT+2d&@i9U~eo5KAx@=LWN2; zxgz9<;y;USL)2|-qGKf@@BvL=+$U*3#I9|DA|{L$DLD7|R6a2L{FlPkkt-5)ag{{D zcdZ^yW`c3MHLZuD&+{LukzjA{o~11CE*fhbcLC0cK49hjSk8SaVVmSv6)TQU60I(T zXDfH1|2(`@)#edX;;jT^M1G;)k$9qOnJ!W~m8UfcEdiO#IqSoGZiNSbwxkGi)GT#J zQWshB5{R^NesZX`(jr;+boYX4`VL|o1Tw-fB=f{0Gbc3P$0UM@AX5WrKA!#K{6R1D zYYsjWNhw&R;_6WPW35Ic@?AoQLkWwW-k?kb@6A}9=kh8=-JvV7pF3`=%HWwCR*M+Y5-21Xk8ou&t#y6d|4n34Z_C~@Et!|F*mx}W6pTI|s+(39`pCnFE{qYYsptk&6)Pxd zq=Hg|6^9F8*1B=fax@l~qrs>BtwC#$2#`zeSy=px>>KBS*eo7yWM@a=aPGjL+4#k< zrrI9^H_nZLM#P`}fiVQlXG z7H4`9izECqUgAq#D4cz#mcmsH*gdy zlg%LOD3q_5R!bI{p%=Fhd0CyXy~j>hA2Cs@d*f6w9TJD?{tG-30e0%oFqZ?SMvN8s zBtR#1!w8|h{D;sz>$!##C*})LZEV*^HhY6lYO}1zUYo#sQ1X~Le3KHg2+L5*np}Nh zAA)w=^w2%FMj6Q`z-Kp0*?6|nBGq@7wfp0D>}(ghi=s3Di7U~Imj#EEedBKRpBDC; z0QeU0`ktiINsOZ)wG*JshwoNSJv1Kd?>uI9AhFVA*^c9RaX^W5H|Nbu1XlHO-?wfI zQP<8Y<3e1~o7PHbBV)b&t|6T&cp$px)yei&moaqMg9kz$zE|)4XWzvx+$;2P0t`%E z6=a9@?$l(g5E1qR=1g*W8#v1D4F2#dTV6rnkfib|`5OFHfDEHFI5tP-;&3_6YA*F* zrR$dmbagV_;&veN$CJN|w)`wI?~^#(fb7`>AJcXva)gFDHAuECx9dQDb4H#Ua9fE*dzv=+)q0GbRfI4H(~aAY)(DZgR?P zoIw^-vT&u8hs^n__UfF#!J9pHFSX*1P*tRfb;S-02_#%)jz5Gp8Zk!k7VoV;o1xLL z)=l7Wuct_TwWBJfb`Ox945WqP3=k3$cErg9mT6iqXgvh>VqD&Fa4vlWnD4JX4Lm8X zt%vd#%{>;KJF1o9az(ohQ*`5hir69!k&STOS27eCG?lAxoG>$T#j?FZh@8t&@s*ur zT$urTP;FgSp?r&*$u2*aorpDO4ygw9q&2hZC`ie(Xe8R5bsJ~>Qovx8g4}3qa>0&Q zyRKSO@ET50C$2EzgHyuaZ6ie_2cS9Hq!%Ii4S?O@)^=Gl*2n|lR}3foD3-~n zJhM;HRIz0ov#8^1s>zI&v&XMGmzBTnRJpSfe^V!Aed=Vko z3Zouk?I9Em{$ z&bp!a0io0LPJN}Rhl+8(;oGD?zi`lhAsu~mjm982WE9vt02zh^i2poGPO*Q(9%;O% z*4W0}xe>rDYN zy%E7_P7ODV%F?_zM8bB(@nh1{`K%mI7aX7?$7Zzq=oIG+(k6BT93k`bAQRK;JC>ba zMy!G_CnkGNZ}=+b#Qb47k_I6pd3H3!MEG|$${2@)FpT8On|WsL9u?q47l(|WjkB88 zH6Ex{J58k}b-1O3uiv1a_q+ypq7kn~<(TF)Yl-m}`+>%?Nx%j<8{m%+Dc;K79fm0U zFYNmxnZ3)O5^LyV6 zLK3)MC?@=FR$Ak?p)!X}&;?df$L1WjgMcp5W~RmbqSSx(?HE$rV+`TCT@jE+Ermgw zRn+eS`j(mV-LOrHNzi4&aqOH>Xny10))JhhnkwLGq!vJY#8xt3j+j7KMvLflm#$)b zlMY4gu~fTNJmK>K_-EROLTi9LS$ELFpx9x4Z`zair@#5ZB~Uf&B!@-7-sdDK7_bQN z6jF>@0M8wJy2p_rL&R4jL-gAnT_NJ)$@{$qEc~_z zyIlSI_(8un9R7~$Q}_l_DM(VCyeEW{OVHaE@GIoM(kTpq#_s!=NH++pJ$;PCjf7Th zKA`rqh<37yz$9xTG+L#nxe3s>XnmKiwktoeuhLU(gt8y$aYhkk|0KZZx|c8JxRfBr zt4`7m*s+!PM?hbNa0@n^-sXfjQ*n3!*5#vr>pA_NEBY_c>Kc8tY@5z~tE6n>(^l%|6SS$Zwi~Kj8d?2%J=w?LI;mji+eJX9#(8KF!?bs!& z1&}lD+6eg*iX=)^vt6@#y*t+70fT3K`HBApd~}g$;LW?Bb0;C}%tuYvZohaajGQ`D zI1~4ZX-ptqk%M3Nlyu~ zU>O>0SVYq1Wc2O2ysL4ODrnXA$C!!XN~EGtMVsq3(f%8c7v>ZKj7gyrL@pm51QmHl z+*ottE|f&!E`WP7UY&Bo&eFv1@Sk5s>0?OM9xex(*5TN2LS98fJzARJ(=IA7oS$dP zevem6hUsv6#@!mVzR<4GH)PwJ>%uJ%$4RAF_b8D=2oOvHm;nYAF|c}lLRd<644-EJ zWG&;`Zbhn5pI1fqhWhqLDqvS;s@yE5v$&%D6pwcSC!1un43bKnJj8*T&nye&`exkt zts4Tav=*gzT^*Mr1q~oz$hQ(tuDvC4vzewa22(Zi|0rjd#8?5*w2)s$oN8C5F<`MS zP|*bs?Sek^ltau$Orc$jtO)H;{L+xM;r49C>u!@nmAC?6GpLu^sfloc35+=8z=JwB zA5FE9K>g)^GZ6Q7m)TOgUydKtFr99Xix~VuP4C<_);;1e!VGcs)%P9RYTrlyUj~!1 z+h>(egzmSpk~FKnX2g^u3RsdR`5dF6?10sQF}6C}(E0bUL%p?W$B_c?BHn6>{1edY zdRW=%oB2oZ$kMR5H=3q2z+^hsr;lYHRxZ@7zlVHA*12QlneZ-b@08Y7v#~Qjna7Zd zM!PGHp<40%N;agc;-el^{sq{~-XjT2`9b(~eV#Ks(RMi`VOCp}ztKVQ*ARweNj`P?;_m5p;S<>5sbLG>l^TL>VFL z%p^cPt3CEa@GHFGQkOC&a_=;*XqNp@t!DzE@2Z2>y1|n!Z1?^;QMwF1@1iMaB>Z0G zO!7!qB##RNZ5{%eshUU#}YRJXnDofmFL&HxB>e2U28&>ebM>)8R?9oP@?$8;R zX^MeVY#G|i$huH<>Vy#`3i%E7|HxJs>sNK$scs}~@Iv>3YGW>~TR#K2i<2iG}sX#T)+h#O|VZWU4M8r_yFmJsmVKJ z0n_hhPhMq6{6RaAeMkQ?02`X-;#mxrNA)R7GZO$)7Do2@B?^k zN!GUp=OTS)>IngXM6QX%*^)YCYo^gQu|iQ%u7MuhH*E@rAaoREopzjb83AY(Pzx?^ z{td%6*e!H;MXYSJ!haC)GP{`Mi77wgGTGM0ut!#dgKE0&NNsL@Y-HS{$0-PQ-f$y# zPTuVBG24qBn99$oiL-d>==C#4->?X!j@XY%5Od*_g-g3`2#3U;k5xl zC@c^#)x^$g&GckGfoaVC-Bnm)Dy0t6`T^^Y9w{o7l`+Wx7!vsrfMoVbs8EZ@uT+R& zP!HU1Zo^AoVGE&I;NeJiG?I2A($tsYVVZ?F7Un@_%w)vBuxAI!!2Bm0SA>8j&YDU( z2Zlk1OQ{5`NXF6$*sEZzUoa`qD}Gb;iL|COsuWJs+wP)j!t4>uZ`UB}qi1ud{duQJi<0a9hmFmQ%UF59_n%zw1FWUm*GBCVBv_;>pPE)o!C z_s)Vt!MW6OZFH`V&D!TA0TklIpt0ln4d2M6vuk&bfp6_U2$AevU2q4Sn19Vix`OCV zId9Ox|2tS8v@rU3R!jGCj~ms%_M8S1t-s6uk7zEUP2opuSb=ONCqtDr(Bo_#Rwtyv z`V+uJfM5A!Az#~LBcvhu3G4g2ojOYf1H@ouZ3ObmA7#ZIch5z1kVgXXFZ+eFGD9IAGPjj%Wo&+uQ5!<&9Sg>^nkIuDS8)WgIJ=QVUS1C|Xu#^A; zO}`8E3Hq;x3xEi2twpks#@$1za!xaEy9oRa9sm)R$QFLmf{&I`nq5CRfg86quC_<5 zr~M%*4DMR0xRJ|PWfB(;omwQRn1Uc7aE=77qOP2l<3RaM-<4TmX**c$82)OInDy~F zi+76FaND#KY!8qq1s4i?SBjeXB41b&0x8?k(v)F#BBMl4j*u51BZr@Vz-#XX-sAbm zg3E5ZH?S3jG&BK=^Zf%PgNo9lPL^OJD_$GJf{xIvtsc@4oIBfI@&J13;yzw#MkEES z^5M+7J1H-F3~Uf+l+T=HRFqf}Gi-UKdmA=CXvTw^D_gag83VI@Q%<-k$EW67XU5_> z$Ru&p!YC@B>RqAwsz+{7+GymdDR(LB8rwCf8ow%br(9$0?#(s6$|95%nz0i?^dJc> ztsms^QTp9hSK7d+`Z3b{LJ8_Rc+a#GD0?LaA98)W0s?4r@;GT-AM`j~b2TaiGk1*O z&9(Gz5mCkr=%m_^sjTSK(|CuH3k`D2Vi3<}UJOIQzB9TPGDT|1-2L#piT2R<`J@s_ zV&7SIWpFDyW`zo4g@a|q^5)a4>3+OJOF|@qOEYTHGNCjRMUt(2=X8*Ra1Q(x3|h%r z>+L_1-j7fs25@owWD4-OtAJBgR`@tRka_=bM{*kb8R|gf&WK}k;+)-^N(twZlV$7SF z=p|45_9OfD*WG@nT6q$%{yW6X72=J|o8dR?Y0~B6jWJbI_>$B<%M4WE?Z`Op+NQS^ zot1p9f{8o3pf`KSE~ryPcdD(Bq`uy`T{60^o#Z`bq+BAG=3zC=d2(fK z%NMGrWY%3}B*N+F$Uq(}K6gH_xCo$=nw%8~eJmxOSTGAh?0LjJ>R9|j0oFzH`g}g1 zGo)~dfic!*NOH;}2a&1Ibv}2P4R+df=LX-qMBf zie9o0ITu??|D33?0lQ|vD8_9-)d-*9j}V;7DH?pN%7{%T^T@QC#cMUv zlHLwdH74=L^#wQ$=e%;*ga~SpD^%wrp9KCuhkcaL{o|;q-xsPKRv!la(65uli66Ubp73Rr{S6=j3p2|>i&-LF8V zC4xu0WHcvbPegX*%t-Ygr0CjwE)5PY@Odq}c}VngB(SHNzHs|Kj`sZFwQW*z8q5o> z99I`Y5(7JYT?A*GMrQ#4A(N$;U785Q)PgI7hV(tWR#%GyuCY(ZYpgQ_s;OJvzrId< zAv6LL01l;@89DUBU9Ng!q@hoo&B|p(buX{SVOcfBoQjFU^t8~)Y8;&N5NcmEkAmoe z0Oxue*K!~HZQ`N*nz|GdgN0s``xx~JByFWZp}7aX5WDdGIqwamkV*R5W3!d#HhcDE zBed3mN>Gro5q5Dl)IJK>vR`c=s^5Q%K=6y(*9iLE@o16cuTUS7w+`ybX3K+#Q&r(iLK;^AzX9l@+~D#jYPer^vWytLcFi=zH5Ws^0!9*mvmwb@yJ82xYf@HU zy(MSFpnXG7R{{JAZX69It+QgZW~3?YUWs~&pS+zxGD3?Dx2(H{ zX9)p!xc$NrE@}*TrN3XPzP&^!t|h`^`vN&>{4u>0cYw`zB_OPxo`XcLAXw>$+bxPS zUze;cXG|sfK9a5+j>oR6yIs{!R1=BmVK)qOi)nkS$A|dSF4r@Sx=pkMdKuC=X9bUx zHLw$GM96VPFBp7QX0GgLX|KV_L?O{LgO& zJymz7Tpt1vyx&SWxI~1Upz4DPQK?c|V4YhfU z&imL=c5P;Hn->-aEELU0-%jh{GQcU&|M6mNKuXLLv|R`=@E))L0P-Lf%}`Fzn2&=O zZerOeFH1w}pn~k6WeG^r-1)V6$&YL1oR;W@KW(Xv-%K5s!#fxEdj9m0l_+uC*uV|L zUb-K{H!$3^=4!RM<(=2aBhu@GczztHqZV%O+K`Sh?cH$B6mH4<%j-teyI#9eW~uNV z-s_kNICE^)UFL?V&Q+JGJZmK@G6?@_BeLx{p(HSzxrqX-K4m3&gA*94I=0BEgKCTA zVEUBw+hWU0npl-LwHi`L=XqX-C(qFnL}L?&NQ`P7Ar?lyats>b4bX7DSae!3Fq87# z!(_}9NA+b+h^pAP$j_Eo^q4lDCJR&TBdLnl@p~@DHMCu%NJGr8_w9Rk_A*7=tM3~X zRdqnQ@v_8Rp>oqeg0ivggJCkXqjYz+aTUD@2mB7sEf_doRAPg^Q1I!J`ej?zJfTN}Z3Y8&$Q)@M3Ftfg@y{K`>8))Hzbg(UKGZ)DGU4L}YA zj9bc@qU|0LNG0!;sVno}U^x6raXmvAs=7q*CPXDNF?*GzW4t!sAcfzUdf}B#q&VDR zjd>IMm#={^EiLZ$8Q(-(5W*|5Mmo92UWO^A3ll3uD>>^euP1d8IU9i3qq;Z+usVBAhB}5rm%hLM zP+X}pD`Fpz67-8V@ToPMY=Co>@wya-Aci>qkyh))C<6chq&sIQE-UZZWU^r3Eic|H zO^to-x9NcFk5J6d-VUb4U?ZA@@A>r}c=q%2C2i^Nyo={0!pqQNT+6HwFPM3cvKmr^ z@EWJBuf68!QC94Y6Hc6+(AX2tfr2b@_4t=CH<=jxpIcZb*NNlK2FheoIEWx(Ulra7 zP?@cDvzpbx{vh|+#v)8{59Bcwq)kjZ+*O{UI?wqGP0_A|OKYjF2w3z#^$1g(RpeaF zoWd z(~U#Z0=#LQt&eiH{HvROSMARF$2x7-JRQPn46f=0Kr3ykFAa+3Yx8dU-KR@)tl z2je%i%TS30iu$<}o`XMjCE>Py!R|5=Bs5K7Mo9NAI=&dQk3Nf5Eq0;2B13(&Y0W~L zGe5~PhS>}XD}nlID)njvENcYBst33567Pf9L^Fq~&EJ9KaDQlwKz9EQGAt|mo;td% z#J(Np%H(ZCIqn>BTwF35FaSw0$&Fsp11YLL8BKN;ikucfG4PP+5vF`N-4;!+Zy;YA z+&SO|ne5zlO+Mu5)N~mFP^B8F5Os3)yFVCA4A|%tMQoy?EFcNUC*Kf`&UBRHep}Zk zszz_!l2^QuW%9q-_$8qGcq`h`P_Mcx*fmrpjJFN{5jy06knPtDn|O zL#J(NYME7Ehq?ZoqfB(H~uCzpnwy6=m3L;z*i*<@e6H|+DyA#H$-){Fd3o0 z*fO)lZn%?|A#ia^%&laBOpsgG+FW8{gY+x}Hk*1S(+i_6@Zj{xdAdL* z5QWv zix^t@WLgn}D|;TsJ>H4iranNS%Y(zy(O=T$X*9Z&Cn2*r;Dpr@YKgr4A$lDC-Ojoa zakb2#2~X>!&ErRI_SHHt!bmy!mS=y!zg+CU2{<|O<|tT(3vFw1Q&6RX4QAHzKMud{ zvp_K;N>3Y9M2=+TCl#-Tg4aU06X^SNME7UwDtw5L#OCFy$9q8=34t-@FGT5Y*yN7H z(;dF^1ineA_W+O9Xsg(j67KrQj`h4Io{##M#F z?d6H6K97sXVJ9BdL}u5m1Nt>Bk!hq$At3JwKz zYzQMcnxw?az!5}65#|exY4+-4&Q4ao73EFJmi&%xP1$)CA}CN7tpyXEH;~tr9p+H~R6Z%rF$pUEA!gbK8s>wPCjFpDu=%b3I9{cL zXpBZ90~ruMTGdjIj=gV2W9A?YIsqWZR4yv}Olm0*Q%R|4V7sofK({s^sbu3}z#y0n zfONG!lMAS0Ue`^ni8sk`2MkMMai+Dt-~0UDVu+a)k^0F7(>j=`=X;94esE^0r^dMS z@y}9^x-|0aPS(I9{PO~4ZHmIyU~9_deFsU}=*VloCHe~4=mfCYM1NBK)%6O=Rvg~s zf&sscYa?9uB;{}M-L@-$YH=+k{~Gm-_u+2z4b`Pcd>h*Vzau?hz>I~r6Jst?0kFZm z1SN^iG^_uNG$<6AMYZz@2M7~~u8`yjjslQ;j zb6t*1HY7}VY2a6=sKAIMwLNtqe1$}{S-M*}av>$X?`#amd2I#p>GAg_LQ$U8jUb%; zXSZc#-OJ9*2O;xZy5X!BGAp|sz3c#+0V2j``-aghs<94lLV8ZN^mJ-beyoH1(NVMY zB@oIuXR9s55|HTI_S$;_C9}5I6$LzV0VftYIFn6RF z{Ub}_A=`KTCS0y=xr?kt&+uJ?rSg_u zT1-%KC%QZShCJ*a5-@-OLVHpE{%i>*h+W0WsMy11M-l`Y_D)X^NnG%>q#Xc*vk?0m z$$V8azCW&O#%fS;^b+BqZ)WJEr{qGk|7&L09+wj(bLxdUXGz6P*pBBm7`*x(d9WCw zpN!#f+D~^dWl5V}A3NqczXqlzb3Jo%J6tV?n;9X7u|iRlFUS zU|I0L?~QRU!%Uu*l69xCzEvvw{wy#B1{n!KO z>Io8Fo?GC4?wiYw6M z)`SJ)L>X>pJ7}b8KOWe2;bur6G=H{z40iLkOD`);!r~2%IU1HNQ#Kr}xf_nBdz${+ zJM`rySith7sg>4Fz9|Bec7_sRTF79}jUyI}gU~nvBk_?9T*!R@He~P`7AI@`5y?z< zVC)(o0Wb!l3c6z9Tiq*nzd@4#a5xSfAG_}vJWUZot`Lc50&PPigA)vw><1JSRcA9g zWoM$mlAcMgqrE!yGSR*T;8yi)LV`{S7B#eY+u*Bl$7*J3g%}WC^ejPPUh@~+{|WT8 z3|`?Ye7fiN@3uxK+4~;Ig|RO%5-L!|4oBRL#IvGUA*F7HyU7N>0y>H`T%w6Mwy>Iy z%keXCL3oac-t-AHEadsn^Y)*<+ZC(Qt$$Nk$JZme;OimDr@Tm=0Jxj?VET=T^NKk3 zQfuIzeA`oDvToBeN($_XWA2>>Ebk^uUsoHf!k9H1u?E~f0xl+{<<3$S+HX< zV2g#QRn}`7HJ*2;Wi7^v8 zZ@RG>1%BhvC8V|hb8U{4*P(9ebgl4ZCrd~u=m&NxJXMkakI5z`0s>Q`H|?9@WL*Wv z)!*y@7aA{|5eVWL%@7LjagS3kk1hx9}n-*U_)Z8`!wi&Ba>V%OMRN{Xx_aQ`4qc4aC4ylJYg!%2opcYTnyjabn@i78r63UQ zLgP)3FMSH;i}`GO5JlVQjRjN7nm= zexC7}flj4Q z|1wIPbBL@@_~U!tN?u2U%48*y%clW`wh>aHH+-Yy zd3Rbia&Z>7?Dl8}tLO%xah!I=m5tkOWuboJzG(*C&z!L;-2W*jkR)CEt`@$WLzxz5 zV9xs=BQi&%#7sE}=J~;pUvmS;!O;x-Jb5X|P;2J_VaK&6NN!dTMT{&q0Zro{1G9tQ zt8}@olFn;Sy-LnAovKcQMy7kO#vE``kaO9T5tjD;OwOhR;NO0&cyBLVKLR?@iPJ!d3lO69(7Jpe|ObXl7)7Nxk=n8n!Wg(1hLaZXa@aULV{W>YFwyH#RsO;S37MvR3w(TEH zE85>`-1^-k3>q^tGqsNMnlWvUf*t3Thl^TN-4jqRLtcCa9&W)Ua zgIwOGJPkgI$NrbHmU0MBU6DqP&PxpQv^5rwjDuY^!*6NB>ngmhKGsta0U1R+UmS*i zAefprNzu0Qez-kSH~L(zYR}~=VdU4JGOJCjJ9Yx28L`b#nq)RoXFvS5sXIYV$ogub ztLy^VKgM8JG|$As?`d2+p&D66-uBoVS0X2zmuDO$;Dygp=m1bDPTKFOUltgE*x);h z9hA@=P!{V@7PsPo-6ru4*%D$61_VSTE^(Bky3^O9SU{&0Bl5x%$)!n+0Qo4f_#Rk% z%@{;OO!ZGso$gn@=$iR9jM^xOvPeMRt0eA5C|=Wm&QEX+2xLx2p_N+2AhC^L|DlCcFCtgfTOYBs=_RQu)12k-<8Kwpwe zaYl;4C?ITy8P9=>P=BBE;y<)TV$-81k*Dzz;t|5{FM#57gyC+q%~t8j<~w~CzjuZd zmgT0TCr5GDb=#OgRfw21j3TcCpz_9rkAY|(CC^daoDC;FONmbIm_pN6R^R1vD|r4{ z1DDz7LdhIHC2zqsjs}ze6Apqc*nCINg~?A2jsI@v)w4T<5>)dB8rp<@k#hqKQG);j z?kG;V=Ggh=AS0OV9W{(@p(p=vEU8Y~t&)(GWn6aL`KOfVKy@P@ajLs|J(5zs_T=RZMie0zpqgJYk7;jkfbm7)AwSayx z*OUwe%`InN1oW@a_eWOgcn{kD58W}uTnIMJit4z4#F{%|gKq#(K(D{$08Ch8Pu2bc z@us%LS5L>Tpji?LLK<1mYk^#yAQ%$W;J1QY?NzWZ8?Zi=?-qIzE(zPcBED>m&X{8S zTIKFj45{#5YJ;LxOMjjhYNm{`l-1*RoGrQ`Vl0{T8WyL8JXaa9m;dv$ESjD*yvYHK zY#cno?rDbibEcMLg#lOup;Bu7-phl2L?L2|i@TScSMfPGhCXg1yL9wASewAlS}Bds zlS}~2;UR;bL&v9be1Rv2g8*v`L$6d+Y5m9o38k8126f2x3gAE}QxScFiwl`?&ZQRM zI+t4@ToBmxyP+{ZsK0ZR@-HF-&iS;5si|_Mrx8Bx>8qpm5}9MIV*ouZ%jAzmveL?3wkF8kRrcl5dyzC;iF z+!{WTOO?XmB?S%Ud$m5}(;I7Ph4SWi;0$!HeA7Uq>jm*lw98<3L)7%n#r7qb;Cc&<`^$gNl)rdtQTui?|wUr-`H4tiz33 ztzAxA()o+WC$=k_T5(qO{a~h4p(n(*5G`^wdr>Yp!w@c(Uws6h9|7_!y$6=Ll|2K6 zts@b^BcitGc0AuzQ0Sce7M$4;ioj>P+KZC~@Zw)U54=VWbjk^MzyJVh*^aQgN`a)d zjfzoI)l){2QkV=ZTGZyNmCwSkk%_fcx)2gFO-|91yfuh2g zZij*Qb6ac^`C)`soD;J5+pR7aP>pNrKduPbm8F~HRKsDXNsYg~-vr|@gYQ_^a(J2v z@xk>zN)KAqeLY{h$~xy8$>le8L22!~s6LoxgSSf#Q78pgw$Lj$DT8hA<{cWHmG}_( z3s~gBEa98#FmnrPQ$BaaNF_&bc__2I)i8i)+xpCLPd8wzjF*we8E$3$G&6donqpTKz7 zHs>_Ve3e|4HO#-s~iR_(AuWO0Sc#i7o6Ai@;Gm~XD)PFPC3U?pLGfmu<) zNx@^J_|%t6r0zUU&>Q%%AiY=hPKmN&7|XicB{a2qqXCv5q0!JfRUm#X8|PsHi~`6Z zM$>DKV#F>=pQ>;j^CUm$jeI2gVCY;o7$k_BNYS=JjY-UpoX{vZAFWSBdRg^XMl}yz zv%Ri;`ARq`5XsJQd`hJ^H={hN?M7B?YU2!vmA`SrF`I%nuc{6L*M5iZJnt$PK(i`)DVr8`xsp2EA*)ifz{ zvCzTi$bR~gkXv;GjTd>KBVKzwoJD)f2{mX4}6E|fyq4!{0^F- zRIVF{kY7`lQLZs_yF}YHbDko6QQh1-MZ_4Ml{{qDKbJZQIObL#l3f|E9I~^Jqw+ek zz2-K+Gskww#(LJ}(@BysCsp#QJX}ac`ZEv0?%c$Ze3Il`0Azw99P6C=>{gUbB)7{_ z57)evkoky-9c%=a6<4&5bg;E&ESBW_A>*j{kEpg!6nszP-A_A+CIh2HGO6kN^5k+| zjn_jX$8nHe_jhpx$6FpQN618azw39vW?!5=@La4q>@E1JPZknjJ#+jaDa~o+i>=6D zGE&GpIP8aBnC*!v5-U+GkF&Bt%ZaOhFbtP3fn6U|zF`?sg{`P*71Xz(nKNT-o_r6yMgmL8uoJ0& ze|h<1lmm>UUaAQ6bFjrkj`!Y4lY=uKZ_TGU zw%1QESzVtO4PcAzXh?$|WV*^HqM3$TF+{kWt);UJYIwZm|2YL#a zlTZKh|H0YxW=`9SWs9&SAhUmqi$goYs-v<-CIX)3EJ~FDUV{?q76yh-9i`UOSv(gq zH;O(yj+W!ItgNohv8}pBE)H^ur+7|#$N-~;Tyo(p3xFuhWob8^Vd?rraiQON(}j=e z76lFuaz@Gyp}b^2!pO46DDNVGRclS>ar|N#foQH|0-l}%hiOAc;^X}g%3Cmv?W08_ zT^C|oA3&&p+X!dzi1y!-coLC31gX0cvh6ah`r)2$jWutDa{-^U4F{UISfr+R(JV0+ z=rsvdEb=%X{v7?lz<)*feVO1~hL=~ekC{8oSUn+xLZ4vZeq*xQe3%pEa?`hJx4NP@ zIRx+JR|i%>0ce+=B4l}n)aBhl$UwAm^YjSwYlF)h}B0q)>t&^iy~j%g8wb*!;lp{Z*` z9*5a!#LVb;)4L2F79WH1dLN^noU_)mHAG1o-UsoRZoKSLtj=?Czz_45>upVVfi5t7 zM}nIKAoTh$IMrh^D+L2?NHCI_g$&|b$ROpnWsd~@2meI6P40ec7LhZB9Ed+QvRBi( z;?%^4fK3c(ONGL9r&JsA{X=2kE?xo)Asmf_pc5-r21E<7KDu&j%*qlRPC9_jgtM`+ zzx@ep#s(4lpakmsQ1%+TQU%g5V=>Ayw+egU^qex|0DB4zr?(C*+jN8XsgVEq_NN||rbKvdZmRSEuc2pyXAiprnGN_+wkSuM*@yn^)}brOmd%ltG0s8Q=4jF&Y zkCRzM6otreJl4<~iWY9GAg%|0EyP5dl(+WQM))+jV)e`zqf%(5?@b2MSayV3;Qu-$ zuMhw?+V%O0TFuR6yw%ef5~+KO3|cNNZ>&Mh4RP>J<^WZtl0t3RWGznfaTz)~xCs8> z5bidA@Mj*Xj8T}I0uaT7p8eFX_HyI3Af@V%az*^_uS*PEZaL^q8RcAZjtQ7Kz5KtT z1z!5fbd-VLElWH8Jr=1r_W4#UPu?e)%$|}$PJ$v1xJqmc`(F0PZahK2Rxrn?6NGFV z9^|H~qBo_X2vjr8l_+RwY_EEEd_k%gi~0)0)_UBoDM2nk5zA>s?wZ){9T}{(-Ky$I z&&-<3W4mVuWdo`fQv!wV+=Bf%D+5=2GKU<28(V^KA}f2Id=oo4^U9algly|xo&;_J zV;yDJ)l*B7I)vsK_3nGD7DBMC0mcLBkyi0xUp=_)JpR4v+h$q=2frQw_l$evswEt* zAGZ!N)`}ROfY-c}>lob132I}-pZlb&7YSL37TSUO0 z4Jilkr4e3gM!!BET%?W)pv&#Fux9~mTqmgmEy-~=dH&J}3dj>ZqOO2-$+1c-Flay& zFaQ7`J_RBvdw%#&_QuJ>0!7mfNUjBv7CnDPw*&T@oGE6lGY>=he7o0;>iWq zsSRuviX=ngHYT$y8S)EHFePHJ5>=ZsvL7IG z$SXdj)JImG2#`nPuj-V1Ql==R3NxBE*pr{175QLysy&`ImR9+p(H@#P?P+7~42?m# z{R5_U7+s{5w8sWzi!wh|Jk0O3h1S{j;v@0B3zt7~X&wJ}OeVsRmsElD5+R#0#(GrB z!$A2QHDD<=F^*j-GMvIJJrix#FgRedZ6rYG6qCZZY^vS-?YINq2KKi9hJI+{E9zU7VMdA?5VC z)~|9WtYI2%OzVBJYVJ?O6(~Y?2r?frj4^RSqNApU9K-R!D%#H!U~BDc`5>cVrmimx z3cNH;&=k4--RZkYmaaB9HM}+im1pc3|Bzw%*jIce3sXcr1YFG&#T+OR>OWyB<|Z+D~u+N-bi(# z*-b;sKQCZH1$-)^H0Ba^n{cQEXYc9RacSXznH03j{l~zee>D7Dxr|7Z&v%a>F$KRT zZq7=5!0rH@!a$fGtrSqQSzWcYnE2D(6~XKe@Grxg`x#*g4E%-|>-mk{G+b-&KPDiG zTq`d3ToyDb9FltI51-V2k_wZ=TgL#j1}7zo;WO^)Qm=eqtMf8Uf;s*Ygs{odB8zia z>H@F+3)iU4Qv4)f=_w_O)4Fdtl^fO_|9u|{Xzxo=Nc2TFnacr9-qg`y6G zztJ4KaDBuv0bbE5(~bx8SsGp9eyJfVgwvC^m?Sb|jmOlc-bpK)!b<5NFq+`0T8Cox z2#KZaCVQcwwUy!#o0~=FW*@sXA|6A0YF6ATe0Awz!_XHeGnmZ_@<{BmHet*LJ(sHF zOoxMWocJfjRO6qQ?+Ak2-OkgC>=^THJ7w+9;%9XGX>Q@u9M0Cv8Gz|RM3|juWu1zJqUrOcN@sIFSd&=3BW}iQxcWotnBrKQH*bIpz2Ad3*Wie_ z>)whb*SKD7`k_|BJvF`TGiiavT+BQ0!3GlE9 zSIz;qa4p<%;9MO8)1^YyJ42s6gV>}_1bkwxw|8z;A1!S(+hEMkF(`WrC*EYqX?_WG z;-yjfpKUx0(JeIosx;K6h?wo?Md~J&*l?}MxZmD#GMp|cQ4Hd`73xf&AMraR7EJ_h z^hiJOI3C}|$&nk`9_!kmL7JK{Ruw_9n$A#EfAXlVtC_K!&gISM&9dUib07Nc;H!$g z7jikLgZS)N%3b9$rd(ge7_glgq>y?dr72pC7AKfV^8 zUOiT%E}oYv(DpnXU)Z>wQx#V6GZTBuN4i3pw0vuLM84O>Qd` z=B_()QJ*fwZC?&WY`jO^)ceVFBE^0B1zN{Vw51ED@hiU?zEVzUZ0L~B$V6y9zZ*=^ zgf3GlC!ek7Mn%&&|3js-nz~}w$?g-9#s^Ebe1O-a1A%$RiZJ&5Q7Qak za!Sd$&zIzq4Rzyc5NX|%aCwNvzIe!gwccy`BR~&Pt`P_^yg(H)BxmtIBiQHmu}{fo zox6M;PxSTNTLaf!k6dM$7{c+P(nm*7(n0>~IDVQ%a1Z%5_BZu%rbV|%4M+uPF6M1w z;!fmo7utZiA*PYG`Gf{i4)i767DV!f?m%W-mSoV0hcxxQ^@a2X8BaA1{tM2nOc6xO zVQbcMMxM~VFakNs5p3u!zO{0$+Z8Xdna1{!c|#V*ophp@j|6zHQb-7pd>8-@@NkL@W5io2BsYz^@7wJ0hhnB{fyJR#Hhsb&j2{#`? zx*bWtr_bt8o+u0ZOJ?&F0E{YYDtWggwU-k)zKeAM&8hQ2RaHm497>vNCDNm&L=#-s zu)l)24J*wE4DZpLOU>(i!OuCMiU+ayxkSA+Cd!2R_U0Wgf$u1u8J)5A3WL3+N;{L*tY5RoT_%;Z~`PorGBggtO!(1l|9^pM0+X=o{`C zPZfb?Nh;g;kOAh~xmOiD?IJ+9)Ub7mq}u9>OVhySNs#)rYn9j@3T_7b+@3CvH<$W*C&0m>(N`#0w*Uck`ss?{|*4S}+ro3n8W= zC$A(*^x6;reo$*xomb3*LnNd1*vk_LtLaRs+QCZ#IcweJP_kr;-Y6Eb`4o`b4%ENO zhuzuNH5`+uOJx;&IH zgaGMT%{Qa*nnCB%5gz4dvJ4iWHV*-!*(xEXClSdfI*hbg7B9Rf>4g9UBGphSHGx_g zEg1X;id;bIsE4d`l}F6;C?USp@B%TxD-IBG4rXxg;EmpbfFhU(-rm7ednv&$`Khl7m(&VWcDZX71 z;OwZ5m(P4Y4kD*fi(pi-y3~!EIEHW+ic`DW)77$LE=vArO3~OWy6Ow;S5~`%Qm(oR zV(ND5w++7Zod3sqtK`W1m~qfUw~n}em62|;kTr~3wZFuY{H{+z90gpq@aMty2b(2Y zjL{179=|*v$tvEJD?+h~mO_q4z7u^wVIxBkj~h3iY2v3$$^O5wp7HxpHf8W?g} z{ivthnq?kp&roua+S5u3KE-h_2bJcOvrs_Q){WnID3_E)$3O3$6!-~zEP>LO-JoPQ zz^nECg{}xabz^npP7 zMb?AFn_Eyuy=KVkToT#}>AlW%-WHF#lVQ94v^-S}mYI@z?T5r3)_4_$C&zBM9^fi4 zD31>MG{41#m-@!oMybH65bS_+PWtWgnwmyA;wO{Fz-~HXt?H>kjrI2C{bXChs|_{I z4ejo$?9p37V-A67F0eK{6EOKT`T2Es<&W{Lo+A%;2o$O^+am2jh@%esWGHB-TLP)C zTp#DfJ zc102N!>uG_07zyxRVyEG${RezR%l{46M>sITzRx}TnvvJrQ{z7aGa%ZFhO6`&1#MU z*-;5Fm?L=wLCl87vgnnTSnr@5C;O*8sEwQ5G9pYI`B_G(ILvQbjrRvq9c%FQTh@vj zun-IV@EISf2fy^O|087LD(f7}&SBz~6ZHAUY3AhF?75eT}59G-a` z<{CUfMjpqA&C0nzSiP20COIM+m<$ve;wbxegn&zg%r$ax^JD4o-baT{1dr-Gsb-j8 zw&Dh)${6_1DoMO+tc_lwFusij5)Q3AX=~aI;*@4+_13$R4nctTu5Vy?NZM)Z#k3!du@y$;-l$8x>tj-LHgdj2^ zJ(rb+kN53ZH@6PKg3hD^1yL`9NK(xK^-(L93W2&$KSTg4AU}E^p)xu`W~=a_9yNmf zaOFDr+)#v!AEKp9D^5yp4KEfB5_?rE5z`9(xk(J11&5d*RBgZh5_IDlp_Sp};2!f; zI34e-V$A`s226TI4rD}j!$aXpUmK<8pWp=jKg=a<-e>s)JkXMT1`V!s%$OzU+F*NU zf)mt;h6oO`OyKYU000*qS&-CC+>{vl?T_5JIlS)~rx+z!{xW5ED9&ecdUrtHl`@L* z_CO(0ef_`E^FHusH~_W>#+PDl2i<|Y8vX8#fE}Z^)bO@@tZB2?ta8+zN};<~v1D>- zQfnzaL=yclVk^=ZJO%nvF}Xuh37c*5!d}`kqPF~4L+A#Q{k;7jOxH)+4N)jvr&D3_ zZ@Xc`nJ`HyQ!e59Zhaj_`kv?AilbChuf?twiC%xTVtAoP^R7L&9)HMXh-4*0NvT;< zHqs21-Hw-(_twkUN@P>2eWf>pQ<8GX{>(4|?O1g#GFwCYyt86mjrN^0_Qe30^Y^a|y6*z; z*d~tS^3l651S3qsqlocIXhEa?yec^kclT1xK}F<52=L`*lhUy$R&HRND#OT|08XTf z-CHij*4PLjQimu-JkF2a0yRg%e8W3^g#Hhj@xU(Pjc|3#S$e;1l-Kfsy%IM?X=>1e z5#t5AEqMU`30ILpXG6KCiAoMS|3JO#4UIHl;0*+ZQ6-br2klxFnvA>6ml`#-hd2M& zDVLc+tWVvRzK0!#sT2o5rRdwIGrx8P2zlCqBtT^}_dfDZEh!hQh-E5HB{qyP;yHbmAH+LnXEC;HOcvGzAHMU+efQh~a{ zVG&MZwSsTMH26_e@rhUIxpnLM5?{AuYjzj2qo=bK@Xp z?`r^}m$;>S*10S}8!!B;*zS37$0L1N@SwmUk(1z?jx7J#a#uv>96R&=zMz~&abO`8 zA4eDt6MXmWaQ4in=ITSKCWk1RgUnm1by5gn4vn*ZEyt~z)-JUEr4Ga@VIUX8t?0nIV=3zIpKJFixiwmwgvyF54HrG)5cK~6bxdK zOg)Z<9f0J*ZX7k(IE}BVbXt5IL^%Ji#cbdR0K?xMGm3dU6oSo#R-VbLT0QX$OMeQx zds~q+E_ACNx&i>*%6y(oUfRb<7%M}2()jFQ5ppRWFfz~Q5NlC~YN&uD_$L)Vun@#< zScEW-Gpef#K6w0e;E5@g8d@#x$;-17jjnh3EjCYYZ-TzFC3b$N+a>tzc)B0-C4i4# zi}%#CzZ}^q&7_*Wc!v2#`sJ#{fI2-`Qz62xd3jZr> ztVvhnV%ttL&x^7=!S?tgM^je(2pY*Rkk}?EU6Z1=>bH1eL0LuwhAN#ONZ(tHg4C@p zl18qZLua&I!~~gnk*rcqt&^vtO6KSl5zjP^Hdfab%8Lk*(v7)#q6=lw*-Y&?A#hi_ z4qQaGLxa98LN&3f8zFJ!twE27^4@hm&{!dZH`arJw8Xux&!3h1M%$ak}dI$bEc z1TynCcC5_TN(7+vRbetzIgvsV9ie&I@VSKBCJebs2S1=-Q{Dbm|em zI1HjB=R~93<@N9cjuhTn75JE0mJk5xM6nF~q<&p4YgTaL{fbRz9vDi1yIi>=R;wex z?n)(B&Az@R&Fg=XmOI@MOcLV@Q+8VV^FIXCFB(3TSHR8i71P_%Wat;r7_4pe0m;lG zT?{v3(P0*g_MJQtoudhKFsQ!LnR1$w^Sm*%mz@G6VOs()$wK&+H;1qDVu(CV&kt%( zu{HmCX!PQ;q}yGr-CHh|l3f@zx`xoPrJJufBHNg`v1*5tpikmF7kQ8V*0DqE8CM7X zeBYQkjeIN_@m{kYQv1M{;(*|O_$*}{UEFTc!O0pS5-1;{$Yh>~@fo?)unuT1guks_w zguriAC`x3xX^`dM>z>K^AMv;TS>iZcd~)94@NDjymOX$G?}wXF;qBxtPL3peoso`KiB?XC zf-Y&ijW1sIsB1FEr2T9-swHiCcv%-q+92*f%O~3Qc^;s{52AZ_4?52bX?dm7!?%xq`#n3e;S^JQ zJgxTXQOh-M60*D~6DVhfSia2~D!j=5UfAYF5QNM4k1bx1D2q90brB58DZOrvYwkVG z*CQ!)#PWfJx9g}vXoYL1W0lRVLu z81GmDN+%I<=imO9%U=qy#tndvkOiGvj(&Shq%=DZW1A2TjLn)2X(~XYTT32V!!~P& z$O68KeA*Kq5_v%U%sQo{Rz$y6TdUf9YzGN2pG$=6@C;h9;8pD6=}>_eh+`{#y}yYm zvw@5Y#-i016D~jG=Y5#@@12XYb6LNE%r;w0e;*ac>LNX)_(~O_{Q*N?Hj?65s(72~ zxv~-ON*4EbC`pjOAEn292xJ|Qs9XL|Sj4S`P{=u;YgQ*>CwtLg^B8>LSu&gpj=5%s6kYPBd#l7GDZm#5h^e{*eSD4m;VI0Ao_D|eD-H@8(;r_T8wY^)o>f$8+ zzMwhWj;v{1u0UD6eu#j)Z_^8p;EdwtAq%J}LnX(Kd=O_I z3qpyCiqxlmplI-lT~1I%SBz&Deoo%*{Z$FwD)lqzIZ8>4ZxSQzlU;3e908Jnz)d82 zGgajLql}|{T$xuppz$^a$z7&>_<6V_WnBwb{I>ZNB_Ly6?~mkMz>$Dd00k?hzQ;RY z5xlCtMSsyI2^wI!3?m;N=BII0Q~Hj<^Or_CVJ|mh>JpSQD~-FH z>6USYw(f0=yko}e(v$TEoGZ5EYz9=3Bdsu^B-o63h0?CyN);#?%OT?21Y&nV9|t`I zW)%l4fIVO{-7b4-hG(mkYXtQewMM0aQ3;FYL%Udk8}egTm^c57=r8vPRP$-fVKqBp zvjRh@xV2!3Kj@k$~+M zuIb4cjp3~p3)3@myu9@c)R-&FJEomaJE#TFEgl~Em`CU$<$yHx(yJwGCafr|I(9>% zC*b_+^mmpd;uq%pro3tt)dm9R|6In#W7>6@$jA@@j#V<%CmM%x&k+wAPaEQ=r=mUav8kCgV*8yytqu=)A5>^Qe*rK6tcVSU;-P{9$rT4+*X^*+bRmS zb3P#h%qpi0*hJ^@nU6j5gCmikz@{9D^29Rvfgczu8(8p({iV5(v45RLE@6sy`P&bc z=b4gJW*J25WNlt`E@=^E;v{^{=P;!VRTGAX-_sF^P&3N45I)G>_NJ=xT)D2Fsr>+eNQ3D3X2!!kyjbW3~e);Xg3WeiO zO0#YV06zH>&jjK#2-E-s!H6%;lcRrl3`^1Zh~LRO$lm0(0FU_0^Ve@?sRdL7gGu^J z%p^tjofmR>~fN&M3Ry(0mzIcgeFRomv@45WMX|BGRHSc9l zUB5)5hH|R)oy@W6-mF*VlfK!?oJ*N@XO{A`bdzn)vl4i+t&wpyO$&8~MTnB>a);iZ zq7U!Y+r>xF*G1321d4l33;zp1mq#yx^kNG%ZIL%1CPGDSgj*f0K6d1&A9yR~zyOvv z-PqJUCN}OrCy7R@PF_&Y`g|u>dyo?XkK47re13J6h~?ox+r>35sHC$UJE!q8z_OgI z53d+QY8N@irh3bJ_~<|nFlgftk)nC}EVuwu6N8&X)u=q98xDTP4b^F|RL6QAulmqf z9?00j$(Wagt;6tyF;riO_7&Q_L@44I$grRZhi>AgA3c!Us|d@s9Bor%v1&RT2y^7f zDwd#b=up#uR8{9yrjp;L$=JBZUZhy|U%Lfzhp&>hl7av|+X|a}%5BTmbu~mR{R*5r z)k*yAc3axhO33ySVLCltUP(&i6>Z7Gyr+SEAN8s5v5Go4!R%0Nl4s!05$CwWZ#7Ecfa?itElBNTzPP*iURI{;=|6=MlAIlmQIx$$k3N*}@=59i zlh}tedV>*h!9+mzQA(dy5$EEYFd<6weGxFcuM~dpKa&rkAO!Hn!arD(W73=@L%VS4 zEf&p;YV|La4d!jgkDE?7oq`oC)SJmUX`S~!5MF8Juodclfc!>RK`gN4J@Ip{N`{!b z$yb@_=ZznGj|lb+Sv%?b#1B;)TXA8TT`QG*z_mrHH+xaYC&f>NOpg6#sw7$Ov&vex}OMV-Nv3>0PnO$W6Z89G)(aFS52i6%ARbr z?Y>8u;A(aN00145AS^h1;rBQHj{&zkmUX>#%$JhaJ|z{#U)T4Z$d{}#Bkn%G?|Py{7EOX?y;HPd^-_b zxk$+OLB40rb+(0Z8beuB)i-y~psytW#yh?SNFqRq=87Ld{Y1mlRlUZckFiS?H27JH z5TSEX(x%OG3M}_5Ic?liSHYMLtfQu~`MOHxHZg6dVO|nh;I~F`9ix z1*#aobusL+Uc032nz`ljeDGUByz5vCCVZrH;SltepePZZ!6e>ean+1(kY&0MLFvLU zb^f7^)zq3^p#bhBxkUs}SyMZcCG(!tgwkrik(h-1E}X)3ZObwH5oC5*ihKgIjnNbf zm-EOabR+qzEe>>oUeMGxl>J7P4Zk2ous(lop>^n|4^A}2EOCs1Y;dFiN$i6X!7C1a~s+)nv zwvz@pLA;3JvqczUWiW_1&PIRs+6^Bi_!1V)DX>05LDql(000V10000*%#a!?Ea1{+ zKmyI}#|#eu_ve;7>u8$ZwyNOWR(;I-pUy%2)c<1ZdFrGo4!iyATUU(bn%+3g&@XmC z9&7(ExF7crT>x~wDJxp}3N>G@#~tbx4(lv5>yTDV?MAsld4?a88X=O(G8QVWKWJxF zOdMN*xxYXmPQfzV;4Vai2TNc$_c?|^na2>^cYI(5W=feK#sdkGZ(vXhgM2D&;00nF z;oW9oP;A;>HJe-!<|cdF@qeUQ{n=^j?OJ0m>e$NnZbe1i-)c4Y&pbEqhTw|{B2pBC zMe;JARps2hN!Kgald$vs`hzCaqP;8DTq{jF>9Lm-*9*~3yPT$R{wX-f#7g(v#IG;z zIAtO>&KQ$%a3jYNcEte~*kZSud&kTfI$MLK6p$e8fy4*|WGnlw(ViRTXvCISxslzd z?g-^^Xd&EG;xNC@o^peYHrkY5I|+2EYpU>yL;g1J+5YF2*t3def(g_y^ZmskGJ;r$ zQ3^?+p7OzhewSmxWivOdaS=M!a;zRM-)53Z7f4MIB3=$f%*J;Xv{kaTJ%2Gp?=REl zD;s3%5#IM6L?@j%NLPl_LKQbz5zj<#2x$INP`^NwFF@f2)u)nr6aWA4vzWI%gt~s= zFUio8(2SAy|8xT9o%>?*Rg+iRFz)PgDG6df~= zC8XnDaC^>U#`TTU}JD5~zsd%2I?eF&};6vMEy{z~?Mh*p`8Q9uS=XOZq_OB{^W<+T)RNom-P$s0mf@s%jx@Yj|1*iY zs%DhG4I{m}IRc`bu=Nh_<#aVW}Bt-LvRrV`b?0sqwSU76dQgiM~yAM4px#a zI}kI7a*YAF3<}l^NOnaOld^4|_T8BbWBF@E{#{1)1X-A^-)*p}W&4;ZCL>!5(7tS0 zVq!7Y-Mblnfb4QnJ_&=kN;&@rO0CZ1GkH`3<8fHSU+ue|E?0^@{#w$8kyfSAodFL- zW$4Ryo&Nh}&2|N5s3xAW`2P#( zzc8&;{Ou(P$ct?aKh8Q%eJ0wefH=xrYagzM^3>CxSfJ)O42udU2MUc~avmToY;c}H zdB+VSeN~=l%P*drSd$!?t`PB|4;<^sSeJ@wt=ahPTj}Z8Hp}ujwOwk(4%9Wy=t1$8 z45Y$1&xKwMpw>*h?PAv`!*{FwJ>VO{im9)re%7G#i7YF^ z#oqZk^34f=xPVm=|NLrp!k(KH2t;}e=24;hLO%_e2d7Inc@#}LG zVsll`pL?)r2}??(d!y583OB~1)KS18#vEU*FPf7`1d*$!hP2N1FDNm-NQVFh<$wio z3Y^p(AvxtMDEQkCHX0B`)5g+3hri6yT#oeYq!f?CQ$q;2uOO8#e@eJw#Qpov{!UAd z@%!OD0@!M5zkYEk8LaICTz+%~7vP1foNge#EXV-kWIzFu=Ati~~{j$2o=H0J-%&2yf00J(Qs8YDGTUY=4W7J@-oo1!!8Lqs5fl>Z7ce@6(0 zX8^VzOLUj02h$}?0lz%Ijv}=bBJ{BCb>rLUtFWhD7|n-QNZAN~b840513;!5E}wHp`p1#Pqa{arFwFq@ z(Ok-%aXMslnN2X_RQLDI1wUK=fsTn7Y<}=>QG9XQ`=FHb3k*7~`o`!Ef1u=nql^Y{ z1rjU)XnyD|Q$Vc0S3rmQ4A5V?TdIemG_0ap34AZDsYLN3 zTnuKmk&}H0=;ntS=*QmrXc2qFF(^p6J4&U?aw4{`c)p{+6y6V&N||J6B;vEhsZu7T zFPWVtc|i*~n6u1@PCOe4taUDmcDaEbim(YdDT~q(rbFk7?c49B8VX0Rh5ay?$augI z(X|jzEEk^zf+!wTMXq<^)XMXJ1(fVDBdON1%y=Lw9j4)XEJZ*;+&1xE+o|k;{L(r1 zY5HL4tSn9;6(Lgg)S;X`@D%WIdP|}ukp1Hc?I1wPy;z&bF@VUbFRAE@X$J-O7ar_T zFw9-7*&l`M!=&H@Xf$^K_~B}RDGx4wJ1!S{E0B?RQk@Wf;%AJH#(!U>YXw2 zo1y<6kGqj{+JHe9BuZyRm{t~vG5$)t-mPlJNjBVevfER zp?_|~G{QDUbWI%T-GtouV}&)J43M+%2*Qz0=W<%otF|Ua zJNi|Z@qgGBMX;@v%dL_$3LHOP_u*&XiaSSr~sViNL zoa}fg-bijW6w&TUSAx0}xC>*bgIF}L^3-ik%D^=+%4WRa?(=lil|JU?VC|!G6_Pu-kF4@# zS1w?_>NFOs1KiP6bH7K61Am@DA+f@qEsYi#t-?Jo4Q|9kAj3N7 z4N4$9)dt$*)R8C88P1gO)~-Tdb~k$K89$F2I=C(g9&R1GTFC~nstImxqS{gQya+?E zS>xzkHWsjmTgr7R@U?8$f!e?T9JbryBCnqWkY ziPNUeXCYN<`pcW~@nyb2p#H%D6KHApnN@?m)OGwy7ZRJxf;8hU!``~)u76_|?7-9D zmHNK^4h5+>pgQubNgSat|5OB}AS+u4=0dM*^A@`yV_egUs2)*} zVNv=2{_uwo7p6AF=>iaUMK$|pK8Pta)|QJ~>=_1C>Z|J!B*78=m9tp3C(3!B$B<59 z%AjU>JeI^wa9ujLcMYouv7*n&eJXISqg{#v-T%Pw8)gC^#5-{?b|9}#ngFM-@XwnX8I|0Dfj;4Yiuf)Y$f>m2JgB`hZkyN`nO;9 zG7bMw*8+>O(^maD!E3mdr$kI;8BD=1-TnaoB%I8M*i-+4enHa+3FuYW>>NyAT{bEu zf{@_!7`^zvD!{1bFUn4!VgF0zDvxiyw}9W zP_(Xq@>wBpbYYBNJ)%FiWQ-_Q_x%qZ7-1Q(Kt(QxRj2@#Idc?LUux+?f{GrVD?eXODXq~crbdxhjzQDu5LVY}Dm;?hWm&DNOTumq zjCjq2X8fkL$St_A{9yfJ>iGpVzn?{Jddy;d zDpHJnkZ>Ca;%P-(=`ok9Xwzm}%bZYB)j3BRctf-wEWis;)5?dBkV{mF`@3c*z30(?2?Q zrLEcwXI@+Yg9OA}73^zns6mHC%8ud_`M*wI`Yn9wAp45BZB}->S=vR7eY%F+V~l>P zFkl6LJrmQW3CJ_4HeAYZ5_;GKs)HX?J2w8+tcu3e$S%Y~n=@3xA*%QEDm12(b$>xB zW^qUdrQ^5i+oA$sP`4pxS;llP3RXMZBcBg~ zLmUMn2PHMm&Z7|_?j4sro*mUDz~hr)mHWv8E!(Hdo%QWD1xW9NhE-!TH5$|n>I@%6 z`4){`5NV!-B*!6#liP96Or!`y(4bVPKm=IMS@T5KjW74bz&QH%28(f~=Z0f;81@t1 zT2ps;`QIBUz`uN>Ju+uMlyck21bUpuMou^E$BupSz&%9$ziRq&iQo!Z>8qm};R3^P zGErUWtB`w_Ik2j8MIiwA7ndINK`VO@pfXHqrbG9hWRLN)vRkeUrAQ9;XIeJpVHfdRWd`_^6a`T zOCW-Y#Y!pMx;yd}Yi6o|P8cGHa2c?6vPNjv-9l_0$)cV=lrq7EmJH2=k)fe59{N7T!I-iPD{E6XX zdnfA&H?UMPl3NJEp-T<1h@+}Ox9FIiSR`+=i$%y($ZvrV$MEgKFtc#M3&0(5LV?tm zL5`%R`ff?Z95JbhW>?MNA4s!f$*R24zC&#<+>lDJ-yM=G)^NJISYCQ2o>4_SmC(Xr z7ow31Y|k4tTHVUPTY|-1)>U?W=&7d4^iRhzjACPbZrr0JAt%a!y`IuH7eNPyib0J_ zWg(@`#U?_+$Y_pIJp4yfe|4e3yE^n?gMQYwL8P}1dbZ9tTAV~Hb;H=RunEDVK^0+A zcU)dHLMd9(EVo189`h^45^V^ZrEguHxJoFxAaZ;1Xzx*hdb@p^XVZz6#NsXki-=CP zP>$$cQ|wCvq4o^%#S2T(%lLj|V(GpV4m8qD*s(1g?$s+tka_?XbMWW6d3ju@ zf2aKj#A$+NBTr_w5mf)#r~g8Woce)x5--@Vz+Q<4F987z^f93Z`vM(Y`rdo~fs`BI zYLakC>E!Xnt}>tO)c}_0&crAV#|^_teEqG;Hfb>;e{h@P%*F&Lbf{SuX&|G%0py1o zGaGVi6l40FPk1ze1aylh-sG72Ma{!tOVz7uILW|V@+rB@&oB2Z{CN&I$JhR(S^yTw z>6>IKS(eOPrv}GF3y-FnFMlLMxwg$-i2rDeMS<7WgEY z=*WG6T@A>=GY2+jm6ti`opZpwi;FTAn=rXyg#;{%H^B zF0R`iD}Jg*ssBR0ub?qWX*1Rh`XHuQ_|U0{d!4vR47c_|e&`S8WfR#ve;EH7KhNDM zFu=_uWmV9nq9ketmX6uekH9Bz0%eT`QlE3 ze1%cx|LB8?%HEl~CU_WJJ-2#bo=-MF1;# z$NUU_3@1n&0MCSMrYosc_87Rzik?#fPDN-?jsp2Zc7zrYv}aa<#mJzOIo5^2Z;5_@V}$wTy@i2`&bWA2tUYqXIT`p7 zbz|5))%t$Nwzv}KJ^iDD%Ii<--|uy8+&39^sIfdR1ub^Ol1J&}^1Jxr*t9j$0|d?TGxR)AnWT1VaW;(jU-j z>rCh(pOz@vc6Pb2=J;Wk^6eDt2Ja%YtAuy|6=GG_l6D4gZ_g8|q5u{TNdrl=g6cQ%HZSn}-zy8{J-sCG^Xas3jO~qCX;8*Qe7J*ho^o>JeCo zGIRCZAIc+@%4XvXm#1hS{i@%zxHEsz8_PxB@sTnBAY=CKmJu%`J4D8rV|Z{K#kxR6 zYtx^ixrJ0+_+q@lcrLn%xNTAqzdbG6YH|Eerx)7N#xYg8_Nav=x2NS1zmTfEvpo+0c9}P09CKw^F(6$b-^)v(k`wz*As`rn@7%ZKnUUGn;wnl zc8=j8DOJbfOd`H7`&JW2AD>v(V3MvPT+8Ailam-^k|-N{pR7${08{%bU5Hpp64V-( zA{;U!1yzeL9c)aN?D2V>jE(h9H(4=3RK&{Z{Cqw9n0wa&6J^mi_J~WIKr}duQr$~d z_-NI-_o)I<FY9zf1~euZ3zHrG@d@>!$nA33K1}(w-Kj|(Aot=1Tr;P zxh=gAp?sJz{VDwYyp>2X#pU5z=xHTSvK951J1+>I^Ssi3-2f&0PD>@^-PFleA#9a* z+@b|!4)#Nys-AXvl)Y+IoG2M78=ozJnHfYps~M$=je=-JY+S8y;@PG=R9J%_bn%B` zn5aX9UpT8R`qQ_A=Q~vc>XZ3iysbB`m!vVi7UuSa=Di7OjWHj(GkVra?J;x;JBORz zAVT7I#v#U}0b#V*vkR7hEaI1IW{^JQ#0!i!{FH`_)`WE!Daa2aW(Kix(NYPSk(^6! zM3QfAukZ$*p2fNm?t)auICT|Ad|K$6xy-K47klEY*@r*_fG~m1je_57Iu16fu0^WKtgExAKv07xXJzrAGeT84jKB_^?|^xhi^{ye?nhOLu9E1e##fuM zq5J62;D+I4q7L*hiiWqj7@ndGkIHCXS_*E436*)FH5+z3>SU#ceLi{5nTfP#k+a6Mpz5oCK01;xa8Pc5%TnPFOJi-e=CO|>~q%Ax3qbcQI;Rqr@cg4r%eV|8X!=xm! zP%4X*)x4o~M!kf8Sw89v%5F>-^80Fw#u?@JLb&%hQ@VcoWY%k4qX&p;a^lY~2_fXU zg(tZ|>3)TYQkIzjf+W`Oq4td!wAu6O?W)_EXt+*9L#nV-Itx${%O%q{?;Gip$DNP> zW{C;()99<5l9Ky@e{U*~AD0J};eaOQqnrd)N|Vl?Ty%5-^q5d_MG)^X@L6x_(5)4y zQS+ht{vjo&O~k8CZf1^nt;}a)?katLd)Czdzc=BJY)SAH>XK9AI z_Wn0OJQ>$@Tp9~B$S&*c|0kq@ODDy&JZ$v9LDcB+WX&@+Xdu8zRRW!H17&0~`b;%& z0pCbU&Fzriy0l^}Ws^H$jj$!sA$d+X`IbUc8QV_W_sxbH*C0A~U=dck!2!;?);9x5O%`umS-4Vi8LJ)T;{<;QI-2oai zD^O)eF)92*bMKQyYMEOW?X3{p60+2|{>qg*46t>crap|pb4Wzy%!z9UNqKqMNa~eC zO@I<^QP=yzX<<sw~dohZoq}-&;-Fc^V2c0M2-rFQmp>95K857`lGIn1h)Q zQYKs}&%{rw1{>s%#%j3TQ7Y@VDcds=ChMpo2nzL&)RMob{1Z1*U!9*uBka6TOn>g@`1oh*dAL1=RcVSycK=IgmxcaU+0?W7>|Vq z;9IjNnapmVD~fkAwXuMM#PR=dIOhVUQLTn|7aq#tTtt%#*5fCI3PTvsfSjBg6ScDo zDn}dvmFEEPhDoPa*b{J~7EhAg9Qj7zS(!ZRVn;8=9RdB7%p*Xi|G7=kXZV6Pi>K$^ zm|U~^sDIo$)GfPBklXri5p{kCq7ZFOjHh<&wZ<;P{SHL;&oe?ZwogE#{3yhuZYv5( z=^iS{MBh94+b&OZ{V)(<*tSptfplY9zSLb*ABb)EyETM_t1LMx*G8V;`g8yapZw=f zoLA6ll?rm}IUdvb?2`})PE2Fn`dKVx6;WLsbZne;0}A>bGBBZExojsJ{IG^-abF@AWE==LJ6pX(gxr0^a}h?1 zK~}!z*$GMzm2IzqvyYWr9?IC1?wXG37ziGcN#$y9WLHcD*#wmZ0j9! zYChEQs@>0||L8p;MVz;CUDshkKHEH;X$#NE%kP93=5!0o}yJ&2o!(XREDJbIg zGN$}-o=y+(rbBjPHd874k78-QJWQ*JHITP0h+}K(2l$G;sBkw)tH=|i`XEZZ7d<{S z7QPW>DZULVGxrhC<2yaDLNY|Ewa-H{+n7pdY+%eUutQRW^e2MAq1VBoEK`KCm==md zw8x7}tuUm+2*>;X=n;$NeQsAePmvyYPUNgoWbdV2pOSKM7geA3%B zjhyoAS?})Ad#rAo3KpGRFpC$K#b)^~|22;$n-K{IT(lYkaZ~0xw)+gHi*EhEqRJ3n zS}xD{b&5rtYk|OEa$tM`(#&)arQLi)g5&^af(`-*asm%ark+s9e&l?!s!sg7|F=d8 zl}S5#T(7~oDmp~R1JXlKb&IgKs@PJ0ytYPm-BUc>>$YXVx!c1cJ$%pd-1E)~hKDlOrJ`AB{fN?y9F{DYTbf z>i!Fxgdm%h!u>RK1Or-tmR#NgUl)@w>XR@D5(zvUuWuN=%t=Tx#|m@ml0b1*uBecE zB#s#`YIssE>)Gm$2v|=k?#PO_&JQdaiZ4GsM$NA&h+x*%o0X-Ry>+aHYLfS5&?iDT=}UBPjmJR9KvE2 z8JYfUElX0q>@`mcqRl1Fw2jN-pSUJ|G2)PDvrA}fhcr267UjySFK{AEGsB<$IJS$x z006Xr0s0HiV*mqOMG$lGqEixj-66g8Es}NuXYcDTaFPnoXVZJ$7LLanU_ zazcv|(qeRFv};o^K^3vK2U0IyLjz8RtISnX(I7}R(Ex+_3mVDtAH0K{2bjEXfmlWQDfzG8*y!{<*#iV#F%Fk(qB-61?n63Ig)MGq0BKW^gZZkA zJWXNL*n8+uB@8oO@1XGMbUj^?Ks^%!k&sy;RMEPC*RhD1ICqmmgf|obU7f%nZ+ooA zH2oOGm{u+rFji`_s8rrE7#!ka=fVUrDe{;6f|%PbLJ0?FBS7%$e&mHs02asK0siZh zC@duBUaKCYs_6FIb;Dj(3-%c~ROLqb!(|lVO^Y*AqMJrIb&myB)^PiCT1#f zaA0$c)&$F2C#Vmud3SqEFoqt?NYa=qj5%YO6Hq%6GHfez07)s-eoaWwG$*`1l_eRd z^0bcfYzb-rT3vgybmQf&<2Sb=r;}ako$+M4~WngJdgi~L4}UL!+s;Z2Dj#*rX!k)m=;i?omk^>Fdo zP*&|{{Ymg6@4B&VZ>69wTL>!F#`!~q9hV>ys1od*tT^P7%r+)x494=Dx zE0cq&dDbasFcf;>RV-_Bp0YlYaIG?6Uttu48QfO((0(FDh$>;M%pqXq#z-M*nj>Tf z*?5kChz;?TD8<< z)UfX|99REPe}U*ZsYVk>5G; z5(@F?L>c|DA$B$z51Rw}MjSV#Q-WU;WSS}UfTTg*R%a+Q6G$bYk{tb7uwzxEX|D=! z?32|fu3P{B00#~y^Xlj#0Y@MCrk<<^eI{__J0eZU#7}$LvxwY@A_OHHqhP1a5M+UVDoUJj8?haT#oA{(a zm-okRN~jnN`~n-2Fpc;#8}q!8Wvqfv3Toz9=D#t&VJpNOrgB9?KqaT@;**>B@YR5h`Vf+6)Bi-2Hs|z_NS(RfOXqsIctcjTVN=Sv7GOn+E`8)n~}GS zenV$Qv4;Gk5W5}}SwCQd^^nIZMr$F@xEBIsNmSsHo?lfjC004ltpvBc$m}i;N#xfC z*`n*ay~_LxAo<^o{Tvl}Lok7J)B0syLe)}U~ip#cYqldIPF6z` zu5KMeVGDU}ScN?DjK>_;L)zf^KQ|j>C~W_(mqzf`-o`_43qxb|FH-U#iYj3vuz{cG zWt=B6Bx<{!COiG|%s(BZiYpaVrXe+$GsbL(3?OoQFF$%i`A} zI6O8&1-p$gr$q$Lx%K*oH#S&u2125bz71K0M9o0+`g>gm=bUZ@E!w-&vndG*(k8L!>hi4V;Z(VG?un!oo0+ zLIeyOxwPm)Rv+g{_QIqUGXZ6iJr) z6ADZcUVPgA9_fMlTv5R0(RO5K$90ti_*x=^@VfzEy5lIWlMoOcuVXSq1Lc?hI|0e= zouSaccDgV>l#{FYXYinHC6m5vQV>MtlcPhy=9b$ri?sbNE2t750Dkxj=0f|sy1UdV zMMg?hFd&;8_E?G}c=7~*MD&sk>c{2^-(Ueux%EFe0*P$-zQwhs5s0f{Hz^#-m!xWS(lk>d=!!<)-_eb`)OZ(&_A+o$3cV*u!3XD5<=}>K%k1t~Y>w z5s}lImn(P=FU(L?IUsO3O58+piE!DO*6=J1)hNnkHbA^!7bRT^vfWOd(e`yh$v6TQ zD~z8v*uoZ>z|1QF$RU=i02QtoBP+NWPZlKC^+hfq^Kwi00XW(hYy1ayF(8@&kBU>M z^U@GZYUYd?9Qx@TC^#+t_)VDt31e4{WE!`BoY16oiKk@Y9@ClEKJJ9 zVwB8Aiqse_d0ie!j}e?>ECPY*ycGTM+97du&(d%V=dgs$te0|CkJPlXGgr+O-oqc& z^8f$QoC1h|02uvEg;5#(C!PH)ySF# zFbu9k8xpoZnaznlb)=4CO^q`eYHutRD;Bqz=IJ&myF zL-4e|MjrQ)ojShchp2G7N8k_{+!9Ct@;%R*paWB1a-@$3?Vnzv4Y20~mdx-(7Q>9s zFr!)W6BRYnxKp*xev}3aa@lRLUOj((Zl6wlo0g{5>M`+IG9bZP55@ynpB}S6EA#$F z*2D|tQsSGMPCywsM-R{sy`%#Oq_lYG#W)n+GT2cE+NtrIemmR-^xktk?Q~a{fGd{VgF9BKmY;@%K>cx0FmLj*1DHrOP!LFPO3hv zkwK!DC?!uODKGn-9-VooC;YU{63~k!5#W3Fa_>h%AuWNluyzAYv;!OHZ?aE zL_1Ul`Xy_Il$`xZ(tuTo&4yM_Fe?2ZOfIoeePzLKd%>p+yKN#ke#j>Qc&ZP+xvLlq zSRiW&x->_Vf=~uKu5%g=33t%Hy_nIm;$UR9GC^tDII~0tJ6NudWz78Bj{mB_R93)} z%EpPnU^BSNPZT3$EbBg$4~U#SrnU(%ZKOx;_Fq9zpOP8M{P;k)HP}Iu<`0^&dKXwm z)~Sz-Ee_VBGZ&MnSq#t~6+(3#9%FijiMc5R%I=#U$blgn>pnHpaiNp+ogP~3Y%w)6 ze2W;4V*#H3HtZ-4DcyJF3;MS7wKE+RBYDQoaLc+h?Jz9E2Bg+R#C9s3*)GQPa#L0r z`Hh4f7ax_`e@qTXA++Zud&J+`(s7a` z*6`8HRNxsm8&>!Ndje~p=%sp(3j4g`ciu(zY1?M<5ru*QM<`OPP}QhlHN3gxThn&5X9-W zhsqrheli2*O3b5H6uvagww7|QD$DO^wdZR6f2xU)(OjX*?{FYaFa))P^D*5Fy$<|c z&gsHc(@nFd{bS-PeQ*jX{uF(Qy3j85LkI9VpG=P$UXg04*-?8`B&3X*FIAQzP*VzA ze8Ba6yy|u10$EU&6+sY5s-mxkJCw~sD`s<_P$TmTfVieggKVXS>;sxNoF&!TZZv1n zy>FxC)6BQMU3Rnf{gdI$_}SS{FZRI>|92}Kb{wSoHmv{#5R0Ng6=}2NddHZa%lE*$ zBlhG>Gqs;PGW&pV@6B^KX8J$K)2mmt8*FJLv&##VY(1=X6}JHi90TRadhNTh{~`72 zsV^~_d)zNZliH{&Wy779am+AU8s|XqHDY`=Y$f<~C=Nx!Z5@=1x(cT(te+sa9=pgb z=QsH{K>C8_4UEh+W@w|AM6`bEq3DNAXKRspACgb}Ub*6U*b7K0VSlLkp;){&0pc9T zy6;cWJ%Dhsa}|`vr##slx`Q;M)pCA zU~YZ|l#g0In00zvolD^sa`0sQ&d);YlE}i2F zCs}>7PY(Pb%2PZjCzAXBHUIokfB*w{00)$SQQ__zZnoj|LGNj@2VQ-2T`I`u&Exaphd!{8SiTL_pCLmNZcgw7wk4FD9 zQ)OmL%ui8d{LFjbZFf~&0{F|LvQxh!k#TYr0xBy&ZdF$m+Wa~B=i&eJ5=W?kPn10? z>%Vdtu$drwoP9ncqQR%*|C}>^vqjC~TZQVk&1p=;hi`hgURW0D_U67(Iu5a*h@kN~G>8;a_wt-w?IQ@Oev_aPr(Dfdt;q z25#2w6u|q%d6hL1OA$(cZu)OsEuuQ@Lx$hu7KI~kp~)(IIz7icA@?AZ)JRHBJdNHr zf6lukw_|nQWnuwZurgjjD_7Qk86W(fD>(T71E@<33DJ2;kZMdSmEgbRtQ|!`=SFl3-$SGo*O@N@49l@5z$XJ!8v(L{WhSGFlWuL4)dZRC z+^S+lp1)C35X4kJZ?1v>Z>mGrL*HvbMppUw_fpY^BP|p;_8-7!cL(0@mY02Pm1qK+ zyHrAsVaC{5?GpnJZ}=sV(+6|`o9?v3B0W7fNuOb5bc~)m4vb<{&-?YKOR?&(2o?m7 z&7_Wud}+~;DpK`CJS~V)5Fn~a-`>xs8%^|bbn*A|6+Gz(^x#c>dMX}3C+TOn@KLC6 zy>^kXANdW4bpg~l9=B|41Z=GY*keU;zU&dHCb6c1i;lKiN&~WQK;i3hUfrwFLrObj z?6^;P_#ZN%Gj0#`S(xhbjv?5BqrP`i4E}eseKwij2vIN@MwEb{ca83oJ_Jh|`qswE z`5}k~M_%Z0Q4fv6uF*Mi;66C_>bjdh61@imjoDy&FPoPF67)WxQHZK(!w5?rs#tiW zgdmDcShpg(z-Y2KP*K21PD>N#$AapR)5RP!1;fP|@qID@Ik-`82Lo?VsaDl~gJCkE=`Duj|J0+k z=6I1+gp8vM?5MaGUGnhQABi-Q0a1@r8F+rjWx#oCo!@({shnLC*oo$XE@gvqKeK=1 zM571ALb{K{ge#<+dsNU@OXoBa0(YlZSMY4T6Nw9XQA+gf%%O2b+mc8hX`u?49=&41 zV~P%EuyMZ(II$HaJ}Yuw<6j+aOB4G3eb)NsuC}lbnV(K7DcGwSr9{L@f7%Jd3jLJQ zTLm{1!)Z5%DNg^3$L6y$b$NP$0`S;x2ym2z4-pX)-vnB-o>Vz{~qS3 zScON$yz7t_g>d#yp}gBrwwA~boKHq}Y|pzO2EZ%^rK0b{PYR$ADSZsr#4gb6@-L}C zgw=7yjM7y2kq~D7w0u7x%$-EqbIKiTo?FCJ*6&)R$GeuGl4vB(w*NSu=0Z7&eYdxaB9 z&#C?!7s`icA}ukwEHMxPmBX?W=DeFI)uJ3;2E!@$ciB9fxF@8H4y~KFYx;J8rec8v z0sdo(Gl!*F2-E*2x%>!pENtN-6{WT@y$g8 z$E5#Y<_Sno=fQdjZynbBF-=<0(^4kul@Xsug6)?XbmpK)<(|MrRTK?sW8{ND2m^=7~NM_s{Q&ELVKhV{fup(WpWVCvC&mBjpFv zgcYA(BZSL=#An8z`+9np|5h>k2TEZr!i|GrHs$l5%t9ld|E__Q(WjvR@{ns-R4IXv z=ujByFXPQv*aK2FJz)^Q&i)lm>S4o7gL!b%?aqxiK6-$Z%`K5*o7{N^yv~`ZoyVsE zMA#BjBju~nXTszMOsFz30S=|7!LDO61!l!cT$ZwV-8^by4$37Wt9=|~N_GX`zyJUP zpgB#$0@nfmZs>p(FbHO`g@VZA&83)r6@FVzvm=OA3-4pd3No_Ok=O*o!tWGM02Oc> zb{;h%aH3pF7HP*)ui;vx)m$7(_E`qyfwG0fn1P)#UyaNSS5m#;J{nG(@V-G#N%(#(loU^sKsj`~{>Gy^;|!;&-}h?w;~Jxr^nJOk;^H!q zRO>$=UkRL7xin7;_dTKN3*gqeStXPaJLY^NG{suLknl}CJo3hBTu4T$1ms`| za!XL-prm|_5PD>h2&C=*isO?q(tMt$ z<;=)YIUz#M(J%u;$n7fvNog+atHe|$_>vq-Fc=%U?&pbXG6sjCp0G#E;3xNOc?#Cc zQ{r^|@Ti{epeU`{$+SIiy9m$QgVPF2eTDe|f~^H?$It)(00005a`zPV-&^U4a;<+W zkn|w!&a8SxT!u3jM!(7QHtNQ56~U1u?XL4V&Y?mauD*Rn>gV%&QE>e$Mo9Q{Xt9t_ zAOHZf+T(k=Gb4fu-K4)ktxX=?nx1R75D-F%T);a$IwxJCadS_=hTZu;Ted7Y`|sxJ zv7oJ{fWyt|)8N*~PFVqr(P<-kG?|v{P+R5`U5YkNilXTP4d%z+HlBfcEY=EaR%3WE zKB>%j7xkEFKlc0GIbv8Kk(j4gpdiNVlCel~1Lhhaiek4jR*#MGQoCp<(8ToRdum@Z zANm^c^?8LYZ0}?mofQESpoJ2lo`MnKaZdg4P)NVcck?NZ1(;1CFs-N$3kwG73x*vb zx3aI`mPoLc$*?>uQ}Oczk*-nn4r?|*?;Mh`Jk;QG9x#{XYOmtxiZz4C3Rg_oldYx4 zqAoz<<7=BOob8r+rNq434tzC}Sy#W&sIov1)9gRg0l^}O(D=vOvu+#(wN=^tDK)rc89X6o`6BHpQvl;VQ{igz<{eclfwTUh^W1chlX2119aoH=G ze^$ewuiGkoUsdY_>LYeVXdI9`2r}EKXq=CwgB`>_!JD5I1Q@BS8j@!pF9*cX^clNx)-X7_5SQDg_66z#uA+!?-Qwk7WM8F32Pt zqKKo%^C8$e+>urwQ{;B%;PqFk7YAkBW48b$b~e}kh`+xyExeaggIL-b{q1+I;8R8FyLPjb znbM~bkx>q%hfCiYMTX{?#+DO-Ub8#vP6Jc2q_PK<@(1e1*k5((*OSBG;kJNhaiv~RJ%L%otAH#<6+c+oOO)? zkP-5oqMUF7Xg?I10xF1eERAF^LOKFHTO*(@cqry4M+p6EOPj=tI=9MB3(YT_+6lJ`t+_+5|xYAW;Lh!JsxcstY4*U zPfflMBw7BYaPVkkv+#-Pt-SGxBvAE4&4A%uh6n{87-1RGYDX7h=HVU5@1N!zHzwLr z^Bxq$4VT*$iO9v^%C2j=w4>L4=tCNP3+Ef@={#R~(fO5GzCiaGIx(SpFvUQ`J-?|s z(VXlQ5qK#L+>MxJmG_pQ45rhv-=KD%rEuKUsxS#r1ZxQgU_pK_D%bw70lT_zx0<|= zCF&jsAm*MTfl&uKLnt2v1tBL>7Jt=5GInuo`>oU9jgH3}PrKr8QaMw(Nm`JW=d)Z8 zN@hh{*}u=`Ooe@umL)R--3=qaHCMA(iqN+dr9o5uY4GQv~z+9qeydzM1X6pI*SJ zHF)bnL84e!TNsDpKcWox|Y(2rnWb%RlYe1C0J&9moEptK?LqRV1_{`^BoT#LZ}YQIB>qiPRbH?n;vbV( z&6PI6RX#v;*&jIv1B(q#Ce2@QeZT|{0$0}(h?aL?;_lpf!h3+jFX>w%W;jh7+SXOP z=Rt!8?DeKgTP_#^61DVuodQH&cMW)I#@QSjwVLBU5Ai{Dl7+k1kP`Topi=guu5A*`@Zv_jY8FP+&J+2oS2yGc3p7@b?fFT{`De#DUAJARN>wIJv zC?KwC!04p)!_9^hi2r=>E~>q)-|-2di+~f?IeBqo3QGTuf|@EjOUJ#f+Dq=&#;xl- zq(Y${JU+y);#7?>2dM{ls#}>ffuc~O)Eb}?tGl_hvuyGPtB;Z%osO|}RQ(vJU6=t0 zK7+pP7Kx`~HDySdS+a{>S`@Yf70pS3+Ss$JUXlTZmUOOdm;TP>d{t>d%gs!^I$;~yMdX)*H};gD+?OK_AQ{EKJ4LQ?w;)1M&c zU+Eh2fgo-bENll)-PjU~@12>qb!YgjfU$j_ze5JxQAho?*5~oze{vL<6ATGansxG1h_{cNnQZ>)|YM>KOTq&>Sw9qQeizh01|(Ih{DN?bgni0z?TwVd>t>0?|&EP1XKiCy*Z3OY9Qm)%Rx( zqKX35r^a+$>)sFDBlgCM*IuNIyb)ZiXUO{g-{gCmPtwqE8y8pe-94K2BiES#h>O@; zHB!E#m#e5}uCL;Sz8M(Z_`4J*O|T5>a69Z{5y)NbBD8w|+dr44)8oL@d21n6PIl!) zwk}%yYyEu|6lmQhId#wT#DC*3g8F$;!By&2RxBZ54sHD1ltVy3|vs{69ZH_CwPFV4lM?xmq_wgc==61n^Nx;QGpC)2iIiKn~Oa4vu)>q>$}|eZP;21drMtR^q~N_p}tXkSZt}d z1u;+NLida=m2q`@d{4LQ$qDguE6Us8$UJn1uZ;Q+~VQ%bpL^24+foGTFvjY zY`Zo>IeLMmR}yB`kL&L7Xv0A~&4~)c#HNZTxrzK*D0v?F=R5!k_nr_+xLE?dOHsvBvo17_N|2{|rm+C+Q&* zl78Jt*k6pbg1+$Nkd957(mf`y$_(hV3P7`vF-#h;Atr#RB8f6PR|mN23#H}SGzBxq z_UNS${R66X!R4vCsb=2r0&_Nr@enHGT68QcAEV1;H3QqYj)#&;a-F*$@D9I?7>^LW zC4&AEahvf)O{GA=$g^XKu&_>k?WUO(-o%ECZg_C>&g^Iv-S-}kuy7KHmrw+T{$d14 zTUo@&)VdIy8z)|(6aYvZ9X-|1XMw3+56&IStvCh!k90HD^FR;Pd*9@4ntwM-_Tp6P zLnn~=+i+7yL84G_L=Tt=2_Kttumpm+;0vGpcQPl8Z4r%0ISIESmwu|V0sU=yR(J38 z6DJLPjB9Z3ACA?qHj=r`3hJKgU`P5>eFN+pW#(mIjQ{NSW^nb#!O|0Muc+W@iU*BD zqk&P%xt1|2&_{=Uo_01*0{xwRW;$8jls)EU7lo;3)q01dUY@V7BJFWRPm;o(>=)Ho zGXqU&++sm!?Xm*_gv!XJ1z*zR z{|X`pYMJQLy4dR3fT`dPs?T5fR-4nHK&rvv6P~LKEqbRII0TjtgIp?p#DL_kln_^v zH-o7bk-Bq`?0i8$DNdd0oL2craHm>l)r&%3g~zdl;PqIG(PZaFU4DS`O^N6xBLi;c zA#cfBx7wf|7x-6sroz_EDl-&NWctDwwFXBE1()()M8_N<4~$V&e^73)M%wrtQFGps zzW8Uz!;x;fm|a#TzdiKYdA z;vlE-%t%ZE;Vm%J()3P2BUOPKSSs`nlirpiH@R$%2+2(}xv-Zrs|0k-D~_)IwK1K# z)ky!VwD0Y(nb2{rkQZs=Bagklv0h>T3==6#RJ;VLHNroMPvO6<(eT-;ge_RN%R2TL zPwR+3NdWZ`*mj3r6aOYM;Qih3Sn=*nfvQS+Pa^<%Qqw>v^)bjS-O^q4R_f8;-6VON zjT{C5005W4;wH4=g=fAqZqZgtT=G$gTIr%bz!%hPRbcyNGSRJ+qZ*TTFpLnC2uc>& z-DR-rSz`XqfQePJyI%RPtKm|>=m)25!sUI$ler*h~`#UF=jheRGpf$(#~W;kEK^kttl(HsB( z0000004Klz0007pGG#@dOVZs8U;z4Z9%pnGsnteTOSPY!aA?TMH|+}vqsiS7sMGirK5wuVqk@5h3dHPVgWP7&74q?|H*0=j&$?BINf0K#KQa()Ogsu+qLyAb z#rCv3_ZKT^tX>5I;B!?Oa;^q4=03TdX#o3+^iW)z?M>Phcc^BoW-vz|Uc@Y4QJx2M zi9oroh^2{VlFvPnN&JEcl7T+XFQCAVzXJSfP6nq#Mrb^^rHH#ZC6zy?dDHvp8)`(hlGIp`l!TN4?nQVbmQqMhwoIO zH(ooIEeA@XNnHRccNJHcLycp#hP=yDV1;{`p-l~5f=1;m9usaE?VnZ)5~u6`jETYd zH&uSF&G&Kfl&#jF_&rb{$eJ}NXy~`79mRl)i~5KQ6$s%lX@7NH#2jojKHw&GZS8+4 zgV8v<$$)S4L5*OO$tA~QCbuKz#hpEnh{+F{ezt(yq}uI~dOOl@aZ&Qj?ISIqiJ`N) zVsrDL3B&5&eR)}y?-m5IFHffr!T+TU74M-V!UAQxf16Hk^jp z+d5sZ+H86~U~WG+FZUUN=|&|}UQIB2>u|er82KK*P%~ykYNiu7Q1)IiU>tcE-h3Cn z7^5dyuM`Q|HaayX$z)kmRDg@yv66AoU?{D}F3dmi4zw_A36-N`P8N9lkEvbB!e{wn z24 zm0xkC$aFNUY&t?24H6>-P0Js-@Xv!L>6o_19$LIn)YJ}fwm=?w{3d$w@6#SJ`c4?z zRzRlsfhR~6vM;6+U+~bV)kdd-R;+ch%-Xuqni=$woGS18blJm5dgRlx>1p$_76=Y@ zH0Kb(3#F+30|0#314SzcAQXP;G*BLbeVNRFN~47kFgC`UPk(j$t$%B5hBVc|iUTvO zW&oPOQVKXR0S3QBX_X?P-%x)qmg1D7&~WWx9p>(8%q+Ish3W|Axj)J(3rJ=U0`CxS zscq&aFs>yY3uZ4XTJo8IWPg9E6G7jI*R!3 ziCp?faCb|=P<1#7G{Q3xrFnbamw zT|mIW3HY=JwR%EN5iRhfDQxY)tCBP)Pi>zr0HkKykdgjuJ<%rIR_~gSBaTyGv@8Gt zEDux7!UW;B@(iN-ev|dcZV8?74UfVW=_&&SW1|5H+L~z=G;gX{?|MK?GSc);|9}@l zW@3@%sU^p9ci~Rku3@vUS0d7YUE(Qy5^Q69P)=){L831u&y%o>dDmSv6pB+PLnF2t zslP2Kj|=VFH{?wP#~+G}w3@TX`fj9+2!Y7IqIuoaT9^2)1eBmQ2PpjJoM%|WicdaW zg{95e;nc4nV8A;t46W^eDZXn|86ClT>&W%u13=2C4vGnzsiCnL5d@(3_j1Z@=p_-s zRVp(fk1E6NN$C^PPP>JP4&9b`000000B6B20000M=l}o;#ZyeISc&>OqVARLpxOvM zcp85S7SubvOS-KuT)M#!V4vrzVSA^Rv#ceK$i%1ViYMCZi5#R{Q4JDg<)0Cw;MVA}1!I!#uo0`G_7+N?>YoP9utm2XqJeKs%(FjQVMr zMo(Kc<&VugQ!Uqh4TVIh)THLa#(8VLhYy)_@sN{DXW^@g1$z9G>7}z;$41)svZm`@ zmkDyKy&3uNWZ8QK86jqP2-E@M0qdE5(K+*nW67ubRy?HMXNikIVVtcr8CtfM*yY36bB>!WWN`kNF96ZjeQ(c4 zJn)u5c1PNZXIl+sZP&fimg4{E&8PaOa-y2)D*DN3-NOaCAi%U8y!nb+4j*}?OMeD^ z-~2yAGi61)77@rF10zjZ%+v1ZJV}{>+{C;kV9uukH2U@bvqvj_l;wss>ykCzKGOn} z^6{G^oJKK>9hc{79IGW5Ym!d-Nefqk!08DH2GC*jT&()Z+pp>al^Ypc=jKXnVI*V* zp=pjhB%vTvmsosiXbx!l3tDHD@M35$iT|iBV!54*{+DlLflC#x=wurhTp1{4_kfJB z@k#Kr$z&LaPuAjseRnS@mBDr>pk&tauthvhd65kww+$xrGUOA5Emx#sG6l%zVQe-9 zfOhYX=EKR`&>YkS9lCeZ09iy3|WYRJIODqC8)iDr)hHC_z+p7{~Gq*@?x&Mc8NXnrz1#L1tpVoAjjVZ^_JWrduZ9Bs{;s}CD5%0} zm+qj11_y9vH`>n{KN8Cgyz}PNyNRE!Cx1u$HUT|5UVA!DfjX*=F%!EWevnR@y=IhF zx0!Dt!Lg=8I>}qC7God{%Kt*JIzGPR8IMi5RrzFcQUFO%;LeRJA?DY_Pz-ygbu06v zR~8ml7!h&1RP{ROHNYM!omXoEf>V$DwUEud(t&-Zo|h7mF8jTCRf+(+?-mQxcz<_2 zCFQj7yq_}RQz{%8>czkrRG9Z94|DU9_HuwZ8A=e@K`CN1gsK2|XOz03D4K3GynbECougkU_9%iNh7$gJoyt;{0)yVfl`nx)J z7(OM9IR<)H>bZ5`#!fj2*#9EvOw6*9+~1HA8?Rp;dM4-OtuR5|PQ86dZ45Tck~z_u z2Wpz>IR5agy)80I+%|$eljadvtZk;`u{3{AIuuGyF0sB7$Zz?*fa|Xz>HJEF$a0_I z@rP^lE4vGrV{a1%vp(Mv<2tGya3IRqYlBOC5AQ+w6ta&8zJmelAm1P9M9|{a1E+jT z%C@xW$?$0Kh|E9$0OEiE005bQrhotdB3raihL0gmACqqnPYKch7PdN*M?-~ z^jY>1ae@?82OW~fOMFxe!>)Pm@{FP~#PUe1)69?qb=yqDoRr7zqJDk)3{i>E>BPzX z<|R7PjfK>mw!{O%OS>BH#Ny~;J@?R{`{ygMW0i+oAb28*8Y_G(#pT%M;Y>ujJWT}A zvi`|l){0h>1o%o+zDOb;ZIf|h@Il_S$%krx+Q`oxRyZH57b`dLCIIfR(10{JL_s#Z z#8QrU;l%|nG<&VTCo}+*uGbHEep&RKVhxFSp4ds3z~_4C5>E0QT{Xqc(Z^sHWHo#m z)xTw$$uQ$D21*aQHiB46%^NfVe1t_(^0ZIyy2b~x5yrUaQ5%5~oT!t>tuQuKt^1pt zcLyO+10sA;ruL}&B&VWSY&kR`G*{FQUC$8G&_G`FY-_hpynnQsH-b>Kw$>B{{m+EP zw%_0J&|JX@Kjr=aw@_oKZt^e;l21F-%OrXMlxt1Y!MZIxhxYa0Zs3BAynC zHV3H#QM@F7)7WSc@=!}F zg#+Y&h)D@U{p&~~!0kF$+b4%Jg7nf6cmsfnLx0EijqbcF0))LL$Z)<=U5&zyv5bFX z=N{zB(!Rs*Jnmma?!r_vxw!F1Q(f^*bH zp`P)+1;3~{T4~V;gzJ@tC803qCU_Val)VQxXFipHja)ad>L<&ytiBYQE-eCz&w7*; zeXo)Mu{Hkngy?h2Pug09P6&4mM{J(Jr0pP4%J9G)v=GaMcvtzS{cnOM5mJ(+(`w_V z&t&)~s3uD!$4?F=;qgfMumjtZ6FD5G$2i`+iYww9IK!E6xNqSFlf^niFKi0gZ6)@7V2x(9%wy zXV77d;wrs2y3~+XC!Pkf#2jLuyixXk4`kpcXcK1BSQMUTKZ^j=zT>c5277k9)%lR^ z#(14xi_av%IqZ5Bh+N*2W+&_cXM@I4F-`gJf8HR%xpf}ic#LH)(Qf16i%$VF{6o!z zQBR4OUL({=Fy7z^fs^9;gW>w>9EDO_E|y}qnanNhCDWju5twL}s7ZUsh1IZWf3RTx zSoP?7uG>z+khj(Kx<2pxDxsJFGk*Y15(>SXBea&A!Ct_Ga&R#JS_Pk<-&EGp$)ErM z-c^evD58c>{bh9;XoX}wv`WmUU_+%;QQSwJ*4mb2MKVTAzSA6Q!HbHAFb{3(5B6;D zwCBOGx!NcB1&`|y+W{pJMky&n_+ESlcCFB+bde!0|86yO4BB%_QcbJKL{%F%m*^8m zvi6by5xfZHX3)6E!G%R$nSp<4S`=reL<9{q%%;}()jC6i}oTIhJe^UES-OUoxah0Pc&BiMJSxxc;WF0~Kc+)>-=FQ!@{b^kGrmyH4e>cd+Vqz`{SR6xS_~W<@hY!- zbI2w29Pk$O8PE=(HPvqWrU4Q{XSKlQQMspqb@n7h4`-4>;#tDP%j#r+y!Ci-pb)Rf z1{7JBdOtmTOP``n5PV-(m(lR=67SN*n54Ujd(@thWv zh4bwnhMsNQvxJMx8P9tTbF@;hlmz|x`&fsX=>;AYrWnAB?BJT%{#5rq^vn&NU^H@(vodXmc9aAPhVNTE)r8gobJ#F^(OsRUP&( zxuD(8Mq^t%uhB_=aLkBa_+D*5`t(xs9+UI5#^#YOHd+}_i>*CYIdr)#r3lR53$md) zH1KMGS}R7G*RfK#u}mSWgb<0GYQ4Gk=)r$Tp$Mi7>bwABi-tFl)CCp9-2WeP0h zoU?+_LQ#XgpMxZ*L@1b1@^?pbBy${2<3M?2%m%PIKF+cdNX-QVPY;JpChYP<_a8a7 z!1uXUaeKa)!8chND$|kr47L92D)0EZVozq9{B@JZQrZ&PDgrKEdof!0+gFJC4eF5pPB3rsD`1anLn1mnocdF))yktM%2&D))blKLARba;C@WXc5rs$B#M8DH1$6NK%J>F?U*gc zD?lCM5MsB1qI+T~owi#jL;oGloNkJe>sC^XwC^wj*1IbPhB63~yq)k9B;c)%J>$BW z#Pp(DVqV4}HZ0?50v#b*sHbwg=&&@PJ*)SH=XL=-^n8@1*o9X5;7)4?e8STVQ*+VAG1;eB=9NlIMF++FozYByjwObQR1I9Z9Drj zDWrh}M@QnjBtRuDgA`awWQ8~7yB`9nj!bo0YJH{#F}NLxTPfwq@_p1ie_Cwd7@_Dw zW`Gp%Hv+NC`fGIc+jjFTs!1;salWuEwXFeeJcVwJEinK92)KX%0000001G?TrdZQy ztF|u5glr2FX})d32X{Peo9;PIo8$4gHi>gP7FOWNX^;6tf?NtdqQ)B=EtYb1qr4ae z(~gh=y&s#j_U&oL+w!kOZU0W}(c|%Sa2hnD>%i9h5dvxfsUPrf-HZ!A*$I^XqCg#*H~A zMEw{u45f$hWjt0dH=Z6?lP(A`M54Qmi>Lex4RAkAXOvPa7Zz6%0rl^@5FnYspD3iu z?|T!#edA}K1Pj@}WT_T^Xe-}+2lf_|?S8!N1qi$g^T>KsHE-k(-im0_dzlsgmwf}? zqXwHA1|{YWr>2G^5jwv^k>&c3%=u4Gjh1>6gcFJS(Ol<7}=b2p(@alnfYd(QPv3ZE0=l9AFUqGcoa!scXvb%-tO zvTrSA@`=n2sw|5lLyxQqh)K5)8bCi!?2@^a^a zZV@xt4`v*HkMCH?=UPJ%Ma9NZA}AGyF>CVf8N83j$_gZt)4^Vgj>hA7%JC}rZ=rg!v36L-r0As z%E8!)m{)VTq0TF$$d4+;g~!OL21;E7fhHk*g;$gM1<$2>XpU$IbXKmmJ80XTK`dSr z$o1#dy$uaKY0g4mt|`soaqeZ*-K&zvg*8Uf$u}V$9lJn2C4;__xB*0MK@LXzuo1JU z#;Q_FyP@t90QnD{)shcD`sZfaRwidgpvN49S{coe(s{2a7))TVgSowc#Nwxml$U>F z%>^KQI{;&R9c`%p9y4J1Fzy}4-JLdZiJ?>fqy{kXR1xAJui&t)dqc^Q%bEDIa5?3N zsn)*k`2L|`hVz6?S&{$)EfEgJp12EZm-|kH6A}Qk!DgW)*t*C@BX+d|@Zu4N;Z-4F zQwx^!+STBnS?{+HZchh zO+M)HDLLTS0<}B{-}=R?sc6Xbwg3_0UJE~;3EHA;_$=(aMKZWLgTqZfP>{mKe%Hf^ z==gMjUx0=JE~Dkrd~CVx&m*v&U^zILd9X);8f-bI45xB_Zt+ow=k8XUiEYy;q{%Z( z{5yVt$w6S3dtx>mDS!pfEo(bmfduR<{qFJ-qGR2!1%5w-LP3o^YPfp^rQvY`n->Jq zm;e;m0004MfB*rwa*8aivFJWPUqPPjIRRTZX)b9(uYMCTRd`sWlIoTa z-e^MIGZUJCbQbiMN5r35WE>2Nm+*xp zk)x4HKH|LR)?gJ`@Aw!e0Qt1llWV`O>jV@_ek^E34t7fr91-DZ=c3b6Zm^v8rWfnW zsfiHf`ToDtYm$ie&jQh%CW$;crxU4x@n~|fv?FL-=^NDezo*unt4tInvX8q-54o1_ zhMW+;zagMnQl0p>T=VZ5UL-ol_N-10EX4IXwpAEfdT+F&zCHw1z)S5bxLHZ(?hx_C zRlF!lB>ltJKw^aLp9i6HRfAK1MzU`LYI{<~o=bbVkz=t2$tPu$@o>>P0uEiXXdFmC zW-I7l4`G}?rZR*w%WC3L;C7IU5N3gCX3iw8((uv;-)6zANd2)9=BJl6V~i|d*vw1A zZjPPuIhC=8X5sqHKB^N6m}8Mr%B;^H-c-$C^^*I6#iafx3~U7v-sa;jn6(P>LdqPo zi(tTRZy7@BM=UDj^|vayY?e&^v~sl_Svhp+ahNg0({wNg2_Q)e>cTvs1jWVai(GUh z=BHtl=c;P%!&K|oH}Ov`aJSs>kE}mrv6Z;QX9W<;>B1-84K$w~I_-=RmU9Cq8?{nL z9%bNMhhw<91xIVg+`)bHGJpA!u7vgO7ReCyktDmMh*{I^uiY#)a}z-Ap3jJJs;)$H zy&^?S093RGKy_#;=LXd{wp!pIJ0Cw;up2g-+qpB^l|lV2&%yF!CXvq(p5a>e?(Gu5X_Dc z4zh?a<<;eP(%|uRL-BT^bPTvm-ZlB&!LYxlCGx994p!6d_*oXqU7a*YbxXIqMSV)Q z`NOh8466$x<8%|Nc~sFv@QR2!aN-!KVln|-jB{Ctg_ z-jT$)l@(166FZiXhdu*tY~+|pMzhMr2NZ=CjM^TaHnu0yKSj8VbZWngCD~^c7e!}L z(vjZ=;Bar(^MJ~z$e}>sdGM3%I}EAr{^fn(ZZ1CF;jNPmT=bECSPrP9L+1>^GgP6t zQfj?|rqHw*oq!?ME|uHSjEMFZ+b@<7wg*K-cT~YdZMlX22Si@~PBU|v`qO73Rj^M8 z6a4MKc%htn%^N8;Vd?H|Xm9|*d@VM;PhouqQl=B@`H0ut!+wq&v!e2)`3)Ntx;yF2 zSJlN%8b%A>Yw?S*$DYw9Vp*p2i)s(;*IAL7L(XAaCBoCum))H0?@-M`cK``=2=k2W zJ$>|TuE+i~O{^vI9c^v<4?6yLcpcD<&fu~Yu!XU#t*4ZTmSnF?@;?!#M)XL=E&qZe zo?CYxE+1C5G5*Ltlc?j{!sY1=$Nc2dN*&Lz-I|;5)0~fpD(T!e6qY8!gM>gqxJ&-M ztRUU+=ZG0t!3pO&Oj492M7*RZ4ngh1GERWl5Up@q;1x>t>Jsn7RUc z3v&eGG;E9Mz+!|9zgV^kCak+3YGfGiZ0-+y|qbwiArpd9l@OiLzD?2C2eSQHtB`mKQ9KWU3ox>ik z;R{-)393R3i|AoE-C8^*UPTBf#h8h(ubC=DnZC7M`f_PH%=kC5S@0-Sc5g&ek3?)d z8H{aC>_-HjN~8|s;oQJBJ^ZFTT1|xQpIuE&>pO!3ZN9*;AL+tf!*P?Ku+WCg6adBW zD$~qbm>S@X2PiG?NvDtY7(yiladPwuhHG2y@-wSHSwUi&Qp#>LfmlMcM@&_KL7vi> z2=Bdek5#2qICc7gj3D!RO2*RWx>HLVuzP^75z)!~4C`bv(SqaBSkJs!*F0Mnt7;tK zAPE0t(bJd<0000+zyLwTM3TUfIfs-3T{!U72D5Hxw;54nc6r*@*z zvd{Q)`W5_VZ26bqCqKtUcC5{QC=|gTd`@fHBnJi ze!SegPg3}cebk^Ee^zVIbEipv?Cw6}K{!~Wx($|HTZZ5n* z?v}w57cK3E&On808_>+?*j5o)L<~hMePcX<-N3;yEnylS?(`cPc29WCY(PsB>^fVQ z3CcvF9M^{il?U6LhoiX^<(+S& zmXd~Ny&-bH!_LoF6eOiMV&=jb(;+gHJc4x*khY~2Y>p`tP@)4q)m!+QQPVx*hNcJpp>y$9aU1e`je%gfUk;x^$IM(92 z0Seqjv=2m5a7&eg9m<{I!IbP}x<2||3x^F$h#e|72xYsX*EihaoBGu$;XWY{Gch%F z-Fc(lpV75KxUN`M`dn+~8l*q*njHcb^IqRUPw3+(LQD~U4&QHTz5*9V$apMupPdmz zOWF}1DptqZxiEv>DhvDo!3jRKMZZXhogErcLP8##1%yTrT;{A_G9L(o!v`R9zxE0> zPkCd><8NH>U#Psx>GvjFc!5?Vf7^c#*O>6^W^wHl!@qMuuNuygO|j|Xpx;V!t0WE?a!MaBAm<9t;Siz9lL5x3-=-zq3MkDL*ycwSYLDDRRAROLZnA!C zgT=9~nTZ}gsC9IrfS@U#v3qS9l323_2gKk&sEQCF)Hjcai|!rDz=oym@Cmb3j(iyk z#cQkSpUXo^M5?RIfWwp5FS-=+85@7nW^}jMi>w4z$*NKnK5^_0WVMpxL*kFD6OSai zPzLSGsTSb^qZbW(1-Env`=~6-{Wg%e6kP%`~Nj4Wt7bX(g z_f48kWbZK4QYNHVu;-|Z*W|H+mZ_Lfiz&aHddG;XTf{YT!fqrlquBPMnA1Om@F4jN zM0p!*C4Vj|oli{04tKtu@f)9R-63;&gD}tYKUgli+5s@FnO9OyOp3U-GfR#mSRUXe zWYWm4%f-6vcJ3e=RC_Sq!xtJ0lBhN1_U{_(Wt9>!E1UuN_6q|XHNCh`Q+N1p;mZAV z(Qc^{L;;nJNH;B+XkQ5Q(3n#hqW@#*ekp+1-3chBDf5C@!(qvwD8-qeNE$}8Q18HA zk>e$D+Q-Gb*&yWOu|aU{gvWaH4noBCN-heSDcBWVFfVtEU46^EAI;gOTD$d&7wyzd zLhfEiLpFeRm(B+UuI$In+BG4ZFyK(5v4? zmr+fgUO(qGRqoEr2n#!<28G9gGAc(UznQBXbaL+SF#c9NHV92X|C-m4DFxk5$EfOv zI+CR^uos|$$-oNws5AEFE9|YJUlWAdXuTM$LisP;97#F?T(mjQ^6pmEB+C$KKyIkd z+fK-*&jd!xCrHHX1>>KLK|f(}21Q>J3I-|uWd+Kj*y)Dqv&*y=D3~c#$Y-aZT+5}R zlg52lyA_VaWMe>(zg5tU3#hagy8j8Pht0)COaMz3LOecolj)+Y)|9UrP%0M2Xd74P z@~J&xMIJ_U{kWH4!>3PPr7^TAOXRy}QOr(>LtiAajR%T<_M70Vn44w7r&u|hd{@i6 zWaeZ*Itm01-$MOeZ_f6m6nkLZF`Ea|fKyit9}hcH%MlCLMvM-^wzs~!;Tqyt z3yDYc?wg6qm4Y~jlaav%LLKHHH$nHWE2a1(5R&)^O9{_%Nd6f}Ebi4hXxL_9_EJ?@#sqNA`8iE2q-1Pbs<(<9Of z>Wu<+W!0@Zf=#w(@|nn6?(AUm?}U|Gg)TN)T_)1Aw)+qO03pe)o`3)V0Pyb{Se{e6 z1Og(W5`Gozt5~xA!Pb@U6xjWkP5XD}*wm#A~=;vR;Ds-O3TLrU8&>v`6BY@)h z9W(*4Ydm+BEhRuH9VjHSiO&qg$Rhfa^PjCga~e2B5sFGGA06jl<4A&QnMbN`R^6$3n{Pc z53af6bfObBWySCq6=Z}i{T)hS;TPdvsYwBOjgyO%5*$v}@tj;GBA2vIj(u&m9j9E+ zMcLw{s>=`iTJ8J24jk5#yGl5+@_d8fjt8z@OhOp1I`(rF+jOn8LzrPgQiXo$;^T7k z91SqD0ofjHju^7cJje}asn3-^_i!5nMASKo*3k2y+8Y`m3+MK-p4GqSgWu|F_^Lt* z+G*9)77G`c(1I&T?mSeut_#%?aC{u#yqDww!^_4m)s>kbPi}X)aj72LuY-;hDBSrH z7w&aDiH48?64`UGDq&tNl5Znh@JZZJFPMYV30_PFee|?a_G92zmE$)f(ZwQ_OgLK7 zDUbjI{@>Mb=%v!bF8ZTxST`(sm;;3#yZ9jRZ+WQ|VPv>kby5k1(qZ|n=NGR`fsf1_ z#6Env125FV&%M@nZzAwA>R0pfj^#RBEf%b#pBCxoudPG5aHtU}Zv@d-ujDj+-hBpv zp=HYM%!V1i6SCdSDub@B>HJY$5GX^?5>^$3;aYzk5;20j5FzSaJT%{9p~H?q5KS0R zibbqQmaLW`rnZ3f*H%s?0T+sR^>eXh;!x8lvG8}-vGr1$+(#kfc&00uE3#rmaV?!p<`GG8`wWCZB?Vda|jI7tnUd@a+A!#s})9w z`V_wJgX-&$KEr$@uHx@HQ#m2Ex9TeFoPw3{Maz@8hai3;wPMR9KBZ7?D^SXk*z4&& z`{a7+K6L;dl^*d!{d?jE5azT*nj|e5$~)|r6F2_yazxHBU{CCjs9~Qq^Z1JGzz9e; z0Rww!m7aOK*E>aMPqVmAXSVcT$Vhh!q3*ucN5`k|o?+P8p`9gLfMUV%#XYWmU(p#_ zrD4xfPx|!0RD$TFOaTq?s3^`FL{9~k-3*g2AeR5{4Ze$E+FrJKXR$8$75`SW!}l;O zV|*TCsi7)~1^eG+^LnW&n4E%M$B}!VRKxY{O!l|rSzN!Td4TgIFKNPuqus^YIgWv^ z3bL)(w0Q})DQz2XKX3o46drDLgnLe)JO<)7-UKhek^g@jS?AK=pIP|Pnte8=B3*3) z;jYq}yYlkfffZ~IAvcX((^Z6G<0|id%LL&eaB&3UnXEwXV5H)0T4}C4Svz1h@5Ihi zao$=ub=P<>box^4PtjlKfju_i1yx)J^3jUdK|XOp36_0mmN3VNHDZ?Ss5bu1?Sp%| z6?^+$2xVQuK9{qTa3}Q=&wY`Gc+LLKmntoYkgjb&9s9Cm&Ow-!JD8n456_$)I!t#c z7B&F77@|Ptt!gzH1Ck3J7a8#gy!jY zVQU9f0C@|8!Sz9D{5bjL06OD-dCeDpN5BhW;T?6f-H$9s17Cig{^g-ZLc z*t-c6XWbm|saATX<)q>Wb*mziM=!_ZG67%A%*#oQn3Nu^82-*C!K}VrzSJ6DwSSJ} zRG9ZtP^rPmZTR#M0hMDTuTaMS?UE(OXL4kR9P`Z4*TI{3X#dmJkC*=6V~yZ5(OC)3y51TGPlSB??|HSvL88Ts-NU2dut07_KNdNw=Q_Od zQ|k$}ufv*f=la)giv!G4;2nDd-bn`HoH-@{leQsXa=(tI3J|qv#I~2C=^(`-JRsUz zXab}~oTyQ0J9uADmnfm#Dn&nF*6k1&5Q$RP`d1|L2e4=X7C=Pt8>hK-Gb}Maeyer} z@#x&s+DM`tY)a~-!T;$K_BOaF&eh^eAoCU%Q19mrfAxnFs9Ujqb4UUgSi3yEoG|4T zoR4hZc_teYh8hgHE*dTyXY22qeoq5)MxH^HTfV7nLeEj~_f_d&2i-_hz@eXOm1_9n z8x&`e4(x)sQmc(7Mt_5ZoqElYIHD9R|BE0Nzc0c6CBW96sxwW-9 z2Oz8nPJjZ%q(i^}007Sa(eUMjXEPn)?1@lq z9EP?@*By%Q($i*K*=4W+AGAplnAWGo(uTfoaTgGBlm9kab1(Ss+kTe+jlke}vs$g{ z=AWQHpxm%U4`gGYzl*F}+c99C4EZ+%TD-CP$BepP-QYAapPrGukjk@UaNK0pg40)w z4H1D2v07|3fVTH^B*z;L7a3VN4j0n^IzYw0?19D}sCNAHb(1{ia^9%c%rm;-(uhlD z>f(bz5Up;-W9l$jJ`FRNRxi4gm9yH*wi`2k3vU&?7R~X=@KnYs$G@Y; zvSmN!kSlILIPjAihsGYo_#$|+{=37VdkvdGa95`5H*mM&KcE$ul%lon$FinNo83H# z4+u!n!%)~H>YzFh=J2;p4H^pRQKa%3kTXr^=HSIdu*g`}@L{z>vB(uAIijkh0e;V) z=A1d`m4C5teRl9~#CAW;EQcl7b0kTxBlc>={8tk$YF{RS#^s$V>Elf$w}d*+)BJ&| zA^NrDXzAVuG{%<^WxhZl+O1!_(L!j=cr^j8YZ zcq}Jpv)`w8UT`opVjFVHNRkOwGIzWblxaUTA6|5+Y5E7Jl}lEj=K?j$`T+vstO-J?L2q&?!(yN{A4dsN{K>tzP3d1A)k2pvubG<0C5^%8c zrw2M)Xe1y9%cUtQnigTBm1&2=)pO9t5v=K`F}Go%`CbrUK6Dwm9n8{fE`JV5$=gAd z^(BVAt*iTt*aQS7Vo#w;Bkdf&eFqULMkg)IO~2v{vT=FrQzj>*)i(N#e8*0YxkKIB zyUW~pN4C&4u7DlliPG=-jX9Brx;=N>dHOFe)+6-WIGh={x00RN1>p<6_swr)C{lw7 ziy_04&UKKStm9BWQ!Km2O{APjvE{2ux6IMG%6utmEsKKo&rXJ>c(L=GzL}QdaLqoG z>rQYzL9&j6)HSBP!cnD~`CS$&Z2mZeLALWrT5!Z?U)d$x_1FsVu5ou6#4$wum-cmF zmT|~(%hb2xD`B94D#<7MLv=&im9J{~opK5yXvzDfX1UXmLy>l{Y< zB3o<9v%LFII&}MduRbhHWZE2YL&&WZo&-9tb#Y7f*LtkMzFGWgKEEpdUJ@zg5WH!| z=6WP&79(MlXr+==CApH5wo`4?xhrqFX<5WuPl(1tKhs z8IPGL<~fxz3ExMxqFuus$)Ox~1QD4$DBBmq>r?mzVH%?o72hEkUU6$K(;SkC?xMYmsvofL_T0IsQfi>j?1agf$u@`!xsVeM z`DZ8g->_+0P0+mvq&uA)WXUD=y6tY321K#U_;`SKFZdRj3MM;C;{8WF8G~%ShAO2d z@G#YfN~7sSjol@_qBTG|>Y>IjiOUD9)LhGC+Xi!Q0&)<^Lg1vQX&kQdw|pL7&Iy2@ z$OXYZ@!wl?eyX#^j`F{QJlbl zl6Tn{Z|zu7=WY^07J@fQg>NAs6Yy`)9BQLz^7BkPZIlG16(M6>WbYGlM2g+e2yPRvKjVEjGD8zjj}Iy|u6 z;8l~lU)d2VS3Cl8vOXY*E}=|;^7dp9XhJr3!wU{Uib1qU)NW*!T5tlDhuX{F#lW@~ zytPZQ{RfwQFe(DR5Fw$Krl>;pi^&8vo@dmI)MT{lq$LaxVyUY!AbWRL`E9>O6{)U0 zP=0*^dBYp=HTQDl(_J+#K^`2A^wy1t<*MQwT>tV8c~gg47Fzk4IfW<3u%4w!?GG^sATeEKJg-2YEm%K3J=5>p z1qG=!fdcUYMU&~)Me!JHVnDETG&A@T8gNm0*CkQK=}>RQya_nnMl$) zZ2n^&pdD7bH=_WybbdxaSkV4k05)%?Lc?Mn#VBPOO*=@>tORbdD9_%hnY_IXVSoSt z00001xhRnxr6H_+AeAg(ITp1@lSbc(?PXHCl@=oVR0BiO{3@PuE%)!*kmrq%o~J5^ z49*Of2HuZY+3a7N_)*v9@+V$iXAc71)xhfv8px%c>dgq*I$C$VfixVUj(4>&nwtm$ z)imWJd4$T0j+ld*7-T0_lLj{(3{3t~Pch1^f)A6B+vC1%$XEVWlotqG3Dy`ru#fXs z3w!Dw1UP9lD!5{$S4a0nzRS;fWcy%zl?nyTOiA%Fa1NJPM;#!{+F_MD2WI)De6E!fJ;OVR)jM^S0K z;&g)M1d}Z7fGI8zG+sS112>HvX}$P=OYl59#U<;=p^NEgQ#Dk8NVy;Z$FKqwF${K$ zBg2SOUrQA+R!MEkr*uPZK4}GcFy!6mTo+7NQzV|9Lv_Aop)!l1(ucI$Z>QfWtZ`v3 z3nVlwpPty@m@Pe9u=LSNpoN~n6>pjrLRz)AlB%Kv5FUkK>aGGR2{SsA*;iCc&$E9_ z4eBRXQMBsCF+8H-vs=VNNv?pgIs4gRPZo>a@J>t;=Q6qgIM@(&U?{z9tI}oR{9_XI z>zfL{Pcw1h;C~FZ)g+J{-|9M2R?(0b^=RXzXRD98 zKxU(0clhA;-6|czJbqKvn>QbaitW^@hUXZprh1QUZ_?`<7mipsqe8nfoCVy9w;P**%aqERT0!8y-@b)qD2S(pN?8?)D~-m@G~=cuE{& zH&TnR(rm#MNAl~T2R=?by^ERoY`!1=133;{jrG6VbBXY*r;icKr+pADmc=M;ttAK!6c*K0x}|I?O%!lYw%2q-f9r*yNjvS*yIjM=b1EhoY^i&z?P1q zT*awnD$r7g@O}8FnZ%CkUy+V}GDe@3*K#K6#iPnVmGPf`aBlbkI14|DTV|jz*LELz-6=`eHmLbRac9MG>S&jtg_)_FmxW*uc| zxcCn0%zLE{_yV&)r2V|;jOGeQh}R-Giu$Ov?$wu5)NTs)>WtkR#f~ih%B!;@hTsiP zp6mLwY~Fxq-pHqxY(RkCT=GaX0Kq>9-?2FX$D=zzDs*` z7!O~3(?sq-9G*f9HbRTA7rjsfTGUE!xWbL+BV!SGhwdeDenA>{-2bJCxrouzB&1C&9g?Q5C_HcIpt9*B}4qi}sWi`gzeP=I5~f?yh8`cEqH(4}ab z!o;b!_}?O!1}8#SuLMwBgeeEIfX9Q-T;LZN0P;{8bI!oHz(UN+Ed?S!kZ6tySygGn zg!1%jdm9$OgT!J#4kB3u@7bU;O8Uoj0DTT6|2Lp0c+3$#!PB`R<=hIS72wcXgl041 zJe99SpHWbw=jn?=32kup6MTP^#vK6a*&K^?0D`^F_EcaoBfNg(H)(T*VP5%{vt(ym zq@p_0X?Ndk&@XBe})A;x2+SCLY@-V_=QP+5315*$nh%kGi)$5Xqb<;|2*&Yzh3EjyvX2;Dd1DvgPVf_9=X1ylqQpo<Neb}zGuC3Egp=#S&CL|a$Y#0qgcC10#I;Ko2Y{lp2PswO=TP}u*6O+$C#IlpL5 z3Wc!I8Wam<5f(d=!uqqBezS^#a3C4%16yL@Pr@Qd%Rz+YR%U*yMI7SW=h6%K-J`5I z5L_7$54DPNhN}zb6pjVLEp?!=4xuswZ-%rAS#R0>kuAvi9yLn9@oVNH;R{mX=3svr zb8f}gKmq%U+7;U}hhy-JpWLwI8^<6}@X!C{(!@s6DzfgHlZn3j1~e^WdNqrHF$)~8 zF5q<}DUP(Ct~n5km-6bhqlX_BvP}@Er;I;13};mkJt?~;pz?CoY@A7!8sGra2~i*V z40h}Xzg=Ouzx-zL;vXA@u@LTh1B+7)i=X1(yeDLvnsqv??frY@9ez+gNHADu5pE)b zOl7?9!ujFP)Jw^>{dMO-C*{hiVp4GrjD@; z`uOe&y#4mp`FZiSqR^Cg)U3Q$C4R>!{p63r?l{OOnY^x12kAPGDukEOea-V7Y11#| zrjncoQlEj7jJn(-SWJVr?REJlxoNk}c1MV5{3b^uQXV2xT7Ny=DyN$C=9%D^iga38 z<1Yt!jD?JogKB^`wU#Z?2lE6;x9$rnAT`?HA>-g)+YBV=6k)v0`z+7rUrE8nMSnda z5zsu-0L;=E)U@j*ONakfF}Tv)^iBxGIy*Jr4`hxk4Xa*9!voTv1L;xNA^#h*OsA?l z%yN<+pE~O=0CCa3C}>IJ-YoN;wFVN88k}ZGIgJfV3ZjaN9GLrq1KTtjC&P<2>2ftH zIKJ4Y5T?TA$lPLeXK{gHw_ zdC5%~!Hk_>gQ$9I-#_ICfdx~eQ4nqp`9Z%!kL zi)9aq;P2^*tw(#CyZkOgr|!l~lNv5iOlZ{+grpvxy6P6PTn{SuLMfE)y4Ajz!+;%D zu*KhPNv7yN%eX}#FX*;%SVzr=986AIRm`AV&l#E(>@{I;9C8wv%)Hm3 zc>p#Zfa5j!ou$*DAIrONU8IiJa8_*Af{JikE2;9Iw@hi_A0bR8<}RR8lSeKHsH< z(ayxeks!hMn`QtZwLkFOh(Q2#0Vh6N>C5g$a@<4EmEB2bW z_{+CoIM-z`Wa20U#*^VK(vr3$Re5@s7X6z?0L_IIPkN!+TC-|9Lz#`ViMx#8taHTQ zZA(5XBQp08Km7R7+Be{EArdO2@KGtzyF!;7vQy%MQ`dhrZpDvMCtRjQYh(${yTn1= zN&Lw(vuu-*zb4!4$(D-6YD=)e99SH`5tt{a4X5wa5o+QRXIJjQuZ<2}7-KG^9~fo# zeiEo^9q810gdMsnJ^M!mH6JBMM953ZJYA=f&Y`nZf|PVNQM1)lK|EbQC9kBc{KjB(UJKw^iJ6?qNwT~gP+^#u^1tC9REyL1K|6K zRZOsc{R52~z|#ATGM(Z*D>qV1PLe*Hxgg1mOR@qfunW)d*A2k{aML)?$Y;O-bu@(E zVXY>LLg@?4S`o?^1Pk0n3qVyD`t=FO$W(BgUk}df8Y_x-&JupX6VP9hfic`UUQ4te zfADPnkZquF#qMg0zfW51dDV%hLf<;*M795RXf%+5TD3*<+F>HK{cg@F!=c~P=tL#$ zCCtvS6gM)%pv683{>cy=RSj%wK!5m2q@KeMEFIDl7UfCXUGh0_RCxIn`fT;?r3U!2 z3aIgi!#4#{PfV1vM=+r* zqh7~Tv>7mYC1)2-qFL)HWiZlSR*o||M&lezhZu^O%CKC}0|jO0a0x;~Atb|1N$|`_ z*LclEZnW&7b$&(7Pm$p<&a{^P7(IVI$SAK4ame{gTmKpMl0%ILF+$SUiMlWfTiONC zicWb^zH;RsVWR?&oak@3mkx?z0~_MLow!PKfjD2Hjn80U<$LTBYB-@oSsyX>L*gA`-CuYBBF()(ZDzGrH$Z}7$Va>6ng2G&sGPpA|}N1pJk1h z(d1GtKQV6VC&glqjI$mP6i+c@-rdo9KXxmV-DJI#{AOoV)7i(~C+cxV6(f;s?kVht z!DVqPG!Dr%Ccq|8T1(gnn6aU<L{3;B&6p)T@rYl%q=qwgI+Q!)_wsx3&+z zARG%#nswm^Eku{5oOG<7e)FI|uR3_&Gq!{rpeRxMDl0AEqcmZl9hRuw$_bz#_ZB=t z001EX098}l!lJtJ*I^M(yQAJyMozHN0Q@;=Yvw|LTZ|jU!$SQO!-5z*INE}IOIV*d z_YfjfS4(0yI;%ls##sCFgQrr45yq+b|D|vIlw)%p7_bpcJLy=ZMj3LpXxUsSQ7m`W z3glvIYZ8P)BDKcw@0l3T5iSdZ*@w}?vGTd!H)yZ-lqv-vKP=P!S~qQ>%ZDug1cbRY zGSfJoH3a{N8fQPJdJEo{k;wHZxat)t6U*wdzr{le|Hl6>JysBh{z4Cn-$BjX0ks`5 z`&1Qs^x@dflnZ5+m$9EJfq^MgiPxm;WGSMHD0S7QcI;8Nk-}HD(mO{28=_hC?qPWL zdd(E@bam-8Ur)U6xkLeaO<}<{d+bdhrbAKIQ2{dIx@uQF-hQw(+jrx zdY<0d3VhW~hhKRF=sdDTBa_0oG2a9dE>hB}}kkcGy8@i(rfWT~dCBdRoO*a7`(XYhTKJY_8{V~)<(|e(3 zzEqnvrz6A6(HTP8!pzifCInBW)2)ZCHoNpfO%)ivA0mI&p-1lXOzTP!NT&YWwQW>M zHT)sEdB=kh;+s&UioJId>}GNB!}4!4La z869y}8cxd`4GV~8CT^L{Jp%hl2|?2n;c2rN#{q;r3pPC6GUg@@ev(bQpuosTq8R%-e4sTVqh)s4$IfjzMQX2uGuvw=S$$^(=&foX zE{(RMTh4O&LWAR6pPRni>%EfG7;dLgX%dw$0a(Xz0LlHr32nl>>!q(&2@Y0}b)CZ9 zUMY9%aJ3!+{St@&ONVeepOW~c`Pf|$>4cvyPx<#dkF`a$mN3tYC3A>%5f+AMb$(&)alc)KHLde{9|w1@{S=Z5vudX{gZgcW8m{>fyAQlIo!S@)9W3hO$&AvMt1wkI*w$pgEV%oH&mk{GoZyhw znQWBguu;V#BA!fl+(9hFZG{G0F4cYalE zQ5!+E>Fcl3Ax7$O6l`y^qXed$c13tnS1KLiwY`0w3+i3GWz?YTdJ4;Qb=4&rNeg*X zabE}odGB5&tHkR7^X{-Ra(FHZJolS))09ca3(KDY&6 zf|<)X{@9;1gd6TTJ<9 zvSHpR$Gvz=p62DO&qw{XQvj;cTE0KydXPpYsSbm>|LzFYZWC7p~*@9d_3Q0re(+Ru~|kG&f@o^Ij&^Uad< zr7i^Pq4t{Pe}Q^Wb|&4NR;K!yEv?F_Zy|c@EFFjQ_iJUyqvkJl*%{vmeVTbh_1_B5 zky3Ke3k${K1>ooIr`XY=LWTZX>fCf{fi+f%lIAA8-Oj-4V~KO8OjJEI+jJ}@l9G1A z;}j1eb3t&$(|}@1s~)(4w)SX>8VZe$I5GM3(h{vUVO8P=li;fPY(}$B1C=o4T#Vd) zjS{jxFAl`;#Ss?Ev3YlxaQQp=7CqpYYP~a~@#|af9)x;NvF3JGpXxMKGnmMV*nd9Z zm>t?hzPmg9NxF=>bHK27ve4{{lr}&JC=)B1Z_iUluIAA%CE5m?nK%!&B01gHj!Xr3 zcqmw%qB@qSFCOTxSqer-c$?VbPA$ky^!&TNXFzC+5XSgRB|tC9=Yq0tJq|b26V5Cm zO5KE|5WDx!fh7JnGL&}nJ%~g66((wp@>FqX&ENn7D{b0hH9pZtx3}N`H=Dgj2XT$7)E_4X=3@mP#4o0q(|tr8r%>4y6Gl_^B6k=yCkTpK&Fj9Y&joQj>KVR#bVs>gah|W{ zAyq6dsjnkLcr!rq5gN(9TcX^r?_MoIx;utzJ*| z)`hhVSj_M^-|J8G&Sf@|ZeG|$3et;@Xi&$ZpZK*zQK~1jjSx@w+Y%!eITCuKW79#i z^wnmZ+$CDPPzF-db=coh4eUzwo*pQ)(%cOJ&JSwdQwC+JiLbeCD?blU{ubFEYycci4Ggk2}wx{8+z}^9(Q`sE(~M1U&KL zb2BHRk1!pRXVRwqy`R%_8do0T(kPwnq3ih3-T;W6jx5=bjCa<`nE&79|Lhym z|LyY7Iq&Er?|87_*rD7bBDLDo$sksvCTeRLxzOD03QnQxvoCG2I4sQ!+v4&rU(zkg z@F>`rxlwbJ8>In0dE8&SQ3@=&udA;+6RTF?upv3mv>w|J_UM~=IVXjmQn&&7s}Shq z8!9Rui7x>aJ-^6bFPFq=5q%X#bsm3^eG&(N1@R7_WTLPcuZ3X0!A3t)SK%aBRKSqy zf#e)I6tcc$X+-0<5D3zLOq6(NCs)SS4LBzy_t*^-t&JQaQ8eN)&(CeV#uXo>PCTLZ z3hf!W+pCP4hWWU6xRxf>eBb~801Hs%L~Q-MaMQZUGY3ux?|2g!3i2Y}Ug!ej`^nn; zRMcgWT^gW!QTVx!kZk#wy&(mkwtY^-E41oEe>#f*)X!X9Sfwh~BomkIpQAB0B}4>R zds=X~^)OMx$|bP4B^q6jGp5w{^J-D)5>KH1z zqw`p)lHl$;LC}~5&KRfz=F%RY(!BaXAKHT~4+|6W`%>1l<6!LHSf?dlQV)XzLa`MX zn}TSvc@SvzxIQr-|8+H!9RhN(ZswnFgwu0m$*ZS}!sRYmeU@u~NuW;#qlaVFAwOpt z2`eRIDzsLQU;|Z{{3Is~l2Q1@XhFr>>Y$wPnqfrw8>akuJeeziMtJ<&==W7?0{W0Y zw%T|gJvk9P^rvfzrw@8(__{$~P9Tbm+tmDjCin*LQ-JT<5*bkJu#1cM5(<2+v(A|;{t&RYiJ2BtuKI(_?0 zI=c$5{1LdZUblwbj$Sk4o8~@B^A~J_5Kpm{I71>t*pc-q0Y8$rOnS6GmS1;B6{dR7 z(T#)YrfJE<(ZH=B!AVZ3Z!d<@s3kd#z)JB_wi#44awLY*U8Py2gU&)Ch*_!1u8n<8 zB%-}N`8K_2WF!Tu-iHn!=44<^q)HML?1-FG^5$uYwj{yU!m|=qU+N^nj0N;Gwy3=h z?{vQb$Ph?_X-Z~;Y~#;sCPnuY$lwm`G*A2 zpL$iloJOqrgbRtbsqDUxPmEZHu)2_6MsHsNB%reENVe)e$nu&eI&gIznp;VSH*kCq zLITob24~unWm49zP;s+?nXeHb95MiB7p`#l2+vs=wy!N#va;#A9sCnKFcSZ`TK2TL zu8wW1S`KVxm(3_s?LHMY`QfPFHIGQ~xCRk+A2DBEla;(>9Dzc7EOM7F8d3OYc&W#V ze7+5lpd^aIecO>TU!=VUi!RVL|@ zyy}>L^M<&e0tBF@mipmhaUYZ5ugbY38rhshA)u)dt;X%6Dp{|i+CBQJ3^>o+Cn+Sh zcO1J|wZJ1d7+qh=MSBy{f+yoY^2Ys*k{7n@?EkGtQg~@5Ctqq z6$O|$IDXUw$fK_LX8-`=?D)1x=#NRJM=$jhf%^ll(G0+bc{IZra%Mxk?%?s0iikE# zT%^~;6D*_p2}pf_Mag29ARzSNX=Ld8gPnwARkxv2^(Gz7xrgZfZL97DXbcDu)FPk! zvozbbpBk1UUxIF#GVK|1-L$d&hEPq80bF;J$bjSjHMU-1O@k6yH9$e4Ci*wxJYUME zjea4vpi?PT2l2?N^GY8lShk9>5d1zJfqUXMhiN)iP9L=}yC8QT9a%q z&C!XID;zpY=q27#{V|nhU4Rm;}(HJ+JNJnYMtF_3P`S^ z$w|GejEoAOplTFE#}3zSDxRd@tw=YGHkIWmShIC)3*g`5$pdnLD5Hh(M^S$jm|#06 z&m#jx&w`LU2~*7ytD#)D_65GXTRW}yx>VCBvL)Vr>b?qNx%^0W8-{ z3ratW61Cs`1)`^J-T-EKKjk{=-_&{%>1pC4HfN;zXK$u0_qOz@Xho~@$;(p2Q*47x zJZz1Vit#S)YQ*G~Z)%nCAv*9fYqOk(+H!Wy>(}i9{^KP6gwSM&KBNw~QOP%qIi)CV zpq5b$=OCsjvr$cL^vP$I@-Yl$nK%4SSZgiy-?RJIG!)4ROK3! z4*PMwHC*>hk?p7X>mC_(L61X|wTAtlf1c+i-spETFiZK{%F9ikZ6FD5^|60?NH+HO zjmFS<+P_X%Mqa#|pEx=rxe8hGNU!?ygt#dPn8pEM`6x6@F{VsSag7)dW>Lx`2 zORW}rj>n^Xr8-m#R|sU(CGQhkyyX#5u{7AA56O5$oe0J(3o8|TIBk0)3H8~u(4jBM ziTi+Hx0@3?0P*Pv(>U)op5Q(KhnZJi$SPOk-lFzwR`A$zRIkCCUYED6>~UR4W5N})S@GSOwk}! zmj+Y@o4*YLMr-Tm&CP+@T7Rw?kJxd-Gj}0X5pJQdbi%#)+gn(5Wku6k?fn;~wlbji z5CvoC+npJS5Ab#9V9XUujDIod|`g<*$x!ML~{srJp7TJ=5`P zxjYOAX?Hx@eG;b~qWOsTj}hAfR;$1&G{vR2W&V-ZBeSL{Ls`Y&Sd8y~kKMK|GQfnn zBri*O!#<->XPJqyM2i3O$S;O7Uw6I!BmMuAkQKqm5?z}#@#Ib-in?MP-+H%o9q2!# zjvl(?AY98jn;`$-TS(A6VxmL&mw%K{>7Zjq_cQDt%R7X7AVRx}npb9{QhNnSm$Wg9n2KFQcil=RxLK=33Wx_;RACJ(z=xEvp-wA zy;CE>9>G<-FqBlTtCx%AqR4QlXnKqZOaay|GC;VJo{<_7G3h^OTo>pFoKW!)sd!lC zqQQLPMqcNv1HiBl;}|F^6OYF^()au_TLjjs7d#7>cQh)^IF}x&`6Doy9DHG|(;mtb z9Qi(TqXVWSo~sL5==fVX#9uDo1#B`OrA$|s_~%){l*V=0Nr)Z0^{HBrqgoHmDGo)Y zB`OYk-0(A3lafR+;zT~AD&T_vel&3UYTzf6c&ApG>d^XA&hx4KCxuQ&jUI7+mz85l zr(q)KtBLexK@y+e`b#ct?kQzFWK4}l(1U@msRL47y0W+Y=}j{`b`2sTzyJUM0PxcJ z)Ah3s1BS&V!71*;aH256ZWqfqUzH^hy23xCpOWgvguADP!be3JzbEM+tVc8fZM3vJ zfBv3JU_c61ujuz_Q63DzsL)|aW!Hox_)^Gj2Y^8V9#)*jDf-v$NAt?_K15&t9no~s zaeG+F)_IX{f?6(wm8!0R7d0g+$Wvpp%H&co_Z)ghwx>;GiprKvUm@eW&uKfD5SepV z%}`B%@8?*9HcK45ozH=}$B4q5Xr>uK|2S4f*{}02eUqBvzytLv=eteEnH^iWo70F0CMTiK%zrqdFv7(vJoz@rooe9+Jnc? zl2D@3R9ISb?tE1ZbWQFh=)3VKe&2Xx$5m=_D#<|eVxZd0F?!^sv$7f!XOMye%Zx)i zAoG`w8Kq|a6OQ-j!ErKsK&*X0P6!$ad4*&raz4F_4S9puFrqQP-E@VsQy|$j~ z6v;o_9SM>qGaX1xPeaRj$CJ{%aD%$`OzB{#WP@5qj%efv`dD>REVE1eweP8|g|v0z z)2yaS19eU^M}*=VK6be51dBMc%A>-4P6PDIr?Ihfz~Q0o4b8R%&Z7IY*&}X^x+$D^ z;LwonJ}z-ClklqO;M^!N+N5$Q!SuN6R|`Wt{}0w#sM91ugHiP?hTt z1=4UeI_FOq#RGyl{b#K)Hbp2sunm~^gc2;hWM>Q?W7hzhtgmF}>f-o{veDSZbROp) zx{+K*KxcmKZIh6!%*QjJ#leJBCsa*av)}e7R!Q7ylFDoJUWWh>;z{uRh6T{nAWlXqHII)zG-(r60}5Ydd!obwWtf0pZ0OP!@)SDs4ZEu1Ij zYed{7AtpIqdiOCjg~CB@Fdz$+2ic`nZ;5m?czzAIijodDO5QUDqLN%Hb2xU_B+nwD za!v@Xr2U?iilMy1c*&RSB6agZ)fR^>ez2srRv5!Cx3*?yRRru&2R3HbID)7I?7F1= z3>T}Z)#gR&LQyrNG)wY-U;Ysm0k5JkD%HG_5m6kblF4Nh^~=kO+N9AK2?p%YU>7bQ zK;4*+@=O#3tDhywz>3)5M9q;76`)H`0ryoO9yxNjXF>rTuit0{0^%dBfyp{M(+G>5 zmIgCtq>2ZS_7nvtNfbzdd!OL)c!L0ISv)|qt^@*rH0Av@r#rz`ngpQ*JK7*o|EtiX z#e^3I;q`{4F9OW{eVr7i$rI>UdmwELsTZYLr{6Eol1B26L9QdQV#FlU;OI&9IftbR z7!+LtXhPe!)^g^M6C+zV`l ztSUWwzy2NMe-i#rSP$dX)@dHb5&r1c_W^hY7!4NQ@P_N+<=^QpimUETi&@pgsOYr5gl9B;F7&OO~_~fSA6R zRuB?S#0YjDWZ5QYCjpmgBha9ftaQ|!9h7Z#3q6uF3ke(;Qad1+Yea`Dr~U{fc})sS zz#rXgTuUs@1A-yl)rs{*ADq~ECrHzG+$${QMQOk@aKP0YoZVuDPa`qca}Eo7AxOg2 zFbQ@I;BD^K6RvG9HY;zJkf-t}03b%ks%|k3@Lhvg!5gzOgw0}ju57ze*R+av+CTH$A;3tG5!ijFK z|1YHrllCTx-y6#)OAlOxW72<=n0hzRSaUyvsgi`dz0gKuD(O(UhmaBE81x1_%6{s} ze8*BfC&Y2?NoBaKXKmV>#>s8J)$*rD6p=Tgyd9gLb5YNt|%4TDONKv@LO{`f@meHV*$r4 z^UP3Zi@>)ZHMfBcHCDw%mfW1RvOq7*ElaV}Pq0CF4e^Qqk+T;c55@R3cK8)DY-6mp zV+iC!r7>JGi_DflM#6!W`e;$`g&hxs^qV~0xE8OkWkd{X$Y{l-o z9Q&tQdjq_?A*8N2UI>VaV@4Jy$=s;BHDnz;cq`~!g6V*j;9_0lChPVb6n^K-T<_M9 zberVtc^PMR)F^%7`an>rZXjoIc4As2t=z|X84w3)ma$G`2OJm=owJ`lH}&+o75THt zc8y+-CRH?v070x&Qsuc8$`4Y+>!Z0?c&wOFi5OW>3lWltMY+Ck69LaZD`L z79W8n-Na>H&VoWn+&o@pp^FeZAOKC5ofzo)m>snR_+pZP1wIx1b+CFYayQXV0-C?) zbTk+}aqOGH02D3V3aJW{)6ns=i-luev>+F`Tp#8H;H5(~qy7SEvGzd_^vcWx)yK%F z`O>SIz5NmAyac4_l?^hfbb!@vtNW9Ql7tkF?pio$;EDk4>+Q;LkX!6iNF_Vb_E+MX zO_Aov6Tl4+;dAOigq>$cfGrzF0;A-p(LjPHVeC7Kb6agK`}&xZ1KNaZN`RiY!u(-^ z_$;2`E5RAO#&If3x@G6Am?8z*UxE|N)|4L-`H{%NBgdjAiSFniDo7IVy#`SfpcOgI zQPUU1abh9_#9fIqG4>xQ%VpUf>%ErWQN+imHTDb*h{88|Q~EiKwd>iiQoj?=1OvN; zrjI?oT0AO-JE9}MzFfU0P0(+A-@Dr`aM`%|@TB{DT+$cy1Z;Y>1sg&}IwDx?L7HUP z()oes9r^vpy-zJ&sYbc|V`&!od-T*GDFax1!U(>J5WyzD3=c7RiZ?$Jtq89f71OQs z;Osb?PY$71+sH2x_3tL7#?M^yj((V4AZRJYwK49(pufC4B~jsI{g)G)b7o(AL-sgK zZ);0^@w-zid(UT*&!nHVWl#?3U|+xh005ziXhbG1q<4+zt4QEN%NO;*goYc@SNlFz z`r4R;2UEdRAE92!>xWDMLIx)3#vLD_ew+|p-Y0X7`I9G>B`la7M_&S_O5~ZFY-Eh< zb|zZJ*Kqbw(sxH)d3e^FVXL}?hO#b%U?+ry8--smT|C5pP|2KAQ=D1_@z;50qM`Mh z1D%~oF4a|%0Lv-G`v(`%nspPrr?BlClgYmP;L{DW% zYCl7ocZ^2{0Nrrg9Hjcre%jO&H7l%XS5Se8Ka-X*pgYql3fRtkJoHu#!Yw%s00?{#pjeF)(M z857vE^_3XN@-9~2fCKkhqeY+S&~6!^sX+P!u^61M^JFMGosA(?n;Rcvt#(rbX8Qs> zF5`-2lKWu#egFl{BuFH|opJ~3#2do-gFFNnCOBS2Qm)`OnM8)Mcs4`8ZX{z{4d^b^ zu27kj5>xv8CK$||`0EdHbDgRbEOcG38!gRz6=(|FAvrtOR=A}%P5U!;C!ysxNAwO;tgj8|D zt7)`=92NL6F_-ccU_W~^# zNv1~R6y7OUd`1-c(-`-W!;<>UyE5H(DCM=V_$}EL`a0te0w?(U|AqK*xjoMloE}gd z^%)hjx=ov7rWbyQ$7;OaM}HxZM7;PfI%E={WB$7)-5i=)KQ|YRjJ^n*mFPM+os`t2 zm12yPb^=bWFY{yl1|M9XhB#>hTvK$hM;eVX9$bQ(Sq3}5#Wh_*92(J0>SYW&D?7;u zL~w}m?{XbPW=NJ==%xh5oBDT?qE#Y-N&sfi#h9v)kaQG~3S>M8j!QqLq;^MIFLl# z9!wpM<*niAMZS!GGRU#|1?ha>$ z>=Y@;FUVk8r@R?EjL^%TdcuB&gngY3-fc=BtRxE~bDI|{a9N7X6;^69a}|f z9?I)MfV~v6$4OYRHDA4F>nD)UxAc+f{zM<;MQ;+MGUh$V*N*lC>O%=f}Qe0^00O~B^s;LFB`^&xWIdkG3Gs5kt%@jn|J zc0T5ZG>L7sC=cAK1~p3#FyM?OyKcZEwyjfg=={a@tG=GQEY}anU{Nr-qvUJAcGBQ9 z+QVz`#Fj282RH=;;QFq}JFcfNg1;jXITq%IR9{VrVtgc1(ah=zU6et8UJ=H8?^&sj z9!2oPC#EOhTHA3|HL3XVIG_rYhY8Ha1P}cyjjQ+mZj>05b0Vb?k%#eGEFapuTQhUd z?54_4nVv;}ywrD^<8#KX30n6G!s@kUgGS3GXx1{W5laZkYe;E$ zI$FvFklxgh<@|fGrY4TMr`8oBQDHcsv@jwIF$L~c&n=hXqrZ2eS4BoV-?)$&+IAkp$+cCdY<}*=QxOMSKm~NOL9WJ1Q zg=ltx&z{a^gRv$U5Y1qY{mE*Hhp?>FDDavhR`#g_9l@Ys;&2h$ICx89M+P}&Q}rL( zY(`sMvf`Su11MY}?A7~@z>+U&?7PU6ZDIFstmsr`eiwdFjcJw{P}icr^)u z&>P&hO6n3j=1icR*F;p6vm0#?)Y;Be;hPQi^E}F(eC+{c(Hv7#F8?>=r4P#-> zKIQzD=KZ+8w$}j!Fs0cXIsut!s07pu>WhIKC{bdkH?J1f?)mcu<>~(nzJ^=^_zHMA z|M$w60N9D6`&-epRo5nSK|a7jOe|J_jhU?CPsehJ4baIr}F5>Vkh2M`Q<>1ORFA^30!iK;?aSu?fU@IEWfm{0} zFTB&YmR(V#)kJ5dK!sXf3^yc71+z?^%^~mA@Mg|rP~gAvU%t@bSY18gO|x-4+App< zGtJ9Y+S>Wz^9k$?f}yR`tiGWnZ)RyiU$moV(5}8#EK|x!0Q1ua8fy%mJ5+Yh@$IWa z&&~!y07IL`5(1;+xHPl4EAnQ_hF8s-QuVAAkP|gEyS!ESr-{jI;TgX-Qf57wKKVC34DF$CDG_%&9INhC1uExvzuHU8rV7oed~TOvSlg&%L8`Ez;}qs&tSInv zL?#ABv04=#Dlkj7;H#V{wZAYRFOt9jGLj@tZgmVdUx8M6Y{;KvDc~F`D4Iv0Cia)J zvloc+0?ldU71DD&sv`E25=clHj}!Sa=&#LihCf|{rZ^%b${9hZU&QIxH$u?jB`S)N zhEhYvF8!PeKYy|I>|a zDw{H#IR-E!9A4;fsUmVB8u~M9&;RvHkLO)S z!o!|Z(vZWKux7EYKh}sP@RD&FX}vta7GY;&WPOJ3O!>C+Tz--19AHx$JQ&Y%dhiHP ztin8;a3M6c)V@{69O6lzC*d%s!mUDHa7KW7GH4ZstXy(quGxCD-s5lNIMqQf6T_8%i>*mR+x~Fbq*rk7Q}cLYjeqDMuQDcOI=-l zc3ih4RkuE+8>JcD0SgmYvf>NcJ}sca&}~1B%_+T9uduV+S@w_nJPQfs*CjptK8%d* zc@{)Z2zeKy!C75hjI%L(ZHwdO7{TDEz*;vV_|<~|iJCh(3y>!hf4QK4cor~H zV)Vbbba#zOR5@vb84B@H-apwu$d{BQHZ^prW>!vULA%RC^72mY0E=|narM`+>qaAm zfQF#nxy1%Hgd?qsyPW<-tcS8CQ^`C;zW&{#-+?$c*ylm|mw=eN;Ja zv)Y2zGhpuF^Og?<%xHI=P2m%PqR%tn{o-U|vmp$B45|#VtSqO`YiDV~ zN)FSRk|R8^j55IX$OsBNFNvS?iOa;IU1M|S8?POsE8@x(RIPYe#I!WMuCNr5us8U| zn#z<%;B7*Le^Un+gdZ6m?|0W5g@zneqwnm&USyl6B{ScX>1e`>4&vP*qdUdDalq1o z4euOjOf*fT0>%$Gn~o2RGSxeSAQT?F%M|aHQbHpEv!8;n5+zqXrr!Zy8`Y$#EgwJZ zKUU+p(%P}-57TDPyUg*2o?!__e_(Ga3%{2VVH%-e zTH3=qg6x|av&XROh4Y#*g(lTuVfc$?yg^T!5L! zFjSa?N+KlkRK>q6PU3Dpfd_)zjk^A~3Ir=h2%!}&+t(LN><@O{^sp`+`q&I0tPvz- zC~0b&%(&H`GeAg!b6_?((_v{;pcd!POhtiP1x(NyeS|Yk_llkTu%c_4iztekHKBZO z?`|2Y#Ep+UG+r#2Ta+KjpFgv{`$GU_qA+e^tBNpnf^@fj=Ntcx&bwWVZ3hWcBPi!S z_g0C4qX3yMlSqhS!Z^kww<+6tm!mR8yMX}oZ$^-DASe^WKO_ExJTMUyC2h0HV;3dO zpRodK-heT^=jWD_>(cZ{U3hdgt>v`5Qnzw|Oq!47NotT#8T|>M1Q>&0CASNAw1}?qepe-6Kg$V+S?ABioDS;0~GxX#mYEN@)&cok;2)|lg1Bs@3 z%E)7IitO{EF-On<_4|$>lEf&u+I{yz$rZI^E+;1m$K9aQmDYHz$8lRF_3MFlIM2YJ zwq)$~Jo&pzTB({RZ{)WoNI-m`_q=V`h{Z*6-kY^kX5J5rYNS?rs@cpNsTshg#@eY! z_+QN6OKU-ivGJ2vu&7{KJoZXlLGY(|Q>BbwyeV)BJ-sjq^jnIpHI+KokgH(+P*NRV z-8KHH7(EbS18}})D4bt*#%OyJYEE@ETU&(SIG1@b911}ra zndvQ!LQhOjl0~ z<9H7Xm*ZfMjxA2&?3s4~J=12}qO@B3!2Q*BqJCbFu_%yMRpO+YO`2S8Z~3JgiufZ& z5yFVyz0Y-`KtW}_1xzY41amdr3M29BGH=IA+$Jf#MaM21l}M~6vFhCgX~%Lcg6yhW zO4ra>M5#}FbQ4k%3`g`9tO?KKCP}tw5k&>0K{PM?L{<7CdZ>qaIP=DJI}MLc>Om@~ ztn)oo&GOUw@{nNd=eY$LR9N+ zBuE&@!3NyY*!N^le;?f@Ke1wP7!PHNg`g)BW#^-zgq9%u=Pipjfe~Ml9Gz_7d*&sD(%GkU;96=H)<5%2$!4Z ztBn_Cj1ua81rm9hAM`QOI?bxniW0|$ZNGH!j@p6C`g#j(aJQ6(!4T)0c#;JAjew}z zL_qmt%^RsA0?b;d#u`o5E4$Qy76sdw9-u329b84=gc_=k396cv=c3f( zZN}Djf?Ru51Sf>GrkZzNXxSrh07u-=k@_FWhS5l6(Zfsz9&(0$k5*O1Wefeth4V8K zSmo1%1?g6%O0D*V4seOiSGp)nJ@DVzI{kU5vrzWd$)|j7D zBxa#)ocyT4-C->kw)D!>5~1gr9dk&i&C2m3qC)(@?87G^`+GCp;mcw}%94CQC}TiQ zv@V~_YA+p7_|X<{;h*?YeY3Qi4$rxo1JU40l9<7?GLkNnEB=NO`U}k*@YH?Ec_oEp zL7htUmjuT;HLHs!i7%Lf3Co2q(Em`$Fb|wMdC>Rc zMOMq15EQn0a)3^F*@ay7#hv5URNq!IQF~Ywp*(WONF2<_dof0@n9hq=^WQBIdQTm+ zqPJP0tfMeA86Z&bt$5d`#>sSAsEvawLbfR67ZZ3V@|IrGf)WeI#y0e;1O>84=mi;p zDf)kpi&0kLBRBaQs_5^Q)M7h*uVYnU{*4~zBVqx$bEfj!QX@YxZ+IjCJrkvXf>Yo1V%#hi^X{-0ZR?C%l0?zDraW0o& zLE1-lr)IiE=4MId0@Az4w%)wwDe~_v6r;o<$IpV^ZFnxN&N1cg&XWU%H2vuy#zaRL z^wJ(ldTf?jUPn|CWFRbL#1Z%Q-F-M&R-%X|q>9>T!}alfc`-`3q~vgMzK*`~G+?a* z&tE;VWz==(iL16O_nTG9yJ2*j#9v%)!i|LuDJlqo0Od!G!IQQovR?UCFNM#5rZ2;>`t9f&x4*v1i z?FKfFEBLjY^tmDcZYtdNva6BqW;V&E{LggTIPu=B_r*?YmZPs4s-BLT=8N z(pUyzgo)rk`LAZ8k5|2050q#tG4!h($N+%kiWW@Ew9%I34fI?As%4{l8i0fW;U#fj zl!`K?{PuiiaT(%#Ul~Pn-O7%kyP?l%brEOIb`N%4xfHyW6Y-}k=V6mkZFD^TqdwdV z=9W*J11VFmV?%{f2DdYY3(shS5ua&r4b5fd?zd$MqMlw0fq_fJ2d%LmFkLwh6(Zq4 zO=@6r4Su1ri55t5(P$2Wo>6Q*;!%b4GZ8qFf`?O-y9K{lQj*| zvhH~MGq~~L6r-!409yJ%*=TyVdv)G0j%U3?6gtrO> zoAdS2IohA2Znl;^FoS8SAR@p-&I=%~Mv`QPWLVtvU{lM?;-V1TB{+U~LG1qWespN) zy~X-EuIXYPR2i2hu~&62K}(d0C2OR~86wg)7=^j=><&U%Js;;O_|7nxS#i3_6LfbHsEdY(O2I zop9LN<5b$Qc4MSSVIIrx)s?a_JocrWE!|rxww@W4i2C6vAQAE?O<5*lbVo(=g|kNE z;8gubVfz&uB5@Ah=Q=XN#>2huNQNM%XRQTQ#SVSYR* zh$i=z(9{{2H_W^O*E7cA)%|em6;gCbe>B~%ER|-D{n1eLXM#`bu%B$#YR@iQ_57mJ zSHUt{`zS%3hmh9oOzR}&#Gs~ToLuR=6y7koSnRK6CAfz7kAX1{Z9CZ+%-nnsLWfYE)&%08zy?{9q@1yJr-UXKM#dzxftIZ_Mj z9~mG?9L%l>jt8zUVgpp$z{2mPZnw*W(W9l&FsvDt|!J?*K+_ z<$R;g4~G}(#SNuN;CLa4DR9!(nfhK|f-usw=73y_M+2(_>sR~am-?67;U?=YWd=%W zk5~%?0wt{J-X!cOMdmFUWXc5Qd?|~VtxFZ>l^}J`6*rw}2lKzRsZbbtrQ43cM6d-G z7uFc&BTHaFmu}6mmMQcrMqC7zS9IvXIUUjjCu91|Vpud%XW_nMCkX{*;y*qn%KK3FD4 z0|@tV`=FNBT}qEp3iv5#7p~216;8|e6=aGp?W|wi=out=#@ZFt76CJKXTBHYnqwp~ zGVk-TR@A1V{IWFPEbR!;Q`p|1V6vUl9YNt6^GW)g%Vzw`cmL)4De{S=4QpHCk=Wh^ z7R4qkIJbZN*qs4{O`B6fcQicjXHwx{T#BzoCKGE+GL#)V3#wg^Rs2Bx{*_~N^LH63 z{%RC1i8%2cm2pc<7WX;?b1?IjOW&%gR)6}7`Jb%h-z`^_$yw7Y+x{Bjwy zij!$gxL70eA9cy+^96+F9%4s)#TR#Q6mT)(G?##pwglO{L>c)jMF!R;Xv?-WBw1g` zt?C%i zPUTj;*3UA~QvJo)+EwJ9YZJUI!|Q#0d1D<(XN~s;^@Y{>X;2)#*{p}s);P1oL8r;Ue@XblzQ~p) zJzw0XUJk0f#>}T_I|V%Xo4_=$jhOt&*2hvb66^x&+)LfG5tnP-*!o7<9M2TIXbzmt z$95T1;pS*%M-sDCIgEJKj;?^T>D`9 z$d!3AOrln2$;Ph7D8p`a`xGq_zF^PTpb;jwDPZ6;8c zr>zCWv@lIg2dA54Vq<~$jr&0I74!{J{6@^UnsMR5$Bhal8IkbFeXH5Q%4_6L@zT)- z&OOpU-Kro9a9tDa1$~n`NeU30Wn`a=L_4$brh70 zyOAAS!S&I>$L54z@;!mc?~y0JwR|4Br}(-cSKGA*LSya!PqtAhSQe?dxAPiA+jUJT zEt^Nn?D~K*;K*;iVxG{hj^h6J=-&=^mw4ixjTU!SojqVmWI_F^dS^8QK{-(-6F#)7bZge|xBAr9{rbW+1&P5yVz;?Pu#t;3| zk1!MKZ8kd)Xxj2#9n;fD)Ccat7*P6@a?_3{?&;{m&;CqKPQ`|^Ww0X z+sqHNfXFOAgO+nPrU8k58QounqFL_uWhlrSkW^7$cdfzEg5bj?(tG5CAcvxkbgg)&htvgKi;d(>j3q1y= z;~Y%uddfdnj9i9<-jMO!F4uV=nG1q@w0F+)9>k4dhuR@6?F(3qx3XAQ68^+O(qM~Q z!PSZMSy&=QzEB;tGHpbgsL|>zI+_#ax1NUrbN=gTU->Fr9aLHqy|UjkjJv>CcatP9 z3#zL!(}oR7-q{Z5lWRH(cx}jnpcGoJ>!skj;9^j-+~Q2IJ)j#UM(^+;}5>- zCvk-G3U8_=yiLVEf1>f*Xog*(F%|cdXV@0m#X8Dh+tJQTL$!2!@gVS3n8nH#X9C7key74$L zibdCZX{u09Zdv6h4Mh8*bNfk1=Y#{M$6IdDEk)CfTI4aLKCWUTe?A6EOZVCp7H7<* ze!-)a>UNn1|Grer6WY!ZKTCS;eol=unj$1?y9&&p&t^aserIxo5=ah~fT{a(~MZeVG1*WNx$Kw z3Vz2vYig?i{h6;J^>K6!>;2Exn1fE$Fp!{SF{=6NLe)l%K`Vr~4Z_U-)o5F^(^vU0 z*`U+bV9)fa^0!RUYNa;m5NF?q3j<`tt(_)2f|#sxoDu6M6uj?~8k5(BOpZ0wrKj$L zIft86Pm*#`b7Y#TkLknNG#IGfS!a4!nu>DohgQR^d>hLeq*W=m)4VAkkiSsY{HKBXB1^&oic4Ad6cqYgViD)J97m(v*_b>X}Vk1Q~@@f3=i zn4bGbj+@tVz5o5AZKR!^c)D+ir3{zn%5KCclt+Z8`;MSCzoF;GApnDw4>AO%T&Q9JN5xrgO1GuhPM^}RByN>V5g4A*4s z(iCi6U*#S;72xxN90tM8(4rGB2+%BHPdJ>fx?B*?fbmf%oicRAt@5}Z3M(|Vi~uQ*SZqm zh@7@c@JHz9fu0U>LrQ96>Ok7d0XhEI9FWMdm{z5WE`JOYO_mi^i0?61OiPyIn*-5` zm*?i=h)D6hEToydqNIKTA+V#CNg44dDW-EmbWG%;C(Nf?jyZG$9{vDF>{PhrP#AMK zxb%hqoq;N9Dsw|l6;U?9EWUCj&gaVBLO-!?1ycar?x7(zJQ?Yj9uuObJj~UP=>~Dm z{=#{}`yc`jmnx5K6r}=J6_I#j_b!#)MOMCXfkV@QsEI!^o%r+H@-k%$Fi{lu&M->pj#Gd%bkD++uUIA%O&8B6 z!+@|;b~#XAoxs_T^>ibJ8|XgQ*2Ea6ls&L5C+D^G1o0t@q^V~=%p}%YB|d6Nx-ny~ z-T>q#MhDo}g6$}vJ3Yyohm@u31_K`h%6rj_PAh@`FiTI7g4%EOW4*v%YiMa}e;D=z z(mE~|5=b^NiH8YJ)Oz!=Si0#H4Pb767iM;#jn*=bzyUz41i5_IO!aD2WZIla={Z@&rj|Pxe=+Ew4N#tcdWh2I!Qp1D z6O5giwI|da90tISS*UF4oLZCTdCg!_VNBPn-_H21?`~aStt)O39w--|aY)(zouKL4 zariWak4q}+sqMJxJ3ac7JivIv9J&hs5lD463|rnzwi zNF*I-udpX7=6MHH&fEm((yBESA1Q;Y*P3yMGuy98RT|GOgqlW$O~kk3myo1%XB4=# z#V+xJ<74>M(b6WtR$0vLx*Q%ZDO+lWrSXZba5e24dISQ0Gsyn~=!xn30;pa~LrHhP zeC;661vmgPt#Ns1jCa`#A7e>&9&aJ2Z%JN zvP})!Yqwg?;6HQ2fd&?4%14{~&L~x6(kskfsm1g0 za>@z=;vzsXGXbY22hxN!Rrr$taA~s7kQrIZh>E4bv(MoM`;D<{#y**vb7yF8{CfRoZi`oNrUhhOhSXA6VSYKggOJ8%(XX-jl7q|^7 z)j?U+^#l*!>9^t6qs%typ^_d;vySVoM7aN@WsPw@P3Q;^{>kHkZE4RVdH^lEnvO{x z=qpU%zPMBJCa?1?QmF8w1M#MV`L=IZ@v31vX9>r!&{xX2XGEZ$l{&e+6-x1;rompm zL@dMueS_b^R+;=yQ%^u1GDOtR2I|fIgHwxkF(C83-SQ%E`I@avRqfs-vJK8qE28iRG&nC*JmV#cs-z*2ohKV93vEf)+lZpWpAnqGop#AnI#wP?#z=$e)=Ejcq{@ zi9ZWZuSU-h!(!%{=5y*WIsn=L000Bn@pnD8XKEjfiAnSs)ETKg8Scie(IHuRt-P*+ zmR#qbO_dOfVF{;(=Tysyk?ih?VSf*&X+pB_Z5LI`mBZ-<4RR64fmdCYoJZG;uQg8I zCQx)N28+A!BbEsB;t$Yl!NKkOmf$><292v%O)Omzh(q*!^jx|SLDG@qHBicFRDl81 z16f89rC>JIc&pM560DXMX)ta?Ps!_J4ka7h4M7JVHHuN>nGrMdr-w+~jyG#+XpZWN z@ttj0Z6&9EjrzGB3Di>%V1cv#XXPxWnPTmwLNvnLnmh64{FnCvKC2=mI6|f zALZg1VQ1w zw3BnKpI-^PT)ZA~Z`hc~gVWyK(3KM5Lb|W7bJcmQC>9AV-`<1}?2WSX zx!|M!9P9+Z;(W!hyFlqlU%z?%GZIguBWTe3wr>7f4zC;ZK-xw40xfztk}=tQlj$B# z^TKh~%GHgcc)6W74iEmMZb3xgx_UazCaUH$h>2bEu?ZZCC2i`)h@k~Z_9AVsgq;iW zvcP<6XvA25JK#!_y{42KXJg|%T2qAl`;N@HrM3;yIqEx`?Fw$}w2IbShclkOsc_l431`+bl8TemdDh+tsgTuq>~shZE;}$h!JwOy)8}%IK-` z+LA)G4zS?OZ;BZA%-l18jxV`s+&dPwjiclmgxd@o8v;`5a;;uw6{+V6nAS@mF_tuv zfFp_@(w(j&i|R;LqQ3q!fRA*pYgpH#BWL}*inMR6Y5)ibCg&7eIrpCZwfgaJO@ER* zmcjHN(#zLch*4K>OtAE6mxRY ztqSur&6HtEd8ySkMQoo^Z?00bSp`NHfWDo-SJffm^cF45-@AhoDD(c}-aK_ykAl#U z{x+;;|3)3>PwtfBd}GX5yMKseg2K`To{UsMWp(cpn7wOxIj>7dhhchQ*peyD4YJ$!I|!@0NOEaoLJZV`vaZUwB*ovwFq=&L_3}>DAaOuY$Z=n*qjX|MfOFL7)!eW{kAT@@ z6ZSY11Fn5FM#g;#xBiWX?;5_(bGOc(F?EB{x+B1FKia?Z**>mfXscWA%dKvMVTxm0 zzF=5z5RFbsv0Uf7zB;Rb>tzm~X&J)^y_e2zFv#(kp#QHvDOu3e%#kerEkH0*xjA?s z3@!uzB-Z!-s09#h18`&4W*<>!h&{_c&gQ4vD?*lI%XJCRb^iuX(>f==_8KilSJv#b5T`4=~}`hVgf~(;TF|Zxa@>d z1R_~e+mE~hcv{dnj53GfvHkgYS)p9eA>Ir%MPgQ3eS9mgnikMQ*pV0sbV+n^YU?rM z&(m(ggGY}=N3^v3{(Gvg?u30Lf^v$%{@oqUZwBjHOAvHu z7z%uuDM1{!3e&HaqnSN;4ac8sY}5QWDhJgs!S4gc4aa~#&Pklk3Z3~-x7#vqxnQ^sl1|8 zf15`aPL?fX?c~uQT}61)pUJXKv96T`(V(m(A6Y-Omx0yqh58QFLvyA4)I$Jux4c6R z{K18Qz39^)9wmEEAyC(3G~4qxZTA@2cn~ngZ6z>+m?V2=pnN3o%I!PP_X^%e`knvc zF9OCBPI#XP4;LJA-4$IpHpz9}P>n4FvBcYu*`<+og=r*>EvqfwZi?p;zJ#z;bA8P} z;*z)D&9_6%U6+t8fPYr?3fVa4GSBk|P!YeDhdletXI{YzDcUahSbbQq)c9AcFWsfP zsEAkZ`XfGj>d|fnYpR43v!8f!L*E z5VW7s`}-PHyKb1_oQz%$7gtN6M$6Twejx7Ghsj(?WP*yv%mK+xDyIX;=LX!+9%6hH z;waECP-;s1_y-hbe{6W3{&0dnzRn{$JF^oQpEe2srK?2Da%a4LHJfsz$WgumsW+c- zA!_#P8XT7^vx7F77%@y$oFEwpw)|hcu%<_B1I7MZ7(YOCjm~g+jCv}qA)ni8Y31wB zx;kBX_rFQXwPU@YK22|bwbp48k}ZbF9E+W0+(=*Sy8+XkhNBH@hN6TnzmMYfn!*Xh zVmg~%;YrS=Dt>3y=bui4R>jmhCgl}^-_UK67ud4282CD_T}{IW!DlN#%00Es{-wML z7!87uR9f6vcWLUQ-I8f9%jacQ`3*Xr-EWXdeBZMgOwDAdmB9y7_^zgC3$QkK7c)Pr zxpXKbxy1@wxa|LV#;$uoDlHzvXJ}cwzezg+KIo+}rvAgO?!eHZE(ZmaLxb(sa&|l0 zN$%JQfGU&K9gv9oJqv22c6`{p4l%^raEF=)iC3cDbSvD-cw)BX1raD0gUa{g!Wi0txTkbNhNZI0>;N9zyA6oR!kz5OT)#>z@Js;yNhh^{6ZS+ohYx zfeCJZ0jg62s^}fpNiMsJ1J_R0bYOS)xD)!D;&0T4%QpM8u1r`GZ9Q;4NT=wNP>N4G zfUm)jYXB8RGYuBAN4u*RZWl(;vvJ#+^R>a)JNyT9zw4d!Cj-S_#pnI z)ERA%MI4{4!t8x220TU>2px*%Kl%bNhaKFo$_wI~*?#HUuNCFC0!Gyn-4yi#0joKw zYE^;WHQNRg<-n$fr~6TucZ)LEnHckVLm;yEhcYDudPIEU6X<+qy`+>JudJm2c7Xm60VIti`g;G_g0nU{Xwt`%DIvsEx?!i zHIze<^x-P5{C^hwA>aR9Niv7ZuSsaSA94vA_+X5ay3!{}L*l<@a)a6rD2{{N7*s!+ zhCxP{|6UEXCv&ByxCB+a()#ul&B(5!z(tKYUWlp046YHAp6K)pdBN$O>xT@2H89V; zfDgKMo&c{Qj7vE?p0=(ZS}3N+a6n}1|K+;q){ZiqtUDYqfi$4xA_Mef1CQu71?V9Ukr+f(41J{T!4dc+K#2gjOvF0OzNodZrfC#Dmr zWN=&5V~KJL!6dL9%B>p(Km<$8M#Xra>5PY=G@##h3=Ilk&_Oe@yo;$t)#<_C3Ft_} z+J!Wip_-%G`XnBOJB!s_cXW5oti92&#{7qcKWAnK0p|;wWQp-7=mA6VW*8p6yYmkb z7nda8<*fMDE9xP{?`0cytDjQVlDU6o-3N_>L9}8B!sh;} zo4ywZL;^m4sbt#x)n5nQ)V|F#X{RdmvFP?+dCKFe&*9Z(?+(4o4w+3g8ZvH&`1GhR z|H&B%^6WVU$)G&#WsA3kA6VNLy$MLaI9+b-2RK6jM7bR5SOJrgv|5z!!51UJI8DPU ziXo@XQ-=L)6dw&;7M+wsd6OnO3s)%&f!nu!wB9F7Ba;j18Fc)rc_Eub5!gwTD#1WL3*RGOnxYO%if zV+#}lDwp!Vio%!O-rGwfPk;Z`%1^$zWRYRAS9i1tBonk@j0mtT@q1~s+$mk?mW%f{ z@!1|}Qow%}0{MY(s#Ly6-H&qLZD9jxZ81KXRB=JY=z8U@AiCDDi!|2`JKqnyKp9b+S1~L>I1m$GBj1%c z&9bOfLHUg?BF4-I7)DEkWJ;iaJVFQVFE!TRD0o)pPF|)Hrp+11(qM$_-lZTyH{yJZ zl||&&u;lT0*hjpw#fyX6y<)`$<-MR2Lk@t@kkp2oKji3lft-D0W#?M`xLvZ{KaLccuhOxyEe7V4K|JsT_CgD(D zWBTI2n7E-Q`4%IBW?scxJ*>0>%j|#)1D7Hk8~)612R~$3b9%cz49Oegfw?p$WW44tRXWGIrI^C+FEp zAM}Rlb@FmYy}HVjP?8o z!N@45*u{f_y=+gR7Cgdrna~!6t39N`(n>IwIJtb`zKl?VjZtbiLqF3`9aE$0`4CVr zkT`8FqmuDY-gv(8F79iI+H!9OQRa+f*F-t8`jL{x7g)31`bz6P4J zoDgQ8T{KWKZZ!%B30`rVecieOgFMw&7eDPlCkDeg?w-4}HH{~X9)s7MfME|(TyuQz z6%43=mq>sOp#w^FxDHqMMAqs_gU|t-55DnKNP~B#Zz1NJc4i4=7EKGPwRZJGLVLbW{&4C(n%lyZh(4 zeE~8UmNkwA!4ZQVRRf7hJmde}8&fo)yk^^a{Td%2Vz~`6-TK zj6)DQ#!;^NG*^Aud;{YO20jlV1T{T+eW`Vjadhx(As3g(QHXv95-0VIKMw+Hw|?Zu z>*tP*Q~qEbubzg45rd2Pk?m43%4mWMU+tx#wJ8@hnui0L2{Gc0P~Dx?BWmk7&n+VR z{Ff){upOn}97}c*vrVh8UX@kScA@1V2%eDror<>s8g%3Af=<#Nnne#A}J*sL< zyH`Rj&S0A#awwSJ2~Ld7KdEDlWI9&@ll3McR1j-`nug2Md)(;C{5FLApGOdNiudrO z3F3!Fdo_UX^v~h|yMF}yOiPiuo7Z7S?K0b*VJ2CVHG(}N-rjg}m>-E85HmhKhAEFJ z&H|F2G8G)p6%I=m<_28%F5okp58>LBYl!z<`~Z~olpacpNr)VSoT}lflo1b|_;@@p z-TrsPLB9Go{MTTh)orN7I-Mv~fzj7zGNupl+C&DaD<&S?Mm^h!Xs1xMNRlLFGyMQd zK(xQNRaNBJOBpk$Un_mL?kTz>{>Dh@p0>Cn{#lB&V2Z-8w+BVnc=3LoTAu=Uhz+4Qqb zBid&M5LI08LHQ&tyfi{+ad-|AHYN5nK>nKy0!>)sxFL9`Zi;O_XDI*>2Ib~c+u(Hl zKzOI5=(W~H^uZ@l0(Tt#LwTSV0591w*6yR_C+jEbu7ju3aa! zF<*b=Y@oP$I5S?_N!ur-R5{;RO^7;7O|)nds~%tkPBr|HMG>=Su-TqvlUdnM)|fGW4Z4~G zzmrJT`Y@wj$Yrx|Nv6*?h71?5gT*_8PH&sz%pu{M$TdJo@S^Z)cyKX0a|&4&ox0-J zLJ4PSvI%BjCzE1W8tzhcO4hldIV&_L9smj4KJanh*U+{jl}lIiQ)M|(9^w1AV2U@H=~6zo9OoX`@XLv6m*Tdzsi!9!7e82kmIF=;F64go@w&9lv~& z81QOlLHTM1MM$!%k~7s>M<$r7#`Ujj8)bt`UrJ}V&5Y(%05Og@Zh#naV%8-61~pl( zw4~$DO|b&f(_3;MUEm51Mqd}B21?o3>?h)^TOlndF!YWp0Wk~J!Q*NrpU6YEcAAE{cD?bE4UrcuD$DTycu4RvFK01-7@7&qNPJ-$dy80-!;ngpXBC!SFk%3c@< z-u_@TbiI*5K7K{5L*q;39Bu-(hW0|jPIgf8?sbH1Ek&NLl67$KGIpI5f0** zERBkX@MKoLMpxR+MXxX(;EQ-beqrH+OnoQp zA>>h&JE&%-m3<7sJ!R6>zaX}J#2Wg5CLgTn+fH#weNmh*e{PkdbmD$K#KuIf<0)#>3sN=4pObV0*|K`sv_+1dz7T|%gYc^E#t@8H=fPK)MP1n=*I1Lup1$h7)jb`DkWd#=aO8pp3Q9e=Nc?&9)UU+z=4Q@t zZTyd;{}^VEIC<`9W@#TO}up=DNi=q(~lY}r!<53Hxb{oI&IhbpROhLwl9i2 zR%A9W4UI{0wA1~*uZti$OI%{>xX7C)88>-!7N)2v?_!yS+eSeDlZwfrmgEK=Ra!2y zU9!M4%uv0}Eygk&&s`p$*W$ag#N;QFuGI;;@Z&K{Py z3pjoqbDBa#r$W4afHkIF(3aeDxU!F=cih6Pt+^6>2U}Kj{{TE6KwQw~F@%sb`pe;{ z+8nOiW=0BKZpVp(Kd8%oW(~LP{yYAnM9pbl3Ekvg@D9~!K2xBENYE0nUtPpynczUF z@RLCr^dFTTvil$3PLvsD?8x5So`vW`;$J#N+l<}UoNdk`Y&lF!ZP)8pKKxgK7R!&H zV^(7(6Y_l%tl$gj<*+JW>;M?R)4$0~C7G+F{NhAlQJn5r2OmM=>Si0oxN%M1MU4 zH;(pY<8yeEz1IcLPMR$$k?}y%1g{w~0m4cSF3TN-z8r;#E%19YKEfUzR zd3Rv4+@73BZ(R`H{*{~->v2J|$tpUP%7jG;xGKF)%!tTv9&E>vw<5w^dOZL7u( zcJ70KhxG`<$C+=an|;<54VAJ7xwiJBa3%~xU4V@=+#aShcaRiAKdXJ}eD zrK03L;v2G06@Kv^5LB?YyFW1~UL{qM`A{ERYk|T9qy`;BxPl|vSHXU@y)y>49{uBY=asoJ4SCpfB1Uhwb zkFb-IEC1-^kjYPLk>9e&ZQx0j``h7mCvs9g1biKGq8PvDfv`#^T6Y^>Y-Et!RUTH3sDTXggL{o^}`Z|4jmsw?2 zqq7XkM}+5a{uuc^0+2Weq>-fuEyyF{Fm^K!>59t2M_-|5C#Y9ZMTPbB1{wnh9{QND zTp%}KjIWyPraBt$V%_$vZhIcuu|Qfmv;%_%FKmdaagr7zU&)+E7iu!z{o2;^2skn0 zn8EW5hGWoCLeyrQlTeM{Rw$WbwOPBmBQSJ7Qq~yqll9khJ6P-3B<)1KBoPy2r^Zd- zni%`0Tn4@xN2NuYUVOqjP_t+M^8k@?d{&a*gmF{2j6Gv2BiZYvB>%h+vOT`<=F6(K ze^E9q&mdzQQjttn`Y zNw5(4MtiPs8a@!t>Y^c}4cn1|c#8{GJpiqSaxjWTE|{af6m$t217(2Z(0O1p#ni4F{Tt@bBqF<_h9z^I7z>ieL!amvE}Q7k6q{bKA}>Y3 z)Z==fUlnM~@-svt$meRDU$8td=&X-fRsswYhQPFmh$IcXuq5VtrCz~hB%Hc73vJ1j zK_affKpV~cjbzhy|BvOUBZ6^f2k^D35lhrulAdNDt!d4!*Do99OmdQfn9}k~sgUpD zR5-7BfQ;$CF0NwkXFtU`NeM<<Nhp~W%9kF}lO_vZ|pj`?P$PhMMfQkRJZ*0Ynt+-HYw0ylauf>}5UOh2PEHW%LA4P~%?DisNQ+@kBVdBiXSu|=MteCwQCvhGw#D#lRh z_1S*_v-h3W--IJu$kV;1&XYb$3OCa7>KxFdd9L*O;W05i;Kj{?aB%D%3I>Rj=zM3Q zFmhd!mexX2j zh$8$uGzb{=%C!9Q^qtY4AuJI5OWsxXTGb^&i|58V-0;b8I^r~!5EUvkts~>&T5+^{ z1?6!dm)x?rsNP@2WwL`}INp>x{a$i2g?VpHdLKeF;0n-$0^UNw|M(z1K7sX&d)(l# ziB=}jHY7VE2BuX(;$bzb+CV`_G7iHZr-r|ehw6`~U71&GEkN9+l?;FO8N}RbEEcR)wPKKSJ{cSAVb_AuBS5jeTaFWT zQ72u7rn17P)v{)tF-Ri8EDA$aXHP|v|5WntylIpo-DE{zzmTBr#kLxSC0Zwhs2UDo zF>_sIU1tV6Ih{hEkH@yXJi#rij5sct$VdTp>xZ~LI9*4OV-50hK9YYt{~4t$2$%KA zChOZj?c~GSu2UqJLBMm316%PgQ?^Obw|^batAU`|R8X0md4vnzRGp@Ktvk#YI_hH3 zqT_G2107!Om{_n>Mx)dt2M;hv|E565$*MOykqYK$PLm;^00ErK&@_2qTVHpvFGI@u zt90v78{GHQhzo7EG-Yiv>V#Cf+G#-+fKoDWr^qg0Qv-gThzKOP()4yxR6LD`HbglV z$2Rw;W1T65(2;013I$QG;s}u?C`(^cXT?_9Ld*X*%=QI}P-T_J^3B=3C}on@E7PV- z9I-TO6`H7u7V{{Q19w1tKvHy?iL15jmt~07ge|}K0+|xC?NLpg@`I8uj#*UQcLnxs zgrQOFL(gq1to1aFR1I=&BzLemRr);ioFDVY=X&{FSo<4RC~4?4^?|FELI<@}8gj@p zqQ+TeqO;udigD(?(oH>|zK?YF)N0WUXlgD7O= zX>B2qg108xSQ%em0JD=adK*@>UDAWFh-s)sWi3( zptxNu!z6Sf&efE*J^DYF7e2VW&aojYVPS_szEbeIiq$-CK+6sv4tr%M0r+B*qyi+7 zo4QYcEyP-gL?~B{=EC6zdP_8npPT=lw1$WL?2#` zc6E~(1wB`iF-v2?iX(x_Wp!+N@y&hpcQt9Ga1QnBnDTLZe2KV+Wjz#UW1N%$Tz*$? zWll@>w#L+`no2qhgS*K1ut&UGutTz328Hz%8=iWW(T?^j`0vA5JlqS{pZp9+&5=>f zd`oniYx4xG(2g$U;HVOviSMiw9Cc_kPR9u6-7-K(F33`|7zkr#HMJThcJFBGKWdPU z{%LCuW=$r{LGqpd@`%PF36}9-d6%JkK&%&8Rh7ftz%WcV zlW^J=@ehT`zKd1V+z0d%iH@k;EBj00LG^^rQfa?RnoZC97$2$iaQ>kOpp3EVv*T@; zJbd^*l`W3`5Z(sIA~kPB!?zGjflv)>96ShZVF`n28!5k`P;g5+ST*N8cy|e1 zTw--Ukjqa}jyw0$RgJhx!K?zC!K?V@)DSDsi3Ddsc@!wnCh|pa9_4gUNp1k<=iL>L8i1u>t5D)8_yCKr3fqX9Cl=91YasWp0P_Gr}27l}4;y3cyT zbH$`eKuc|GhuWN+Pv$VDtfJgAmqi@-oAy*vXK;j|O<9Rr041#8U9)`e#DE`2i*y_>Yt3lnK>^-C(0AuLjOL}- zb^tI3uxW%V9u_uR94N??z9x{f6 zvZ?PN&!n2u{L zy;CFU+m~8^_xatpN^t4*HnxM_R6YTt6dFvIyQ5Numy@qrMSSwH@-~{UJbCCznhzTW z*z*c*(HUW>GpQ3;*f;Ak=$$(c&4)(eJdD zGn1<`znmJMSoA74MNOJ`WM8d>WUH9%8fFE>stHTJ;V>1N;X*;XG&iN zE$-5a!X%5@!Eh&9qH~bZ<9d?hIYSG12vqT8mJefNLrO`67N<8QQ{gmC?P}@&7iAN> z3n8ZR28G;;U#1(+g#VHD$OvFhwSR3=rYzA@pVZL@Ov?7`Tt8eLWI2NPuN$2-V(5l* znI#Qx#(KjZf7Y|iCRCv+3-Kjb%QW5hCEqIrCVg&qy-3GbL_!1fCiA3XSW-MJfz@%X zT`Q3SyJxI)_Czbm9fxRLJsTLEMO49$U5Bz`FPP$Uo(@)9z!daChE{TNl zd=%+uy$l2sZfp&F5FBNM?$Dtv46IThqGKP(PGQ-C{E2*hc83gxTw~hG^=A#G&{$=# zDk+u$hvg`%aR2IVpwimOSJq0dwsTj`;pbShb)k@sEaHL$dlnVY2AJ=&%ie*Ci{79)iWEXbigqvr=0-A`mqUZq^8F*7#F0-it^GF%AeLITPBETmOh*np_~`r1k}t}IxHqXV9lzr z5+=_f$~U{YrApSJ-$apy@GENZas!-dm4dO|Pk`P}H*>~1%Q=IXrqBsYYoz- z-X&4k4fo|}%|07^{vK*fxqw*B?`gm+lf68=yFGo^IvRc{>eVAy!-}3!n9l=h2PV1S z=pseeCauvFnRY(?8Y<>AaFa>@4tHv*v~v#rr0mHL0QY3foo}_J*B&6e2#evV0fV)^ zLGwH?7a6D0hnYeYWATYm+ifZc7chs%t}y=iRe-<~kP0%CpwzPcPG`z$9Lh+bWF+uT z&ET?{;0v1q1``XM6Y@p+i6~STf`!59UL2y%hgryXtGLfifTF!wP^P4JZ;hB+V~?== z->+8?h7>ZT)B~rx_zV#r88CIiA7AI@=nYMeb;FA=ve^;l6+}SXN4c+zZ!sN+Uep5` z%v5CN6w+b51#B^J0-H-fa7ADJ9EbS0Ruw>C2ue#n$(y|*fVZf^iMpybc4-lD6ulGF z-Q7(!`l9FX)|sCxwj?~-yPLEg_AVALCk|Gmq^Y5Yt7{!`r(D^AX^%9h zE4v=nL|(T(PvRyJiUcuir8ExRM&4k@nh~2$2pAwYjUVMrQ-UKC4`y`nL~c?oFzRP_ z6;$p~YNDj3s-6;QaB9a;+sMQ-*Eg*-K3#w6C=7uPjkOusiil5@%je=$6o$9*sh!)gPH3rU# z3HDTJK&V7clNM*59jESGO%o*y!)LK+PM165LmBamHL+by%gq^A=CIHUN@-J$hvYwm z6m4MjusV(FD1_nl!1LPv5aS=58Cvo;{HNoaN&?UqI>cpPM@5}~s+;?NXV39rQ-Nw+ z7Mi5s0)VbpuegN7OH(z5>DljrlwjR!-}~${Jh@Fdu1qjB_q4ZWLe7f`CU@CzJz-Gn z=#*L=#f?Ci<3m4d1tcgTfEfss1oDb`Kq|LzYrh68_PO*DYgVh4{_sF4HDd23? zrcS?+J&v@qt&-n`eLC}O3p^tySAPVeQJj2T>U|Xf4oH3VwAO6|-4FXFIp2;1xk26! z+}Vv9jl}uvq-U0m2gPL{ME_3K=01G|6PCEhBGg^00I@;NbsswM$a0W`-62ZYDcSWQ zrvSocEYMxt@M?*PZwF6pH`o+_lClgw0L>d zsbEvK7?ge_q=Q46cIr67g?z%oCNbL@Olnhe5Gh=i7*!7s^Yo)r%4g6JCJ9bUfXEhX zd{Om~h=41bb)oynEcio(ynq$=Y^Zhl=xV`uVY)SpCR-51O4~4&8=tzuytV7a^k31L zzM2^vubuf?t;|NDXH)0hAkd5qNwg(*}f1Fx6NBR2D=~3RP zA06k0M}P#j(b*uGK~{RB=4>%t;ks)Vu_UUzI@E!hr-p!Evo=ozRmHr>Uk0gUoy>dt zRw`S&(W(yI_A}*Z*+EmH^Q_Y#AEVuI2L4p^h;q7lh$dgh^9%(AOI@m1hD?vPv{JU# ze{9N0cpRR%dFmFcDSjErCX5(FB=zJxz;Z1~)?YhD=?JmV5SVD|AgZ&&PO9zsV3{lT(gmHb$KQ*pH9&z8U`ah3HxyIQ(<6qSV!T2OwDmo zrtlKj~8>7r;}}9n-eft?E|_QjK_Er3s@b0vQ z>V1ot931NZFu9;dRkeyEmRc|p&~iH!zTPwK1`Y00+I9sp zxa{|wxB+h~%$%NfqpGhu6}XV%&mP>Zmff`4+8#fg7YDafrk#@a}pq;Xp`qseyS13oJ>4w z(T^B+WrLC%*YW($gyjQ{Ezf-O_l8cp1~bC@5^ceZLSmBFbQMDQ_8Lq#=@HS>51t?6 z!0&dLhS*)ZZ@2kblgxHz{kfW9@-pklJ9Vi|e7T;}3hN|+fC4}e7GRZ2C;4++BOSkS zrg!dRz%Ecg@sX~$wpzV=3J!CD#7;`iKWCl*!A-73^21=_1qY&a!QXZKg8kCHC+V4^ zi;1S_V4ad#*h&y2oIIHQ`3wNvsB_3qw%OEyC21nZOAmV)HQWGt(bw>RTCBw{1`DbW z|E1-EN|YkyXrWkY`P&+{cX#zPChqX}I~@SiT&^lIfZhJMAF;y8`jYy*Q|XqfcBc}b zsAh270S(P-I6BbMgiJtP$T!fe;;ZG9fZAzx(Yp5G;rokubZJ%G*fM8l0?g7a1z^S=MyE(+kEgoX30*&@ldr!!HLfl0Pk<`&agHUI4$EmC6&ze zHYigRArZeNll>aCjnf;k{VF@Z7mDRlGM|Ue84?tR+b}DqNd^t;+{mu8m?7N@iHhwM zixBDphg($OLi~6Dd?q$NlP6}H)t{YX{x%`gF1=rm>rP^=a#sUkW=q-ayf3{%Vq_d@ z!d=IFB}KVSNQmC<_YEhiKdv@oNeg!;2f&+T2n8uD^8elv_~X+CLFkz)kmVm_nEq;g zowNjs!mepAsNlDjQ4>H-012gZjmFmJJy1ocNFxY^kdli>H9iclSfc#su&bA~$!^2) z!h%ytKP-vduxZscS2R6)Kly^Ng+!6|D4tj>l=L%gP|Cu0z*&8->pTS=JNq4g3 zMXD7iy3LVx@CJIPtW34RZAb`$%Xlb=UEl)%x7km?ak1=bZ8K-!`B_Tjw-ppSe+OCa zHTe5+GRcVMQRvX>rQXPk28E#?m~;0TXINbR48w->w$2|y?E^OfcFGP$bTh_drTl}= z8O6AY>Kiib9dOEzOq2)TJ~S{?eH#8-`$jNRC>aNx_ERf&+Qx-0Ez+FT18a>E*qU0Z-6y4S zX4?kc3DW~~JoqR(e;3Oqbn@IBOl*rSM>$F}7qxJ1-rZD?3`&!-m&8HXQmo|(%+i&< zMAW;*tn~G zH_kwxvb(B&r=qtU{u;cuWJgVCGli6G;p7L%)2ILk7xh-e7=SD(_x9T-wsA6Pw4P&d zvXD*12;$&K^)jPdwR$*l7S?54$Ch#3(PPVl6qE2!K1h!fK&2~Awy+(9-Js%FplU31 zO_r7km}+pQJ6=9rz>M{kM=?FBOl6W7l=8kLwV3hNS!i~Ue&odxp4(+kkR!+0s4nKU};fCgT z{0DZ0G{h{B#slbrd4%ANjDnC1o~3C&txDK99hu>b;EW_e|TRHtZ5MJ=MltH+*? z{gC$HS3gbkX;aPfPIhI^X?@s^eH8Yl)9xqaw5U{qWjR7IX3%aHWQtB4K*%!SHT=zWlltrptt#M8aRg2$8TLH!c zaIW!?CW6O6LLLo(8NtH7hPe~z>@kgwRaGe&9CaW(q#7w5IZTWmT4$#ajcJdoUWcPv zz&-9c!3aC=gBOLw-bgHDIS#dqox^NIPxbA3n-$6U)LW$u**0JO5(RSuw8M=-K_{il zI{`BUpL8pMdbT=H-L|s@1dS1!;X;EL5f6|g&MeBhZ$>?+${I(%1fRgq!a#Yqp)Y&j zQ^VPSwP~4>b@>Z()yU6fEBrGtDPL@2MhZ4p1*J78(Tg*!vr9TmUxwVfD}iEcgWw4i z5`|GM=x=lP;_)rmL)HSRB1f4k-C+#2y2e*grx05n-Y1gheTBNo_{m+24( zr79^|9FZ+#QS|OBZIYS3sU0GeKrypO*)0O>pX4Fs<$i#gY`4WZ@yFf|9X*jdCUS+w zX=kzd=IcEUh=Qeke_Mhhn|@Y#@fFeeT=CM!)eB_JmkeIYUS|J|(Vbwb`~gQ|(8x5X zN$RA~o5ybaj9b(Vf%k(!P6Ut*g9#``qZ_+y97M$v~;c64c5 zsEdAfyX$GA8sUc)k4*3VJ%s1EjHCRk;4 zjd*?C_N7|!g$TUm#|B}MYZ^uT4xgx_zG4vJq#`L8J{$6AVs@Z^Orr>|^%B%e`6w1s zBLg8+ep2n$4fE5JXBPjCqiq}kto(1Zq8j~Vt<;9Iy1@p|m#0N-4R5*%J0UQM-RYJy zv!qf^z(k&|=E9EGgzb8L0CauahovpW3`4S};VGOQF$owmN~V#nHFC~QGfuHmdjOWF z4nSYd-p`;HDgPswd6+V3ik*W!u~-~E54yx=ivvm&La{5yLTZ+Rm(TJJDOOwP=O7El z{J1)byw)n6n+v9CJt(loTjj8(Up!k4c@6Z<9qb{sb`TqF+^EsbcQS~YIDLM({1*DB z`T}7-L#~^N$786DK1I1hxm+-sjd=$XwfI)ahVcEaq?L^?wfru5?)}BuZB>mnF`xclSh2wsw~nv3^Pwwr9Vz5 zTvzSbR(NR8cLag2w1a!-S1q-G(YDLLz0EWOd3qgb9lv~Z7wY4Z0rsy?n~GuVa;ID# z`&C5n{b4J`zwSHG=dY0eH$Lqpwa=Sf<1>Lw!hwL*GB*%`5vEpuydK+>=ViOk8wkM! zNzDL$WA}rO5_q@Ft|}A--@-KVUQE^5$dp&;fro>m3><~1zB!}qw7w!b5xV-GWah89 z#8+8`=q5LlM@EiYe8E{z)8>B3lWOTo7~0E(+2RsWIB~&D`I`weGO>F1Hf&qeH=N%t z28?OAG=9~e3k#@bwt4uXgE(NfxdE-SvMZ-3IELyyQu*^6O(Bh_kG$x zkM?#EQ-wHy0!{A?qd0yTWB z`6?z{(G)JadEHNdg7l-Knh=Wa_@^B)`X95bZu$O$Hp|*L#tXntn0UeI&*uK}TP`2c zwu|30@z(2l2P5^*&eo3A5Kp!FYuMX!vwPA?*-kbDwdRt^S24u`$bg37(K?gO9x=^# z;lqaYt-de`&yRru)wPK6R4e`1b_ed{Bhon6ovc2B_iHpSL}rSY#7J0Pl(U`@?**jC3pxg4vjn`Z>{^4mrx z+Wti(m(H73YPt+NQ%kzTCTrvz`)j@7iY|EFC_I$W*S)>Mqdzo083lz5Ntpa#t=6TFL3{&z?^S0gfHfDYPwFKfq z_a0Q0fkd}=Ck;dNz=iVHC;ALFEMiE@dk-ZL=c2|^`d_BZ4JjHD7MYZf{PK@HcxW0s-!8L0q5CJ^QGg7t}JWCwvu;;3|vavyVYmp@m> zy*Z9u1ZDn76C~Zz_wD#akA(PPGsyOtt-nK>Nzqz6$U9GfOq&5{wZ&{!S~6fA5v#<# z;+jV1Z`i(9TS@4Oxm{q0>Br>x`*2$I#T-$@J><_p@oUBMsEy}%^K2?ev!X{uvkOeH zk~nzzN)&>+R@sV@kaNiI3u7uRXMa6EShlv4>}h?3M>@?9DPrIce}-mBpynLipOUY& ztViZ~F49v+n&{_)Vxzf&3GLQOMTm=EMcE0}$VFU15n}&F^oNt|ANl@g%Z3rL4FsZ+&AgXr!7Yz}6n=sNjMd++*@<}P-(r~?+;n*GPcr6Uw>6ZJ8`KcOoQuls~QRfOAV=B=w z4Oi%eO~kl&8c0_XC635_Pw+u9^cI-EkOW3P$T5T;TWV!G`OIqActjvsvZqFk;#aq! zWq&=$vpfT(n`@qLAJ7Ft`w2NWhdre+4Ix>$t}CM+kWY@^dPpK48|N9l%~<`Bsz6rV zEF#GGxMZLeXk+813J{MtJMcqZI4-G|e5_YnnhEnDvYS4@i~ucFR^>^{$|T?DISbzl zxAmY+my?n^U$-^f#+V}LB_>r)LlagpdPrLnK(=G-BMJ=LL(^8eXNxw*?Tt;G$XJHS z@w;5FHjM?7TI{*NmtTPsKxokJVL0*>8z-A-ww|3L7ytq=EY zSMEtZLsO%Sg@A#)<3S8=)fRp@;?Yx4{TLKam%#~o@9pZr8Il6Mt?uKtaS9w>kfa=$ zvK`++kx6sN)%8OT5+7ONON|vMzxixo&9TQ?1-jb8PK$xmBxJM_IbXxc`0WO2Wdv46 zU?laV2F#26U_3QkLp8KVm1HbO$O?#Fg1+2Z{aQgLRumD_Jq{-b>{ldH`rr*z&SPwq zKA&)fVV_m(hRqgs!@ARY#F~<4_~~t9b2S^j-+i~R*RbII?y_bJGQLLG)=)Jl97>^J z1~mH$FdTm1L<6is(%>p4QJ}IH8OP2~nd=r?ZAyAc47$wEv6At`1wgkDH&?k_>gmzNfS#ECK}eD?41n& zbOVf91^t13X^;ah4EJ?~*<5S)(cHip3iSLyBC|t}HoKU2`f(x9LaHGLoFH=gJ!;)n*6kFku*fOdz(%L9gfPKiGMm2nt7PS{}x`Z&hfkoLQbm zpFBw0O34?24)S57QGgXTB#$>URbFRx4~ogGCVM{3s|~FDbT%x3y_G|!@Om8r{wE#l zu)o%+-EDGQf2t$~n>FprpJnd>%Aa$1*}Sxm%}P}9tX*&fTRuS zcrt2XWNW7h!clQ9GzG9b#!vA{6f;7;`lPoWNAg2ajGEX#016>s$Q_<=Zt?(F%wM=G z8+|cezaXw`@p!J`_zFi{Z{tj70%Bx2d<0XtfvTN%aw4)4$dPNi>cA<(s3l>Qre%P9(N8tAV!E z_AT0}ygwoAX%)& zvMIk%K5FsY53E~0dV5E3xDFxgR8hSWGoU9B2Gs>bN_GLBUuRX6@UftdZ5G+t;G>{P z04h4q$26ch*X1K36+qpG3nZ}F&MI|Fq0{U3s*){F%Mi#_cEzxs_9;=KcP@=sR$nD+ zgsZOdr?t@X^fUJlK^4ETZNo9&oX5;yQ_B`HnI%SZ4$(@@Ilc;)S994N@f}}x+yg12 zt?(UggG8EM)MoLf z`hy!biPmIG_?y`uXT7%@`4WY>!8^Tvn9ye75@8FP)URaSr!w8%cm?7v2H%CATq8Am zY{jxVK`2ui(iiAxTpUARfg&|vhtkBz?vUA0@YfIrnAg^pw6aFSWRS1&MbJEf?J%6S zxTajc4R{0P){HA!9s@Y`bEQxB76G6uhUzTcOpV?0!&2L`{seD8E)7tfrsNF4`K8N? zd*xeXj(nK3bYT3o;d_(*la3V6^F^*7VDjnS{|-0aAo7n7CJ4`Sx~9BYKYLtq zBzcFrwBtF=lyzm#KxP@TZ|`nG>ivry-S;CIJWGr+X_5^&i&g;&i6WoGl!QxV-EYe) z&%;_zhLj2(IM%T!CYmaTMH~`U&~q4OoGq^1@{yrO(^yq@*5ehlB}+UM4$;>m1{1e< ztLd45FbGmlX|klIS5_cf1f#R@so}SLx%UQnZQ8fqc2t0X{4XfSpyJv_{%dFY!%ob^ zj4U9N`k6IlN!zTGrg5&DpR4#`jQRLeikB;;#YZMl5$F_sXoA}5%Q^6vu2y0j3ORA< zxyVcK@jC-B-PgL?;A^kkzUUq?!7O@|z$SIbP2jSs2e)uvs8fsXO@q*N-uYC_j+D-c z9(vkG)5V1{u^WUX_+}q|*Fv+&x#6%PM{ zbzVtu1=S`9yiYrkW)}6tWIa`t(!A1^*(L9!Nay#e5x)V2B$w;{z6)d0@^22B-77LQlFlEv+RVOrn^6Pf#E^pI2z)VOw;9=a#{wCT-2@MFaW;?FfK+D^WAI+ z6(&thC>R_iXi9l%%rEZ# zp?zGu+J5l^M2AH2#5}H#_Pca?37vv8{5Bnj3+BL5GaDUm@FN^>8dJ9nl$N56%bG?n zOcEBo$|v{VqNnv%(v~Pl6<&0?g_sUeRXQsz0xJMRK)knbynn$$1*adR*n0yqp-7^KjkYDda@ zYlO^P*z|h=DTFx~jFcxCo}WeQ>qp1P(Try)G>lw^U`YOqR};A)o`Nz^E$4VgV8fnfQ;*4%DVEu- zd6t#{-3$+*v;poGO4Q@$@ldykkX>w8KsV+HC{{%rTE%EH);JeWbTq^Wh!NQ6m)y8^ zngpFgcL5AeD=%e{3)dqjT>pN+`H=`@1yG=wvNYe5Bcqh0jZGC)N04ToEgWLeM>ffT zNt($tF-nD_9|)&(ELFUBrLf*q%Q`blQN1K@;tu#xKSqf_x6Swh3_>KRK#zb z{<}ovoAuV458p=kDg3PD4yCSn@!hhTi_`Xd4KTUNqi%FH1OV;^W-H^Lj>`aDTF)r! zFCWMeaqbN%9_^$*Nu}DX-vimF>WBRy_t3Vuqd>go%oX8Lx)-;4O46@kp1G>7BK zR@=JNfr;%?U=E@~+R^lK|Mu2n;r%XazR3-ua^&J?l-J;vC+C3o5G`KgF8ya#Z2)i5 z>yJ+I#|XSPOW2%okX>i{4*05|q%zdaDcd&OVsg!ORA!ALM}`07#~_@MEpb3Se32vcQP&G`)Z*t7|@j)MBL-lV8y3@q6`2pLH z@g1zN(VugrFGnbikxcm<@6J)GzgyU*k0UE0jA6KG*x~PZ(rlLXO8z6}zbM6xWQk$G zH5b3QqIxtJw8=mwNt|VX|K|6A&mu=*(teTMiq9W?3&p@u;_vz*yp|Nlf0~zACd7m2 zr2J!y^$~%rC9`-oppVd07ea$1iBL>sksXAvsO#oZ&)+~yFF^;nMe*->{8PNeUCg7F>groU07z45{mMtYHE8_=1WDg`i`E6LnTiE2SuTfvEcg zTJ6W7QJPU^n#eZEyCtUyk2yVHcwFRCjaZn34^VjYhIRiC6QT<-)e!5^sz!p!S5&ov zE0$UrsC4jP2$NY?=@qb(#%k z&CIG4n6Ss4QYBSPp%pOsGKnFt3v2J`ViR4)ts+pxoT#en`op&_wOgK8(3^4ni|Jom z*v-OLI0jI2Ya9XS+?DbZEM?TSP+=uRV#tO{1FrcRrdK9W3>p!s)=q(PiBbtcm%Q*O zj@q@E{e13u$yho64_M4Prw2mmmyZHL94P4YC92$_Y$>;&T*Uc+IxOSuu9WG^vXD^3 zdAX-Q86b8E3#`d-_wOn$RH|QP@StV8H5(nq3%wHcrM>j`ruI5?ekHKzn^E9za{AAc zX&@9_SbdGe;3XwY7Z@jn$!)L+`=OGL(9o`VYbfbXPsP&=m$AyP=*2DwlN8N-v!y`5 zd_$id0vZw2MYk@RXtbfGFoY=h81v}jj^Tm;Kw-9&1LS^L&>5Ag4 zmfX3OMa5>yG5#AU?52;L@l#d6ImJ4IN~}iG^2VV+vNl8vPAahQo9QC#lVTayG?2vX z6W?j_(ut@aV$x3{*yFXH^4Qc|()gm=Zm2MT`05v5Fm4}EIzHmRH_?yBfJy=btrxH( zze@ZsKULdX+?8YYzF*ETEtnKJ2#juLg?fAizb6}4cob*$zjPcu{cKKjbNT>F%-TnS z?;13CFZb@@!%|K-E^!!e$!Vn3xq(HHAH2SWBKm*6^9dn-ALPQj~~G(-~wPoC>T+`JF#Ot7WA07P8GRFR9wlC@)O&ZBb> z9u|xAcVjG6K_b6Yq^a?W6nrB|4(nVDDc_I`O+vwyrqqZN zD!(Slv6zzdUtv0kPeM2^H+0y*;{HpM1-3DE&@2RSCO{;zM)uLciQd`zVpoh zN&RG$%{4G68&YddK#DBW5YeHbBc@KJNagqKZ+k`0(dA<@q(%J(^!l;hp!Qf9ypyNd z%|^wjBVieAFc6=x9dEzbG`qe`$*#jytBH*cVlb9hR&!4V-wPbvN5<~Q3%Xp8-x=-kqN=qD`}06b~h#wSBDj8!uy zrw|}-P4%C=z6jH`>#4{xYJoGcH3?{|f)XQ6F(p(Ry1v$sNnHqYNH`8lXYn1i-vCZp zJd7ZqQH7^ByEeC7a=BN=LqcQ?D`mPn2~QcJe}LZ5KhCIK*wZIxbu5pqT*oH3l3$Cl zYo}nXWAI!1zu7n%+6STRfiO*2p2BQpu2vLWdsx00*c!Jlsac6@f{S$^9 zre-pE($D>itcSs!=1k*KTuO=W3Ra&+iI&&h@Gm-1suAzvj$tsn>Ml05 zfKN<_&CO0{1zc)40&lP;NK!l>&)p$*b?E#ofQOVP@XPp$)op$NCBPE%z?_gsHjtFK zkcm}7k>qi==lmnX7fKmtflM1v?d;;SyRa3}D6m!zM z+Je&1C#A{U*)l||s}qV@^RHDS~J2mKZ(MN4uMs}#q8+6LsCj2aI}hSTy8En^qs?aoj)BzXAZ+B+Zup$#DZ zG8EdV?!aYYl6V%)+z^68NFT!0nk9c2n2h*&hJ^)0=awdc@5_F-^kbYH>Ns0G`j1eS zfbE9mWS^xlRqe`jdhi9%GdfGEY$NnMXrP-s{58(`cBQSV44=6xZTyOuiK`m!$#%$o zwHY$V2wP;$_{v*-t3 zXGGw0A{k;JJ(mk=5x=@m1>O$idN<_IXMy=vt$CMHS5ihBt(AYUHKVN|{Eis}J$ze5 z&3dg^XRx&_x9&}w>ibkt{8W*L^+P)#EC7SV$VsK2sHXi2PMR}is!@M%&VPw697hB? z7(VK*5^a%{9j5`q2`G&29DT25{)YS*=}(}9E_>{~3mXY#P?;t?LR^p477dv$33RdWRT5G?IY zV2rmokZIx7P0*iDXz7jhh{6%jdtz{BjBr2)?93qxl@o9(F`AMvG8fqru>p5RBMV|Vt;lzKfk{6F76&Qhuc^9Hh z&pr9P9r!4rm+5n#HZjXGreEuoiHx%un7MR8NQT4i#q5(8T*=O3Q@-D%)w2x(bTBP` zY=)jMBB(}AJ&z)vEy%kQ%zi8Twd~FQOXsz+nycL%NNiW6eQ{Y{C+AqK%y?J#fy-jq zI_kVf%Uf73{2b!2{4$=&Z^_BeF5!uwP*+VsMid>Nd!t`I4SeLrTMoikefOlZ&uD%{ z!mp#sf|}a=F#mI@cWI>i`ou|c_qi(RP773vysm&OX-w1C^+~ID1chT3wmia{O6u(v zS#A*sLlUrSug2hJ3U4*!wrha9Z6eqe^bL$bkBWjEA-}i9^?>)L>((?07tdO3GTkBA z3}cvQOjo(JS{&oeCl!mpvHx>W4XNE()`lTxNw>$VTOtAxan+N)O!l`+&#=?gHS|7v zBnVO>*LA9+F>4QA`*9iB4Ms;2YYU(}#pkDxHOs@aT;m4>r2LKb$EzgH1+~{$+K-Ob;;5#S>dPpyKZ+=2Ub*ZhZXm81kaW;8F`kt#{EYpt0IZT z>s~*yNM(gbpuit7%BNyG$PHy?r zOX%%pPXoq+Ygp#av~vfm8v9&@^y4;ic7hc7*KVZ?Xje=uHIcLBc+PTv~9Azcjre;l@8-(lf7zw(5dU z1J~xhVIF9IGlQntQuuS0f{py@2*L5JzGh{J(Gh{k#M|`0(Y#dPv*8W{!m)`dd5JcM zk87e07##4UWM%`3>TUW$){Qr6of{sDQ%A0tUi#!|d*pg_k#k9BJRAv`#0a%c}jl{#RD@sqDz!BO1SK zpIWbyyRb>IgJ7k(jS%Mmnjsi zdg;G&-{rI+f_rXMVVX5V_0cIXY3}iI9Jzf=owD0&i5YHe?&;fa;He7?pHT#LuCE#ogL3VSIUqTiwVB54~ z38<{mYe9pATp30~dNU-}MlBMGPM!FP$_G6#HHo$JtpGA>%)q)u9+(`T!}ZHeCwkF4TS*_XXeXnu8E0jp<0 z3U4wK_1OU7d4BIc;gVa2QPuwg6Y`C-_1pHbdcI^iSOn^8lbyFB6heZXoUGW&G4V=r zPpatW=(qnISHCS{M@b&^2O3$QgY&$8ibc_HI5@ZeruUwKF8kj+Eib4)nmE@0^xkO7 z?<;J>@$oPbucI7%u}M!2-MkfV$7WC5HnejAKVJLAMg7T~e>*^XdBKSx z*xHO8Xtrut5(4!ZXto?gCOAexm4B-WSHBcgNM~9u}_g^T88p zN$zm+eGG;~e-LC1;n>q|0~SddLRlvoo0&ZV(*6cu6fytX8^!){XMu)ipSXjxO)qLt z+b$ZJdW<>IMW9eOY=qVwxHstXOVJ{um;h{cDnS0kYA7fA>(W}9Z|v$6q>ET6ZWsD( z5UddTki9E6eGGBgyLU1UWBb_DP;(Sxy3hjiFaWT_S@Og`z+qrE;dewwxHR|g-?P4n zzO7CZrN%<{7$3` zN}!XHGo6gdmXyi8?6+_$)=Oo<6!JW-%-0ae9r_Dj!QCH*-XJjTz05h;G0kt|k4#n? z3ggmM-ae(vQSlHoYsAYRpGMlQe~~6an>di5VQD9*U`ca)0FBU}^1siTB>A^wjBSPK zfxx*9UG6e`Vb*1|5(eKkzgChcC9lCwzQBTU#q)ILz_WY)G_&LxwdP_35Lh1N@%$w6 zt#`K)IeVDMEZ8nH?%_ye`WPLNo(F8nXzt$BoM)gqf3W$WMNT{EQ9VUi zh5m8&jU5WvcO81udIm4OeB^=`j6%K%W8IEfdobNNu3a|NvB3VfE!#2vkC+%5j zUb~N*tk-I%JGbiJ7$E3EO%JggOxp`KR8tB5EE$JV;!?y=t)j9AB4aKK9wC}YKI z@}?E!;zq3G4^RQW==x%3l0m<(Q{R(NMG?I*A2SKC!g^9BgtBSF1N88aMn8uMu2@ru zoq4!dEP3DC#wrhhGDvejR+dO_%@V-70s#s$Yc*)Pg;$j=6Kf<4btY&p2Km;!La_Y#kKC&-8o8C6fQ9W>!P`*4H>a`OD5X%XfC>l zXbrD6hi!&I>KAasK+s!_qVC~cA8t*85j})OR{uFAS+b|uwnepGM+PR1Qrr3u7ogUk z<+cPzCJ&ibTP@610Lu#uY{3LfZ=ep%<6d>1l#@Th!ZI;0mI>1~GJ!{0*mfN$4%U63 zdrUJnlp|4YI!yiRfxja921Bm+wHg=abR9(yWthAN=Iy;aH!?9DZt~xic8vZTh*blO zJ#&*G;7$^Y!&^+FH~Ygk2c<>X!Bb^})c}l{X6h*|(P*N2UbBj{Ez8+^uG|e|f@kZ_ zu;kr9#_Iwpbm;kVpLgWwQqxJU=ZJz$tR|A-~54NI;jwE}eRvKl3jaMGPuraANkb%bnP6n0R_NLJK7l!q1@OXr0$C zw{tk?N(kq|CQ@eWyZ(TXET&YJY!dLzLg)P$J4nui2r!8)tITlD{Bh<2UOLfp_c7a2 z3&UA+@{K9-G{t1NiltpuA}g&jUL>`xdIN;71To2)1S`DjVZ|puh?a z#i;<3AW?eb^0D@QB7oF!!CHoe&LmDvRJB2pT7&uI9F|+ehYwR6ddd1HFITQ|B@O2b z4Ky_B9n~#iL$W~^pVc6H4~MyI-;t`bVo$k;E^=anNs}>!fzT93O>Ui8yUI6WFt;vT z<~VNAW;3sk;$r_2PtaIocAF4%sT%N{%FlkJ{v4W ztxhhd#gVQr2|Gp|>9Yd)*Xd_%M~Gff zQn5EU6i?2<`yq$%{0^**rCgML@cw#xFdi&_P%vgJEfcbq;Hf~0vHb{1(c1_OW7H6u z##AVX8xBs`PACMf4~4yo^0ZDaE&7!&G)i#LE|&L+Xu&beh9VvwS$>c3e)~$=@Wzd#_+8@!L4X0orEm+8+W*sg)v-(b!~@HQk)_bJ+4Hcskn%F8ousbXUjW<yVc9hvB$n0gwCJrT%kXby@b~B(r}v*ua1iOL()JI zXfbBTaNDlt-tRf1I2l9Xe$}KQz)B&s8HWkFZ}{F~ zQy!59B(s-{50R1|m;S<~42l;8#5@@g5nV1LgIP405C|2Pt&Dq^anzt-B+(3NulaGa6mygYBi>d+6fi?Qm&mxlEACV`8}V->Wt>Jn z+aa1{ZNM|;L)7TE9?gYK6Z^3q*J8qR>vJqf)5*NNPesk}Ql8KX6{z>$du+HW*=x`Y z4RU>o$uiz^vI0ndP~=FO(@*&QY1*CKoC@O-tPz6dmy0VyaV}`N@29lY9=rz5hPy9D znTZE9e?pOCC(e9-S|%<4oW!Igdklc=l(2m~*Jg+aSEbGc_=MH7W7eyP*I0UbI(TC+ z@X#~%RV-_Y@Ai5I;d7VlfrQI37v1JpL_H z$f(MJMtSKn%Bkk5s*bTNkcZ;C{f3VR;uChT*hO_KD$nHQ?NK4lX5 z@VO#!U9+L-`*$2AZ!V3BZnHordmCQ7Hw?+w8=0S#mb-jGkE#6x~EJ3Ua=`^}FX$Q`K3R;vijj z{`QwT!`(CC4e}&bMhoK$Nv4xuyd|>Ct80~L2Bda}#BzxsgBqRFL=v{}qc|pWwhXND z3mk(Cj$%y)&-AgCNrh$;q5b^XSGo%vex{IK>rsr$C~FC_&6kT}FCzx?FV=GJz4hXk zs51mljqiJp3u1QJzBJA@cRUR@$)bc@C~io|TKA>%@(UGfg;#xqsYHf9=w?$mFWAYA zabz0B$Qp|RBua?RNpW-R&(BOH%mgJn}M_~+&({Ea3{A9+U*Rjf7?Lx zLK+wJnIxc;#a0Y80~4t;XB&Z zyKLV4xh~+F#e(|R=q+A1}ta^x-NtjfXIwR12=m~fOSP|!E*3!RhoEG{?oJX8P0ksC|yy=5QU9-N|Zgl7C(nXy5ceY9GzIg#~_1`g{ zK7}(*>n-elV6|8AJ7}9xJCPfHp3z;-*awCN$ul&>EvK(5#x;wYDV(VWjF~&AAi_LT zzS4S{Yo}-*0Bwm2cRb`5SB=-@nDOnh1)jii0bJajLp{k5y7?QksYn>pK)|tTb>e3b z!JCG}Q}FG>n;RPHL<`tL`@PE*_pV&b| z$`MInau0^F1Ah+$BCMaE_3k#@_2E+o&xFy!8F*=G4gqLbYYSm1w&zrVm~+-67+})^ zLw}ZBq0z&RwhSnBE#`Tuz|3TPi2M0>mQ`wJgw({Inqc!GT&B*aSdo-9ICkF8(cvV8 zb;)q%z#mv!4x3awO{KHw%e5_L-+$e=h6<8#@{jCY$mEFPC86sxpQNL5H}Y;#1Hj2U znlaNpSfsR5xcQ2#I$wpwQId(Mbg-;KPx`{33J5Yld8f}-VNc3lmt$QDEm#CMROn3u z;1WmkK|^mujzwUp0m>N5XcY;q>RqwhUQAP{^hMUIgDG{x?Sl=51dv)EZe&`)_tmI( zm^h`2gp2#^C59g(C)FP2T2+USd`-mnLVfSxm;LlvJtPAp!E#XOGkAoC2k}m1$$CxP zvhvxX>6NCwkKJW@0oRj5(nRYipU$V&7Krvlp8aGQCBm#YLG1oFfOU(^TWU^#X*dp} zci==hthsT}uRp5%w%%@R{@~?Nj0?%+Hn`{BNfd+tCl*mOn3J@RY!x+3jK7On=b{e} z1F;!&vV{W$ionMZGlhxJc7X>yIn&(6B(lRN-1-@wNCZirLD|Ct=abA9fhi3UvcFKV zQFZ|-N)?4I356cW^5ZJ3G9O_Bi)d=kgyqfpMm#!ET|?vedcs%(F-o-*GY>e`)&DY; z4Td3;GWvbActK!u$|-=U7c!2v##khF7A30gd#TPDzQt2n~nXUPv*dM zlif)532Qu$xO_E=b|E`)4)N6SEHOM<&) zx319w$~)UTxaSQ=W4`P(RSGDOb6K7=NQI(XJdkcNQ0oL-?BKA84*?h-10r_7?8w-^ z4-g~r1Za9jO1eG5IDfj-+0L_2VcfnuIK={PKneuWR4HSy6?dkYcV)#_C`g3fwi02k zWfKV#O>0JP?^hxzz*^8g{K=@`E(prN|Fcm-8V4p*R5#MkG8>SyiRIwmDode0#Fe(V zq9pFHW9Y_YV{P&XqlKQE^ssD}U=X+vR0-=tMl$Pk)a^&!4g|~gSvS^v#T}25Q)rCx zFRR}*NnXA#9ore?Wxt7Vs-?#qFjk5h(OTr7iyleuui9C5hRk2L|K~VxDJUcal`;Bs zp@qxdewU+_2;B4ne~1#MKxe!H-JtIEHIB2a>cflk3iB&y0*F-*L3+xArc7htrMwW| zY|0H0M^XvG|4J8vR zN5-R}M0VrgY;nU>DGu1hHX_HtRe6I64iWkWS(iWZnNqxND$><8n<7;r>5Gv25W<(-9Yqw2@71gnN_OE+&+G>7p8F%g zQ4@jkBAxRksD^N0dF-+y-$|k5B{?KxA8ula8*Zo(4-6t#c>a|*pfvhODz?|m2NC=F zRrf8_*~i}*GCG?env=dufL&oa=zMeIl=od1l(<)FMc6EA`(E>AfOeuMGVWOi0^G)G zyaiV`VdI*))Ireu97&mQT_N@G^uwc27Q9s zQ;03FDEMV=&LG#C(o{s&&aDAsjc92ju1h$>Dr1cdWHE&ks2_JtJy;f~TWe-V4QPwV8G$eQpoRQeDa zSktg&LYALXL84@~z)6x=vI%0LQs}O$C>f)fHwSQdi!&~qRXlD9 zKn)C!6MpuuR}vkMB{CAGcTFP!AzlL$B@;t-s6?W57vz1y$OvpA#vX!D)j+EGUcQuPX?3(|@X(un84f&wew-m!o35425~{kc+=A!a}877MT0@SO1YvN5~w zE{R+ivL7Jc3#p^~0aM8shak5cNg$4PBg^~T)1FRna^)A7r6xdQIJMq6yvtBuN{#mk z!@vdp_&x7aL~ZCP44QQ|!ey*hUxLKMN03rF8#03JV3WdSAB~}&6(1LOWzuL70*JbE z3Ul$ZWvaySoWtnUAQh~dCRD2xtaXS+*5)qr{-{rM@8b+7iA6qzCRVcGkF} zSys}s<|?_K81;iJQm1lMzrYj93$AKdt;xVNwIia3HcS0=pIgvf>7fbakl=bZ87zdq z;3q}Z?o#(jij}cc11+nq^jM7@!06J7Co_JoJbX!+TF=!xKgFJKzY8>)?FX3M81 zU^ifn9ZC`iXZa|x<41FGpQZmL#2q-F8qcpC#4Ty%R(h(zo_ugt#>U3kZ>9~Xi)*le zW<08=d=%FK+0i=vMa^bL=U8k_>+|#U@S+Z~DVIH!$sWD$PwcK5)#OxUbLq_6K&q$q z5R#hsrv-qL)BFv((5jxFoGiOm?so#V*B7f0iqv}{CyR%m;mm_UXTH!W+hecDdRB^p zj*V5))cvECekzzZV%auPs!#)7N+^ahHLfsXuV$ze`ud2v;R17_rFY-Ao9x|2aD5h` zAyltj>!s^4&=IrnG}5M9WCVRN{x~gN$61 zX!|QNS0f!CXnAzt0|)WU5-Es8MM>S#kaLG4JB(J*GDOx=MvmV19aVV9i1E`N31x`8!V3rZG3lqFa3J+T z_j=!{yedc7ja-VAAahU<*h+l!S8|J;;J zR}9yYx7Yh`yB`Glsi)`g9t6X~a-4)AmUHyKuV9f3cQXGi4IpMj!oO zp3t2Y>&2E%jbVctDeI?eIV&S3=%ItLupr9<=}P4<@hEkCab2CMsB$sdL|*fSFFq zwwn-J;>VpR#I0@(KXt;FjGmuQQjVyNLd8aRJs3jFowujC@%1M|dCjCp9VDy`?~x@I z|HG(GV+FZOq53o7`reE!^Wo9|AkBiy-hCpr{rH;r3B)p-U|19&*8YF%kWBLYJ4=D|$--#pfeH{)qH=@u zozIg7?qp`6LGe+@JW31YwGY^AvB3jhI_L9Z3bN#~)kz%&1bNU}tvAV-2g^~tCUQM2 z0eZ9l;OWzrrDMNjhGU11JE9VdVk z*4amJrV9HGA9FFVqcRXV>UHl49y!Un1-XAlYu=+Uf?WU1`g!YXzlHp8xK=iV_h4vQ zZ9)`vC+sv?{;M>rn?6N~leXBfy)xWzWxVT{Bb@83a(;pI5c<~hc+n8?z3K+S?SoWK zl#e==0Lb&sjsrZMf*9FTO=Zcy=BnzWaOkj*W=f+#uf6*?9b>c!hxc*N6l6>01lWQp zdWMK@ZkCdaXW8wOK?8{u{2_E?k{t8VzV;0Na6{%Qb<Z9b!Nj7CtAg%tq#^ri&h z52&8C(@*H$NU1RbM1sTzZEx>6k`JAz$VHvS^I%e^GuLH1JmzdT*skgEB#H_4q|B}g z8f`wr5aNPHp6905j38KJH@Ea~5o$X3BiB3o^nPJ|lsbt{W^H<>T2z+>_eGN-AfJVb zJH*by&x+RScAaS@Vu^bVHzbn0(}_D=*?P`&}Mbht^M@~!f8Ww+vM(rU^GPyzsN zaM)aXFlhiH3E))$t4IJCVe1L8WH$poH%P+>ot+rYJ2BZAz*2)ogJ0$C95K(s`-~Zg z2ImJf6);5=FAT0|34sTG-<}FR9*FVW^xPiV13qix0Q_eRDFfo%?_L_{KI&Jlp)q^` zhe2h^WT7^vvW#a`(?=x?~V;5Amc-V>S(; z*BTOR*|~-i7!a_C@CZQ860Mq9v?efoT~#TZ9euHlN`D2?tEEKVbvFMzo~M zdWC>=;Bjr*pru-`_L9~?qKs2`>7Ms!wnNy%mPti|7P=7S(YL*r=_7MvX0#yyc6=AB z{`oYoqDWPn5b4QwnSNmvxig7Jlew>k~p}~{;?mVWxRXv zkN$1LvgseXnGix}T{@lkR^3Pa6#i%3{m-P!<~@ z2nEUt7uVrl59rGeRg4HWZA~gIZwZZ?fP=Ld#@SfQ? zG=~-WEaxG>M+G%QV2-l>Q`0WncgJypcTz$X6e8`pjPBdLYGbv{EAQsy@&Vnm!jz! zW_zt>IN8f1eOe)&bw45@t`kLKtQ{X^`vd;=AC2%iuqtp2HP@QNN6 z=3Ymc0^xC`Y)m~JRtWNi#ZqUM#%sxa%bDzHeA1J_t9^(QmI~gEOgxctaY-EB3H)!{ zY;`aI`cr%+UkB4JVvxNhipu|oHWSlQrG(`hp$Z|l9T(#D*vUX-7fH`$E@`9^B%61G zJdVTyuxy{dGCTG8!#DHk;_^X@`2T8^#-VG34qm0@+U1zFc7!DTMg7b?_suLtNQs-_ zhh_PR&(VuH$jS3Uw2^jsp}sd^dUZu+aO4|Ao)7=O(;q^KOUjt`HGB;3pONd|qvF8A zYGJ))?Y-=aDW7o^WlK=YOcu|^;Sv}g{vGwD*fq}yi-|?acevMB7Dq?FL=jxRTcVNg zo^%Uv=0SJt??rEj*rGnlY!YJhNEFRAcOnTWtS?gUKWbZ?ED7Nwj)JJeZ-YevgkjJI2pao0A<2+#D(#ee^wpo9=!9J7=+ ze206bxwnv7Vs5t#6UY{2KXz!{)iPiL4eKd9a@TdV(ExJ(v~`Z+f$!Xr^9?X(;{n(2gfi8*z^6a7gH zx=+frm+USbW>aty&ZRu_gwLPTbH?T9NfYEex)pS6fuR_YQnGOHP~09~?!o54IP;$* zWcSD&;c=44bS>nrCS>(Xo6Zk<%(88h%OPsRSjTZMdryWQrw`5^bD?U{>ru^e^Ou%9 z?|nJaPA6dE10LubN<&=KN55HpqUfBZZ0-seQr@IKp~Z!od8K~)Ta&~jEM6izjh|MI z)czoEGN1M>6!-qpO9vhv1x1BvML|Srpaw_d&Wq8TBA_8~*1Vt+_UvF|S4?fBuVF_SGjXn>$GH2c9Ji9@rU+IZw84aN-<> z0G#qHL0?REISl?*9bOxE^gZOv=VNzeREISWaBlDMs2l0-BN_5=*fs2UfYR(w7-C9#IK9AMhl)%^xIAe`Lu*8K1 z&$Tt?dc8uWw03u@A4FQXuIv~L+ntjyMPs1v$RvL1t-CO2nhL(XnMeT#1#Ljx7`XqZGEDJK_OrZMWGe;c4g&8#$A(wKi{;3q7-_ zvU?5cfyl9ED*@@$d{T^BgE25Kr1^>Mjb~^DZ_@;dz8KKN(c%+_9|>5U7yOWjfH21x zntaYMn$Glwp~6uXK-9m;!hIfyT@jc_Fdt6!@iX0uQ4*>>uEQr-HpKLM#oc;Q!|JI2 zO7J&cIo~mLea}cPZj`hZ0yjD1=3G3lKDUm$PgZU-Qt zFnbmjr7t}+)y@BcMEfUZ!8yldQ1%=-{!sq=o-OGiE)7rIU7^tLkG@y4x?f~EH!0^_ zxc{_?U~RJYrq)Wh(w28JVH`FgAzWau&9-C&1DY^?)t@$c~-|}TN^}qv@ zSHjrBXp9r>B@FPs8-&f`5SC?zW575b8Xn1Il$m+q}RV?=}$qaQEIS? z;kY|!9rYwp``BoGgivN|#PgU!zasoK@}k^vn4b)zID`d?D=G+gyuM$Y5$kOH<8*zW zrFr6|OzYf%ZheqnBtq$6VaT%NwVIUDzB{L>{Sq4%`TpE8v@MuYy4pO~G%yV0W4=|4 z!BwX>92d}z#SvBgg+O^*Y?j+7N?(xPpF=TNVvWBuD;Nbd(8%jq1zz^ix|)=s*s$ z05q`~8oXJxs)p^Y-z_YhX(Q}WTxU?E)x8W`(h4Qd3MYMQ@4dBweX?$NVGU+Y2_g_cj!EXuc^YY`Ivq41xwk zM|t#JkxstHp@%xH$0${Kcfy(pj2oua!lC(7Qz!)3yKTxjC~t#|>+)Mtr?1r#POKfC zf*hpICo&XNS4%UY=$Wq?*$8oo7muG?!I1M0`TX9Mrn-i10*eF|h90|iZO>LpxPQNZ zPW5_DI3Er}o4YGKk5wVRppi;8Fy-LVh8n|MTA#f958)&)tyi$-ibQ|n0JQg7QmXI( z#gZ4nlu$ciF*nWH{0wB5Wx5~ghAi5xnXm)zttxaGqdUqovrhu2lU;?jaEqV!oqL8~ z9L1ds%2kYorR9~nn5GFxeBea#p7YNu(@0e{Ig97>1&mNrl+o~ob`Vv-hBwTuIE&Rq zWDaFtN&iWln9-1Jy_Z8}fQv9Isve+N0;t$wpi|>wNHrwLB@;{c*Nf?>e06Jx*Jb2Ixd5}jXEFGGUDw~Sf94_$XFDQ1XAIhJ ziRvSVPvv_Ntcol;^7HEAfJEoL=cfS;U$6y)934{3?cNm*Qb#D(_mowy zON{E7ofRNXEZff2{q!Z6_@nkx`k11=9EOP{$QBBqDTXLK$l5lY26jO!wc*vECDS6F z*_)tLVbCMw>q=^```7(31Z>X60Bu!jdmDhVg~R z7B>M!yBsdapio1zzWjAownDYx`S+4L#RRJPt1GVRlwv^ zBx`;h28(h98F|si`E*xHoPqJ(2mc?*z*?XW^i*JOZHW|+R@i%lk*3e=p z8gZH%Beu24x0>Fr?uP5Q8SXdz3H(Vx3C&s?EWzCADz^VMU&~UBVDz3o5FntZOvRjS z0a>T*;rYwYLiQI8TG?^xKn;HxTFEq;e18VUv&u;JC58bnx|{$56%{BEi1GN-2B?I} z{5P@sXjI6E!QZ+is$?7%%sQlgFrXU{-ub`X2XI&;M1_tlz0b~x?dLA$LQjTecAAzg z?!9;aW@O2m#os{NsqPlfK?J>rUJWxB_<})XO+1%7?er@Oi`yVWY|;i4`xBQmKKw*~ zrm}}8&CgQ)$((hWZ~h7yw{jQ;o>Ue8M#rs+oS| zKn*1#qL(!ZqAWh?sNE7-`B5Wi_Ws|YEYII8Z1A}ft!AoYG-gIRGg!?+5 zj4WiVe?}U*IZeLmX?}~`l(d+~AX2TK8~!GH*z~hs?BP?JGxpQHW=KuqAb0X<=F#`F z2n-N35eP^FmftsB1iVEnnHprm*DIW0{w0m(p<3cR z|H(b^j5HBn(c|{O&QW3;sV+o8xAKfbUI3>ysbRNzv69eB)x-1U38W}9ez$%_lnIxw zh*L%Hl&>h(kW1%>h4#bkB^BS1P<8-~3~*#c{5m+-FQJW+k>GIh)N&eye;(F~V(Afs zDuWREhCd!I$N_sqJWC(UEQzYYC054o@mKEIJLS`1mh&-IJ}2nV3LNfOVC+t0xPNAdaef8uZfasE87 z6{Fa_H*UAe; zobA0*xkjO=PwXRa|N82a)2uZjtfDEh24>WwDXr>*&uGr3^O2F2v@|${?%ojW7GdZyy>7U-M0il+0tt7D=DezD= z%$r?!4aeO$uD@^WqPwlgOKCHWTzw@pU%9~rUzj#S?X@pMk?5?^{zx! z?qk(h7+I*7_&zLBFXT$wA0x4+0vjXE_{f>zqIZ zV>W3xazIO_o?L1Z7WAVb!UJ~&y4*_TD?6AQa4#*rfBWu?iF9_D7ErGTk+S2=I!+*0 zV`8otoJ^CDg9JC$B9AMBJ20^zZ-2Q9itX)$`G){B{q}tMFZ4qNswJCk#D8Zxp6Ht? zPe(Zlu}cOZS>-66aV3cHCP!CP7>;>|$)uT1f^$>&Qb9Ff48FzIyz&T;Qo*1B!e#yq zoyhKn^IvDfwVRIY?jEz8Y-mzZMM&r;>)>B(J2c8G1}&XjqFCLz;x(~FqAHaxh_P!n zaZT8mkvrWerbxZ-CxLsX`-0j+1}2!=vHTfZq1N4?P&hkWCfc0xy_C4F_JhA zI3P-o^k{sx=fSJs+T9W{L}!c8GA>Z}J)Il>qQR$n_2-j&T{5mH}i) z)^X?~f)6L{Z~)46$>}L@406mbF(cG+jfU%>LbmUxbnV<4hF3af@nEE2(zFsZ@Txt6^=Z+otqh z)dWn5EL&>s--uvaMf1r&+3QycROooeRB9?1I2Z?!?xVfgKvd~vrqnoQE{cdSR=?4y zCR(U-$rPG?O^Plwh6H_kYzC^_>{o>uqC3zSX<92jcD&f`m$p{~xnRy7@OcQbzh+f66&p`-Icvr2Y>L__07S=D*24I`fC6|A7-?V8$Gv!Q}C^`X1RxB%ve<$`@ySG@(!9RBq) zA6A3W06L%AIlxU)kjwzNCDFF@knMy_6G!&NPK)0LB5+%tV;}C*C>~@jKkMJc_muF? zf_{C3^G%6f%)>2opeum#;}z`WXk}rB;_hJ_Sr6LH2QT=yS5r1CAHzGU))Z_BuUA1@ zRNbevm5N=vYkBw=tT`aRtxry}gk1xhL>izrvM~;CRFv>h$|bWzwG!=#uI_4tQJDRY3^9#fzXz0`-Qh1Y# zE#qse?ifeIA0h!M&0dvU?=Q?Fk*AwHym9j!o0Hbu(l^=9YY!xz@#Nk23JXq)FCIi{Vx3mu*J9_M zqt5DfBCC53!|qJbPh@!c`hSVWcQHF(@vSCxm}MdXPHBe#;J$7L z9|3ML1e65eQG#8=6%uT8tgW`D*r~#9b_`fIzkRbkP`ISGr)LY~ECww`0FQcbl}^YG zy1KpG#PCTxnM#n?{G2l`p}5(q3?icMW{8NUS<=j^)Xu82Cu3>Hi{X`<1=4jmoK=oI zd>S&Tk(HS2{bW?(CoK=dw#OZnYTUy)DZk+%6U`Kl& zB2Fa3{dP=2v@~5AB7SUtO89nP%B-+i{OlpW5RtSc20(JNJ3(#Ks9`{nshD6ZQC~Wfv>-=!9h!>UjWfU)O5;l}q#zUrN?5)9{ z4=}{~B~Za|;7%JcWjm@F-7uI($G;|$1xSwyU|Q}Bys{VQ1gD$-e!BWsag?cvF z&12#u{s8#)NrdF1Qk*u2;IeL^_p-BhFlEbj$({MQ?Zfk=hOUI4Eet*`Cwn7|d7j;= zuSy%$6uk()D>pOP3HHA01h-dwPITIUnhrEtiS>C0jD5X)(#QdONSer3tmC{WH_aL< z4>9py_4{JYmX_J2H7+PcU=3X5$xB2zpMDeB^y`|loq%$u+M}k2B%e^Iy#p)~u8}A? zho#ID!cU3+aE~sF4KYq0vjK)BD0VZ+L9W!ZcXY_jRw(G?&*a9WA^0v&L+Ds= z^9nCp#v8y_pUwhI#P=j=Mt=|8l~7bMN_Z^)zw@I@F!iuhu~vpACR_Y~eg6+5R40aS z3oD%Y1V8@Ll)x(oVFMnSq39FID`z)q=(cCba6;{Xaa2xmQL{jJJ#BzJP(c{DhYNFJ zA}?NF2@wwJwJBH>64ZNs#Rs;^Rsi3_mR};Ii@@5-&M2oe;$&sZVBu9v$T-5SYgeKHPtaVYM7`1yRoSw~B8p!<@8B;!LJ*$Rt0 zFXDAFn3ShqmkxA{uP@F&Qk;<8k4Ek&U|Nv+wyOwD=6Hq7i4EIfCSK8$h4s_jsh&6w z>h5*oo`awO(yi^Qvm4J5%0iqM>e``^5cTpE=oBI-9>5Tfk;$a}JU`cL3&5Jaq`-nZ zifDyW%%ewlyBe0xEL2zkAiQ?)MYa&EZF!q&|B~F%NfI#CQ&y}JHGF5~_;ouWU1>?s z+tv?ucAeeDKFn(Ip_qD0521J{#U#kd!aP}1i(fPc!PMb+VVJXHN z{ikZYytsOxwFE+j`^&p2T7*X1;55Tpd7q7wTF=N}tKGi-&lXQ0KD{rr;QYTiX0AKQ zG0pu(tB(QFw;LUQ4s}owE@(YxVrgHfvAJDYtm_own_Fu#uKv7&Z1Q3}2l*uzS{5eF zdg3oVI$)wpE^c%A5Ok@z<1;mVo41Sp7ackLIvi?FweUr22Y0zt=UK{$&o_CGcLJ+q z&nL%X$Y-Bq555GVBRdW~lyPbdw{6HPTEd}K8%Ts9eLP|qK#LX$ptU$kKWevAhDi7m zed-CPk35oLZIF$F@gWJg_*U}bN*6kYFh&;CzL05ift5^7NXY2^L@)UVDC{DU)^@h` z&#EooUfN|Y=kKY+MS%!6B_nz69F3m=j7DZOt}N~kWCa25LtBi^o(qKieQbOzvdC4Q zP=u{)nJ{6bqdTWWZ~|I4P!i9mpgQ2^?Fml#iv1>twzZuA^h$@O1QG`*umP*mH%m_+ z5LZf|X3P-`ILJ2U4Wv_a#jNQ(e*U}YTOuKWCBK;b#KirTVtuBiAQ?p=1bD@`sc$zADxi$h1W@QfQx=eVNQx1mlGs*m_!2|`!refBgVWfd zm#Pe%qNdwuKP|g0*F0?ZS@~YEX5`}6xPa3c3y#?d1s9?5cm0Rx>k1&>FVzELwT@Be z6CoE(lr3_1>ADG^QjgmJNG5Y190eJ=LH}5btS?@{uOEln>7cNiAtH4{|C=*|2+S@@ z)A}a`QwOzuWD>cP)F_T2A}Cu4b~4e(PcS1e$R4;_n_wJkuIeFQ`&QjhzSukby)Za1 znx>ZgzLqcvQZYj$h1EKEyvCH~?gO=L+U*5%!)ng7Hjg9LwZZ;M3$ru3+QP3=v5>&K zIpCyiN$Bi9o30WqxB1S{8XBe>#<6d(p78W3&|L68;tTjUyZEhb|68PXU;V1Mvb58G zoflBBMi{h7@2*YJx9|R&eP%E8bFc5Xq}3B+Eo=4p<7$YMw?7d0&iI+XyXS0=JBd6Q zGWKdng}_iPeZ$&&@M9sQh_X6S5n#r{&gcA0G#o^m`hyMUS@wg65#eC@JI7v!-$5D* zwFY>6`nFFu6_H7jcVW_YXD_UzWbY0Z264YT)EP0Ed8bkUd%xMN03KnEM<@x{sCBA9 zdeN`C9VNM7tiP)-kXT$WYl#9k^T?E>e-mGSIZbMDh|k7PnzTelrmVfh-nD*+8Oo69 zKZ#!je5UQ5>2Ms>O6+)OL~$hbETh8{+jvo0B4y=~9cafUWUV>?wR4 zq}hD1us_r?P-ug!*~RC=Vv@1I?H~L^=(f2^`+?9Ku4``Xdg3ogR4viF|42lOy~*6-ov2XpSB85B)U=|ADxppP`p@TtMQ0E*rfr9#nj&1g1PFiZFyps8CL6MV-h|Ob zzPijk!$g`0Q$};1c9j@6?v{N<<_7Qk%j-^TLWc+??!I+V3qP)MA7&zyFGKzT<$-_wS?1M zKKk}*G#}AuKo=jz!#m#EijgyA!J`K2f(^gXJ3pk=yl`Ts9x>&4Pb||0P6y(yJG+uE zN9$`oNLK5pD4g`DYpfIOu&g`GtDtjNThK>6NrsTn!ew>sw-Dr{>Wp>4YM3>wbu!~? zC*+~2jZBXqTI8DR65P)eU70AHCmN%iWX3Civz8XC91e1)6oxL-13pWEegwV7t|b*m z({KL~uC1UE!fI=|Iel+eyq&a$l`aX(9kyk+bINkT7-Ct)XHfWL zAc#2#6+L*YL=K~wOMOy+#MAJEzHVILoIYm}6NUJP#mac2ZcwxA)$zb;UZ1!0(+zb;%a>tt+U zuGE-7&qJduGAeMFF~ef^{R6m6JZl^lrNxO@WN7X`r8v{%-5Jv&O*#m04%3v}=2`kN zskvSg#mzNIe5MO0bdt7n!zc@@PFqa0AQXrH5@U28X7O*_qt`&{u+N!l!{TrLgx3#) z_LFc1J_2C_cFZ1L#-s>5ifBx{#qwZ>#8PYp=eUDY9`qWO3^VJG78`K$@WEHUNP@8Q z`lo0wqIsFA+Ez0VzdgD(PI(e97>@r7xT&_BsO*S_i;a_*|3drGvxGg2H4K1!^yt52 z5X`g+!PqHTrHtM5SQ{FN9!|~rv8F;l>w|sDz-{MxUjeZPY-^IoWOM06CSFBc(XN|p zuro5nPObbOx0ucZL+Rdn#ib2UPh?J(s?Y+tQNz|&ax2m+B$-BQ$fYxLj+UL=KbgweW>_h*EU5c7v=}Mu3b+3%3u3=w zX$W#lwdSIhN>#M3=rnTiWc5@sEV~u_fnrDit000r>m_VpjLS@<2nPpDz%6Kb#H|QuFJks`)O^m5XA*anCoST zH~$^mVE|tdP!%Ei_US{j7>9Z+s1A+SU#}uKNvT+=q2Zmgm!JkOtP@4q+et$hCT7I} z3>|A<_`u zApr1_*_(bJ7OH~9S7Sb`(ih%$rS0Cv#pHixGW>iTZt|7FVurWUJcte0b4DIbk~G_B8JS`u zUT#W#t5E9@`d#6O*SoY)UnBKHUbi zfS6Q5Xu*zz+jwV^A*>+|ELM)OxM8bmSyU3*$I>YE-{`AnCeIyKh!)7r6 zO!{~p7fV6NhxrDXZAQK-WmfW*0|O3Io0M@O(+Dbayh+#EfqZ)kU9o~grc^pa++MNY zV~8jC-LuV9V|SZDJ23frgNWzesPo5{K`1^{HU_9uiqGPjW&h5vG39dVeMGB zy--g9#0jR;XTQ;-N>NAIdzWIaFH1_4<}CN9h*5t&ZMV2}=1I6!#dmZsnyLUcM^A;y zXoNO(ESh%#Qzc@$h0%6Tb;4o})3CEdx4rg0y)HVzl&c(TH%J=!g%u8z_H34EV*=Vz zvp#0`0j?*5p46G92Qaolt<^y2jI;FolKA1h%aS;_P?V;I#mXxa1YcUfWZnJ7!q%CGmU&7N4A&Qt8^^Jb^CSdseed|0lhK4LCL^U`L6wWWL9&9=pr3AdsH({hqaY{43kFhAMqFLl&|{) zDv|}b3td@ba4q8{W#$=`?PUI2XjHb&lntc}crfV!4nL46ZS#V-?%$yC;vvIuIDspWjTQJh5x<+tKo-w}x||f&<-; zL8+E7)cEa*APlijT!=MAxiN+JWI=Ec8DGrw^6NSm`OAhElmAULNTr4t z^=%YrxiwWV%1<=KVig~9Ksf|-e@1Uk?tEmMBhI-zBn`4<2CnCwbbC2?RYYJFRaRLl z7PaB>jl)SiFa`F5YJ8=gE2xxUU|^m zK4rj0MLir2+h6b3Y}H8UDL3i`0v)Kjk#h_%XuS;7S|no;S~18-Cmn*e zSD;WT&R-?G)wQX|RzU-fUZTG2g~W>qnqndv)flpv^2PY6N?LmyO(t!)N@X1^D^Df_ z56}WoPENV2F?A8d-60py8g3)HG*J0Pbd^mhHQ7%V$}o7F-voxuW7ow7WH9Enc9%j6=CDQv)67DWe}|k+K<&A z$Vk90J~f&)-Bb}FfjR0s{tct^L=|-&cItqTyEPGSH#fB9Pp#H!!>UXiR(7kj25m;* zXNF8$c1y!#W?Gi9!-gZ zDC=K3xr_0+_d?j~tY?cRSDHmZ4Gf-sgg}UornsP*qb#f0VRqSH^9%WI9wb|5^^wyjc z+@bR_RRQF{+<>p4rNuE6ChG)=9mSn$7)v{JY9}QH@ty&jMzLr34Iq(J!E|@gvAegh z>qgNS3gk--Bl&7+r)$5;3@;k=uSr@J`iGrR^bWC*J7T4%FErXSencWc1%|kTwIoeC zd|@Xx)0VNr`9@}2GO)EWYs$w*X~ewomDLM=Ye$11@6Su1$cth2RD$XwAoe;SeD<;$ zNgU43Dn-46*r{CRs1Ux2ip!RaHrSSsN6XZ^>%Kkf;5qV%jo1F zUSFzR!-&B?7=ftu-IDg@LU`r0BbGJz!e-#VMT>rIJho#aBENMyJ(y=#C#wNCh(Glitp4v|}Cy<2hV{tMA)ud+v~GQ%3f);YiB<3Tl&PL+*Ez-t`qR zOsytWEPV6LsC*+h?OpF${tAx9U?|{_jNS^d=ILPc4q)%iP>ycMqwj_V<*^s&caC^2 zGf=n9V2dzL`o!)zZlud}VDwm|yQ<#E=4 ztd0n?A)~ERm z!dZqi355f2$M$1w>qtydI|W3t;kZlUq7q1oyBU+zA$CL?j99H%lQoE-h$Jw0V;0F|igS#w5U$_Nb`~4c*R-`=M|5cbjj!sB9D% z7oDY+8+K!0O^D*J#sgpRoo!I)40`GiRFRPa%Q?akJOfk2$ zQ2RBe>10UR8VoMf$C+jgglh$?;ee+rGAUJTjsElg*UJ#bMdG}8BaaLokhWeKusQ#h zB1>ut9&ab-^&H;#aN)i^qL`_g@drm=Ry{ex_@PUp(TM6RXQdD2H}`2lC_UOd^Rrel z#*o1?bV=wFdwVi)18rX~cXv*-ty2dZKAf+xK3=*SF=I$qeO%{152eNwj+8=~50EWy zsISf>1CZX9Cx)WAdB1NfT0KHSD$V6>(E#qkT33PmWl&`1RI7E@lKvtyElsq`N#DGS zI}O;ZfRS#KF=OHfI#y|P;LKT-fYnOpIYt21cA|ZB530z)X*sMj<}Tkgu1@DGV5Z1F%oD7zvNOVe_O~_w}julkJ z6@4E7-whZ0zYS5kIuv4|AJG}aI5|Ed9AURiwsX)e0?>&2lu?f3X>5o>-po!0|1X0t zYGF*uCW5Cw(I%Ee3LtT7FWTDQ(6L8S&X}AL7ZxjJ-w_IJ^baR%`G=KZKJdqNV4T)R z)XUrioD&xhC?cucGczjcet;)X#;{_{!^8_ZUzrEEB+q*zyciPD;3Jm4)r)ftFyCqRD|qOj`zRLiJ9&)VPuMh|FoGjpEFJNge*Y=Lz;acIt2>lBC*P;>!vnQDaCA#rewxTW2q4%|MT;r{p9cu^zgK0BHaR$*f+ z(H_xylWgX=fUL}h{lk2q5yywmhzip>|J>$U01E5$$i;ptWkE;cwUc}i40G0a&$|q_ zX8N_HlmqQ=5pifxevUxfwwyHlK45-z(TNQOtbgkQP#L1w0Jx29 ziL_<$bbGP>9M)jbam2+5%nR-Bg%?nvQ)#06D96tJ+VGefcjrNB_`?&t^WV-04K`3C z6mIyALFU$CZ#4TD_*PHI?!C+-vtP|?41Db_5f1zs)^|0-joc@Ohl1VtXZoHw3-0}n zc8B}R1Y^R1i&qNgk3w!ffnVAW?9;hhy1dx&@!;1CvH#8>_(JsAM9cQn{RFcKt1^ zd(S1)M(&-oTAOhZrABYIgZGXmJ;?2UfdkYJQ+{At)T~1f%BdCF7gT4z^!YC8SdYDI zWJS}|87?N?k=P1nk7uJL?R}P6s?MLL7pPsZtXQ){fWPVVr(G*V4ICjAVy#R=YIZr! z;WFx#H`_Q(oaoGj*^x~+6qy6|g9#=p9V58VQK8!_^a~BnuTPOanA)D1p0r$^uiwNS z)f=XWL3xAV$i(7%_{SbOLCp5T4Ze_yV3QH2eJg1R70%a`TA$eyNtbarmL_VRgfC!Z z<8uyH=^VfD%Ye0`^eGnBqqsg{tUdG6Jv*bjp(W`MRJLe7iin~jf6Q6jfkM+i^{E&8 zv8k=2q~s`#=mE|PvLCf18f=GLcVHrnfcjr4hv~5)zlvsGgwe({GGM%rvAia?Y3T{j zL}_dX&r|EN=juJgJsDMbJQmr*e|3_g1W^2=YgZWR%=$qHJ?%K8Trf^BnTN=ok38`F>n>F`W)eLp6KU*ylrCQ zxX2gx71sXf1$z2=BMmKLq?HMQby-d{z;Z{kp4z4#`oC zZV9pQmlAUZJ15Z2dAmugc$kahE;htlNyA~NyvZqKdi_)-?wvvhK@S+ z>a&=`7a-XYIpCKZb@JvP_(m)_wy$PT1wxk$@HMdFP6vqcA2RlV<6cv)^V+0=un&0Q zJ~59bGQIcUo3EUiK-)SSN2wOHN^<9I!p}$ym^?V~WN1R=*BNc$BM{5A7xT_*o?=}+ zO@%R*a?5xR?i{wlQmiaj_q|fb3IfsaD>(h`PNrkYNHn%pSs#&yDvuCFdjLPOLV@ z>NTP1u728>#Q_S%6BE|HDr~P_Dhd`(A*)(*1>b>;fc#GZYash1nn6+qc1I}%8^eBd ztsfQ8Cmqo00Fe2cbh4*z7uTZhdS5^~)Xae=eHCx1?N%Mu`X&*82}1DTcPbc0&|RH& zp0;t*yJ0sWOO>AGsg!+lSrw~7mhLj=qQ(Td9kgP~mYeoa8Qeuxlj(%%#o$-8JKbao$a!IuH#~wKk&wJ8ee8Z7FF2*39*5s=@uzqoM(OAs<6-EV=5g?fui`v3 zau|op>Er13c?i4TXPO7r@y~RXl5f5|5y+C1?j&DD+zU*i7NS3TN>KAwr1I_Lg#;~I zIOpi~P8z%>nIf`DtD3bL>!xTpea)*?SNXakvDL7NH;M~$`itcD2QM}I8s?|~Xfyv) zB_p_*HK#RhGoxK}dN0c@6~M1;P^ouZQq$^36`paz<2*UzPryx`mTgPDIOSQi2T|`U*-@6X;7N2qG@$@&E!|qkPM4 zk7YU4)qC}y=-L+GG0OvglV8@Oe5lE?+z{-!4+nnBP{4neKuu*EhqHWwXO{1KRt8q+L2wsDX} zi7@z~YjzHVYes2$9kZ?4@8f50bZ~k(<8uP#Mjm*_R6TyL{9ZPhU)l#MUKLZTry?d&mj@MsZPi6IeWbk+-OB_mprwYiN68 zg4c`Z8Z#m7Sz)Y(7?I&<_f*#0B}~^b3POt+Y!<%h`+e@cq{WS)88{L^|O?@eFsO)k~(v98gR(0|r5>$JpoAUNhciv9$d=(S?y~&M%$&>-|}efmjj0G(cEn}kv!y&gU;fv0W(|Vg%^R! zWB-WK`8s9#GY8H8^164S9TD&<2)3`}MJ<6!+GFQO$Ia6Fj~pXl3+HF^%sKa%3BbyO zv#hp+uFs-d8wSJAjRuJwVP9RSYev|-^|c|{*vnyEUeIiYJY7YANl_M#){ZAR8~0)2 zP{oLMQ|qUT%=5rp6P~slxdSG?83V2JDb971z3_(d-SzpPTV4)5Qt-nE$X$xicQ4K_ z9~Leha@=Rke$RTBp`UUQY2^7egH^g;#-|==xa{E4r;{*KWf<^7__(vwI#fWM^6yk2 z599MiPIy&zbQ|y*?3W24jCA3s{SEPMMJJPg*hLYmtjNEYvNUV5mSf2*CZ-EFw}X0c zXeI*KXXXq69!;CyKv5kwwr$d8dGa{N!x9M}p)36_F1#>Q4`mOH?Txz~s2xO7gg6U* zDb?lc6dE*de@*M1ChdEqnn0jTFs94cNl>C{uh|fL*z}VaPwo|w?Z5fo?{n|HQ_uC0 z3pi5Bz!9Dr1wBu0|1HP8HwH;6{Z>15^AT?;vg$ihpQLqRD->R&=$+__#h4m|svp+T zj#wCGZpa=KVwKUlU&;R)sqM0442M;}w=km*#4|wdgi^dYVhkh9PK63$H*ff?rmZHk zf>%z@#$9lr3E6u3;r{hGpv>-2oWgMJqN@)g^<0Q!`dcY>7)!Bt5%}m--(2>zTMgRy zbqokG9;`%bbE`}r1|2&*KI<38j@+`Q7+1oW!jV0!xi5BYx3XoJQ#hx)k)s7{jOS{$ zUKCNMfS~|-Q?E}*fk@~OB0SR+R#@W_`aJDbNmM|b39l2ET6mcR6;ex?`V?exYE`zV z@}x^`EIy6cFCuiO%=zra85`w|?d-x-s(yTBZ}Se2)aT0*{>@!jR0QP}hHZ|(0L~Cz zcI9ozv;}HSd9G9dT`Z*pi^})(pzwUpLD%g2__2BSWIAk`@C5H7GgK#&zdQ6fQf~}h z(p5ij=hJM&fP?yQN@U#v>@aL@OTTFM8JuL|=QjsPxJeDCb<|u`wEE_AaCjpH!S?1K z*bPwJGrBrdt;Rw9hQPh3C@%iZGXxInDN+V@_~db7X*dsYYMloO7d_hZ0>}|&=ppql z&8INdaKIZ+NdNL)nD1)NmJLgMm|jF0W4swaX+M!X(KfOv!VN&pi)vY3|A23(hbL1C zub3VYh9qu*QZ=i>JrDxaj06NqI8UeJVpg>4F9uasSm?9HJKF{zI*XhGWI^e`M?%~f zb3SrId^`#P#*kd#xoH@}iiWUBSTc}AgJDifE^X37!DHPS zwbWc)TiQhI*Wvidug0cH2q^4dp(MmssJ0PXgiM7VxbTdP39*lSr7sCO$F?Dik`V52 zqt>vTxZUIK^?zUuVl-dLUw%i^*K8>P__=4|NiWy8z^v$BMI7BpAHm=UX><$LCb8LLj8jJpySN9TT!J8q`&<=E)BV2uu$kiE-&5uar zG;5iy?b@`-7Y)=;mK?>#vHm{f(38_qfjM`#NUYAj-IJDP1&q zk*YdQTosyJGv_h1lIxDxCp%lRl@Q;YZjeFNo}-!_@yk~CBS4sfvYR0Y&F(`*K?;}M4-MuJFj zH%7i}DK>+!-|*v8$e%qha@dVE3}AXtC)A>yZLK}RD<)5{CU;s@_+W}X2_p^4GonPw z|D3el^O@h_#GB0t3_DG`v}O8DB{l`)8Fjj@7Jgem$%T$1a^68!Je-i0ID3K(FvIuk z5}~#hu>Jg5QO(R*yylSwF7b1Y>I;@`HZ={|@T`(COpgW#bfjvLU>45&FzavE!jjM+ zJuB{Bbde>};Gly2nXD(WCv0f~Q-Sg*5wI3&wX2uyLO$l#U{39I6UeN+!Sko+239o9 z;g1VL6mw~n)KzH_W5Ri-UHQGS|w%eNEg|Am9>Lh5v@I=`yCr_=gqyj<~hdfbI9-) zFyN%mE}OlEe|?QBY0XBzV5bw@%XvjwyOy0g$FN*%K)~Uyr|-vDkX>w9NsQ)WR}9;TqX-N`E%L@spx^h$IW<4-E~sUrmJx^rJECjdjXgmpWU&35q6OP=3T(r9 zU5i#QZiA`$kr^l42HPd8)WE7&D=h=He`|g=!)-=h3{>hkjcMAKp+e_Hos{vG7uN-o z7gjwxe=Fj5agZ0DX<-0%*q?`IA8GYn!T*fQj2u^d&kxI@L*cex-yoRg($)uHpdduN z;hUIB=XNPLqAO;eFY*ilW6O)-yYJ}ARUu{^q*YztZ@ z_~_yaV8DHE0^QtaXsF0pReQ-=<5fsPY>MkbipqT;j_X9hK z?I%f*A3V)V28O;fG^X#ejLpB!}#v)&3N<%Ei3NONt zVRGCOt}*2=PkEgg`3>?9+G_^9z|u{>8XD*S$b{mV-(Sz7Z832F&YW@-QT=-!p0T`y z5NT5^8n@u21gvoe+tEA14@fO7(a_WhysT(o#HKyGb)h5_zk>@XBO(ZVRcN!z7EE?X zR7m(%`$?0;VQ(u=;DUY{|+082o$zehhQEtx=GgzNQS;6(}y)pLDOmCj>Nxw*E{ zEn*Ri)tD5kq!^=Trq6=^QS1zc#CW0q8R;SGr=oukdcS0^kr}ujEj-fU zkg_KTJ&d962}FF;G$f&NX*G=WLc;z(er3uZV|x3@(PTPvU~Z83UL*H>b7uR-97c_4 z0gI_snxu~P|`>UZuyTn~{>^mHH=RiGa_E?c3Y>~xR zGsx+bHTbZl&(_Dv{n-@XNA`>Z4>mqhU56}j2(A7oi=wkxpW(2zLvHKpO3FwAU<3M0 zg*GRQ(!Gl5KC1fLxXn;}DknZEDM}tq|%m z#SY1C4p`6#|H%^Yf{@{h&+!VW|8rh zCtP1Qbvqs@DDl82tUKP^VW>u;-)ZbQ&&sJhg)BuOQ`C;YcBvSCtC$FfHPzn`EbQC+ zm4#eW++dU+B+EaI97QYt^|l`yFjM?+%;-_(j!OgfKixKJs{s0Py;>H4Il`}cYtSxc zBs_;;D=+g;eqBF;$uk?~U?H=?yQ8ZT@Yr%S3wD=|3NX}MMMWNVh8;>E_PC~2P;rzK z1|}d~34iK*A$p7{Q9<+{bOs<1Phb)7`C(nDdc9k2J#>Gyql(aH5VEas{?cLC{5^(V z!>k67Yr1z`&sTV{llB{Tl?Tx%r zY*-CV77O^=T&|w?QV?w-@YYYL;eApJ5#HuqFcw|_oQ0(>l|n6qu{Jv<05z;AyzDRM ztMX!AAJ$)+Nd*737xp>nugrd!I(wgDq14$9=X3iIcD91#HYm+4PUyF6@CG=p4X8ZR zR*;`xxs3x_~AjyA1RH_LCoVr7uT)>wXbN z!>~!p&&S@5(Gvow1<;FSl|Nx?mb|itbAR(i4kz}hTrG7VYOc|S#0l|U46zD^8m=+& zUOX~h9LR=J%W+Yio2Q6}3kC}*vcr`Ex9NJ-x8&f7L>IyFGb3^?s)J}9QyXaBx@)nH zttjeGUrL$FZr51ZVw76?CR>ej&4?D{b2(3gQZ&-qHZ0sjhiMd6BjK=&K#DL?QkoTm zNn~+pe#rEf?hIiZjk?xaJ5rPnT@-x-DtchAMM!RCDx{!poB$p46wTjga5}#(de8fv zB369Kcn?6R*3_wI(h%*6Xu+|JY@H;+0s&rxj}h|)!fhmfBgYa)QD1nQ&#CCe4kv1| z2=uCh1t=(e79N-zAqcb+Sm+k>NZY^7;e2(H?#YBu#+v5RpXG`dr6mK#SlSI)5d$Z=y=fteP{WmB#`W6q!mo! zD_wVlPa|dz-WjTbf{o@mn|m#DwJFFioh#Rd;iF~o0#6C5@}-X8R;T!(^hTe;LkZ+;!L3FdJE4fyq=?$$VsNE# zU^ZxnW7;}GkW`L73w$Ami5}mU|lh2K*34f2j&Ws z`4d~c(NatIuo8o)S7s&FE20_4K$t>}aUwLC6&SWwp77Tq{j>k^UUo`E z2`Y$E(s1B zI2D`eSE)f>(2)Yc{*-`Ice0{j>?Pd+X(=tE(Z%?TCJ|hkhDOG(*wWF4yl~qY%f<(y zeK;ik$RhnlgqcEqle_2JCsn~KCM1Lf=@#K9B!`YRf^#V;-^FA~UK0gQDZ`=x15auO zsTy$koO1%E9>fS%4kmb4j<1P5{HAH)1(H?Bgl*;c{3CMV|a<}{k)ofKz+3&(M9|ec4~7JUy#kS z2}W^tfz}<)v>Rk*U$|p7(Lo7JtqW&(+oU-TTUySPINJi+YWJVIWANlSAk(a*1aKei z#zvp-o((guiA`7%y8F3gW5R7cB%Ovsi;d{+eb(n`0tp!cg+!asvbXJwfU5Wq<>(~r zKo*fn4z|YXob=n}^!B;BxXU|!J>da!?37GkiVw+Bqjvj(ebu9vf?~=oa;-1xMGIzG zK-lwK=X7LjK=8YL?Gh3ZVC%sLFrQG4l$UW%NYVQp3zFVJA>jo@rr3_V7hE%6_FzqA zzH&=GH8>8`B7ZI(iM{FBzIAbs8Wnzv5X&o*R1AvC(mLg^2l;xo%rDXTL6rX^YMl7f zn7FY1Wf}z#ygCBl@zbZrObEo*I!m%uOQ{lH7G%?@f-7uN*Zls10D?1*r- zEiLj)VAD_(4gBd?>>Z+=zdVFnzwd>Yo3BG7kA^H#j*dvvCsNJHw5RYWnL+*6cb#6MjEfy>|62#JHFhKM}rZ?2vNJz$xXZZa3 z#}(fZp7UVgY;yo|0?I}vG~Z=^O-{K`GkBhc?yaAw_Ep%J_?Cm!G@O3+^>cWRIW2u+ ztTY(gqhRjSjZJZOP~PI}X&lFqP521c)}~&uYO9YFw#)s&w<~bSt~(tc5VpYRbvr2AnmN*{H2%i}dF&>rXPAxI0zyc$l zwQ!ar60)#A8}J*t)cBM6m0kNI$raZK#sJ+Sq?KIL0HS4o1VS{_BqZOsQo zc(v*TUinlGLKzfNo}^6#xdCIY-;ejO$y#R?zT;?!=|uN6OuV#r}LYr2U=V4*1DNC!b zaM2R+_!*bK?kiig21{Jc1@^ddpU963Cbd>p>WU&hwPqNhiCsfnIDH|lD&Y@*v36EE z3`3)MFm{>6KRPDHpmL7!A__1nB~>nmqXG>J0@ zf<^$^gW}J2z_}2q(XgtZ%2zul@pv&#BBL7Wdvx6kDLIFHs3Ioie2tXE^W-L^EV%)A zxqWKMFm3czPIM;Dn9+TxBHY>atICiq1X%hAb|WzU(igLDeM1VzJ_1hnpO>l zU%r9Q5(KKYNl2CVTFjP}?0~^xG*cKLYt||XSqZbu6`UI?q#B2sisb2v+wvpb#`eOZ z6%3(`T;;A9XHkdU&e^s z!73!)`6I*bmNUPL#u_1YpQlv0^fcixrGm+DWet3WuNX%@ur&s0j&*DbSB&%hc0#7ZJAPnWSFBW9(>t{58@YD){_VI_SRCo2WAeSdzc<}EWSE? zh9~_`pgyepX_;8MCjZ1ZF;QlC?nO8raH;aIczEL~#H&!shtl61r&(T>;#tTWmMPrh3C>(A3#Qw;TuCU#curS2)>HHPjWQ0Y zuxLm?E;rB&rR1~mgRL`61@E>Eo30D(>5(USU@1~3+C>31XEKq)umIZB{58+jlc1zZ zjWefc={YTcz!4o)rvd=@XuF~db_+&==hsm%Dzd<6IN%hO3Elin(!``(J_$1-aeYK#%L6`1Sx-qBKNYLr$UeeKLViw za5QZi$d554J=ti#T-@LTPd|bn%he5KRA0jP>Z6+-VzMtj6{g#AC#pHm6XEOpjKV8c zO?Ks1rE%V;jr0%)!_Jg)o8`&u*h6caY=#tv6+8}^*HUYAFSwySY&a?dObLm_^0R1u z&K4*q7ib&{j3<0V%)ZD7t0bxnzhD}Pu&+oN7*>rM$V)e?0TELJ2B+TvGx&-uivL`K z+V8hD5~xsS`AitbQ9N9#7^OLJ_0oI(n<7X`2(g2d!L=3-1jI3T7zboFMH;9jy<1M+ zmB44y*cqZf2pL_dTX;&cmfb!nW1DT3UXn#whwHoiy7ky+azW3qn5OPqmE8IpG)Nz{ z)3VLlA&efqZzV0SWh8|@)-w&pJp_uwHn!zFTAB?Um9&9(mrZ z2w5H>@zAZSgf!cS-o!+i8}1>#B5%Q>F+d&dbp%K1k=!DWKUZCuiY{*qz;@tz;9nP4 zv6*)v6&)8l?962EFh&m)@R!srb}Ixv*i9LQY~2FVHxd0e$01|=TM7;rgf%mMvGZx* z>)=Hlc;*scNA}U&Q8|cVWFG5(VJ%`(={F1Njbp7im^@V9gPFM<1LFS3sCdsIeb5A* zw!2?d_h*LVPE)kjdt}FdJprTUE&}yM9LGXIN@J`W6lU|n?u6`g#Pt}X)|Dcy{p(X3ek@0fsJh)D$$2VczvOC zg_s-n$YK|p$8C|O>5YGS%gs)EYY9K^rD=@2Mtl(s5~7TCqoMjvV^m}~Z1V~vj4Oc8Zv~nU{DD_Mj!zhetesZKO-{kJtUOlrnglWF0q_0j6@#s=r|_sibiC z$6PEXMk<9)Y*mfQAqV+!BdFQT%B3PKP`O-ht5&ZA>2{+~+oQ9lqlBgcOaWuuKL%r% z>;L&P&kIYXr{ADdKE2MuAX@o#KDl>b_Up;DNR*j$XPY`sndhf+cQd@MrR9`i6{1)+ zlY6wzt;30W9MtHEbNPx(_Sp5F7iufLRM->`R%na2p~kf%X3gQboK0|YNTShFCCqL$ z$cs}?j{0%oH%X2)!g!R>_dd2#br4>~#B_8~l%Pw{;wD6&lGuqsR7s8K5{$-_Vxknj z*uvROpAbUxr&tGaHNKpsbLf*6)U4-9|0xGH&Z$p_zhh(GVm zRL}iNc7F2-lUx<4SM&U<+gN4ouW@gY+L^RwX2)=f1D0X|Ek~{jg`H!18G{Hqk)R10 zf{|H!8IW-?RMqq2CbgFM2)mJw`wh}9 z)$L+d&HL%kq@4dp-Pdi7Wv3d^K1Bwd?W!ok@zaE~bl)qKq|0 zh@{oMQ$s;I|CY>HrNm1m)cpSagT`VFrs2gL14YW>Bt#w8+$+lA{g|90(~g8UjR5ja z{6w5KG?OTaB8oLXKG(M~;c5jCx)9fTIoN+A?O5os<%kr0MOR+uil8Inxb#ZW{@Hmw}aw`!sMPUdls9Iyn zKQAsoynROu_6QkM6=nRZ$w*MZqvO0HZRJnXE9P^&-X?PetU7)f?n+ zRXxg}iU@CBrQ#SIiYthMUr&deY4fne#iwS?;b?p#Z;R# zbFi?4n)el*Lp~wF?J#vU38uJOQ)};Fmm4~3A1+?ag`V}Z!PMRplQFe4!JlQGZXlIdtErnDy#Lzf?dkMI|;D24A8NxD?z(+Z{;Sm&b5uo53`skn_ zXg+~tO3)TNT|YEg;l}wEde~DPQAR0WK05Lk@(3j|>IJkp94sIYQ{>}8sf2&0e}UCV z&d1|Oh`bXs!2y8q*BTZMX@yg5O4Rx)A_MlCeGVTdH$x8|xywK&JBxvnukl#Xv*7^~ z?ugvc6WVoQP;yI#>?+Gpr(xtJQ$7vg8qdi~gDC=)>${pyY;x9AU$zgWkJk$sVmG!7 z;h;`j-s~47l9Lphb$`uL=e^$$91~LOEIw2I4aXfCLO80}Es}DhFnM-G= zEZT;?yMQUpQGFy8a?Xjwz-J?8LMO+8r+Dl3G zzenljZNUKTYx{a?-#kh1t{GG;n;a>&LYn~*<-Y+$ue0#OyLUQ}b)@*?PF?W~@#+Dt z3r1>p&dOaq(z@DJ(nz$?5*mCSY9>dK$naVF-@JgOvKFVuD7~h{0a= zrZJP|FuAUh<wzJuYd2Ga2Cq>_V=`o-LM3gx&&!RsZ~0Q?MMqr~ zqnZdeh=NqBJ>ucxSw|+}MQE^bwVkh+uX$MTt*RqxyNAmI%)7a@t`azPTuZMrM_KIf zxhvsld~B2icDW(_N6)}QHG(EsX)@|HvprQa1R~}MkG2=H7RW6<;?K&@ARq}{Mmg&_mkAhp7B^9Jsr1D6k$-N-_v?mO@RFQ zi$sa-q!dG^7a-9-t06Qxoqp+~c_cj#__O{BJ&7>NT(7kEy8-BMhPk>F{<_M{Z*a-^ zh(P}-T5IY=re0;=)3XO2j~JZ^vNT-6^uyrE8A6r>`Eml9@#t_~@U4%tWus*iiEv2@ zxk#ooGf5WFBBNroAu83`vc21Td@>n^YLT#K0R1->5$Y7tcsZ0Hq=^AY2w1nM4m8k? z(9Jp@;oOUCz2F7O z(H4qf+0nQ&<>c4iW?-{}3cio`TGHa*T3cBP0_HV`n_6#7Su~`hz;4+Rd*x)fO?)91 zP&QgWQnPwY&;p5ph%(kDm~^9<$j75>e`4r%Mz=L zhCk{R-+x`+AIY`ES`|SH#2HxA+ti{OM(iEyUi~R}g1Mam*t0Q{mT zo-QI-+11c(6jaw3ua>4naIz>ZhmU3ayfvX~KQuBag0p6J`q%k)VM%(DeFTl);)XE> zPa$18Q`u!A4v}i?5Kx2~#|e8mBm+$@+C(l!s4K*q=h#N)fDXou)wVj%oQtGm zOlQ+R57;#k5P5hDJyg6sIx~$sC(=3SHHd@1Y&XzZg$3vNH7d`0Bz;(BF9Xb*^L)#9 zc=kjT8U$%18|mxIWtBF~uGA>okn~{$S5VbB1DCe!{L1y^XSwwK#2Kv_RW;sU1K`ua zwmu#pYF-AUjcC}tE~tTgT;QB~Zbl1MaC6&yQ(q%OLPi~{4oKW-nqzabN@PoeP-FM~ z&8T0;Z+6>oEk)3K{&G1CWKg$Euc~MyiqHjJ`;i9`u=C|pF`-tfE@?%vlr0Xn?4@jh z_2^q!Z==p$2!tbWuMy+SZ?p#)pN8!W-jX52jrLmq={ zvove$wO?kk0Xim53+S>Tnys22IMZQpExIBhcN>TIL`f$_p~jRx>0ixYsv%&wW(IQ8 z`pczC8x@BTF4xqjP=!Bxu)z9V!TD>JP$;-Xw#4-qv~KTLaD{~E_&KLV^5A@}E8A;px^3bn^*QO@?9q~{??Z@IA zDc0HzjlQHmAFiOCB^n!LHSA1pVM`+XNfKrOL=BTkM)h~amOS;h8?e9n)kR;yr^`^i z@!5*LuBkc3^1rTOr$qJ+73mRnwS{A3lUTHLje&)TYqjGZ-Qllv0kvF~(g?)k;Z1u@ zVOT?p(n=1q(BRyC_5R(|fgUj5Xf0d$)Dkcv%NxW9pah1gPt9(O9)~Yd^#7X#%$|_9 z>FO|d7Xe~`gG|g@lAT|n(=n5q_i;jhx?$YBWCL^h{kcX!soqQP>6{2E>xMcbyRpQ3 z^4ivq6&JVD-V4~?n)MtLOLje3Zl|`_;$`s~RfD}ejVeskBU;!#g8 z%z{s_EK83Nx5{(6`41vgU>`)kCJ^=ab&ze#P0geei+;}}{82180u&}H7umjxnG{2P zD%|6>TjfqK-h--ELm#Slsimkg$P?-jkL_o=hY?ZDkUpSQ7L|CO#xKik^_`(Xz2=_b zZKc;vbUVev>-eF%Sb2UdZ7PYtTQrLjD&NZzAmo?OjJNS~0WO#e)ZDCXUHXoT2^FG+ zGcE}{Y4I84P$Uvo`CW1QNt8A?yZr{eI^3`!El62ZD)1q>`pXH`z~ z2&afW6)xWPFbEe>Op4SSSZELr90%^a`E@f$HM$C<_Xkf!u zLxK5VF&X@rz_C2e6mT>OTQTfX!H{ci5|2pg1!|~0*OaQe8(918!8R6Pw=Av|_tUix zpU8_nJSCuv5+4jOE`~B!Mo7B1%p+sSC}^uDs!67X0No52C;mLk|1iI3u3biy#SA8g zQG$QF+eM2vB+>WmS{X&71C_o5Ze1IyQ&cll5qt&mw%bgPyz0fFe|Yq%-l9xSLqrK!Rn zraP`r^vJ4;i9}KIQ!o<+@CvJ-HBaD^I)C|9RtwHo=~SKrXuq4~c{6EfgAscPVIF&w z=2kahq&V2NegaaG7VYm{MJSj0V)``HE}NdhqMbh7e|9bxlSiUl0ruGpX*EW4SqhxO zLZ{%C&b^5k_^vtfviYANxV?K&A;~i%bypSq#`F-_UKnae$I(3JFHl_8Qs0}K@8V4_(P4E4!61K6llaFsD(-h zSv^S6IVtA&#q$BFIyP~ECNoH#&#f9ydLJ)(4mfjQgS4J*P~E`nwH10+fLDyc@Y?6T zcH{-lV@Mf}xcUeGEHYOSOgA#Cg!uoCg?O|H*hc;5fFrOVkdAv9MmL!rG*@t|SF@_t zB54RXwOU64#*OPBj7sgZlmExW3YT;=VFBzCpU*zO3~wDk3nIIU;ItH@6=$ist1Km3 z@NG8L9v19)@DR*vtG7pGU>RvaaR${wUq^9~bJ}w=XEz*G8c7_P>1u6HxmlMJj&ar? z3vI}S)Z#xUMuJT?{%F5L>a zp)Eea+zcG3WlWg+X2$v?yo{>!Dv6lG@K-oNdR`#x{d3rDVnXwxO7?#j_3m{`vY|CS zX);_3Iyr(&IcHObJ`+~FY2XXhbeUNzpGibTCiu$6;FnPr!kp{dZNMvr0qw*};a|{E zRl~7Rw4DX)@;n4W;h>t=5+cT{VWpJFe zZaG7?Z7cM>X-&UBoD@0OiLfNf%#a4Aki~kqb+(!mdpgZi5GqJs8UL;@NyNu1L#c5Fa+6hJSy}7}ko@81) zjSCnLeYx7c<4tOf?b66A*lGE`hTLroSv!^6({E{|r0Y9~q)XF%JW>AEayM(xOScxK zst7=v;j~t{QR^1^wfYM2Rl}4UD>lq{hP`obF6c0m07;p6eDcVg1b9}~5GLeUa4ti~OQc2j_Vs*HZp%Cap- zRigP`u6l^4`!N=ETOhv%PcEu`iCy&bzp);MkpKyjjXbHWLKUVCyV@opYoVZmhFO-q^fS%;YSD7`MEA>jOD+N0zO?n3u9T(dumtX@x2oGpDj`e^SV( z;e;8>I8}4(aP5kX4`a-fZ0#?x4wkZn?~U5&J_4q%OwF0Ad#Y4w2Y$$+cSK{~q_+OQ z-d|U3Sij_+OtmuwL8|lMhs{k|ent*xaZ+tR(~z7ST$Vbx;b&Id_=#jkdabOFV^9#$ zjj49>4Uyh4PYWn;wb@ZvY^Gj*R)0a>=&M3gfp#4{9&fx#mN0L4Q>4%);z-H}k3}M2 z;^r7Ib^Qk{ppivK^f^8a&uxVA(}@to|MY=nsr;tz=$!UVPG*US6RGI6kMDI+_C4ck>A#5}kG)?=zR6VfXM& z=wccZNN;cOD^0N{HNv+jy6%f{jZ{#C#L<^ZQT5U(eJAid1YA|^zsz@)g{@D>v~)gu z(YtfTW3FH6$Jz9$RAL6Jh`!k^3-v-_`r1SmJX7CsETXRT&7T1h@@6_VLNfeYl{!CI zzvsoAFkMQ%hht3z!}<$D4ziB zcXMUp-mrb!e*=7q_ZpZzTZxR9l7o8bAas>k>SWalP6^o-9fN&YSPbzK|r|@sm@O2 zWnyrL+Jz)Tas9(X^;^*$jQP0J8)BZYdAV&v$Hqr2olNi5Vq|ZFusc@04lZP>OWUUi z?Y{f}!uihn6TQt9$^(z#wA;F~Cco5X{-qB$rV;A<-;w%7v$d$-8u?=&<(!lKQK>t} zS#Eo)-y{ngl;jn1R*7CvXYX&!KZ1(~6Qv z$15x_=SER$Or`RmlzcfO8q6_LU{JowB400>bK}K>;M;37Mc*sEUNBk#Ym?&|!~&xF z+!tHEX$0{&(L$W>JU+@TCjA`9CnhnVE#)Zz{O^lE74`W0n+w`IFpBihHtiJ>u*MiU zs=PGkn<{gY01RPb{M;=BOtbZLap=J#TF>$=4*vt`Z<0^_;-#5DrG4OIhl+k0U2n$A z_vHW)%(nn*%>hf5cDuupB7!|1sE21~_#Kl4UZqVObWb9_wHalmMgu|JY2?-QI3qOq z(EpWvGa5$nagZ2H`<|`p(8bnYWscTz zB1zz-m05Dk2u5;LOd+52H0~I3F9^hNq~u1r4lHb@sJcr0Wg|{g&Ry z*Bk}fn!}D(JLhM#FdEaY{GVdP+z>50f?b(BA>!uI#zDt8p>PJU0=}mV@A%5B(Is#i z=lQQxGDpuM8WlH$OeA6hSgk!ypcLzQvn_zrO9Z|sYvbd6kzbMJ+W%z0ky+b_s>$pO zb`|t?_qpd)U>(EN?&Zx;sw=^HGi0shs!Ga8FLC$Jp__)n?{8;*t;vv;M5(cwwoU%A zpurl9+_9DodD(h14t*LC3DXIu9g9F_%zPdyaMUw5+7g``7VsWPX2ehmlL7Jc6^9pq z#}oA!kO!5k@eFKvACb2w{jwIxOa4oYJ)L1T6G8=J*}@yr3a#)6I~b z6FDj3z!g%v_KV%0Rbx`p9pH{Hg!~BWtFEchL+M|rL2Z-C=-66d%*-XPl!cN_I>oSg zqR*sCsuH#gaHtg!StI{_j2kC@dBV3VcrCbiSd5xCutp3NG?Jkv?@Yl{ZRf|d18++e z08v0WZ(9Ktf1f5)2?bL?w?3mzxn_ZM{QY**(5VL^R-UXqGeQT#jj*gQHX_UdEy9Uq z+4fgYn6~G(Uhl~d)P!PYhLRuL%co*@=0&(@`s3btU^<#t{p+EwcEmX9{5$ah zpL{vw>yS4ITjCI6-A!;Yw3pqI%m~zC^8VbP%kp1sBkNB;)j7=uzaHMPQcn~2d>#Am#YUV!Zmo72nSfG+GC zHG!9e5kefD+*BLdG_yG2L{Kz0f-yP7vaBOMFRQY|ZVQnC{wm+h%$3K&dNS8j%IZaW zMBor~5(}bGV)4AOi@Ic*JO;^|2nDvi)Uc-b3psVg0Vq(<=DSwM5Tv8EpPzW*J5SFF zIo*WN*Gw;$q2`2-X=nv(M7wx!OT7R+G~Uejkmp6wx=mCVMS=0@VQH-()ohO&TpH07 zEtK8e9aC<$pWvln=Q%ufnzo$2;FfxQjqHaMiF74o$sHEsU^?vc$JMqCnAIzr{d?cC zvU>V=!m`RY7k&VA%Zf2!bJjV#;@k|AxDpUq1mM5RFv7a5jodxrf?c8DtX#1rUU;EK zu0=L>UmxSjv!;}z`l&Igp{_<(p{aBN2cXpkm2dDDC8tG8EzsDcTRXmeCOm?4B7G+O|w>>^I{J$(VaVDsNl{N}1ugG|!UEk!qm1UoI`bS+MG7 ziL1~6=^45!HI_lZV;)gQRWg}tl`Ga({g5BR@x&HP{(zc{!hjm%oT-6s7Nl@8jpA2)SOoL(q z)}48EZ%qjNq;$3vv7I;IBvvS~3l7Rx5pxY>*!Vf@bTntJHUNE^^X`x>a^mGlWj+3i)6F7c6^DB5V*06K5%$5kadY{K% zfD9AS@Z=?PTY}g7kh2#2Jw&y&wFSa(GDL5B)#eu0xWs{=lXi1=H+%2=2U9IFkpb%C zEb?#KZd@e-E&onm7@+pM)srIMJv3=H9AP`~YaPy|+@FF6GuRlh1cju!OJE&{If0dL z<}ywg%#3(^l$$qB1J`J=VePH1Bq!xe2)AFE_bY{&JH{lDKrB5Y&RO8xxWkZpBQ7D# zhCpSp`{+A1@Cnm;`-EJ+@f3lZbYNB`EF9!%k4U3X%iiIoB|rJlf==cc-xDZg`xVG8`7;GX18yGD25=ouR|VbOU&@nCk$Qg?3i zku8z-e(xM7MW@^h5CFj02ePypL}majx!y|}s8bJD_}v9@?VUHtfQv;R1uN|x<>cTJ z^g?0Vsk}XthrRpms92m}#+xs;V|y*XK&T+iHOQ}*@bf67KL>?rOd{UpmF%wCN|7D3 z)J24WOK!uXBsplTKW=-HeLX%n3w2>>C{DTete`s3qijRt>t^1yJrnSJMy_3FQy1bf zjb2;^PStYdsH)ebv@rfeZ12}-mBY~d=7A|N3&F_mh)-mO4#AHE`;-rU6_1N?>4Yf^ zeokttG6v>5_RQuJxM$;z##b4N$vU@yGf#*km!NX#X`>+3!i0c4Fnh$1n$su&HvmIT zX(?x`6Rob-uc4E3xtizFcCs=0k>;O}H^ej#Z-=4^6nM!VpPI}RSWBQR8qx@-aNwjE zmGRqwxNLH+om{fZ?&04+$=y$2`Oio64bC8Y9+Re+pAOxqJ-vnxZxk1VzywfMQM}?! z1ph2{yiUxQkL3qu)2{PgtHS#f?W%k0vuLd}G=gO)`zL4S*{p67BTQ*ZHa4NNA2Qc5 z%=!dfd2~FUU!iE3Yz@~2QkP<1;<;#mMKtsMjg-!pDYEj_pTCtOsoYH#*Lj}>n0&tT z54juRKBFv&SxE1Q=KY?r&&hQ0ID*y&7wz%i%Ks_M(PUMV+~zSkpnoa9)Ex&_^}*@p zH$zk#;j)&)?v}?%+$PXI>=LFnfpu3d=hTtTUu)9ofciya2R6Me$l#U!)F#Bzts<^ZfZyj!AqTJUM9_ip*flsrp ztS8|k3wA!z_E-l!0fw_LUC`2(mapDEiS2S1!V78>77-bZk6mMH4BT^gt+G#Xs*F1h z?C$vq?LLjR1Vf_bBgZ>4TH)&V*XOnnikp|E7;gNCfc|rV9BWbIMXI}l175|6`Xbl}NB`)%XK9D`}D)%8QB#8Z^oVGbOroq$mLkPj+|?22%)`kj99 z*6vzKuT!IY5jb0IT68=Zh!_R0q90WrlANN6eehIqxK4X9;Cu@KEilDAQQHlA@sbU^gTQ(c$g71to#;jF#F+6ptlm}}LY#~=Y z<%TyHijmA!34UA*qlS{@{?1%QYh2#OSjQLb&H8X8>`_GN)5G#xs~(OdCoKabFVYUq zri-XgOnZB*=gR<093|`1|H{)E5^ZudLUp#CmXO~8ev(|0njM*{Q{{gEeRGl-W&JH1L zq)I&*p&tk|1b^(kM~%T#Q}Uv+yRz+r^;$jyaaslY(XDS3%jCOxM?*SX=-(Bh1&#S! zcMR$QAMHeV;m(o2MmVudn@Vm`MDgKOd<_Ei56I4!1%FG}K3pyH5Kr3xf^s8??+$6~LuFNv}>)aUo!87G!k`WA_-R{^EstGc)&;LsvYQD-b{qDSn%~n%*4n zmCnwy`yzKWPOiinULBZ#*;had*$>XBK@4jYx})FniAJV8MtpSQ3xz~8eufZw$bLIz z3bf69gz~Z^I07(m3)4)`6_hffYI3W45ARE831Fj)IZ?7BZwhvw?$&19T#X%SGwJg$ z(&ec)Fq^FT?`H=0UJEABqx>KwLiNdyjR8|=RTkFK^b^pG-(9Dui-*B%0!J&RbYInK zP&EI~**csC4l`v&ML~z0e_%pO)eopJC-hX5p@dvh%R_=6X6=cU1yr-av;wo%I5nKM zfiWtPmht~+pr_4XMVDy&+oyc|Nt=i}UCVaCYlt{EOsxJBXG46z3bCOczQ));5y9gx zxme^THj?;>QNjon!cJyhgc3fq?(@JG|Di|3(h$Y4is747y=5EZqONTa02S>}$+|B6 z-J%0UgHQ@D&>0HlgvBPvHiEC*@Dm%=aWuXBN*`D}gue?m3Rm}YeJYutV_gTCWm+NN>g*Izf`tKoev zBHBDTo!P38h0!=Y3B()+ibV6g?0K`R(pG* z1c{A=`JsJzrQA~y^{KHUWR7Lc(n4X z8FUzluH@kDN|A@oSfB%ST>W#ZnV|~SY9Q{!j`|5uf2EW zPLVJLJQtN>mvTOB!=gaIY#&jR3!WOH?rX|K8BYzj5lhN~P5SgT4O&8p_-MuZMh4RM2wXcg*?gHkN+Zb^_27Ww3Z=W+AD} z<6RZPjqhZ03gu})K>JH3mAwLOHdvU@uv+`gITN2kuIUDi%vQkQ8D0g*oXwpLkYjky z%1G6CZz#X$%WYOsw~53sH@@e2yj$+UvwbW)I!{ENnzXu5ap6XU8bEj)8KeD)4?@U3 zMh7?-JwB99adNdpJ@^6P9jsFVy>*)d5{C@#2|13nj_>Rj9OqH|^bA>h-Gl=qZfsp& zQ?7b(ZN4bb9lPOB(-PF&K>p#HX-snp0)im=z5x_G_7V`fUq&B>({Zod zL~Z%mzij>01IAQJrUCMtV>};R8(6T<1E{q_mCetSvC&mX{2phWgU)tJ0A-L2?x4hj zGMFfuA4HWeYUt+>hShzd85m@guFYux1s^)v!54MrF}GxN=}c;Se2GU2Q~Dn+fGc1zXAe-Miv)k%bX~aHonTHZQwpG zN-F+mP%%bU2V)@&MpDfIB>_4qc#)9olX1hqE31~Pm=#Q9EfA5+Qd-ibTmPS*@!7}A zk$ORFfMDxzBq9VI=-idyc@#D$~SyE;xl%}(Yh7VyImrf(_@?KwNDcP_{0 zhCJH?yA?dLrP=;)R8N%@LdU^e!+*5>t?G5Qc7X$HMOB{QV)vx}jjdsA!!WMez7^O) zz%H_>2Vg|&CA|`~nnC|{$Mk+aZ5*uA7=pV68CvLgg#ppw#dqozh|qbD13KO-TUF(S z*QhCA3okQKbxjhHQa_Ma`(`6JC8ypslVhaIku$X|zn~N<3WfU|l6&d6bPIZ1JW<|s z04+PqS^8Od39A(LK5!tb@w0XW*>?G529p#5d8c%>>Pj2qovx9F?8-ZziMwd&kB5zil|M;$X#$}R-AeEa( zczqjLVx$1(fewbYLI{!Ej!xse1F~)wn}fnKLk0`shKlP(84!X^A=zCJJ~Vv zNSnr>b?Lm8sI(_H&!t%#nWWnR6bjwrFj1lR;@D!b^c{rOf?|1>v8u+3H%^<|15ge~ zbQ9a(t+fCvh+Q-~uH}Ig0KgP+)#+cxDWkvz!059#qiMu;x+O{{+4ucNz>vSvf5Q}3 zAEWVG5U!a`Y^h1NuQEamimYT+Yi{x9wt3$Ly6@p7g@WxqK_??jcCx9U@B(D9YH(AR zOoWa=$jpVYf?PEsU*wB6&_fO=C08HLD@rW9fOaPB75y&H*M5*ryR{@VK zi{mT98>gjM+DRjrs@lX-Kb|2aS?X|c=TR!j(mBpXdw-m?z7w7@g#{}{*i#A{!@YCQ z{-BrlD2$qgmab*C32B+jaw3pnrNGpLYqfipha%dKX_N@zfmJ0uvH*?BY~lvH*}FL# zJLi{=9{`*vGmn@fY6nFzAL)bD&4$s@0m7Rz66iaXlrbMZ7zxZ*^YY&Vq1Q=700iDI zMg%JyGA?{bAY}jl%yLl4lVrvGAwWp%L}`P-+JMjFymLZvY$u1daY*$cAU7oZ7#T{2 zw3rT^K~N7852<)u|7pcFimqOzGf1X8L_TsWL~8w@3P35>dUdt=)s|9L))3_= zf2vQXR$ykF^HN@~5rW{*MzeDezL}>t5Q#AqJD_wgc}CXV;X2xVkZ<&wGgSbk(IDS% z+#x%o5S&?K8n^|Jj5Jv5Pgs0D<)9oD5_U}Hw0CE{8UQX_Z#GDgqVx^d?hv8ukUDbS zYq-5&Lqml~G$!IzM%_BMI9*C&Ck92cc(n5WVJsZrHCSSvCMsiVm2nuS7ZUs!7CLaY z;w}|-S{NmkHE6exM_r>^xS)>_4N`jJC0SSe6Y({dc2uiTLrPrO9$hpH2{ZyYfvbT{ z+^5!lbX%ig{`~^36sDn0T^~hUqTd8GrQ-p#PRJm971#BW4poJ0_X_mD)HmxrftAOw z0ci`98)MwXC2dLz_F6Qy6Wc!T1_k141|fv2^NXMTdslq9P`!`U7B4hQy{qaR!s z{#8l*=Q}PypTfK*OcMpbh^nrW*q`OiC|Rk0!N(~&T_IMcMDW6UY941GqVsCpng~(l-X&5_% zR;RZBhAH||liR_;4v%DuA>wv?ag%IOQZ7_47C)Xx-4jEgAH7oqs(1%Jd~t-6VkkRH zH)*87RX7x~jbo%Nyt?h@cM&!3vu;?MJ~RjHLvE(mYRZE@L#5 z1jb!wC(-aRDh*^xrv`zm^n`Yvg;(SsmOZ~c79qydX)j20?YMV)7k%lt&iZL*Ft-+T zE11}VRwRB&Z@h<5ADp2v21c=~Fbw5<1nR<_yYUp~jjRV}Q?T92*IrE)hvbfeWfrz_ z#?_Y}>A4mN8*W(kTUPYzUf&~~7?WE5D3mJ#ZD>kdbch0%8<3DAaO@JnvQ`bAjFFydO=k|>RCYX$F8!g zg)r8Y(ZN7xxS?fO1Pkn|6OEGDHlHg@873RKC?1PD|@HSXe< zy6N>RkEI?FPHC4?oSKL8P@HTT@C)#cBqH=Sf6qM(GS!CMR*Z2>clp>Vh0h1!&tnY2N0f7F*3OftBAo+S-%X{2w}6|LM&&^aE;V zzW}^Ytj8yj1;*!A|03DmZ*0~rQ}7Wsqm5gtto=x{)>dzW0!iPv(k{EqQO~rJRa*AU z@FgcL{BhhgbMYUQYfUegzG3j4WirR4;iOOLxJU^HM?4y1)|}SD!5}6Dk+pX<@FbCu zGV~SMw1y$~+Uns+C#(Rj$ZN4JlCD7(>iz8IoC0N?8iBw*r~r~TIY9dhEtl5ZiKZQ;MaaqlxeaHf$3HFvQBDJC&nCj{ z1u+lMfM2(sQA#AxVn?qSI@gm`sQi~Ree4#BbU#`5t^C z-tGd}E-_^$XP0SEIsg8dRAU$e-cjQ|510c2m!+7)oRBifF4diK>hQODtJlwTqehZ899c!F3cq#={l{qNQzs|6^ z`f4!@!8&v!Xh>tk_+H+V)s*CFH7lYmL!+B7Q6J5^7}XIicF)8}R|WWg^HT$kT|-BD zIeK_d6g&M-X7A>SiMsXE#FxE7xWUcyo?*PttnXk=xFw9RXS zr4kQk^0`ikCxVf+?c~!3?xfnw=@`?vro!_&8ab!9y8{f(&McrSf@3sT(04bfNp0v`E$*uw@py(TXe$M6cSA#sIyj3H9ovQNS+eQq*SG-J5)Je1~v^pMjm!=|S2PL- zy;YJexnsxwkbclgZOV9JxMqxK*ODKxU~k+$L0up=LL=W3W;d$6BU~sd8~>R?8o{NM zWw!lWiurw1Lw7rH^^ij6D8$A`iMtX7%J|#q`SB>ldu*r>P{L(m9w4~F4TrR51>khU z0#`3$r}I$LYo*?DzF(m(xkXu-MEuA1i9yD{O0w%f_!SM@-88>+dWPFgxCxIf8?lOT zdeC<;qu)B;ekj&FW?K$$Aqtjl7*eNGL9|^kKba?S#VE8P2nyx|wikP-V0yQ$n z?MmGl1z{T{D6mg7n?M93FSrmj8@3!3X{;a1%vB%7d;eZw;?@@BJ{RaeIP-RDw^5E` zKsIzLL2hFH2B0%Z47jLLrGCa#x1IYAYM_LRhWWC zj3U8`mteV5C@L&QEyyg!hikdCV+=>iL|s}jzsV4sIFXHn#^BERQ~>JrsI4^5>$hfI z9kTlMH@4=U&&g8YIFB2`ANto^d{ua+y1^i|A#`Oz7`&$->r5)z9rTrEZdFx=@ddaO`tZ*{1m;ZCtYh?H~hqvlBN4nHB{hVu?0 zO7-7QEp5T~96yOZAcS1~dBS7h{;N^Hvf&wu!XCz0puEOQ&mn|GS>#=xZ@)hFioCzLiZ137cN@&Ugv&K*gIo&3``*sEA#+ zHDDk7RUCBO@=0Y$>-e?(j?!QZxU;Uvu6~#U`M3`Z)$d zfHYEMo11V+^2^BG#xG_Q@l4`pQ;KFg6BEhC?HL=R$s6Bh3RRTZ(h*0X*3igOUel?# zg=|G(jMTzmZJu$vN8I~AAqksfZalS?_{99S^ZU1y>*<4)`*YCLSx=j%(}$owlgB2r zbU$!nj_lM9k(?n%M~GjoWsWxC%eP!KPI1;p?hT=mi1kYXx5hOT%YEh9YK{U2fv*Te zov+=0j5sd-6F_`3>w{p9itn>lem26d6wBH%Uc-6)cxPzdTEAdo^(9pwAvaJU@JdB( zAMTRRMUYX7R7?0axFg9yvU@;49tQGHbQ%>|;FSL-wB0tUC4PG%O2aL}6ssH5buF*3mwL#@JRi(0OCc6t%$TsU)s$8+*y%S0-an-$zVkVMBWB8nkW)P zA$~?NRdhjjOwg0SC~+eWMtd@vs`2Fgl8S zqk>!~If=5li{hRFxK`X?Zxde8D8T}{^Zd!?Q=~))uYlEkG9Pl&OKi&ix$;Iu31vrl^T#kK_ug zkqH2MNKDT2rlQd{gIF|#x$m3rxgP1))Apa`hOH?JF&O^2Q~^U~zyl@1L1VDXiaWX` zde}UZ`&}*u_{l+dOvaaN#_c%f%ZuTWC60Qe3JrRZ>FVV{`My>i8L1cW*Sd?rJdPqZ zI=3uP-QWyTfM`R}CvD)TSTZIq!8hF#t9`Rd+OrU5HHcLJA-knZT4Awh zgTPk_98mmAFDVE%Vhqh@kgYLk3W8{-yEHBj+Y(r8-g>z=3CUbYaqt%@%g7_9?cN4V z^3X^o>D0i~LL3`C-OxZljHSoRor~E#fI>R%E_D6WA;n^Q{-ojfo6ES<|0g<;L_^U$m<^V%dfCRS zmJuS{u?nRwFZA3QV`>2W--FU6lX^ZC5lxfURMys|2xot2b(eNkdj*Y&C40``UYe1Bo@U`-Bma86%3e0c%w zb|(8(l$u_l8P&VyDyUA=5Jbe!RDL!E{sjfqsv1CW8D_n!*Ei~b+gZPEhE;=9f*Xx) zo9rr}(D@3DVR)g-okk;Py?*)LF#&T!YLwX#v1a1rrC{hmnb}MG>s8xMD7a4OX$A(H zIO}zu7`a~8m>T$-P+S-s3iZ==t zb@Np*f=6^eUKq%&HI$`X06f}<8R-&$`m=WlQl>j8dd15M?!BMbW3EiHDlLcm5X?>G zqLYz;`|(u`ZQIss5xOzU-4*l6?39^n0mEcU6U!V~FSF5tQPBHj$ek}_J@X=eK!^&6 zuz`^v`nKZ$3Ev5xmwKDTE5ASzY&N|)D|24AszDL?JrXL=0}+qKge zj>voNd{%mf_Z&`Y@yN_%y4PLU^ai1Q`8^M`fFrmmrtV{d5c zmsPvjZ%S^lAO?-W(X;rB`l(|P34`S&tJxCW+fAG*tRW7$h-#iFoi`a*wGW{%8h9_8 z_rG0qpyhDb3ntdtFjlSYelnD-Y=cb+XXI%|5ZOq&^H3fm2qTfES7Xl(B`(@uBOuraX~<@>lo= zJQt!^l(vv};uhS=WNu<-R#fDjSz&InuBi%6HElIq8VD3K=`&2Ck(lrolE=Q(zDe>w6g zGt-R^4{Q{KsIfu|tZ_XZyOnM<01C(r0+0+yNo};K2|^mQ7xyQb0ty3bJMm1LHJKNp zhp3lSCD;cw;?l8y)ShGmGqoVj8j=mqWl~^_8(cEMt_Hjp^|jG?oJ53(n2(%j@3{d0 z0RS$+kSvAG#tl1F<&H-2S2=yP#NUl2rXK5J(DE%{Pc50MCt9{n^@0u>OaDvNCVTV; z3(h?7L0R6lbSDsN8Czz7h(e=M@MN_cxVB|dEvy~N_I7a19yY(QQ>QxPNO}dVVUiJ~ zWSv$+;@#?W-rYtZ1R8Tzegv=$v4kKc5#UVdbi%m@A;I;Sv)ljq-D@@oqW87QX0{ki z{uu+Eztvk`DkMfjm^DnLffGj}6IU`G%Y#Vp;D76|+!BsyU_XLC$P40LPteGN8(@cg z$%rc|c$$n-Su^^LR7l3#9vb~G%!AIG0Qf`8LpFk)^IzGDfytsRG@+SD`cDRyCJmj$dnyre6rMpIh$emaeTVp8do`Q=9_gB2 z1~M;_IX0L=2+ZicWg~6&xFY?4c*`Tmdn4_P#YES$Dikm==>KZ``7gQna#Tnvz~#?b z92Sp&d|st^?*@U1~d||POC4?U*4qF@Nbp#XBI>b@yl44 zadW+(2OmnudLOa!@>cTY07(P{Ix0#f7y(q34}cm!ZS^V8_#H$;*zpUF2XnP$R;s|~ zb>qPY(QaHAb$;{2>-k)a&8Wwl9U=ul_F7=IBzKAGIMM_ zyCqh}fAPgal;d3d!08n%jJ$IvLHF~i5rH+^wn z%)%7?6yMpiFm!iK!uJ+d)oVLZj7Vp&m~`U!S#sI79A|FHX+y>NEb1C-sPf;<3bFjo zC-lTt4xxY+(f-htb?MPS&=lj9^L5j`7z=85LujFSR4DLh{O()M3Q$*Nz~Vy3)x=eIW|yJwGlvBDE8Uu|-P{q|3P$8k z;CoTlEq){v9tOF!zv(A&G>%Ky^7n>JE4 z&{(T@$V%VNAb&!9NM)1%r9M`@13Rl?;6DcsgPf3h?MQh)t0zL`Z+QxFvrk*`!h$p0 zfc11OQRne(9d#CJGVqy2oU%PsDJ^jO*#nJRN&Cw&i5=lEr&LWFga$rkT5p!SOCQ5A zqbks?2c1jZtKdhYvEKynkcfFSQO#QF2X#;(L|wJ8SikkOw8qSTSdPUs;;;c)C=;42 z%+@Ca>aRRK56YXYZzCCrADdguqK1j`ujjDu!``x0)wJvIgG%w}GIF=gzDUP{CogXU zg$>pY>0zz)^Wl@-Fw-xLV1a1m*#@()hF68lxViNLE(h)Lq8!m5z>8GWTF3fKOPlgxt2Y;Y&!Uu-P0TlDXN=HAu^q&?SmSm zNo!0n$dT=1AXk>S7~=$J@Yv`u$@$E&_^18_vA!dKn##19o<}tI_vgbvS@06Ez}zyy zo{XqkbhSGg{JjOs429p&23}c!k**jN8u&1ClW>=ASgMXEZUTRRe(L~HL#DJzW6{}J ze`_dNKXR~M(e+?gkuvQ_O1^e-7-mcVeWqXt4(;V51&+{)>_vYEnmNWa>H2od)ts6? zy|S?f^XLNpfa?tzl#zC+>b7DAco`!vVY$dJ8Agw8q;r_!KnUzism9ST+rEk@#K_Nr z0u<|gTF!YgQ^ulZOny{>__WZa)RF-qwjS|@SeT)-qDwCY(knGEC+IS8p-m?NfPcyO zSlsKt@E`@H<EE@1(%Bh;*g~yhU zNq3tdgq=Y{9@pDI``dzgMQ^RvPWz(Jv^Im1b;&gd;J5kBW->pf{*P~$4X|+|i1q%Y zsedp^^g)}1iBdYwe^a>e1@pGB#N>Y&0K_{rf5u;1NwIq)h8&_$V^i9X96M{nq5tvv zBbri37Jt=%Yihp0f)TFu`ZNGTWb%r`v?7pU&C^aBdu8LJ6((ihc% zQ8aa|hbmIZ5|LI}9nH?SUgyy*h4A_@;t;wIoIp}y3TTHxO%7|%dH`vKWc>b;yCy3$1y|Z_O73-0;WsWb z^H>=lP38?OrNSstEQa+=`lXw=r7Bg~Nq+Yn=+gE8-|Jr6hmXB$MskRKY!alZtnig~ z_)Z`pg2)_M`bs5lW>{}t#vf}SDJO-b^PMh+{Df`le9B~T;JIB*%vTiqB)pSfxua2h_W+p2fw`?yFfGV%4*^dcz#2|U6#!2P)f z`>KOayJmPxyR6lkqBRo62hqiTHKRQ1PcW*(rY+fu_`L?DLR3IyiE7DRaEP7nukrdn zT!s-(L8s8OB7`d@isjX`<*TbCUi_*c8rZjD~#$#Q>A!{V)F#(}pJ;%%; znl>(~N;*i17v^G6{pb&}3C0JuT~U`?3`C^Rt{%-L92m{~aO#ir+a{Bbno?URi@6H? zgWgrh_Lm5WgSLl?gJ=5?Ta8}$&~ezGj*gr29Iy}?47Sq4Z;b#RuZQbCMKC`ub}(-r zinQneH&j$%!X1t7Q^Jq3v*t|Vg#?%xa$HJ2(7L~4v2#-)`=G3h6yJpG$yLiBR`Ab$#dmU+%J= z{Qi{rV#Rp3ep$IwT1BYHK8aGh>>)s+?af{xaliL2^#$+YF*{&6MP`*sk&H6)rcBE` zrCB9;F~HFIQzI1qUryU1#0SlHeKpC>x>H{|aPwE4g}z1v9kBDjWZ~PB`1*u3npGN# z6uLC&NFR?fk=lk7&VRX6@6KJ9vXEy=0Y&c$lu@4l}{bxp_UlM3l#G_}aNf z^(A((go@b-cGuPp#TGu9>VB?}w*c*3><3w}VN*P@8BZwb4q0Gpn?r>tMV}FgP0I(3 zqlxlWclmAjscy8a7YMetv33)cMJ_$p$byzZ!`j*aEZO7f>_wmM9RsH(%kd8JE5mB2 zvr2NR5uBm@*%}0_XQF+H*mh1=6}jQT>=@7GP`y5oqGG)c!Kf7JJ8#`cQvs8s%(krGG4vKUo;m%u zus6{-O1^Y^?!IJdo3XGWV1}8-tKAS{+y__CkKAW!Rw&4AgfF2<4n1EoRnc$Ohzd+< zd(`MJqZa3vjJz^h21UqhOz=*WGJB!|qM2Wx&^?ms8C<>%q7|NizE4dF$U@BiGu<1h z*&{_)XjK17#Zz1i6;HwK`1Qjhn7Ge^T&?~_IO#FgQ2xB9u>83DLbMQeS0hoqvJCOUgf;yM8DP4C>d+Rnlk_sj8f~;v zzr38y_LMM1aFZC9Zzcp%Q%Snv!X}LvW2G$Sb90%+5fm#&rGD?{XaI|R3+q4gnCw4B zmL|j&BpiE(+U^7}#OumWIrW%r2i5N`;8Z(R@X?Y80b>19cR>2z|hnPAIy1~?b0-RuSOvn`=r zV%rxe8nn<2mDdH$ScP6mah75YUq*3^2Lg!-=GU%G#vNNuw^;`4rj9gGLE|yliSZxi zb9Civbysc2+@}#@^(Hbh)hk6|E?2{~(p`gm@A>$9ZI+>XM0M5u3Gi7}KJi z>MN}vX~8p~d`+?lK+DgH65qv;z4ePGzN$Xxw+?vH-Fy@GgVmQr(bx~kzl^}J@r0b3 z@b}wewKL<1Ju>piT9w$Ul~jy`lO#|D=S;R|Q464;OkVUH%du7WhJRHaaW5Z}fn&WjY+8zZ|h? z!1tivw#UjTYQ+e3TI}pmJvl`E_>>*adC=(&7HOa%t>0Y!dpCwe<94q!43Kx^w+Fdf zC@I%V!r#&jBfO{Fe;KeR=3fG)e3aDT^?< zSdtHYB0_(nUQ9U~Z7OIVQj8*$8bByu4bJLvSF?D3{K^mZJ)wATGS};gmYZR3xhpPu zu2+wn-OX9{fjE+l&h}o6Fr3#7HaS|)yIP*(32O3>y^}6pRp@MNFw(eatB6&gO`tjq zM?6aD)&1Nrv&H+iPRwt5Wv$H{Bq3t^Lpe{L7696}@v zN}*nrMs`qs;JEd0ks{T+4ZycA_#{GG{q&j3XHBu!NyGZmRQEzfmsKi%E`&OqNw{%% zp*L%@N%Wj5i~YnkV~OjDS8#!rlf+hnpmXtr%2EoD9Z@1CoT@AO+<<0y|{&p8tI zXYB27W}8do6n!Ja)_e-R5w%!j825WwyD5fD(Tyg546{4)UYXO)^0o5`F{QQ~6&p2oU+uKQW;|i@zsRY zU<*poI``0{C+Y*1oVj?f?b=8*s7IQ-;;RBUxB`r@IN#qRjb&lnBEg?bsx#>NViUEV z3o9N4c0dDrZ62(dTH_VfHm2k_@g*-pVe`@dE~tBx9Lb_FA)|17)$TK2ESf_5wYR-j zBJC5B9>_BS2$Oo(IK`3ofRh5yn%d%GU?74NHaSLQD&e6_q^is})aGP94%?_; zYTvqV+ckxtfqoJThN zC*q9N@`J;+@ntN|#q+K=T77jag}h7D9){COUT>l?+l9e}I1&i1##>(tnY7d3rseJn zz|187CfyLnfhtc;0@1zGJot;Eh#s9dMesr6M$i=ZqM9X;1li4@+aV+QbDont1KBfP zE>S!Fp19~WITzM|C`7Oqm!Me(PcP!t&ZQAC7}K0k(_dl= z)=-@4;>&9h9|%S_n?IJ6RDx(PD|Zo%TYZ6>MV~~)RZ-l+IOvtOr!=1G2}b_}u7a;Z zzMi)?Z9~UudUDIuFI^GUYR4ESu@>M%1KnNzJh!!-$YGLL^Z8HLsqnJ%u3-%fdKwbu ztiiQLzHS8`wcn+`+G3D(CHIhKo|B{kX6th;0gg#by|PkLdnA*eA77clnoyL`4YOj% z4Hg-~H*+xi`F1x-MWw%HNU4LlElzR1oiY)-UeFB2`^?u6Cs($SyWbl!aH z+7jk$n)FzVu5vPa_vgXW1vS{mEc-FRr~+X*i#x{UZ_f9sNcxQKw1s!tQxW7xq}^(9zA3KuR>msFeBZ# zzY6z?*vQq z@gsiT0bhIdS7kz53XvxEsi-+cjH1w!KJOo_tWdHu2$N&xO%WBmQ`(>Y$ZLB3No888 zXC9dM@+Pd#Tjg9Z-9U(xD!`dR0w2Pe$v0~ZmlXJ91{M_n@0{gFW3uIEzWU0$^s(B2 z6M(~^a}`9e=g$)jOEXqt-u%Xp!(65mcPPKw&P3cFEx7P2%kEo+ET!?L@MWOk$&j4< z(8av$>!MA^n@M=FgXw?;)^2VY^}aSKAtn@$`x6x!m9un7(tFT4+pQ7rZBlMS;MARY z{COh<)H#9g8S=m%*+7A=2;PIAWevnog@b;Pdos}A7EYSsM;1Oe)CF>tW-_~ux1G+Y zO=opd7?=`x!Jdu5)D@ZE;Ya&8HQYRZb9l#PkkvCn9F=t*DMSUa#wKC|1iK| zBHvK?H=*z);eXo5omtA=gm+I*k}`AcV9isO4PnBHITA z%e7YFaU7HZJOyeXZ%ZIW?aT`H;$I10NI@Jn+*4iNBNrQNiU`&v6fw&4(Vy9(JdYJK zx=y4Vt$p^4czxUP(N;iqEy=#)M%9g6!(2{?NrtJLXkSNiSO9`u(?f~wD?uF=dL*;V z>3s2=T)cl7=5F8x%Ms$m`*}X66806P=D2PX3NQK(9N<3$1R<)?SRJB4@$?3@Ol}Xw z>yIngFfIe_M7)|z{bj;|m}%YM*irOn4e#IY+dNx|mcwhj^1{4%IHiLQR!pb>01M#! ziix=}t4ZluUCo|oVd>$48MJa?uu+*<#-~QP>E4c-%(WD5 z{3G%sLW7z8ft}P#rCg!Xh&{512l_}ski6ZMx7dmUcZ zEKvYi0=45M;-?PR!BEaID+;QKP*5E+?htTJQE#xrMVeKw>U2qjvJ#E=P19gK|0u|D zXrc~kc{k(e?M2nYUzG(u(9I_0;;2Ar7`6FD&mTdSJm$rXihb;zrteUaZP+H?t23z9 z)N8&B&Slv!GGx&#OI}OZWyyW>;`$H13ortW%34+}yQ*;2keEeEIxmiRjcsf#w)sgpL8F@Ba)=QJwC8uq{KEw`U}%h&=+UX{P(MjabcaJohw={q<};9NHy}Y}gH%91_M_h|i&{7{c)R4x#|nV=vd|%Oh(rA+uE(Y4(mh9$vPHqOx5tp*d=Q#^fu3!+Vw^Y7s9@l&=Dg?OLJQ%MizBa}#wD?KQ3) z&qdYI81-U8wpx+PeTXLFW|z1|-;M4tlgoaCf%Utp(ou?k8LD~_7Hn3Bt7n+1ssF=NO1Ox=BgPGJ-S}lqOYwvQ0qy#81Pe~wQmTVd2<79?@mK=Q;k(2twKfN zG+*-dfijG~vF1BbfH>lAm~20gY}L_qFV2gEbcWoNGu{3r{u%91VXC&_Ebw zE-^f}aPp`LwOeWBjGn;8eT;*g2#!`$2AY4eeK_-aD?dWfugSp^^|9fmZ;~M-9X&cn?}*z@n~odicGdt7>SE&5Gg{p5`KOIh_qg1 zu2ESlB58Ac(S`)_z8O(r3ax`b6k7yNGC)$XXIfyQ7AiM7(S2!YZE;U16ZK&ids6N2 zVm>zo(E>Upq=s} z)VTh%k3|5l84?v(kxnlJjNQ8D{`@u7U!ct|gD12uj?ij8d`xx`)? zH-a_-XD*Xhsgu5Uwc>UZL!a)t{$q3vuE#tlOglY7kUuzL?f7!l4_7cF|3+MLH`Y?A zY!H`B424WOlvbh)Q`*b<=&%qoR0Q_vnA+Cz2Xm1JlSpGz4IO%?987=lPV*EaSA zd!Km8b9X=9g3vf>o+KD0-Me-a&1*hz2kki-p*!a?Njev<^4;b@6@dnOJ+YsgM_Z;< z&~VM8o=B4p4)LK6I#3Un6abI8&kfgx-I>?xvJeTD^)sHk$=nn-R)=)*W5oVD!vOJ2 zMz2Rq)f+Q;Bvu^tT)PT!$6x}v$<7U-Ur^qt1bvh@6u4JkV>@Py5|bqQj+~Qg!zt-n zr`{0rZ@A?R@NIeGAEZNsqv3YLFPExwqjgnFk+A4AN0gW%c^C&woJr~0y(1;6T&W-^ zb2PV^Z(CIJZqKPG%xONdq}=o4C0IhGC;Ze9eB94Zw{xqSa39%tP018I*!gy&8tbuG zJt1?b5@gTlfl^f(-}9(P)hky-H_9b?R+%;@0Yq2Xz4WrwgIh6i}0+}D# z`9WYi4o2#FFktXeGoZ$EddpGjI; zV$~e-bH262Lv;~f6;|d|x_v^#QC~>bp6WF$oh(U%x(h^3c5~%mjYFJXh(s`g&rOzi z-4zs(FLOh8%*5tKd}{4lzQ{`#7>nJU>9&B$*RepnCL{>nLe$JJ3NE|}vNriYE=-xQ z|A=}D+$l1gY7p+jj#8suCNH^+auKy8r9kwd&yPE*n<{chkdg-)>f#UZrNL?6wg5n% zhECt%$^aW-J2*J3ieaAg_wgiY?@*KvAm#M6O<9=(NL0%6sDME>VVLfek)WBK97HCh z5{7Gw<-OR{$w87l5VyMhYJB+{^D}bpo6K)HiX+8WfJ*Y*7OR4w-iC3^ZwOZm+{|>< z5zumpRv-Uc7RB6Q4dc7t8Zm1l%T_B` zYbEwtcSy$8Rs<6YSr54F4VCmeU)bTWwE9zz`SCdg67AJOkcncnROg(ZNJ{mx9es-F zVi?xGk1ZP&Z-YbiZg#FpDAvV&pS{ThH!yMcKZ#qe7ywcikv!V8S@eBG-%c15P7W%0 zz=kKFtJ)U!MySQP^t(D~RIonFn0v@W?za&Ma2NkhlgQ~@jZ6{Eai@~U;NRyP`sx3s zR3Gi4h)JA&NOJQjRXozWhJgJlmT17x>NUXm2h&m%x8pK@ze)FAN+OruSjldGV+%Yf zrJL95nVOA4$%2viXP(Rt#^BSjGx>uE2HaHzPEX~^9PAF@E{+BA<3UFs@=sz$KmbSG zP|+2w8+)eU`*+5-1t|X2)2%|ym;`1;zo#Yb?)S!$aF+Ubm@8A9VuG39OcJ`%ebp+Dx zwA^SD2Ome*lmf0#wtA*UGpHWVs0yBZn>jxIS|W~X&&~8rwKHdj8NJdyDp=qj2+M0ajvZnY7bE4|~jKy-adcO9xm`V-oY8?r*}A+FTIV9*w^BJW==6f-*M#2-E*9OI~%Ve7VH!KsT#x1U2q?l$Fw=nx=l2M|gsk!eh}7pnd8!|MFbf?L97IfDd9| zri;ytd?;Q)aH~PVB&lmvA@`eiv8%C^ZFZ|b68|wCT12YL&KO`NhW7WJbfl&2FU{>Cerw zUmK!!aw`J-(IunSRz}AwS>cNAidP1Eh{4qyHLdAgNJFa5B5Ckoe2`9By~w%Q$~B!J zY%9aE3YU_d!}l^jvT1HBI1&Q<{e)CW1glL-9CBonAO+}9Z51L!Waz~THncj*2TpZ% zQbT+I_I)=I3g~Lt$#g}089rhXhaQ$|m!cj`!XRZE8~})uw2>@8KT+CZpbnacHYRwo z4sH$(oBjWQ(0#G+RdIC6Uu!MLx>LXUUeCDL1bYE8lrnJk4|VNd^g?V$&irJ zCe;zBJS*nW75FkBYTcS4RO$rC@znFt4PH?9WLTr!hYdO+G!R`ok#5u*G@2{)k2opV zqhrZ+Kf2+Uq*ZRk$mo-l!KzY0*0fGy^LRVORAk6`ID?Tc zw{hp6kn%k-4^AV+Q3}=Yuv5(w4f*Rc*=hlIuP@nmxaJr3i9lpUujSlCdR&*OyQiE% zn4mpdu>#M)0s|#V>i`sHbS_K7txagl%r5JW%;f&}PeRv$G02yk^B#$JEfN-n@m(%D#L=Cil|yCXxHVdY2e-Z z90iYaR8j~duBynoJR#BmDF4E|o?^@michO0a(XB3v(f$7n~`K zJrtj`O83m~XC#9!my-WS7#XwcZ6~ZN`V`onN^ItP;9HCOSx(EUFwz|cC;!&j(T0c0 z-Be>;*u_u5Q0|6_KC})-;iA9;x(&P~tciDQ$DXJ9NkjRkyIG@&griim?+Z03Ws!P< z7C0r+SgJ{{$q)7Frb8m?w2dcJFUfX@W~-CVEf6Vvr;xZ?#z!8>!{$O1k0yYv)GVfo zla?8jJ|2_-!)K51dvA#l$m1ZL6zcKYXH{z*2zw`~Qq33Df8Q6crXP_$VwFl+NHGl# zdH~#|8Dzn(?gQrB77|0gCNBX-&tj{cZ&)s>=%Vc%VbfCbR8i04s?nKxW>;y`uH$Cu z0R_Ko#r$mat10+k<%1RL^%g#;>mYwI7e_x58Z*5Tpfi4TU*d8o{&Rszj!H{-3% zB2NhcdLca7I_5jG5m08_4RGM7{WQ#`{S|O$p=jvoO!Q#hXMoM)%B?4h8nA!q8)${5 zClq^s`G#^4zCs6HmF4PMu6jPkWe z8%6kCq6zC_)c&htFENZ>b1r9%wH zRD4LMvUWI-{C!`-Mqhq}ztPmZVFYuYBl350#HBBoRe`;YG?~8uCANh$ZJi(^VV{#q z1UIIcmuGCjgA9&tl|lXqwVE+}d)*+35k4WHutb`IwGOZxXwLH~_n#XbTO4nN1dO1i zg}totL3s8#62dzC5?M*xVqNgeEi$1u@EKoGtk`z3cu48FOCz{Xj=7cTL6`xx80GOA%}S6O~B`%9nfgmE^hGZsnrjfwRjrLjQq=w2WW=FAS_^ zYtmn~(2X~v=9RIHMjdJxqP@iXvF9_1R7=5?rGDSVST;zL3k&Ze_TkxzvI&bwQAzPh#aTYu6UXA~}bCWIsk#CwhMjj1l za(xw7FUk>90Qbbpiz;ecpPjqqPg*e7+02jXPn@Mz<|bcQM*&3^994Bek?CrLsTvb}qwD z-c=w}y3|4DiYlse!y+@+9-@kYr0~z4qVLrL3{qn{aOw%0L|{7!0`|jRQTw`|glS%~ zxM0$?73;$hAJv?P^pPHVNp@5O% zK)UEkbLTgD4y@wcrw_s>NC^5A49BpLNE!J1VAs6L*3Rjlr|b;@+710N!f&e*x4nha z?yo}7ak6hjiUxDjVq`6c+(4b!?t|2mI6-S4_&gnW8-Dq|z2~&D*Y+VCcVsdEug?|pGJ01+{QYy{#$iGrr+J(b;uu|N> zo&((NPL9h2-R1{w5b}u1zLz3~fm%0!y6khId+#aNH#=48p3fTrqoQ!w2&zCCoqQEB zt^C|ultcPv^JrmhGJ|5x1ejzKnWkmL^8Nvdl0@A|JM^B8z)Y3*R%&dHB!pB@Z55~~ zlIq#5*q6_bR?9~Q!>)}!-XR3&SZJm#Y+N#9a)lFkv{0gTMv(-f%@j>+M8Q&wm@Iv~ z`iy%_dRDNTg@7&Ah>CBy&Fi!seP3Aom;(k1|JV}#ifH*)S0Wr=v>5W*+I zu&npGxak0L>W2#Lf2}IXUZ%$y(Z&OLuuDgYLH_Mg&)|--( z=`!X_ps{pe(Nyj+)f5_%o7nV7+$gLEmN#Qx#m`D&l(vS%p|N4qpifg(uTM2?!?k0y z{t(%g;B}&6mm6qO;Gj}05Ys;3wJGXnTQIifx&p#rb7!#UL-yW2>|yK-di@O_eaCD2 z==qsR4H_?C*32`kCkn^MSc1PakhWs$gGRxG`#LK8zBHIx0g1bZel4bz9fSXLAd{ zZaK~iZ$*82EA1Yz1_pmZiZFB+%5^Wo_rF5Pf0iZFA|67!z$VN%P1oqG4D3|4TpKND(>qn zeV1uXmB6k9o%$zz#b}pj{i9L#Y2f! zqxU}L`5;C&RJ{PIvdNz`z4s;Sqnj}AFmpJilzO9bR?+)a%r7Q0(7A*WJs)Ly(P}VR zxYLhh19uZlHUV*e^{oc2x7&{1VUv*+l;KfHQSaA%jz%1VXN-k|?#8q0Vqk=lZd-k6 zD2l{=RwlwpDUtR2rg2DM+lpoSl0Jk z3itcp63lS8Euog$6B%iPLgq;RrfYZl(v8R3h$n!9ox_ykl4;nV3L46TijM^hQ5J(!ZNAUTIXy=(W7{q}))~z0j?1M*6dg7}TU)=67^X?6&P1-6iX|Y^6}CWg95be3d%~=tZ)?S{uSz{~)Ud0zd_Rnl^i@M9fUG$Z-x4$1D|_r| zYNUhr&lTXJVCB^(O^O}8Wuqb{$QdBjeGn*5v)oz&sWuirf^T5dk{$x+SV=(LRoXrE zpbJKy)$IxVS8@AGIPE=7qra~U)1)XWTpT2bsh*ss-6p(g@^2(~&_S|pYOK|+vvf`HN}euz zFTzRzO1;{(2fxAVJ4uy{OkC_;JVOE)qPmnM9})oEEktr&_EI?ytBLqQ4IDeGf7ANn ztEdc{&72AgQcqJNYR(p&UYrw?*Ky^9C1+fC;QK%;mYB9&O{_HtlH^C18znaS*tm@#Rj?%q#XqA1+!c4CXv2wUiI?cHKWL7uhJ` zV+H%os>2Au#KL8~(f?>&d);uB4aORN<{X^bqPXTZH>a!fX&fsn?`u9}uFZeywHeMB zGxDS^#DrR=s6n6ytS7iP1#&IlQHIDUK|jJ46(Bh9J(f5m^2qKge}%yxY#`YBo5x&7 z6D6J>$n0hZ2W@CIS`s|xoM|5JHrz8=_2zQ9&=tW4^Fj#Yf-{3#9obHDoc8HoyxtaI zLJSk(%QJ9nP$hiAWv84txGe{dYte3NZmj&8H^B?Ge(vEH8>z8w^mQ8KAZb&@!nz6Y z|8!d*gNs8JR6gR9(_5aVgn`2}SOY_`P@cK>_fM;rq5;IR=bHL%<-)$_jBRy~vdpaK zms~1!E{SH^g`C&UhaE)#uX=IO6*1Ob7l@65^LMf`y3^rhy|OM%`Tp1#WREw!C^jEQa`IhZpiWq6oI&f#sadspnDUb`f%z4)0W+i30&heiN=`)p0S z@}H`=zqfxw9&H@I=rM(qn}16fELbfujbq8-$E4!%Ei}t}&&`(g4_Q69I}vYcSyFNO zm-hHXx*nbdf-ry}R95N^J1m7hYvixK0A~?lDXrE^dN+%Yw$p#LjdMfF#$ZFnS0MDV zvZZ}_F^E&hh+m#Ozos5xVpC$OPCqH7ZH}!jojYq{Dzx$7N+b8x<8MctlaYm*dHh@X z5IWejY;FG`c&A+#%sBg0GOXTvwo)Rp6S+Kw_Zgm%DJw&Ct zO5#5g4T+e@AjY4c3L=U-d`kfKTUWvPNqT-4W%8d%lPvXYc3dxSDI7EmiScV9(T3iL zRs>lrE)%jllUi7{0>B?v05{^6a_ZvfRwZsa)8rGi56IQdBqiK2s<2VA4opQt2RqQU zWDskhGr)`lzp->sB8`Sh-&*{qTTYMQD!zOta%1y?~z%(eQc1u>2UfGw5wc+~Dt zV?p9B1{ADg`gpHrbB~rnRl0bH8pR_+r&Oa-dOI+fEUSwM!XG|}&CcIsD=;Kd(NN<@ z2MIv9-)E_lr~7FXfJ$#!^h%6zZ|3~&IDHnKVsKa$>Uh*%Jq?ly0a?<>C;6GKkr?Ut zb6Mq+$L5-mZ9C1BQ=G@(J@&&pvQ2S;40sK zVTQ7-BDtYnuv~?dxX_Ng^ES$aw-BeRENEOpCvsG1V$cEu2RA?n{L0G0*j&**8Dy|d z1tM4g<^_LX_lkkYHK9LO(k`AwxR3<~_VJ(pgDWl9lg4cmkQQ-T^r2P)r9#JGNow}1 z=Oow$aQuXeIUWq-uza8V79DaPlu`MBI{R*P{m@$$eK5f$Y`M{OYkHixnwnFZdDkge zd8vOr(gg{9ZR0*&x8~|{1I^?+`p2zv$gc|Lb(5M8I3G#156l=XgnUR!$hfRoUHt2{i?B@$dbx0?6Ja2X$3_ygiO!WQMO&aPYgN!zE17+@UlUj4!lWv09C$K2VNj;NBh{3=vZ@#x|R&-bU!Q76W#T zg>Lf)ZS-CT{Oe%UXDzn4LM5q4iFI3S<_K+uT zKI!yFJ;f63lZ@6fZK@6*JN6Q{=@lo}NR%P;Bu-~@))kYUdP_Jj9swI5Mz41%w21UG z9>6!^$(<}8DN(ccOWypHzw0m+BkFS{CI%jKMpO_qJ!b@`2P&c;K3wSgdg1s_88HAP z*mLI!#zNSPfz!r$Y>r1J$qf;EVBhWPZgYSXBco3{OLFuk7IqttX}=?@A$I`Co?ebp zD~PbIRS$t%$}%4;7W?aahM~BXvbVCq7b0v>2Kiu8oT7;6Ale~<_aV(`@btg@Wj{Va zCgxf@n`UARr}wIypXALX7UV$hS*C1^n`q*I_?5gt52m7lV%#rD7px??3uq1hnB8~ z3^k-36+f<;m_W(VfFjfT(Ry8zegqDN`O}HLMziE~!;4FzNhZrw7yZM)&)J2X2}{1))k#)EU~1QT;-b@Ls}N zbYH|}DeJv4I>`HtF3q$VI<&#h)dao<`s{$J1Bt{(h87|Un=E30l4bOpEBRGC$Dalb zfJ?xG3N!`xQ9V|Z)03j~O>b>6)j5jJ7pp#O=hovH^MhJW=o5a~wl>mW92U4Di8_pi z_3O6XvZ_6+d^)$MvN-(@J%lzH45If&RcYZ#8E%UNCnnl8fkGh*Q+SW(Zt`;Gt5r2! zTZ}9aFlC7rVE8;pmzi_4vFEmi525SPme1;fzz&q^#0-oDXoaotLM^#SR-LqUtx{vd zY*5D{&7+LXKAI8dAZqBpt!}8R2o>H1=?=%@T05;xYKaLfGP(0hKEEcWiH9{`01Z39 z9IvB{@n_IKy|=JYi2!<9XBasU0k*q7s=kA6+=NKe)68#7v%)qKDCJM!kmg}uQ`|(N zdMwff0dtCrufu*MnN_J=NuNVrjzIKwcQwvn>{{`w-C=aoR;TA+EA3FP0=u^Ch6OAS z2${Hfxo^}4hAnm3BdAzhEQ)W`K(eEqM5Y#PDXp^GfmxhnLJPmHR?te1|FKNv^lfy7!<8qQu2HcgXDX0Fm7)QS z8T113^VD(j4^BU6Wdn?2CK+A)$Ey|PUpI7+F$Zz>*O}+0d?7&LqmQ8tCI4JD_qO*W zTi+w3yCFC&m)k$gp+sPsL<{xg^RjYUL4;0xXx~zF!6{YZVpb`wu4dZ?G%|@bLAF&& zxpQ}gM4UD?O(NDd*2Pi}9`l?@l1gK3O}DnnPZ_$FRQ%6cW8{JAe3d_2MMi1*<6-dY z)S!?ehM`pp}*wh44W-dxN6jenf{<1tajjwuV^9b(#X*xGPitsmWZU(F077e zFcW>dOZ6*7B)IIuXX4EHFjr`*arkI{C1ryyM}w)t;qL+u)Skgc;m||G{a*}n>s$~@ z)A3x69CVj3&X8AuAHMjQvHxkk%?R@Pw;AgkzrBI`5lV`d3d(7{h#cd&V5l@aXLNJz zG~G;>#^h+M7kU~d&BX8@`gs~{-h;W+wcUn*(on3w@F9X>Rh9xyXE1i^oJAjj25hMH zAV)ldCbmRoJ@r_61>wi)sEqCWpwb!2GrS|IOJtA8L!HT)nL1Dxt2Pi(xf(YuB^UCg zkS>8A&@R_IGpe@4!67-q40|Hjf?!i>_NOjBBT|$I1xh#aHT|9gTw04hs$N!QId>@X z&sl>G$;$zU`I|}qwmWx@p7mZAtTD(F$)-~gm4Sik@UpmQiM_+)!|#U=RvBe;l>p}k zN{iOalt5U-8bKDRmAYH#AZ=JWa0O5?111^yH};nuvARhcB1JXYXFmrtg@>;ueBIZy zpUz!&s1|u=PLS+tS6?0=^Vp)3G1xA{k4WdE)%9uTQZ6!tkDfsMxi17O9gC?9S)=?z z%|r7j*g=4y|GX$@;pmOR!PXvdeR2WwktJpj>z%8PI55jL?SV3_N9m#>K2bI8Ot&#X zR?;HangRErCSf(}N1s_pMND8f@xIy+2PuY2$4PqY)fEgFh*>BnS44bYvKIz9Bom z|GiS3IGxq^S46-ftG$sV&TPHYwCFz}-D)3-hqO)b5oY%u9|#85FLkv0^oy0 z$EuvDeJ9tDDQG_%AaJN>K4ofZ6?tBa9AQ@2ABPyFw&#tyZD5&@q5^~o*{>xwEp|>z zl)+!LDK{Vi=k!-%D?)4+o0}U=U0c@-%`{zKleRd?<*GQ9qMl@DjVW2 z>~U>Tzi0x)TdfGSM1F=jcJ=2Wp1=uuqr_}C8UY&$qSKvNTGkxi2zFR4>B$sq)EUp* zmkL?3rS>wbwhh@)4nIq~=C7MAkqMIKcFJ|_ME}d?AJlgqX0gHZ$beV9pPwtrs25fMRD_0f?%cwc? z{nHw9sJroajf9$AH*4lW#Xq*~DVJ?yZka)MJ!xO#$XPsX1kt+O8}+t7i81@v!k10F z)5}<`(yr5UUhZL_dzamhVT!rQP=8ISql)eFq>0wlF2Zv)e<0EC9RYOWHh9m z&jx|b69Osine22RP#-@l-d8#rwZydhqNp9A-Zr$tayik^fy7nCt-`ZP+#-#@?c+j$Q!5KyeI6tW>2dGVwPGh@4fHZ_A*J)r(3x@wDz>)n|+av{AW znRyG7ah9BPqJ``=Ig14A z8WZ`Qn~iRwU%pBH4(Y7Rv0)|cF!+)SZL?g{c@q{zcbBtlGESB1fa9}&+8m@#Qpv?xgtqFF1ziF7ty?Dj z{I1B@30p0@~Cbb)QhSLFo$|!j=1N3&i0A zS722SCnVGr3%WU!_V1(i++IVp-A6uZYyAT#e1<(|YEqDCd?3rAQn9wynK4t2FQ1jx z#+gI73ptE_2S4kxRkE1F)zD10!b`;VgaQM5MU5OeWRZk&BKp-UMHXtN9H!h~#xNex zNTmh_rNN1%+)2}&!m*l-&)G1@VRFn}eoin6={u~{{()cEIHnNRHO>!? zo(a3WHsx|oeZ(AkD#$JDr zqdRtY58A`;h6!Ll1U(n=+f=T9eG(B(0HirZsR$ojej8pPT5|G32CQ>K;&00^SQ59v zwUBuif*L~Qa?7e0e76L*ul;V=F3(|AOyjSlNTh{Kom?Mcyp(2CW=;Tke059HB<*@zf4@z;Yx@I)lA*ccMgj$)GK1f_xEID|Ui$Y;bsbWQoq;kpSTwcSTgPbn|0FWJC>^2I(eB29p zVRyP{EVOU~3hf&~6!l z%0_mP;GrOuWla(a$kzT_v6ezjj(CNI#Lc+_mf38;iB>rwsG0|q*B1b6*YhWltRa^5 zt=AVH!ql4NU(oBiy)+de2H)TrrY3X+J;H3yf3HbM&0NrUif1f$-C)Z>N0)3_6}8)- z&8&cw(=Xtm(5ejbW~M3GqhzF77@4h8(w$PBc{_2m=9){FpnLNentvP8AiRk4-g}SG z!(PK1AaGK?bd+}f&l&d#(fnIVu};`~-Vj}TTP?nxDhUt&M)I|((l=2!!%P7yHPl5U z3(`!fj`xt&?aJHkvnD-!RCFv3x02T0okKZ16!*zWuVCPJeM!Yf)&`=ltq@;rT(#|5 zL{yb4?aUs_`=XcL(bLLCZk}*i1nX@cCO5;=Lp9MpD8VnLI;1*Y@@z5!X;k(!m>oF! zpIAS`<(cwsNm`9gp6dNmgxyyege8AVyf`i15sFv8jGCxP5C#iH5wO03hiOoZc^86$ zpbrBz%s^|4Z#j7U6ygFa&PE7!mHYtiy)-#~CVB;H{p-LN{EUl~X535tL-|AFh$^^e zOo8ODh(s)YbRy%}ct`wvy*>y&2J+7u0ag8K@kEeC2;ZMg z@>yT1EXfK9K&Uj+VdXxyQ5}8?$6uoJO;NN2t#k_io&+~r+QPpdR0*~yNLaIEDW6*j z0yDRDb$Lp*s10MsP_yB1{*{bsHq2XOqZ!@DENQzHzFxDt1w_=mOn9K-h>16 zKd~njieGco3#&y|hZ;}P8RGO2x3#Ziv(ht-N4ILg^bbt${8(a(VFqyW8Dd!*^JkKh z6vhrXx^;=h`FR1l{K4mNvT=r6L|9?DqRCMU0&5QIj-YgX?wdnP$w}F@{!!Ufi~NnJ zs+$0PED4mD(*uEt_eCSJ|GGnthuzZI-Jl@bj793ZoIHeO5i#+WbfTlQ4e*-ql1L__ z=D;umCdNa(L2Wy_U~WB6*O{)@g26Q=kDi&# zE|SeQ&d$+O_%}K_>rnlE>%0W21|9zD2xN@{|CD$GMI~I#95sEU6>K?JooEOxX1*~Eo(sI zhUb>fFQ#RFVN|PH%S80plf|Xi+b47!z=h?SCNj-;H*A_+m!c%U!S7ge01H>%L5qz2L3w5M?((;NLou*G)uav#*0$wB$e{%j?nrW@o#iS7fa+&J_Gu`Wbtj6Z9ffK@F8hdidvPmMeIzcE28ZeQN^ z(EwdaUBx$(Cfdh`nqamq)@|Y^SGY+*Qi&fY8bh)|WHg7{;DYsB6A+&*dQO6knBKG% zh;0GVMy7%s02l!G8(oH#mWl*F8n=<9BrIGDn0{faMvyq@mjz_NJ&Lu8``%;J!B|%V zTx>}jr;Fm0l#7inww{gC`gWyGj0Zsum+|?W!dOvoE~=tJ<5>tV99Zdi3YndRY<`(% z?Ge-|i$9Kx&jIB`!!Nrs%EI%{kJ7R|T?t%;sh5?E;JZlacSg)i0HWX^VpP1=k_d&a zq>g-@F1iS=He5)ralNmz@!bCN=|vW#D0{;`2^oIJ<(@oJqC` zWOq>Sf~UkLD95kNTryS>KkDFI&r_Qt(xnvQ(Uk`YXJZF z%W3mt1{zw%;EUIbXG1AYZEGSN-AIIr4-PKCBa){sz5_#~#aM`~zFcU_3+CREq??`R z{)(h~s=b%iM48^V*{!&^i|V`lWq2}#`f7KQB5(&~#MpT=FY;+%Yu94@h+qJd?TAdG ztXN|SSIW84>c0f)3Z^?2*mj;4*i-(}LQ8XfXHfFY98+A(Zd~34BtU1}PDSXC-Uj0; zZdR{$wlMlJ$0>`imizTUik-|~b(d_Mwm~fH>)ByRgKac&k@%~+ebx1S;)iX6dR4pc z;TqlC4h;yOmwh>j7(u-th}-aB5;)w_hUX{l{(O7uMxynj=`nU&0hi$q;u}iFeSp@f z_suNET)g22Oxt9Qgvm2bgfhSoW>5xiDg6K0)P|StAm&GdGMRVIs(prZ1ZRodx&x%xM7i>m}g^j}x>$4{8suKo4As&~g!S zVsRD|Oer$U)r&lyaiV5G{V3YSfA?uluY?qE4;-z5mWb z#4Fb^AT?7|9;NXHJP%tL>JnYXu*)?S-8nex(nh8I&c`ZC=Cswk3Bg2p6>hCH>aZtu zq4FwFJDxW{*msUo!rn$>2qc_u`3-rgc9;*`3sX?WF9d=hZ`j(cz*C zXl3xEHvye_q%sj=1@(<3lFAKJ5L+lDBRhn()Ki{S~qOF^%vzucOfcno>q-+ zm+_*I1ZlFe-rW(CUb>wIlNSQut2)bkGb_IFM zin|!P#2`LC%MtZERu>hmj2vDLdo9eXn>h$ski6Q(sY z*HLsZROOs*CN}Rh%{O#=OV@fe@&*cu7Z95j!YTv0S5J@$qrk2~HE#bt@B#r)7M{0V z?V$0U;xvrjZIP<2^9flq>cFG+Tzf|7QNji2zGlPPgm7ilFGZvPhmHxhzGsoNKr`ab(af#N=J(% z2Uv7Be>P+vtvK0dYjK7n8Ry9;ld|EKkaYnIlAEN3k_J0&s@&7qCU3L^qvPzTSy#=6GUqGllk!9s= zt;;bpYiP^cBO!h(<=ei(vXv4v@591t6$$-B#NgN(%6%43<^rM6Rf=bc-bppg4%jfZ z)FDd@LJ75l{z2=Lv0=19)fy%5{%m*ZfLg%rqx;lHrQM9x{mz_I(q|Rp@RKM~lTTlhvP*kDK?`844z_(;uHNtTi!fy_ZT!92jRq*hjg z2wL}5ZE?(4+5>Fhfo6;RrFuHnNb|!8*K#wbrXl(5vZwQPRjf}{y0L> z2eU$fn5xsD%tWSR@BOAt5)%lCOJtAUQJXs1iAs@ql}_TAajkH2kBG&J{Bhv{6>(z^ z&7buL=fUoFBh`MO>{9b$w}}DxI+;-GKZP()pC_kt`q)Q$B@lrQ&?Yj*sbwA1@ zIW^qEdgTd5c;pN5NPiDJ^SHF}lM72Srd2V;?`m9BTYI?K&ig;Lj_CYQq+4JEY4z29dTsL)@w87!rF>u&$xj@FMET1C~Dr_PT6_zm{@S42#Jn=S>To`!_JFQV^~ zVpwMpXi+ppqU3PVBE5?ZP;~Jajsb_N-R?9(oZc2>Yk-XAo?eWU|NF+pV>e>?h7O?@ z64n6tRgIg|=kL%}gY{fxtABQH{OtK!;hJjDP0S^5i%wVS%m>eD1ZFo%LBIp6u>jc@6dvFFg21 z7`!L6SF4Qjfx39JWI4xfK);(SZXfw%78GrA#zaEQF0b!ly%(i4T7$@`ZxQ4pf~MJK zolZ?N@8%U}-`aoyY|+D9g`;7jI4X)x$pN+E8b4Q0&ySK=M|Vp@dKkP}JB#faF%|P? zRj_1l-NG49Q9JlrHmCuga`5M1-_rXGtnA{M&1gmiCE7Y8QnDMOVw1x@s1wQHOn8l- zt9_3Qpq?5d6~`#ujEiW4wC?HF03FE|#_*=3e=EOZWV3GZJp9T38nA zw!LfJWVI5hD+*D_#C0nrJ=$oB-3*h0@Sr*?539-YL<6QtqVOsc0^*x-EKALlv3Fg8 zVDBCXiZT8zTC}}-kbe9$H5?gvmyI7UVMT)rEB5>1swXn*{SKIgN*0F)GQ+mWl+*A9 z|LrTs0Sa~okQR`#Hi*ehh5M2yN96_RDae`9G4o^N${DRccueo;AnSkS(vOO?ZmV$C zw8VUvNGik^UJToSEaJZCl%TPc)><~*nifXy%kV1Tp9zI6KD7um&mk0_4oIS@yT4y+OJ@q0K2G~yKgb{7R^PHxny_;Av;o~! z5%XoxCR($qPVq1+(qZq3U<8SGQYY$x4N(KXr3s?%xpWFqcH z@Vq+EYoeFgNo^v}djIR0KCdrc*x5c*g1vtkvbPJ~5ArDK441Abm><;r2js5jR;#~y zaB;FrmJ?-to2O8lI(eS!G+1g|-g0Yc7FYl;fOvGfE+q+fK>KPN2klAE zX?8$4o8)h3aB0~fBtsLU8jwX~z&A8qBjEc29>v9>Vo3!(@mzVGM1Bk4(CUsL40b>k zkQTb|69@4(;@8&9cU!fF3Qbh81O=xl!5oUw3$hMhKo4E zjdbtmM)L!SX(>3K_Q0*w>=I+(EkOPVo@K6=*=A>-%_Qry4(Br#b=L^R#_KGkRUC1e zieea#$({d`hEOaa1wLJv)P@(1*JR?=hg2!FEelPc!Q*_?tUFgqM&SnJXI^of~X47Ix> z3^O=KFB*xdq+Y~+!GTWHhw!&uz$x~%sp<&yw<=mOAC^}AaiBDV%|jjkj+P&AX=*aHOO~v81@*lYANL^ebkocnjeAY4q_~%2!y*bAlr*BE_+s6 zR6xg+l5}xmJO?F;r)q?!RNDPq5kS9~W#!iVLQAvLa09xD=CeCbDNo(25M2X>1i0%h zdV6GCUCdW~6*aqdYNp3c1c{}}D9BimEPJf|wTL^ru6|&tYrGnM-|GNMK()Wk=|gYO zEuN>y0N*IB90>_*EohTH>wA5}lMh~aQ&qH=zG(NCyVc?LU2Yz}5lk;d!^9o9&X9q`xb@u|) zy);i#E(LjUq%EQm{24Z*1TpJ89AqGEijt9bcS`Cd4});N$LDBmW%XaSL2gfAR2pRI z>Fc4ekVN$@OJCo*i(h&*7-9N-80P1xpeQdifo~9>{FCI4%chU0+G+Oc`xpw7J6R?rn7Z{kK zoA>QcbjYu@Jb*t|K!upPYX~s4$Xbnvf*X5`ZfaDe$0J&0`(xAEV(Im+Azb3=SBBg? zUxJ>EPVX45s9(PBKz95|j#4-qi|wN&xA%V$K=-a{$DqM8B+%2M3#=Bd$eaPKUANs|^VY$xN{L^fQKbmlQtfSi+R$7};Fx;itP?;T`&wVl#^7!^S@a7PZnu zTcV}Z5h5CB+Nxl#Kc>g)dvfk}SFlmaY_mS4lnuEl9+t#Q-Q&6K+OuP|I%WzSefPF? zg!v0A?EyO{xF#^)xPd+z9aI;dk6DG-CU|_eSv+pZVa@t*u(YQW*&RH0w)Wp~IWAn_ z|GNAm8hKy?90%HQh<(e7gu0Mb#u&1CjuF6bVR{fd%b+pZeCA`LOl#v6zXc zt`00FuTWp|MnPs%=m@tlx{6r$#T%TxN%ZxR6h`TSn>`_M>4JIcpF}*zx}VJ9=MApS@EL&tvIf@}z?n7F410X3!e8d`)*c zw@>`5Iu6iqZ70!C+HSsKvhZur6zflpwH~_>ta#P*@@UixFOLb-IG)eaA}p&7JE>#R zJVyxlLFk6?|q4mxC8y5VC0DG>0~1q0K2ih61_0iRmFhSlsh)m|7+20lYRLcp#W=sD2sHki<(X25Hj`OZtV2wX>?- zri9z3=*L;f>Fa`~xQ`8>6%lK-uuJr7 z@3;VS7gIkP0p@O@WDz3aZ1G$eA?oV~3~Jt#wPRYhp)jD`H{Y#yxFMT{Vj1p6E(8e9 zivmZRJ@)+I`WLXJiAx|Vr&eV$`VK~5zkjSnh`x;iqW7eY5R5JQM=?DZ>O*O_y$Rl% zmoRNnCk_e&*)@{xjs)m!3*^^%-CLjUY78pjkEG2H#8oHAA!D|~I%PojnXyd4J$3iu zrq7-!cIq01;1_e+YdI?{xS2~Blq(5#wJ#Mv7%WlNUkdR7@8ueC;y4-Q6)bmcl^bX`*e_JC8~%cDCRQzLJ*8o>9H1Td3JuV#K4h+6$H~=9e`Y?@n!9$3;@>1aQp{t&GH@Isf z{Fi8&U%nU`M2uZ653ou)wJyKu2`)CrEH2$yLU=7%+|^iuz;}qy{e|uS6{&dg|K#Jd z%H3?KEC@fO<6Z@ANdc94+Wm$x)|E;sE941%A2TW|RFvVmTN3zkDk_-IOIN;9P8;*RIeXlnYbrb~$~kT`4@;=t&3((}JOQ;^&Uy25J`CL$FeyJh zx<;4c5+=_T9+kL%gLMDR)(wm4(dz_J?XH4;+v4c%Sz5wrZ|D05uQCmhvttAU($Ezx zFHkgw?RoR%_0!7ZlzLFD1%{XLBKb@|j_fP#;21!>qvx^Ilo%3qLCo06Up33SR(=IJ zsvzmF@CeuX_)0#*1iEG_%(Y}z|NiaXkQ$xCbb;}<@28gBkZ7tOH^6zV*BECJ@u=b` zR`%RgD}rasxzh+$FM`Kq{`JHD*Gp~Bm({Vtq~=+c46f*!MtSe1E!8nJ%p)oiSSWrJ zljAJ6SGkDYDHp@@Tc6%95k4S9)TE)a)TX$_MxBqoZuDBNKdkK+&HM_OUsXPg1F%qy1nb*lOSbp z=t5UdqWWg|KQ)K0BVs3QhLr`=V{1${)sK5!&LBXQRNt31}edvFC~ zBm;6z)LLiJgDhvKf5MY5CMj_{?KQGc)4*Ki+#>yJ-`&AVlm5IlnxFlJKvdVQ9El4u zzFNp)&50(x>tZvNg!|?B)UTl{Y%i5H!@?Cblw)T6yE)2_nBu3GQCF=uB!YogVY(8{ zKF*hIjbuVz)w0Pwx)Tw$G(j0Emm)4cGq354CgSI&j4En-Q=bU0BMC`FE&(WY*Ai7> zcMD$Q{Bsnk{GK%VZD8ZshQp`D^8pdibA@pk9iSQ09A38vc3vy0WCa2&V)qd$5yNmveUzQ82pNGPR2u$K}KVz5$^)>y$z0E*L71k zbu~GgW-@ygOItSwW#i+QJfioXfb8tSU6O3!@i<|WEP|1mI(}YrNrXiMgOx!vTnySZ zf8blig2i*_pi?2$WiVl(i?CRWW5iil8n0)n@@WN#%V2-L6~Q%acE%=)FW@~d+gVc_ zA!}L1v%ybH^@Zo-4A0CFUO$^TFZzf?r315yBq&z*DnrNLGHOag=V7FM)Dw1X#t^e? zg>?d^QnaaKJ(h!EKof`S)h&gwF>aaXWu#>!*7Q8(#}pVvUf-lCU0%@Nh>b= z`41!!P0FJy{BSUUj44xDttg|gu7s52I~h^Vjb-;M zJ0`worgy?XTa)b5E1`Pv0f9CYfjZA$J3D#|jZc1TkG@_`4>jTI7|IxUSx9UCuu;GR zq~!EfbWl6m3<*IK(14bcn_u;qA{s(9b0{h)5L2ubpIY-)%lt=xPF_ezU!Dq;t2;K* z^qQF4n+VQWbyx|?BlFb4I)NefjPUU?N>CQ?zlBg|#}{q?`74`2Fw!?$yG9Jx>p1UU zw}GiVSuGdy77-buJ87qT0`!wvVMF))=a#94b1^S24pHlsB7JBI2E8;2!>!5wFK>W4X~` zvf#MqEE05Z7Ru(m+dZjsPH>u}GYtSFsV{5ubJKXE=dYMMz#nQH<-xgsEP<6na*d{o zhG(4d^H~lfR5^OIwAEGan&BQ$U;O5Jf5hPgT>zGaWGLf=t2L;HF0Sa6Aw|Guu^lH!A8v$51f8$Tw+hOmHE;p8u~YYw({ zK8l?+8^pF&U_|t{>a-}$sP1|N&ZMqpWHI7;cAAzpF9g*Ue!6qX7Z9dCz7AI&!g3&` zBWnvL0{R31AfZoyeKia6UN*?nk*T71W#QqS+~z4k%isXI)T6Y4d3Qhr290hk`j_Jb zwFx9|hLP6vt)k|*)QBJNKyp*@Z%Ja55HU`Myvuv1yUTdv9rgfC(3n8F*FT+Zg?P1K z9`e|5g3jF?YR%Tug{+jNE{iL*l*nwL*lvvr#7bM`6;$XnZ0cb!*%}dY5+IHIbd~r6 zt|tu&_z+uBb)FGvq(TEW5oCViAvdM@qLMUDV$KO2In-=bc9|SS89Q>MG9^1|IcLSq zL`+N`OK5hl;X*v`2BU+xCO)EMw5TiUvsG>@^wv{40$ z(4G-|91BV3%G%^QBj69}N{+W^AiZGVWMp z@g3${!fDegha+7BIiAtJ2aoAzXqm}$6m0MAImGpNWB=$yQ+a5Q?MpHIsEyHHA$wL0!gs{2M(a1dFYB@2uU8wTB96+*a zTMZsAXsd3QZ4USL;KpI60tik#{dlUTklB`Rb-+8pf%M9azaM?Fi=HLJ_`E^OTRcr$w3VPFJX+3LqV!i*iMsQ z_VRG2BMtitZi_&khwYriFG_U!p!hMHflO(U#~V;S2^2M&0cpEOkjk|?1t{{S{N)}z z)x1T_CySFag0R|{FYY$ZKd#wkd@}D<{8$mE@R`QcJICb6x+;jtd>Z;Lw)K7en0qoX zewS9MfMC6+I~U0Ez#5-h&o!f-x-r06>?<#qk!Tqx^Zr4)#nBtn_|(H!C6XUBd(f~A z2*MmZ&hqo$H)W|_SJlpyHYh|JhAm2o+;!*`O9nOf_;BeL)|JO69DDvnH{T^0e7ASZ z>EeSd%m0S%-l8kY5Yt5apU{we6;7(h16_C6+0@~Qi;=xqJ>mSryUC`x&LE4|8}nO4 z@+9j)YYX@ZZGr3x`U!??Az(*TJ4|UFQ2+oxG}W(k8D>fs)zDa}!q+2`-dV z{DH9O&RP2dKE21uYz_Y0Rt5BUTcpxiN;FvSca?}1f0`7kW32NM{PO6<0zO*Meh(1K zNM>uIEsh4}N#f2Dnv8L~?af&4%@jC3c;Z_2sT$h2OP)}|?$7u+`O3Bf%SsKW%sy3v{E3(#8PJ1YZ(IG5Z8H+Jc9J%0=ZtG zlg;d19CtUzNQbcs@iH5gL`n@UU%1YR%v|G&Sg~A%K+AkieNH~A%a08!It3)Aav3<8Ljtk%VTpsYfmaDSnkt zhtJXcC?YOOstwACT++4v!rj=~$He8BfvH5+wq2hR9Wt%kJ|Mb~*I0Qj{kuK}t2Qds z2bt@tm9(s~S3$cInx=mr_7!kuKwOPJ>ou^5sL-S+eG7O2>}BdDPXP1N=-@+@fQSi@ zcB0w9M|YK#@CGz3Me2rjf^ji=Q3nu}fYL0FdQ?)?LisXRd~n}DzZ*?moJIdS6(jBD zCO~IYqp6AZyeLPCNx+{wZhMtMl>8Zkrp0DXOi`P>1!Zdf1E1KjEp)I)#2>f^cE2?C z36*d$SnKKQ9d6ov*XJUdH8}}QVF0;E@f=>>R(N)yiYeBi>-!XwbG7n}{}O29s{2|- zApA*VzYa&k;ErW9uE?D;*|jy<%7~~+b&wG@^ORzte;})1!s;h1!3V_K)ae*Kks4;m z-goOv0^Ur+p8sv}iHlT(@FeLbPw$97HT7weRi*52i!w5KS>Y|tl{HNaBdM1@(aPfD zb)(`;tu{8>=|~pNERac=M6>JS-McBMC8kIo81E*~JgzD#3eH%w1T(@Gw9rC8{sC#gBP-&x!!-c9%@ z)%Exu_K#k-k6cg^e0y`Px$f z$9lgcFWi73cJK${B?(TlzSs==PKj)oklVb=n55_?0xn5TTt1%&Xx^l_s&L!g`349R zjl<0pf|0cIA%&CMkq{lDsK|MTP<5q3gb;vHz=J3N(Lla3_9bbIvaRh&1;0`nH#$9H zyCr-~$+Kr!ci)i28PgUZsCGsDSUyL5EK=u~sy<^R=ZyH{;e*--17wA>b)w&;*<}ss zw0Q2#i8Y{UbZcs(?Iis3T>ehxM_N3MERZT>MKh6CKPKLE9U)$umA(|7RRA2jYe~PD z@H`}BF|xh4^fugs z-gtDNnX8TaZ8mPIsk}1KEJGHkptu(G^3CxZ=f}6eCCBC&h}0#k7pWlrscWL6o*35L za`PrU$hDl%uCex{*qkIpsF92d+S17hxE7&T_{L9EzB+G9l9^tUwV93Vdt1?H)pzRs zZNaijg2)2{rv0ehF5{nq{N$ye`*ywn_IxAiM}S`*3ja>}Jzw)B@U|YAFZ4hy$3MZ& zHp3)c?tg*eCC)T76JkL2=V070i!B4pR^3G>U#}I4o1rAeIg;IVTU`7oVpcdV4i2tO z(s+$rN2e!n;)@&*$twlhu4M8L&V9YU{Iz*hL?ziw9RV7IV=(){Pfw?e z@o>&Jf3`84=?)3hWE|X~1D>9?_L-!!ZHWwsCft|I@Y=?GkN2Zy*r8h0VaBc4zYObf z!tazmP#~jvnKX1ZA-Y3OA7MH6LZV-Rv*mUatAfk+rzi>SPR;AXttGu)UI zSkeZMW7s;=5_zI)=Bd2o_roV*EMIw62HE==5R<_D0I%K1u58&yf{>$N=WkGI1ft)a%e_ca^wGt_*&Af-HidxOiTxvHN ze^LL_wV}0YS*>xFp(9aYzuEA-Q#Mo4l43zQJk{<2s(gLzFo@xdG7)ftMfx;oITcam zJAtc`HS#sc4yUInnh|EU_wtE0K{)?G6JWf!m{fHR2_c$s?cX<18Y&sJ&Gw%Y=Td#s z)#R6L`UBBF0tj@@Z0)Py;!mX;IK$l94}29Rk49*$>sJR88B1DL@T7A40@qag3wV_( zsobY~x35vXYs*7cwS6hQt+4B}2*~A;3NKi9teRcF?W0evn z4YA2L`8dx1VjT5dQ`Uh>I&heEvj+UNQK0=tx+C;W=S4*$_O3%)_4l0r`gc|ly*pRSpPCC?+O2xNq>gv@I=%UNpQeXq}8 zhd)B;@K7`*n~{kVSRei5o>vbw)NSr;lNvM{4%N|OYvZyI=%Gl}@Cviuoj(hV=-|3u zq*K17c4-+DE1v>yl84B_R`x-32ZC?N-8}0)6<)4a*XS{((Sh>1BN0pNYk6WuDH414 zbzC~pSyMGBjBActnnlW9G(nvi#VwVs4?JwTdb+3*qywNlq+r#lKd+AAF z3wUFz$8pCuDavbcwMXx;5-TY~K8mP;m80rAMpa$|zbVP1=E|kMBY1B{P^Mb)doF4J zHS_gF0Ug+w`HMjoHXJ!N8@3~(WnK`QTlMVDAfLbpGwgZnNO^1IXAT=_uUmx-rm?Ro z>^ggJ-2$itut|GEUzo*z7pZkCD9beldVjb?KleJLkP1p9#_@;G&CK?LgIaU7lk$A~`Z=2)6r zI95_VT1zz)BbGavm_3${so=+1RwbA=Le)>20{C%TSBIj|dODK_BsT$!{Y3tVW3r+=t&y%pl0XcS>TFd8oV+oHc@D;^?a zudn)g?hFaov^##byKM)VD8}(7r`pHr9_mB8wFp`xzWx`Cj8=vepWHoq!_~?gXZd~@ zQ}6bExUO4r{^7g$kTLOOzszShBgmatJc-Byuu@N|W-jGR+B3U!u${rC%u#Ynh4t~v z<7KvxJ(>;u3Oc|Uj|eFL;RKCleHbj{NLB{Q;}cGHG#)LZoOVSYpz9E@Ev+6(vYjGb z_l>}hoJ!r4Fz+aNgm?+%emm`p$pR2{ZV(d)saglp$jwKmj~mNjCgM}& z4CIXK2#0rVh~eN}I4O-0p0}QN9j`Zi;{bL2Bu5rV=kyrM4)N6E)1gx;;dMq>3}I(# zZ_NlBiD4JU(~8h$ugo|g5ZYaWBmvft279{+^u53CHd{)qH~q(})$~w)Dv|l4>^w=u z#SrzcZx%dp5sH)5VAMYYJ|OSA^BJgKAwmB)pT`T&n+s;;hj9Wj$&4?y5ZoM41f()0 zF-WOCGgy7j6d$;Ses2YeimONpFj6w;G;>ZT$T1Uxs$G-xGQ|O(fBIY zh%$8FMe_BH42~v zN5C(!sT6MZJXtcfN2ArFv8*efSKp@6zI4?ci5q6(etQ+f%Tj^jV! zM4Nu?Js>-m%QA}Qya=+dj$DSGe|jbi4D-D{7y!p+-=PX2DpC9~Tz z21I#Lo|y>Tc5mz1^=PE_x(^Hvr0a#x#<*FG@XejPM(Ean{D<=8-8#WK0T1tK|IlY2 z!BVjuRT!nUAVWM;(5V6?F85$2Ow9`R+Gw?GJ#S z{m(1UKbp|Kw#fax%xTM{e?bhf3}0EFb@bNsVJ*NRh+{!}w{Fk8$oA=VU8@R! zxdcb+vMg@dJY+_llphTNKVfizSHYWFWnyQ>sJ(N5=x`N{t9R&8?1tr7pB))18{R>k zF7;J!O-8aSqvq8V%Tgq(N^+_7&B1pZqQv6mjPRUmBf_wSZdp4hCtHopU^L-;OK>wb z$k18KF((=gP;zkgE&IWHBwaOO>S$#Q6Z)xBNN#SXU}V z!Bq7f6ub_ZkJ|wH1)vvBw}$O@G2+7tPqoXX(7NWa*J^n-KG*g6Jz(56@uF~Ly}vF} zp6RE^Bj+>8F<~p#%$-H;h>}B1tGN{C+QBI}Kp76h8oTW)#L1tWZ%K%q-6~Zx9 zo&6oIWSalxvOJI?=RC{l;~}YQ%rp$5+@JU>zf5sN)Uyr)PN{pb9Q}F&Zw;)hsOhhb z{7c5QC4XNo$sHIiyOXhbICl8N+>8TUrnw-bTOzK(O3NgP^h&yTc7lxU_E*!56Ry$u zhwJK#(wt-y`q7~86_{Dj1?17(?~DP3ykW&Ea}e?o>fjBYbpWx&_bNQvWnQ3y-MeR26TvUG2oo0#7K`Obf^%< z(L(iHC`sT1hy`44MdqOQ*!6;2H*)?a_^r@$${ff8&)NXJRl}X#P@quj7%L{WT+2v= zp15(C6QJO_WFzh!uhdB6Ykm%>G8q5BQC%fSOnBvQuF;aYmwiX}T8K?Z+=;FBEOvQU z{xW1sT1aB6hAsBZ5~+J(0hFguI4eA_b1tPM$QV9%fd#<*pJ3c8uQ(RrrfzIRAtn_X z>&JD{s0Rby#n?Wv%w6fNx#_GMN=vWz4e?=E0;Dj5u#+WOR=FCZ=kJr#W8HuLFbetr ztO0gsRP0e$Nq9AP?T_JhXIBfX@!RC)0Bau;XKA8lobZEI?bm*dN}% zKqEV?)tvlN770~8Ado|MC9$hZ zukin9_ETlWJFlGE1s}uX*SQv7f>*%hqAay#HIvZJd|7uPlEKsZBm3 zA}wo@6tP=iJ6yprM5&wyMZod6^G0ubw;k@Xg;VbZP=!0H$f!LpeAn9|?)16E-9ilx z<>Q!w-y5(Fb1D}HT&h;+BobH_VPo{t8d<3LlS;Pj+(Lo&QKgjs%C%FarFIv>=rYIu zB7kce+z{IdPD!#j0&gA9?h^JwZt~2?t=YYoW6jzR))H$>^U;kfWCh*}uWw}6OaD{H zi(d9L9VLZ**4Jg@67FH$Gb6ugdEU@Rs_UDPDUiXs!X~H6{cYtIh94?X1C!HHlSak$ zsvMj2jtc#Fh zL`ZQ1@mQe=zb4oB6w1rWq3@bN&GcjJRb>y=)3p39y+UlGVQYb+D}v}pYe|}%(z7_< z&`Mh|k5Z{K=ar4X5NskHH)_)@;RGVb8h!>g@|yFX<{n4Il&dTIGkTe%*&-e|pv|hyzKu;Cj_hnfd<--J zuwP`fgm|8}#7SV+iAC`+zHImCFMv;Qa`I0fP^iZ%j299q6rm$Ol+>P>`?dp7Lz~o# z^VM7xrqp`R59SHP^U#d&e^Ur$*&jE*PH1SliuJ@|D235@Ufd_f)tj`bXmnQH-l_+b zQ7t6IuT(I3xCum~sHuEZq6c9#t$KsLy{YUQQfxPIa#jRxwh< z;5;3GpIIwK#~ByFg=wQGTGdX8fr8txZT+u$G3T^NR)~)bzRG}kfm7)AQ(^KDkS& zPivqsdTi#XF~owDXn;m?ng*^JN3+0-!Sgs}c2HpSSJZ&_P0O9Bpj2KwEz_KK)wSYR zaf`TEvU=)1U-FB%$FElHKsL_{rR0w873{1B56e5Spt%y@{24yPP?xFEwRhItfl?=}6I zerQoTpys9*tHDJUbH?5KgFOw8&`}EEO@jJ^=6um36xYW-Q(8Ly7_#BGyoIZK+5~|- z94qTfNGJ|YcY3gPPwiuaRSPJpzluCrH6lZJMRj9R8Uqt)H41=02ILszFbmkm+B;5w zuEey*1*`-MYIC1ojEXPJZ`-avN`&ONRN2u#cWoCalwL!&tNh{;6Q<mi}KDr`otJrUrqj~H+E*O#SBKjP%5YW(pp_51@v$ai(ddx6`md!+S|mkv$i9%#`#^%}CK^&|?OjM3Hf$u=E1ziwwb%{b4~euj~F z06*4aRdVn>5CF9Jk9(95{lT4LFGEPUIj&IL_KcVx+loB~{*x(cqzm&a+;Dzw}kV8~OOCMO#J$i?$3V!@km!QW@ zys{b+?1#t-ub%vx@h2d+JI_HeN>$@UP@fRKDep>@%@6@X_E~IaNi5F8UV!RagcgW& z>S!#+oCHl>yX#X##Hor}Uum*x)C|L*a|9ZgY0gLI+>hf{4d_R2E6V|2uZKP{%rdzLkUp^g%dXzHxlk z77L3%3k*XLm>xT}aem>evHeM4Gb>Z%^(tln1HBnQE;u~tL?~n+L^cdk2kSQl9WKlwitxtV71Y1JW9iDh8LE0SrHFj7-1M>v7w7HMxAQLj@T**d zt9!!-r<=uYb@vb)e?d2;$u=9Tw#H0Yz`hDwJx|4Ou!=Nnfy6b3aWG91@5pk50=u{M5Kup2?Jb=-lI1a8I5##ByNfMoni;wYsdMXfmh|Gb#UnFtB`7kk{% zp^)o8S*2zmpmtvXi3ApD?w|Meid2qk*NO+yMA0Nb~Nl;_XkM|Pkd-X^bm7i zU7`3r8dX+AvQ|Qir<&s{moGt#1gmn7HiSem)I1pF2E421a$U1@CULYO1QsvgMqG(H zHL`IOx@5gc#^=#CBHj1G80NIqRkDX038o67aI}Ju##vpqdY+*L4;&PpC^_fl1BFlt zPzrg{_%(sW29!B@he3)l)-s{e5TI!*kQxdg`uS4>2rqMbAJKGCDBO07x5-_0Rj!h1 z30Ue_-eFd#`s-^eDue&ChszpW(Geggr1hvdT#zeC+d)8fHy@zsi{M)Zm|IB93+ZaN; zzzE!G`PZ}!t+*fKziX|DRxOO=*Gn`bv=&dF@6OedMz}Egtk7qa8&D;r6L8oU@Oi&l z0FjyH!7%<&5bV2^3v`+wA~m*~Wfh$#49+fK#}=rl>`UA7g3iGg>93k0&{99O-3`N~ z9AR=XZa#jFKF-hl7&qvwHONc@J{HsxwgB+KR#~ndbgldY-YQm7mpNnuyZS83eDf>a8#y3gU5mBqiJ+{b z2mG@T%G@X_65Urn5YH)2$p`j@koQsVZ!P>pWpj-zpaD!b+rwcV-fo_aHUrL-$*)x6 z2T%U;-ZK7h&3)0FQ#U>{GY!C8-F|fXPt=Fjf~$(d%FDlCNHumH$(+j_yXy$rr=0D{_=-NYLah^415fRgI^Oj>0){wAlaF_X`*8vsWuUEjY2 zohy~LSGhcf{#+VNzM*O3l%q`89v9-j?C^l75Y}@-Q%J$1KzZVgFF{YH_#YX88tn60XjLFr)th@ z%`!>1blK!_k?iKO$bgRXsDR1DnWu*ZKwFt?LvkVJeagJxJGIikVi=Y-c4nQV z*7HqtTpp2xtKb~}`qeHVDpebrnU=>X?Qi9bh^G{Sj7ZN5vtkQi)M51^y7{wLMysv* z6oT-`NUJ?@W=Zu*iEf(r73HtxXGb|8-v)$w6fBPp-P9=ZYF^CnRAK9iph%g!;F(vIZLlMiXCDU5#3j)y)&E54+#Fs8>aW5KY# zzFe!Ln2rQhet6l6l{X#tK=pEKrN}Oeex8#FZZA+B2s@?(qz>n=t6dnC3RuwI+lRyx1L#MdFFOZUZZ`5>@ztJ7d{0RtF|hjg@l{2V~_Dhja%q znE0sEVICgu>w3j5=M(`z-i&naf;DWoA`QurbRMqo+irYlu>~<_D;@f$>5vJ^(G%pP z&@0b+F+HZyHdLSMo+#Wh2PaYD6m(6;WK1`r7tY`5l`;ydo3dQ<<8|pLP=%iuZ<)Li zhGR=CDShZAe-KNSV~)TvnE*L7wLMqx9Ba4otJnFAPS{G*{4>MOhH~eYq=8uyXBnlM zIB;;>i%MT`fH>z0`E$_OvWK!sq~+xrVi2{twodo3r8D-bU*QuyKNMa5F0k3{bs>B= z#n7K_O~JonrM6Gy4E10c=3cgup)4phb3i(D%8KIw6-Vzu&7JoY%TzYrlP!0x1(gcU zT@kn-%v6dLu&={FT!L>p+N%%kOcoSY_)BMD27e&&QqyXE2gL;hr>gpDHTX0bT#f}H zoIh(WC@2yWnug-M%5q=)5*1>1%PThK(AW!S-Tn8+LmvBTS!$xGT~|KeAte>hg#sA` z)(MKQosxn+NkBC!=H|qUC^b`mkFrTy42}1>hFQ(VeNG09dnvSM=lA5L37H2J+U2u^ z6piTNP2G0^Goo6(p~z%CW^6SEBoh=KXL(OLtH=FtFh{%rH*E>EfEmzXelLP@67d8{ z7XmgH{V%##%+fmQRK{-=$WphdS`MSGArt@+L4NrLH6iE`Hh9zwOnSiewcaH79$%Mb zf-xX%R=pm%rz|J? z)Ydg8N#vFVp7n;HuehO5S35ODH=C3*v%>U=AsC&K zq1l0=>N$wwP)M+YgG3_xx<_cPoEe|PT_Yh2Xf!Gngx3(mW}*D2z%5f9R7uo$ zN5CSklNXaD)Nl>@C)@eFHZvJ%j&XA*Gvvq%iq=!%GnDc8$v-Q^cCCe5$E&;)hPmsGS>L4s(Wt|-niK0 znQZf@`q*!hU2G}E2a1D?ow$HkI$JUAX`AG~goQ&Cn%}f1y z7J{`n-hsXXF1jJ}9tFt}dj0>Sm?*|$zV`n+_%(keha3pmYD)WIqC~)Gy?v2o-C7RH zd)Q4=Cw|IYT2(~*BevBAn8>xNM$mMFa$G8Qtv*Y9v|N1L+}%C{KaAG<8}xYdS<=m4 zf%qI!Q2zoU%!A7^ll5t=>s?JezV{p1*m+-!RN+*wOY}eawV;%Y8GSmLGZObJdVhpOM(JP+Roe{0@C1pbH{lU*X;a6Jyt8vBqC@*@6fFv4 z5#YAENXkkNqpHSDIQW$-OHu}`5eBrJPVbX9X^5Tz$MmQsE5V#lTLa^)_;Yv)v%-L+ z%&(;24`NhcdyV+DX>bTVSaaIj51M(*?|*ZAi`o{V#Xjw;@(dw*s=w$%h=vA*&qZ0q zf1<~zoAN(C8y&E^{xR=0`3?=uf`FjdDCS1-AAl(8jG}b7 z#s7BQqqden*6HM_FcQELyM&#B+@Dg43zV@VnrJQLum-+5Z!+M7R=PIKq7(5kmzxu( zNazu~ZzbgxK+^R#px*iPpC9yT5>W|F8DUF(QY8PD9~UgJB!ki=T(t7au-ry&Pz-5U zEx7hVLQaxpJTDFJS?>_Nz5~dJ5qNl!viq-chd!q`%;=>oA~)xjq*izAH9Cj$Pk81` z10yrzHGo3I+H&bjBuhHaqV#9a>g)VxHV{qDD54s}yP-`-wNZ~>Zz(9oGOC-ucJMGQXZ z%X#jX)PohtvU7fQM7EJ*B|GJ@Fj-AJ=cPDluQwX2Rc-+R`Np6$@eNEOX?9Sb;$-PT zr<})|8Al*_nMiH)xm}~894jinhvqW?2B7_vXp#qo29kpEHQeL|>*Ls%h1q|O-0Y!0 zm@&Bb?Y-{>wdmmFNX{_4FN~bp`2nFZ4W*|T?$T52nP6_uw7qQ+d4&dWwYSy+kJJAN z1GPBRZ*3M)`3696+8FsgtHaCAS|r8A$;T7w=2>N8X5gCE`zQF!Y1vlkO7u%QPrh3e z=rgryxpgyh>amJZCqg<^JO;81+u>;RJB-Q{GJZD{KBt`UnZ_?PVO~aK&dd=B-$dHx zp|UlZCZE3mIT;#3J8MaJxgR;(u4N=3UP}|9){c~=IcbzBQ7|tta+6(pQ}A0+gZ*OM zJXqv;-r)U_<1YQnM--Gq*khbm(ZL;-Vi}{KyBo(RZ(_{$<_Re9WK)tkisD8MzA~sOG zvF{r93T*t!6ji;#FCs1(Lp!+eXSMDiGb8>51HV^NZn7~OYsrrJ6Kr6YJ$xZJZt4eD;qS5MUT!ueHb>bx*3+$WE@aG`=O0V7t1Yh)-#MABud{ z?2Pq`x(m!L9NLQnPQ_pEh8je}0t~%-`4F#%k3$!$jFmwPw6bmmmQ6)DO4P#~=!crc z0nP9fn;-e~w5;6hSWh=ylsaSln*4(sY1mz)yjqr9mDS9cH|Ik*baq&Hl5Sl5IJrh% zD>$(jhl&99C2HRQSTl$A+sMXyk{TmX%!_;QB3E-u`quGcN#8omSEeh{1h@J*6#-)j z^*od9#>1^q<^U(IoCyO*3Jod#=)}Vaxp&bKN5$|?d$1V8E-2M5Y`;N}LzFv-i`?Jh zW{2$7&gpqeQfxukc zc-sm((O92G@LF{kPOh$64UfRcY5*rd*uM#fWP{za)4GO7GY7y^KKK$LYRMnfOhF1b?Mg)k%fW@Vah8 zwHpp44J%Tit%7N|Q*T2_@d6~Od;8>H4Q)n&lZhnZmqwYj z(<~3_)o$I-b{c9M*B8ph>qI2M-Pz_-q|fVOH~@KN+`MiO*HbEVy)Mf3ld?@`+f%z+ z@Bja}Fb%|4U~Uq&KTt3uA41*%{2DaF1ZHpfT8FNC`QEQ_1ul59gDl7@A&Zm7-qV8_ zqG(~m0!sA9(G8$j2m)c|KW!UdO|BaQU~QSM7#lB8gMXp)1so4%QEVy{>7?;vg`7&y z0O=i>0Vm)&pusbThdgPuGrT2J z%{r-W_>w+Y#^}Z7#WUzm=^m@MU{FjTH>>UCh_x`)FU5y*hpYO|5;Xmr(wo4iXxk*s zD@n0(S};a)3C@^03vR~xaVx|1$T;PFZd1{m3f%w_1#5sYM)G*92@%>=Nst)KAlwOL zf}pUc);;)q1b4w#g4m$bK4Br&&9?B-4E6iDAawF8U~mE_=*!Pc?CjeB1QPi4Tt=c# zeKjr5Zpso~mfXk6uV$x?#MTl;xcY;OdR3R1sZ=uDsn*CC%lXTE8@9wo0?1q;>T!8! z+){81!2z;k_*KvOu9L8?OG7b)-&Ri3`2}i^Jab7oRf)1Lr-Ka&W5nnU%bM}x=YR1( zxT6N~TG?RgII9wLfP$4Y*oM8-GUf8ZW(0vD!d5vr;n-T}yEWaVywf4yfuug_Es#4W zi9o}vm(0nv9PTGzg-qC7XXUgHO0L`1;=ir;=*KB{aoev!PglHPj`b`UQ;?E05`PFo zj6dwQuVONA)s^arAEE6~r$NW3?87*BG%HUEx>1o1Nu#?)1wbtU=D-bD$Mu0r<{0(9 zIV9ECMx9X5@?`&rA>yL@K5kXg{Cr;Z?ZKuh8Ui6n2gcN*s~6`fHm|*E9mvm6OjE4dcD!eIWa)Pwa>%_=h8Pr~FZBtCnU!jjeA;+e5PaP2VT49nGTA(bwy@A0cA4Uo z;ok*MnsWK|Rqd~)ixXq;lILMHMiKW{Iq>1zpn*)&cB;7s|GB}&iSS?$t1hl}j#lIZ z@k+9-9s*ShyK4EcHS6X&-f-+{VLP<*7B+uJ*-R%JkjLkK?dc4v7pLI6TC=tzj0hKm z805%}^r2cF-2nq_;8PSBjDnghQ545AF)#a$;EUP>oaXBKqk0wT@;o$98N2%)VoUK zd94XCE)g3QK*l8jLVAMI8@lo^~W5-$vK-z(#}e&I{UPT=BQuS zITivS0kF2B{Y8OIMPE8I2z*+AXnHZH%~vHx49*X)f!fKZx$uzQh6~p?#(jiRtAZV% zVMsA{DaOJQE>Zg^5$> z5=OzDj`8E++~8yFnE$=Br059gO{x*5HNZ_q=$av zX8=&Nx{?Ki6W;FH48Q@O(2^Pq#ke$0mSF%HVD$ADS6arTTe&qnls@7p)gj;!>$L!i z2b`JeJuevw_cD&u7@GIy;*u>PcZzS65g~Y&`$)@<0ohto-M}RuTG|A( zh}OC?G56Ptd#It;%L;mnE5F{XA*AR5vJ1N*8ApEzrmXRWiwV#gka%1*h|*O>L-ZPn z|AjgWnbbW*-)Eh1%o2=9TsUk8tdS2yRD9;Q_w0vXY~k(E-#%+~k8N7;hd)Y0<8@@s z3u=H&(Y!S)Y=S6+Cp=dcF{&AVEEg^lBsmX91Qc{!cJV?2`BaTUCUj{r^*L^4)LSF- z%(KkSctLlvChvC^g@`VtT|3r|g++kiSB`Am>2c;#k|9C{{wrL*NIA+J158OkrZ&|N z{|W8c0`2Jlf>>Xm`6!?ms;r8*wX_^zH6su8@!66nJ=|AmamWAvKj*pXHFYhl z?Wt*|)IP3#*|iik4^xc(Xzxc3-#|t^DvTTr=(4^S1VJZ`Xw>tsmm{@I>@VJ*29V&f z7?Ua0zcK0V6`Pgn3F{+5+{f z%OV25W?I%Z4-tiQiLa8t2GJ%O$q6^~&XZxy!bg(?XMGcDKm14L#ve$AIS-rl>#j6~ z(pryYx-wQ$G|AIlMHOs6jmAzDXyJQ%wQJ*pm?Jk}HL2*gGEi%J{S?d%li;*LX9?$o zBYU()uWZ%U?xZ?GC0U*5lTrp6`Y$V3j73IiJKR#lth~LsW9``mYK=Hp@*MP^n zqBb3d&}@C1A%KY@!0jrG{_EI`7poq2t&LvGvOLCE-$5O(FcG`h;jbUm$3EEpp_F7U z+Y_Q_SrF8NSSmcT+B+Q^GI@T33$B7GgLik)4~sscP3E+0;r_w$xfw=-@TLNnB`gyRA2cWMrBr^1F_{q z=79_ibtKXp2Zc2UVp*X7?s(1|LrJt<0>S>0P;JWc($zu-hc;F=U@lrZdsBl5Qzn0} zCAO4%>;W4YE|pLf z9Hf?gKlT-4MPFwHba8V#lb}5 z?gai0&&H8~CH$7>0Ml3X3f%gSS(PZ9AL)y!F}+)rSP5L-JFl1`d2z2bhY^t?lZMBA zoK5UO$1WgS{;u<^*a65YhQ76}?O(J@_^-jc)pNypJ{1D_zOi+ZM@}C8qVT*8^nIkE zL_p9baeI2)v%|7a#XR#Hvt1D!0Y*vz*hJeCR4mV+8=xiDieLtV zqIRoUs@JwVW_Kb$7o=b!2ad9NKo-jQKk&RcRy4L*=~-@o#~YFGN{f9pLyrpb5ObY@MVO&Amy2rwY}+us28se!DPoeg z zfHA{}j~D1JSH{VWl%|PV`ab;YE8d!E9<%mgdt@~SG0sYCdXic>lqf32X3FBDi(Dr3 z3YQQKTT4_kO1=g5l4+ND4*y;X=Z)12vioqT7~gdjILT?Bc-D{Hy95dBBT~FodO7sM z7irVD7KeSC5(XKS=uue50SFWx;XVkeCSy^e5GPy41M>9#4SV?};X9=+9&E%|Vm+i> zVMnls8$>qiuI+N_M)GOFL8X#~yCT;Nrx)Ns*oV6}T)2+)bjk7Iml{%^o0Ak-LhFT+ zdx-M#zck#ih;$+M{#x$ZE2reTAK73QLmvu3xcqXRWDN+bV!aN|%?>}P5~6NNa?RU? z$g9XJr#1S$CJem;p^zr2SthHS?25K;;S@2NxGI6wrdsMdi;H>y`e&S4NQ+m*;{qYXb zR=SmeR>!Vp#D!c;IOQ9-+Kz6E`1#uSXW;;~Ky#WMYm*p&bC(0}(Ae1=rBn2?6|dgW zfPcHQsRl4Z_M0o$j)3Vv7~u+z3=ZI4VOBqF_LL3@Xi0i5_78V}F|fmNAHvxJZcKLvV!T}v(*zwAcfwOt*Q`)gk|KMq?BFjJ~&8Fg%#3 z-=&*(M=J9zk=(aj?7xWy%oa8%zXfWqbZtjpg}LNb?Sw-q2p~$F{ueIOz{7Dlcb6O5 zOE|QlfO>CODEy8E;s*n7oj$#O)(Rn~g65sW*~qEKkM~Kb9rVS3l@@~ z$X@9qb)`6LLqvtvqT(k{y{BJ}vLeW!PzOuyh0*;y1YVt7jo^J4YEp4cX=?m}<91&Y zA&eE_R+TqOW>&&Aa~cshWM?uLVH3cf@D@?S8emz0J`O>fH*FM09vd5Irp%}5&_ygm zSW5bERi&-Z#&k#ugEyHAM2#+)$NJh6COhMpfx@zTao`xo|5Y&uyxRQ=Te zZ?|De6e~ zqGb)Hq3h#FIp^bf*T@JslQpDHC71LS9xJ$a13yXj52`YAzJUZ(tza!sP7)FMV);z8 zdWwL=wjtc>_Rc{)BrU8rx2MVRdsB+!K^dF{A5xN}mTFrcz=t;Xda>FkkP}FOYPAp( zZ)i)B&r=DqccC+-HvS2I8i-IR^b-iY9VmA}_P)hGkPfDWu6h2jJTB1w3cvgql5XF~ zXE+3EI?u5b05PcMoh&K`nCKdrTiVJ_HtOAizy@7uSOJ5@_N7seB8afTtB>c+W;j%t zU1(4nRleKlKS^zeKh!El*P{mf`=NtDabX1-{IqC!B3EUjhf?Drp1?xTzV;R-UXpwd zfhV}csxE#c9A>C`ZUoUlY*fbO z>dy$aAdtk?0Xd#>FY+qrP22nzoHcRN!7gRGw^QlXK+Nn&PM}$0!yG%xWxWgGGgIhj2B*$|DCOn+fK9L zlujgqpxesbB%3KMK-hV--nmU6N5Fa_&dyACDJm4G9IEsoo0rHwk=`~6OO!XmiO>m1#CRCbRbW#Q%R0V+^sh-1iEqyaj>@}Uq?MUunH34 ztwj1jR8XS~^Do}S=`U_++hoR|U6a_1EYQr&(W9})e3b)vb43?D0>hUf;D^n%dLR~l z09oH33Z_h%$U?&e06q7@z$MlHL=pk4mxFR%b$VuNFwa2#S#8OWGq!3{;+LqHv@+NgDd|Wq_Da71))`4yl$jZ{yt}Z%^ zh%k{yEpD5Xu8fi=JFxHp2(Sv*A6wYqc|QYO%I-#Oz4OjTAm10vM^udBEjC<|mi_}8 zu^d_>2EXP<4al^=s(mG{mQrHbZGoj^uhHr7k`6O*>R1sUCwy|@OgE(#wkTexCoSOA z!veLMS(cs`e`xHlmoRi6Km$10O&k#Q1Rol&dbwPfP)m4(NVb*}(S*7w(9|e)J`$PQ zSDqLv3Ch)_T!qheEc2Z$){dfo7pM-gK%(IR)iT14OfCo_rX;+RTkgrWsY2UTrj}V~ z<{_2?)+cI3=&Z^i=digyctswJUZFPK!6M$s?SPYq+%(V=`s9^uP7gb!z`QMMt?NfK zb3@t0b-=}JD2hW8J<*4}HI(=C#PZSwEBL6EL&kw#3q_}&(pXZB5E82fQi+i^9W#1M#}jFvI>WapI4vsms(aX%KT?sx5$m+vz$J-B z6g5hv?U`Tg;EX$T78DCMBHa1ZW$JwD-hXwpYtaMtGpC}&@2*Yge( zttl5KR?$?VJA%Th4BR&O{RhKO;oMulj(v2|^q$~m0So}p>k-C=@LvR>q(ZkDa8)gl zU{pO>RV9OhK>K!ADKe@T+r_2?Uf#jl#}T0+GAh2oMDzijKPALr)Iz`~VCM>=j{r3+ zTeqb5^f5i8-{d^}8YdRx>Wi#5vhTI1TU$W?GOl20xuWp?M8@~$ zYBRUrK}BX_TtyQtZkRQ(KXSB2n47F0*(9eipleepR`PU_E;g_ z?RiPEOvpJoyOW8)l_adC@kar`Sqq|$6LVv&L|7$n1q6fDlbzR;A*c{VN(5d)J$YM{ zZ=@X}U<^S$o`awH@W=ig*^g2@oV3%T7f-Lq!>WV-(ak0wO6XW&`h^k&q2t)6{(Asa(V>_fMQ(td4)WG~NIk9oUH_Qf{kD&bO@D)b zOX8JGJAeVgZkJJ+NnqP3+6^zNkH_7Dw&P+%nxplSzAtP zU=5?i_YLz(;^Q~>8I$eF=?6g|&ZL*n5%TcBc)3X(Pbgn)#NEcDL)>ZlNVC&A`1TUf zerWA8o%)bYLb9*QC#O02g2LJ>7cl>|HpE-Bn_{EGC?oTHfI4_4Tc{!a32jW!D+Pa~ z(z$VQeLEGIhuKYGkDh4Q;HOF~!x=Mg5|xT5{XtOL%yH{YZ{w?ZO!q6W4sATN2t5}u z#VHSqrQn>O;bU+_07T&P73WYheG;c(b&3pT{M$iOW0x#Wnj6}bB2AypE`euNRW2{e-$To{y~+lr7dUax(q^%}OZPQF zIRquuwIW9`op%$%?36JKdna5cKHEuC)BK6k%kvkrE}6a@(r2D`LP2k@_2niBB5Axl zPq9d%s)S6M>KDK7l*Dt~Is(+ha<%uDYcDq4-PF|PFjdhYi7CfO_`En|!I(%NIyp&7 z44%vyZtUth@W=!OQ_eOTGChWz086AKqCEfh{G?)6gsv6Aj@w9tEru+Ff*Jb85 zK|Jfe88}SQOl_x=?+(w;-Hx#?f$I_Io%%Gplp_l!C$}(FVji6=Ner+*oz(@edR#E$b zAypt@82$9<_QI^i!pbjib}X3+L=MDB8D$2+eE8H$>Vzs@c*%zTkY_*fGj7?VDUM{{ zkL(%2iK4uN-p9>v)roeAQ~V%^LC(jEOWX<9bnR5T3*A>o64@&-d+lfPG96AzB(RQ* z|90U>6u{T?^l+++7^E1)TF7qyU?c^jLv)|nn0zM75j6|4f@rblT(=s*vHUl5@QYWi zQ-^Da7yyQYLSKy=TTx}0`BQh{kPW-8&cVeHkUAi^UI9Xh5(c7Z93F){gV8!5;xoAm`<}Bx3 znIiJ1A;jjT!5RbCFQi9$qU9?&*4lJ}5bmCz`ciJ&)fCTE@NB(IC1a7{OlyE@hlaQ}8{vn1O)^v|Kyjt}bG*lLen5r~6Ru`S2&EG-qb|BE#sf z+Kr&I1mb-gwR2!WsH^=K3N1EQ7dd*>Doiy5$F{7P#sYZx34LE9nu(5}u9|paKg<~q zxc)R*<(T_b62>C;&qXhPDJ^&MpUx7U`FjQ2qQ zzyX#X*&~p`eP;V?ecSli={bIt`KqFNFUd5aaMTz{w+_`-`&~!msKCQ0OarWtUs|Sp z+B*)e><~^Tz$Ag1gl=l&&=OYP&l(t<0R1;GF|^B;qi6)VYANAwm_!2^jDhwlYpg>v zaoIFDmRI^4F_kzAo4M=E$12Hl%RTEth~y}$M%m6SO+ESpA&K%wm?ko>G5@w-T;Anl zqzldDMBBxC9L~R;5hOGG_VzQW7x-^hEF2yl88#l3BL-ef*P>EA%S&(70#WB4*E%_$ z%#3&bRPc+S9ciUJhy%EpKan2=D5tD4$Bk%?WWt_H8PR;r6!a<=FutBcZ?$Lp-shkC z+aci$Wci3(6Hd^s$id+jqw5L8?s!fLO|9lyZABJB7WVhztUiE|c)P3$>9EPn#8BStyEa}@!1^mA4uU|NM zSu`b8n@F0>T1-skiTyr8z@du$4bU$<8=I*-jQC8D9}JaksAsr+zn=Pz*k0$oCx7(wtU z^#0o!q8=q_wEkyjentxLGKLtZ?rmF1BvoZOH1!wVnXPV$y{UYx!hDkdv8b*H1WP(u zTqH2)3T1*fD;V@QehZxklK*c~nvAZgvrXuA79K5!CzWqW$Tc=GY(!csy*(7*uwy?b zaxN$o;f?O}{P(sUi0>)#lnb+0>-!aCuERy2?QbtjrBl+^S>ZT!^sx`Z0m8|K(O>bk z?s39XdYWNicOfJWHjK#@T%Ae*^XhReOP*2C*}E3!z?c!YXKvDWPc}aj=u69-92s?9 zT8T^wPj>BUlWqcPh};jjPt}&KUj6lI5_kw#B-Jf>H{r!C+GrL8*4_W+SDmT;A)JB= z7_4TfWugsTw1r4tdla!h^+N~|b6#C>lxj)Up;1dZTr$8lO6vMuO~C>SSfQtc=&|0ly|}Y2M15#|=Ho(Yzn|G>~80Tyd?`AUEA zpY5=0n%-Gbl`6O^4d*d66F*9O_PCNF8!QoRP$kV@Jm;I(=g!?wq>B2c@esr)886;PT{CFN3Yc z;OAhfw?!7gLB(MCvm=5ni~jM?xNj|4}=!1kD z1ceP`&>SJ}-Nqp>K4n2SwC!!y1R-wJp5mx0`HOcJk@O;tw)h=&NSvcAX)G^lkAH|P zNG5HK!xpa8oD0l4A9`^KSVT-zD-}bj3u2Pm5Bs)$V;HXrReMYE&nI*olqn?=uw)oh z>?aNsevP|$w`B6`hTxzg z(eqwfS67Jxm$F(}Zp@u4{$4xem&cjiuFsp}4Uo|8!W>*Vzuvyq!I27HD=EgzWS-~3 zO*-M>CfZxO!)3d0YfLUTq%44yFdIdq(cgPh7)Ky8|Tp(*v_tQBY7tom5;K`2E5R4W>g-=b>B|Z@}Cj~yO{1v4W%kmmGh?5d-Uv4c!Wk? z3-p{3SO07&fgre;+5%uPw^?|niS?EYhVT_?V5`7+*w5dew%EAz2lcqAu9|(XM5aCH z*sQ9}mFtzbyV% z*hu=hqE~^QKAdV)Thh}u_V9DOt-9hX$b7?z{o~OXRka(A5TPCi ze8yjFH=404qY#_>eTb4_h~LAWISZJ}ceFE~V<<~*2Xsqr0K{|+ud$;N=Ysx)HG^>~ zem^oWi`+fH0T&A-p=4$hv~%!~itsIJ7ZAXS(i1?ao!JD~+_-umlR9a_wl<17(+@s} zkfyRGL+!I-ylJwe!C}a0{YjdFs9W?v+8keSkIp=`sN3r^(%ldY=HsQA(04dYNzPms z^A1JF#q@4k`o5CgPSfT(>~jgHx$pDjs>$_l(OX@IuiNoJBb-R4(jR#st5Hl`a5wo5aAei%P`_QCqUhJDA$fR&2zF9> zem%Y&4M`d-Z*`crA?Lj;_94XFM$-g&bA-@Ytn$(s5zeiWaQBG|e!x!;QbD!db)uq+ zd|a=bUCRzkgpoCdkI91$R=;`Nm`EUcW_^K^{gWLeC7E+aQKudv)=5diq&R?ZopRM6 zYoe{#vE~$|EMW^?yKa;F#-oFsiGRzCg(CAhCOZ1FQAc!(AS#)u%U6%iUEJ? z)S=GJI6UPh)(7-SNrj#ZmzN}Kr0{n?!vnItMnLHY-dt&@?I8(Iq18LgqQdd6{GeJWJTAX74NafFU7We|qr7)TL3+F_tPCv)k{NfME z#yD9{N_{D?)-a2{yjK{K62bgQ$CgE5m_|}BtgrQaD9XIKqpZ_wkq|MR4J(6|0zS=$ zDMf>^Tir;cV)#*lL8k+yf(WN#e!oNIxb#-x%sH4S!_>p zaD3{nt0&fcwXLI~_zj_UgXW-Ta~ya=W}ii}iv-k9&yOPuoC6l>`R<? zg2tAhxlOB7G>VW{6j_LM{1fmQ8z_BRbw>6C@(sk(;NqEcp!5mB(q)}E^cj%sCUNrx z@wtg29*r4#U;pr|z=5SOf}R+VQ;mkt`t2HQ&YE22(e7cTb)-uZc%=9Wd@%nuSAwhO ztTeE~QINP+gi83k*g$2R$6lE>=4)^Ei*K3rsM$WDcI~Q?nd<#{u2%5QXy*AS*Qm+A z$%fn~q=yHyV6lObH5#vr!xvl1<-f5-&2&I|pmTSQ{fz0fL*Dl1V4L{zL#90>ajgQM zQWi*Ceb=vldbkX*h7a6TTqw#9Fg9`?(&bo2A0H&ZTT&v)BsACvFey^8hC_;=;yhe- z?+T)G36b++tKu;&TWT=^`rCo$3Shx}+jda|QE@a5k?sYoPkb>{l?S zuLgV4RFOe;H*%ImC6251nH`2|MpuWN${9P>gAzt7W&-=)vAMA{tnkLn+XKqMORfzq zK7F{YjYYNr@2Y!Pn@T6PgM98+xf(0!?>|SFo}+Cj0u5NXZ%reET8rH#CQ_xK+8xs2QE>d|Jm zM zHu1h=f6e}dsG!vKv;mt?15GErjxEK*H$!nF;pUH)1f|LT_gB^bIkTL2bA(NWUMV3# zq;KT7gV1i!&l56%avkDI)?}2?3rm(Wa2jzuLs7ybsn)qzxd$k;u5QDYIX+Al<&DwX z904?`-euXsG=ur;nyspL98_juf>@6(p8q_JyowOWPH0kBd|n5EYfQxE0V7#HV)Da> zFZoq4`%aQjP#UKs;>{tq?#q>O!#D8A=gq5!jh~IoQ?wSQ{)A(^_fT<`+*|302iJ1Y z7nz8lmscw6d(}i$EB3AqlvTlILHCZTJ-MGO?%g3_nE6U^kIwOuqE4&*(wf8P)@ zFo0_b$u`&8Ja{^}#x#CXJPc^54a(4^$-onOra;eUZ0jIxNWyusa}7BOvY$I-IcG{d zvU&E>6Zvo;iHpvNOob33<3=f!9e)R^MfHq=$YaHKC{=S_ z_FQW(Dm5#-0t!!(rv02~0Q&;^K#LA-WPmC^w8P~Oo4OG{bmHo3=RuG_2riuFe8T8( zP!8L6ZjN{+j5bY9AfW&5{N3)ov^Nr#LA?ho)M_nnsd!6l<1}$hQ-ElCmBQu zE{~nUaEc0x5P{&`uE1MsputpAR-MtG1XC&=^Kf}Ck~~ZerhH4r_0mJpqSmHlj|AB) z82Y&ITlTcUHr{DNJQCR#ki`K`LwWLdf%)~|gTIJErt+6MyQ^Iv)oH99b8hyudxD?= zrWYJU?Gw&Uj3c|%kFF_1VP`(7J*bO%MORN0Cwl3~n+bn-OYNZJVP>{*Q*&VXIS=Kl zI)yY4S(SxO-0KsY3e8g?J)bcjQZ;XX1@j6qcE;-aL+?xPr7R)W>Z?WauGs=tVR#0h<8g+=XH%MqT#Md4;j0}=T4x0nQW zL$@43M5a7q$UoXZFhfg1y-{@|dGpjaa&ksodK@mHMvVcpaGz2MF$ex}ehS(Y5rX&S z>XI;eX+AER=tSmU1o zw^y$lJ`-0i)}ekTQyWvDWS6juDG>&gew_|y+&q6qGttL<8AqWmwJM(PM^(~W6%q!OmU>Fll|;I&$hjq;u8)yLlm-leeG_ke3?uRd zGl9E==G3S%^ew`)Ce`xK7df{_KvGF+l>B;h3%yB=u^ZjA7@P$ToPGw z9GH4&RLkdP6UCN4wwptCM>dy;QNkyHOVKJr^VTCGu~TmG;HUE!&`ec0I2I%qUcLc} zh1jEligM$ii(~3drDa<$r@{MSH_ZzhUB`+RLa4hI-6y&Qqg9Etb)VQl0xMz$cWvo7 zxr!>DS4){>f{do-H&gdUk2WtO??bbHk^^+Nu53*-&JkDCB{c{Jit|)@#+?jiq?+`@ zst5$}(QnE2DR7lXV~AoKWQ}!(DiSjHgqO}Hrd#&oLp1Wz4hmzQX` zFZ`+7h9r;z%h34HoO}$8>r)9}05aNYf9yWx=6NPeQ z#TJR%)|`<7`#I<;1#!{R`LAg&7RMLswkW`iMh8A~v_dN>oB)Hz8l7vGWEyc4%Qu+h z%&DZKqrknTUI8Dr552zypPFlfFh|!f^nlR!v+(L}I=|l#jY~}K1R813*xB+Gv3Qpq zD@LNdK@D!aX6ohNgx2a5fG%E>X~nAfyLlQvItpkNU=qU#4mv+>1e2?jpush;eVm%l z5Ak^H*H(c3&hDP-=~^4b?Np~iKIytpE^G+DID-cTMy9oZmLQslIpyH-Z%7Okmv@1p z_h7}i4F=f^5t+$5y`&H2UO~-wtr1qa{ULyHQ-C=wR&6w!_a8Yl7~lw{M;qMn(m_tn!>6;&j;(LM*p6)V)g=2t#d$)%^2scdD5(l#BmS3D=kUI!VV6q8spX3>G>$}7?fUXYBhHGcH%_dQKdmd zn20trC8YyWk9w!50jx%sYq;nhUNm=jQ{fJ|$99Kp992<003S7O;)H1n(}@UJBW?pb zEIku0B){-^cr;9~bfwrf?~OsA{^0JNlxaXjKx`ptn>svUt8v<2eJ-=eD*+@9%fJ+N zDZZCKO$A+TE>_?-jl?nBOs25EWxEvYW9vXOv4F#TNLGz5fJjB*(W8Of>0 z*88J08>_0+yXL&u!i+Kg$+8NnjIB`~$f?(>)Qg2_ZGRrtoE`2|Z~kBILUF?=)rq>r ze&;I%sz$4R!NgI>>ce8AU>00b^!|_lh(JD3ECDG|6E~<5O}rjG*BajgyNKo z`_@q13xevQ&(^TRy)G z9RUCfST(wMYT(#N#}uxl1(Aj(GL)tHJ?|K8Z@g7mDj`biu@{VYKgb4FS!1*iAD?zZ zdGm|4)v4*Ni)=VdI+cNDL41!(+9m`xl`r~n`~b(I5PcGxCY%TCeP9t%-S?{cI9$lBMcdi%C zYFv2pqezenYOFCVA7MBETZ2G{=Uc9Lma;Bn%{ zZ;rHGbjmc>3NcUqPCrQHWWZd2_dOz$p>n8lg=ElwQwj$;gKapjfBp;+ZeVT4HwkAc zEMYDmSxdYM4Zi(3_EH^Vu%H9dGMBwA;6on};_!Hb`olMvT%i%1+EHei}^rS^-(t zSPh~D-+n_m131Gt7@gUI&a;%}pO7=}bwX}?L5~+(1jdfhu^o3%&RTKTBCb?UT;Zt^ zPrfB5!ZOsiEbaR{7~xu!?1Q8oRfM=Ixz;=`of4l=@XEBl&B9{fcJN^y?amAOUFzE~ zRHD+>CJ{|3v_Yn`#YDZMb;DLF=3D&(naBoTNu=(-8VsgGCwP___a#pxF(oG z+@%hqq@H+FKIB6|YT7K#? zueTRa0uTIU>IANacA`(Jt>9qPcbBvK&aQ#3EV-=BJF@vrB$v_U$8`iGc(`i4;>zT~Vl;C_Rb6A z$)Q8;2EWH>!y^SA!azA&^MKR?P236S?Vndo_hl&@}*~PY#}l%LpHPER^Xu zx?R1N$P8Lk{tvV()_#OfY2mvp8Pkoi!1OsdP;Th}uakJS-L>|@fc7QLrG5Rzbp#34 zWh62x%l)(8rtaj|0%Cd0YS`0wB#gPHS!ixAq?ZJLe-W zRo<}@h90fl4Vu~|tqTG%B?uv}Wx#j=HEJWDYA%%_DpYk)%MNYR8{kdzmUai3c&h_+ z5#sQ#GCZEhs64v%8inTPQa}z%b0*#{T|fCb*gxZJ?F}>_{`aVUCeUf}p|oq{$^>~FjQ(HPkz7H#lv!-;&rCzk zFV4Cus@GRw;{YYWI~eA?8QcPH(z#96Rw@#ID@kLNtC@lHM{i&vF=1#b=+y#(uqeYg z?p%xxz)PqYs;Sw{=_=_d!T?7=xWC?iAMrAIkNOkcX-~PDsuL&%E#4Dg_+zwW(0TCG z6X>Zva5=W*P`?9}jRCKV#Oo+;_UYIr-$4?c?>4~)OGwuaO;$>-R+IcX)c*s4x*yYy_A5l08$ETFf{E+ZlP@U#CL`~WJ;+{^HoX*oR zMkD1^%H-WM2j02Icd4gUN*rkrV&PjCYN36A2OlY?RDdA*#QU>aj4%JN@5EJU{ki^K zJHKaguVn?xPz;~nS|Or8+X^NkKGMi8Fbp{%e}*;+Jn@hk%ZZdhC#sNRItIwKzy!WF z%EStS9iz>vr{}x-@nzb`dzN_A?ulZ2ZrpnRv?&@1r0G!(=R52Wg zy@h0*G1MjAeW7%+k|Z8nH%19Q-Yq8k8;v4MpxccrBh~bpBbI4mT@U>;9oPIR9JSifPj$tKdE-|EhP5 zmkCrz{Sgn7|Z64tFuBptFvh?@(`kx4=)P$VmpMXw;iX; zxsx5xkL6LZfHgwE)E~*n;mlyh0VSiG#CIjBx$;JiU14XN?wrmFhNRJoWVWNtw$`h- z_{0fAEa4T?_jzNEZ;{(2P+jgIfHkR!Q8||SAzC;`{S!oWIAeRN_?!UR z_ZT+q-PSl?#3`rmsD4xYu|H4O3V!(dyd9(PfS>!x@ad@X3k=p05MG-nY|))nY}1aN zf>_;Ec0_c;&ftA=3g?nldxepwYVoD?nUV@10e%!WQ4_FP{u1zQ@pk#_l?W1?$}%VE zh(g-v4o|Y*uMnNFPMh5UisnV)*($P@tH|!}Mo&HnM^{<+32?Q3WSnLN0j8vV{B zfwKz4K5eadLs(eUx?WVZAA)dr(jwX%P0KlnJ28<_<=8S$WbUaE?)Vq;!z`W&^LTHS&S*^xFEq!D=e%@k@Po}@bRll{El35M$aKgt+p-;Kzlk_0jK!*C`qOc$#R z#-|D3%keZ`s|06h>N&6#tIlR^b_#@T*Q#^C*yvWO#+*Fg8_lG-WSJ(N0R$%Po}CR1 zp0dsLJUZYkqn>xd`6gGD?N7Dy5c&$Uyf)a{f|`548jsd0DS%KD#wn4bS-qCG7jLQd zAXYn#3I~FECT^R-=gR5KZZrP@hD{*W%81*i43#_?S> zWN7x=vbGYL;~Qq^Tj19-EX?J0`X?J|ws8nxrxkTM*|R=%1{L5A!q8zq&O1hPR@b~E zMWC3G#bvzLgF=$wI0)Np7@frAEgNi#KsfR9E*$q6_o(T{9p->BR;=^8FV7)dqB@X! z>4yM|ies+URX`|g!ZFXm$13|WA@$5n^#rY|1WfLc7O%QtwB?=s%PB5Lj6y@vX*|fD zNK4mI3B+|#H$XKub3pPQKG=QFAS&az41j}B(e9x#1AQgMJq=5*a@WxBDW&V`p7!@ks8AKFu^?N-|(er-`d zG>GV0p0OoHM(?jhdLroX5|u~LtWQRKF)UNjI1-1~0Jdhk(tg{%|M7GD^IrWeiZ^ii zAK3ak{Gcw8VIz_yK@jWo95Y=&9cl}aNx6u5V!Td4nNwR5s3HWSc2nXK8fy}!(8)yN z(w*wkzB3f*nF3?`9ISSwrtl>4(4^=!w|1iH#qcj$)=|!p7s-koLz@iwheC3&=I-gR3DfwA1n$li8L+hg*Wid8=y%$jER?=|}Z! zEW{VBs{}?)Vz~hUf|b-dtn(~t^4K&}iU&IT(=cl$Hr{P&=QIh`ym7qJd@f9C3JDk z^I~6>x7K^iwbcyj2L=CD4F*Z1W7B~f^}>eP;{}&}jsn4!H$?tbwN&o+2-it3jWp74 zd>ZHo7tK`Ef6TWSG)InCsGimqX-l`cyhUZB+%STz9Koo3uH%?}KGgIv5PAwP58P6j z76I7_J&c{KtwGtRL@`8Z(F>}I!{XZ+Dm5yR&#}371BySdFes3a{8rC} zpanTU&iqoa0KsmjBNetI>mJH2O)+;s*08NSE|JxCbFA-V5fCKi-JS(MGM~%}-n(V* z=AL0s{5&X#z(rCYoa*bDLTGDmjf;SMuHNtS8YfmESl3N^j!tpuvqFve7VOxlOv{g& zSb^i5`h+(6^km>R46g*yN^XLI3l5< zCpab*uO;CQeHahsxg=cqf0CZGp&P|D0wVADM*(!rVyF{B5X0l>Wa6ga_=zF02w67P zAD-Y!7_C&tASc|yp_)qWlyXeQ#uVPmpdgwQhvW;jXIn~tf-=?s-JWQ(IiT{^{+ff| zZCc+0WEmHpjwd?2fq#-;{D8`wvn!sz_!i}x?Mlg9(W4|F3K1?q!fp#}n4Lr_;Eu5$ zKs$ldaxI(=nL07r@%rqZ3iBY%fA|To`WNl1>9a}dR;v|`4)`x3{iuJx>8Xnx zIm}%w-=$RDs(2k1EYOigMuB8iv1~v&Aiz~2&S!t#m4s=c_qfA@{Z~6G)>>#6@q>|P zoAlxdu8pCjk9-!*C*mOGQ%0iJ}GUULzH z5r_IehcQ!c@H%sqz2iZ%4)nyfpR1zs`FB`e=<_M8b|{yV5Z<+4B5HI4#gGN-?f9)L zszCq;cQ?j$LQoHcFFKHRi_A0kTAf`0>Bx2mckced_)@Z8?`@bCb@8y;X2TSIW`j92 zgKb);D(JTc`{-M!yyJwR4fYX{%F;PFEhFT)$&uTdvKf~Gkng#FA!jAN6-cwawrwe` z_q>U~aj+tH<#S5UL%-K_{Xsp)u&6Z&vGDCTDkQd@I#BELy;@pL+0%9CdF_rKo?6yn zDAbYLbs@wLeX zzm8koxm!A=Z-Krw%;LHk>10l7;TS1(LB}s@f*hVg0(3`uTN^S-vDOQ%#-@&XHo-|> zWe7VBHd~Q82I!BfeEb*QT0lh|n}&$+At^y1a3Jxjhf5mlz(!K4_ty`zp8iV{9W$A?EVUM-ye!`K0%uT(+; z0D_?RUq3`yQofdYBK&ukegw1p!0VImT{Zrw$@?O@gQ*jQu#7oEYUI{y#O)hB!#7@V zdyMn>o|X_<4hN?R-{)^S!MedR>DNQB{h9_7|Jk?D^@?79f6`h0rL+O27x;ske?)wN1o8;{NAPOug@mPqPa@xPZG`ZAAmcoFs1z1XHbKOx4T(=c+) z+}>*%jj&s03cVUht5sg8s8dbytFeiDm{ormE-OB{xc-|C8p~A*12ItyovyF7 zAGPdI8U&5h+);Cf+h@6Cf@h>r7IE_mAz0nVEPUl*94vsMWvB<0Y9>5#AV>K()N&+bu9Zj5Tz-5}`SIvFBiX`djXs+|wSKKx?#>e`s{BBvj1bYn!=W9ii?c$LysEGlvPWP$(^D^qF$CZzIQWc`!_Ig z1aX8hw|wG#T>Z(;CFe=k<%~v(--sAg&!rQ1QP3A^e=M!4(hf{&8EM`(Gb3Rcf?9W3n3kEr^bUQa^5YT{mL>1uwyD8r^~%J%e$LI(CDk&M}>H+pfIRb zF(hd1s>nEEEsqDpCXqf}KxjAkV9nTko`d>UA}2U) zLnPmr)DKB9V2uGg1*(c?be%UoK0)%gqlZ?Pp(ky1;&AE29STL@cm)K{coozQ5c@TK#bWq|3D zl5L;a!iTa1(xj+_gMEa>7;e>(BCfCbTXZb?RVXD-Uo{(PxBp|7$k?JsC+*1#6+XomxO;XUcf=*7!aM8m{%H*X#$R0_UL@ieQ;-H3eTD|`DxWNxdAX$ z?b^d{5eIyXfGj9*TQo<`&Aic=Gd9D1$?_HzI!|o*&`PQ@4lER}vGb6zE8O}V4SyC} zB6RJf2ph3Oo)JZ{){#ir0&`i`aOGBr<$|7-;{6h$kg*`!EE?I?u~Vpu%Y80XAbPy< zDfRwAqG|<|=}c<TGUg)Ysdp4Y zFCR_r1y6Qy96xlU$J6;`Io}-*s+9`le}i)sC$j}s>`aTF+p#4nOqRc__&bwExQ71` z9OJB_mX*ED;opKW+_x5O%7b zx5GwWwo!|GA`5M^#hMiUjMdo~Q^B=-CW0DDnv*si%z>wdMKJ2BLEFWRhNM*^dvCko z(U5|$nc;}5?s*H&fq6@;zSVbGygS&NF}!$t!IW;kS((mAw*_)Qnj&f?u;c$p7wPzc zRJ%O!W1t|9Y_S`-KEsbtjG%&Z9td;b3Dx)9w;{AQ>-!#@aULlX1rZGZz=6sfhhPNr zA}m7Fr{OiSZwY|^e&4A~c(~e;I1^J^5jy85=!e?cHEbH@BmxFSf1B@kjUE_^=AA}Y zpVZtTCRG!WV17loOy%mzK%5**(u46JBRK>Rf`jbIZvR7nFPM^TwGtg^uakX1 z)$s92G%`sa9;Dd~smfoV@-!xoGx!#4q_ZWA979vu5TrxHJ@!QcNtArCk$TPht&nGE zqD9$O!=kNOy#qzu>M<{9?^Zh-$Krwyu@)t@yF9jIoDw){oXS3X1rf}s2|Q-Ci#V8(5PyR^vQ~R9 z4y75W+ki5Q4Hv5KLn^GPqSzt|Abhxc*T7dPMEJiqk&<=3S6WO=t9%!B0#Yg%kqPs( zft}Wo`m#n`ciH@%{V9_^LU#V_X`_^1v={dV`V%#Y;{yt30h5fI#j$v?tovrFF;#%?GtlhkHIWyubC>@4*E0q3R-Hk{7Oi$RqZzn4oLo=;5|h+rub~X+sk=C*V$BLh-_; z;!iw8RF33Hug;0;{=gN!iCsj&$*N7&ojnK1-g~ZJL`IcJLoOzjsFaUD^e$Gz|EG> ziBWypk~tmSbYh-#8Z4CK)!-}_qNYv;-;Isiqo5dJX*qJ@FSga|NrSuM$@W`RXM=}^ z0lRD0?w{K8^U&w)DqEZt6BNyBPacuoNzBnQK_?K33OFj1p2LW9#6ZCdCCnn#28Vrc z_n2gQKfNlpia_X*_K399l;*I{uu7W&1oeT+JzMX8bWS__ z?;<&}rN@Ys+x;B{r?#z3ZrbPjX%pk^_><5x-<8L4SDSdUS_QJ9`Zc`6k<9kpZ?byx+&ztM39w!*xvK6OC{c;y zGMd%8ETy``Zz7d~ayCH91`)n(eQ&^}>1lJu_~W^m3g&}8ja=mB-VsEt;RLu&t!MdO z;fR;pGJdtMH!-qv$4)&E6Wv$C%#~9Py@An?H72r->$FskCB(x6;lgBv-aEBNEC+IL zu0^FmFUPLZW4v(KYSW}Xg)Mv(g2KSycyD7HDJ(!2jYmpiwh1`az?pWwij~f5d35e+ z)LU5u;3L+cow+k}RZ_d3V1IbQ5pPm~PPlQ5XsMPuj|O4O z$Mxanu~ZJ8*dzsLQ`)T+zOrK$PJ#u1DvcJd8(L(X5UH$1ZzpxI_6_UgiU>`%VpvDc zVLAg~D3+em;I3EqQ6D0^b8MRse{nC!R$(ytHTYmUYTu^OyXT} zkwo8uz3sG1uPO{FL0=+gJ1o!k6m?CK-s3ey zQJclcYeYqU5ubS;Rl~nMbI!UjGskNLSpdA{G__$zws0MNW&>)3b_HEg9*-*|Ti4-l z6)7n0I9)WXV&psOON1bV(cYI|)YrSN-=2#Q<}GOF#ktPDc9yT{W!R*1%ZFulu^7Mw z;y7w{5bun}O=NQ?u#C2DAkuIhRLSCt)B0o?NY(er%=4|I9P+t}IJaC)FHG_RUBaYQ zX2E_CN=g^lQBLHHN_{t#JUaikVnqEH_aHuzsJKbfZ+nLwU*tK%qmCOFVx*m+C=uDj zi6E>qE#lJoJjN6L@_modjUq!!U;G+xSOY2AwIr964SM!z_K_CbH=~(gH`uo5RANJw z<$nJ~N0U)+$38c~=>=-NXhn=DI#t$|ydUP6$|oahx18r2{oc%+wff&hTZrG!z0ty& z2_3lwYPi-&{4#A9!=OI1^6I3q3#`!eBZWQ|9IgCgrZ3z`t2BK}wEES$t}}qP7KONU zoHQF6dVqnR15Dl%pZG)@GX}9B_{i2Bd}!Wa#fwk zRo207^J@2HgQa?%gc=M>-oQ$XxFdjYc!`HvI7;FtDNY6}%MGI#i&x_KD;32QB`$b0g0>((cj*yPSRS&+GJzaqc{L4H#2` z6n6ir?kQ)vn$SVFu5hz+A*8PGZo)R)JWbfxflPx*OI{H*x}9$a3^N!g0tfTD(^(+k zCC)*ih!Tp5q=&K;!J_K{vbQb%aT-a7GR>AFYo<2Y!3C`}zNN#RBLCIlzEriee4n0^ zz)*C6L>N+nKzU+juUXR9K&8b|a!Gk-Z6SyHJrI>j$qYDqLhx8@(1_Q~n`+<*%O#|< zGcwjj4yJ^NaX2lvRG+(pz1BTR;^A+^ga(YU5lS;TLq_B$v^sX{yY)IW&;wxog}NwUbodOzoZRFsw9M&7%2T0VpQFL_mpW2q#309 z=IK1_Tio)j(K#x+=ajv^n%w=$1b3 zR8)g#11VuRa>dnhz$49A_XSg4Ckc+MsX}84bprA@^62yb#n&K1vJY;z%&wU2v!j^z zbZWq3ufEN&R-ZY$8i1xLB~64RujcQmghprj6t!aAq*7E;5^w|77@j6T7ZXw}$rg0n z!O!DbFyYN1)XYo28FuA>xlVkydbfuGQMk<;#?Uy z0hrs#-Q8?^ty5azgwlCFM3HL`69U)_FJ1zhv2f$r+Y(lE%0^J@g+z3XaMI?A?kN1` z;2;pQ78tz2lJz^u+a9k6t0gz}X#1v_Cs(PwwZB|N&GF;d*UyDF3Minf<|6$EAupW$ z+Z9QNCu(I9zl8X`1d)DU)1{8g5Z4uaJ9A$4fCara%+*^`!}dGrbpgIFi~MLyiBxW< zRO9bjp%Sa95z9}kcEe3TvP1bKm8)5vA9DG@a3!7I`A2((ssQ#5MBd!b;n9$c@O$n` zO7S+W2QF{VDhOdeeBY`618+jcX#D$swQd`n3=_Ms&B-h8Ohn()H+z;&m1{Cs5PTt1 zQu^_wX~TgXM2ZqtJ^M?1F7#u0Rb+xJAo>Y$@__1glBoJB2Y=+(i=X9aMmA;c$Nt*)(9yczknEPbx`+>a+;r)uz%Q!;r{06QQ4J5rh8mti;!Xn(mopGAklT>(21_Aeyc8EkCcvU*l)8UuskUZyIod zniyFNKgJoj`3o&B1$dbdVKqnj`31kX8w8{ zUqUoJLVO#>Yd1TQYJ@QPr&t*uEZXEta1coGa}EIyVeuMo@IB)kD;KV^7`*LrYmLDOW!5v_^Te7`XyIc#!3uD!%> zrU5rv&YhPjsf&chUn2cCjxBZ5DF$mlib@08VWiXd6}zfsOVaV`!S6aZ(1ae34edTY zh)_2Eu)#EiHKSbwjQV1R7OeDS7L&dCI-5<2bIxMy8&rwD9S0m{@hhJtvE|v<4;=yu zHdt6ZPh@APuRZ%jp!T@?(Y$Pru|YK#witC#whjavF6S5_Q2tojFT$i^dGl#DA@z5$ z=SIbWa<04?6>UggeK77tK1NlSg*U&t8tSjPLd%Ig8>8lE{}2ipH6G3}dTUS`mJIla zaG>;)#z2L17=87;k;U4cE0-u@8yJwb2IU_>P5#nagmxiu%|RL|<@X!7*~L^d+=i@L zR<*%~4S-H7y`eF(0T%_y!HbwOdA&slms(@EL56xSYHAK8W)R8FHki%P6^I6m07}3& z3?j>$Lej=Vk9B8_MU-NkJV}C$`F@H*e0hd;1Xz}7n6fzK*sRF;d`QrRNL%}eHJc*U z7b=nlL)xQqDhbj!f~+E1AvWm`O{HhD@&1RpsJS2Kxx@-!wrCgnt0)TzH{+$TpTO+B ztvd4D1>xdrBb6gL_2Skm^~&Y7WUFV^I%+Z2)#a7-KZBkLNM$r_1^DW+xSoR|XEm;5 zZ|dF5zOl6tDI>1nJhh3aC;PsFY21bpOhDoQWu~m$pHi!gF`|^skTwD#H@Hj7#Xb{56)8XjI;1ekk2(6>-r}qnM z^UD_4osp#d{ZmlX$2BkIE%0#oaI3E@<747}MeU@`cEW$hN$e*XzIo^NbxPIS8#6R* zZ;qvsA=oySILcZ+{U{E&;Gxyrsoatl-hR9o4CPRhSHB4_lwd$>euhM?rL(BgKgcC# z&^a^H2;s)S5fMmtx!Gkxxl688kIGx1sGR;{oMMQmXjhnFJ`Vl_#>k{vBDs{*#Zj2) zrISdJ8Q|1scI@Ne)sc|oObe2AtGa}LtiKiXHn00vgY>?zafL2Gq1te0Xnvv1t{Q4+ z&&3giYOOs4IX;j|NQ#x03@1!ztgea@jAww&2$&Yy1z}hHA0BPXN%O95!nKBnro!#e z#tG2@wOAAh$^$V+_n$IVMFdYr(|H~-Z_9J^uXNG|2ei2b+pA0!6_tjzS?kZ3{Ar6! znix9vH#N&At%dsED1e^BF_#>7lBYu-yI#ix-No5SmzU|Suh&6Q*tNaO8V)$?ZIMTJ zEIG5m02aP-?(w~NXrb@%vC@uV&`Fo)-b<$d(hbe8V<_U$qw6w|L10os=ma$r8tyfg z?21-ih9+ZlPF*&^$U*a;_}o)!x+mV{yH0 zQvd;2x~u&ic4VbXBMAvMQ(EIK$*gNx0+D=!3G-mMr@Fi=p)ql24yrr`wv81jnRHj&WUOty_@>xTF65!Smm`68e_vuaB1|Czg?)Caj zaZ6-euAWcSFWd}q99SriVo;jk9(foCplexNcNM642@%%ioO0_3O(j(MzcI(wVs7_k zavbGR;C?LQPU|r*Zx{q8QX3{m41ds}WBBwE_GudFLAP`um3SSoix%f?9JVedtqx0R zn{_D&lRPdp#4P){=qni%xtTdIy8YN-f@&5N$JrVrbe@eg{cjVZVoU&BLYMo_c+ugZ*Wb0AA=nCz8-;aig|u&_*RJ0 zkIg2HOYhZT5pqXq`_wH}FdR~|RWqR{>9!_tlJ`;=e`@qV^B&i5Zn(cF+b`0MtuzrF ztj5I=BoGVr1<@|;p$T$~p-1+8tu1_X9So(4J$~LWTSkgzF7rjrn#{9gH>kPH6FqeCH_@!(Fk~Q@fB# z0;#@BW-r*RYh?C}cuVei=V;5&v`>?jip@$TESPoy-omy3F4>SbU zv@Cj_HHR+9L6E=2VS0ahzm(6+KPm_1nmmrpH^guIumUw5N z*m0Lx?C&t3zaGkgifObdoXD%0Y`Dci=NJvFG3nS@xDHE&$j4x#Z0p>j`6A$y{+MDkHFN)vYyV z15z*6p=PqtLF#8bm>gw!y66mO(t+`wzD5>j@e(oDxQhtx{L{wc=Rctvo#}LP-s|L3 z5yCBmMpldPG|9zbeax^B=$@R=(3eE;<>voLM>R^+yUS753f$Ly@KB0D$*b4+_0n>= zFyO*X(}?+nesUBHM5=#e0Su@6P7j!g-WxJ=^3?EXoN4JZj=u_KF3(80fO=AlW=juY zga6S4?sA;|htU2yplJG7hJVx&CmVz7}&xvRYr<~UOo4upf0w_se_tx!8vG(`0@O#UZeFLtn6xBljpuXqA zvHB#Ffx8owmM;pK6zYU_dV>}@V|cHoXCu$PJo$7pH6dR4XcR4Uc9kGH>I>y`Kw8hE zUAitj0&uZsNxRpZ3zvOBy?gU4A)Vg|WT=}CErC&x>yBp7ootWJUL=cvRR`accQZ>X zC^1etdWj|Zvfcx7qQxwEEgERT{uRluog0P8ft51i$3SS?-Es5X9&zjR|)?a}ojIW9`Cp-%h<#1P0&T6CyO%r+cNxi4Yc#E%? zIR?cxQPwx++58;~;mm}PLMmuCX+7}OvkPX&WLGa4!P<80B|d+I^c|mBS$!pp2qs3S zJIk}CzzkQdrORW8Tz0SW2D2m+XSTt`&{d%>DEqF^Bq1ptDv<-&s*UBq3_offP|pYE z^ku|ED)UURY&G*$-P^5zoF`Wawl> zA^8!3M>7X&_<|TJlRTdzUynH>TH`F@eQK+2Iq6HCu&W29EVMu;`1X5TRIV_SK%-da z$ZR8^=U@wD0C(0jY58J4Po|#UrcECu*_$ztJ1;ssbr0_iY2f1jA8KF`Fikly{%7_Y ztR%_r?E~tKw3{$%3Xt>i5@42nxft4us+^4ipt{z}np*e~?^M@7%ynx=s9c$8Uu$70 zd9M`j>4qUDowwca!??a*v-O91^?^Vfa96DyaCLGe@CJ5ad}2cQWs#on{beWfd&Y(} zL?}Cdr&>kGq~uiwf11w1m!XGxcglh&GKfE4+eUeoE;Rer89vGoHE>x8W|PsttCiE# zxIP}(!i8jD;W|IgI>@nHl^GSoZYzkyy#_>o1AD7QJvMw=H6lbsNCYQF?{H_r_x6a4HDX4 z^tAfVZoHM9Ug*tV0)U0g|<)l~KAAnAa-hfYpU>xfg{1L@Wm^?un~i!ztdA=E38e7hJ(Q=T{Pvd6 z0N)X>u~ar1(7byc2@yFfJ*eTm%|MX)YG#D*;|*?l=!D$YS?IU7e+?8a`fUO%|LsT* z(-C67wYMV<5ZWEni`ec}+V9gkZ)c@ohhh7yCnEq+$exw;`Z zS*-$_)WfR;sx`^0u*2}*nkQfp@2cNS8dKOY0$Uk~kLI=fz7rhcqPZS3Y`_-Kje^$( zrA7;OwswS>X4|=Wf01FRY-H1^O@f^3^vy(RP44;++ro38(I94Cs} z&8$fq4~)K%Kr+-jF=0c+b6X9Qx2Q`N-i!}9z~FXCN71qDP8rkBuOBIGTz85gM-t9Ksc^fY z<0fyv`dEhVp8r$t(~~{Mk?qYNJ;B&+SZ_Bq?)h>bf&U8vZwdWrQ))W!VWSxpvhW`s z^2@isYY%TV$WH&rR}8VC^lupEIRS_Hh~?xilaOV{c#74cB&tpq7pWD*&(4(kpmtYn zl}6!_V{?g~xghnQ0RP{am26wNVI+LXt3m93>Z5M*zdT(j1QSWYO>-{o#&Vmh_TE=A z0YgTV#I)A({grEooM(6bY`Qw!+E~WmT;2e6HY$G|`{!qp!#=URs3pRzXAIW-N$oKL zkEY$T>Y%J#;Yn{2mvtf~y#klQ$)ahnNyS11yk}b#t}fh)R< zdwukK%YCS$5}d{e_JvF>V~=w!VE>0^iY!SbO00FEQcwGb?RssR`!6Ik>Q}ccTT==cSG_n8w+JyE`9E{C8(pA0TQ}6<3 zHPrXNed8Td+HsY!I|^v#7#WQ3Aad_UI)<0;Od*Z9m*oZH!nba zB%WErEor@zezLayXdY}8Q|sT2C;F(lX7qjkCK+U?LNlZ}J|(t7o7tL;Aj?#ZX2rYS z+C7IH4;Kt~)xBl`h++r?xG95`z6me!*$L+}U8h9+$-+-VkK+s4lIvpL$$841exsOS zt9MWrp#Jypu;|yha#LnUUqss61D)Ou30%r-{s%F=ccNe z3O^EjMghN*vQw%T2HNF72wwlC?F<}CGNC~;2|zz)CDx@Ls|KA7>R#(VQT9!o60t?U zYDr-w4wE@4hGjD>kxAQuy0M{D*%kM#lm$%yT}y{aRxsP}z>pO`V}e|CuE2+q3g(4nlGo z^--qqnGL)!Gjfi^h+Ho`a`p`9Ll2Pf$)>LA5wk#AF_Y*d_=mCBUYw#tRl+5uo+All zOStiL#G{2L#)w%KzLxmw){~Z%P}*@cOg(VM>@8Vd$emU~sMd&Dv`Gi!bIyBqBwX=a zaJ2)TliM}pFph(tQZHO$l#L}i#H31l9v5+QVD;22z~D>X??Q8}z`YuRGhv+xArtQ? zw&6n&N+KQlx29e`kk#nJcY0*USR{vr#faiFnG8 z;e_e`D|1Z3;JMh)m>Wk64A7A*PrzZuNK?;3itcJHyd9`5b$MG4@Z$a*ixNBMw_Z>lcs62vPXy_82ij0U>g}=kTo%Sc?$tt=HTdLoClm$N( zVt&KOqYFcpYNoM zCCeK7zNHKHuDHjJfy2WJp=y+;?ve-8G6h>pMcqDws@?tsW9?Dc+wXK6pDQ(4rV_!| z`&0Ix0KRNo@Y>>MCEW>3cIvH{3?g+6Gz0><(R_VJI+^~~6Z<2Q1XGDfUytO(lqOze z|BtU#ImoTik4CrbX5^%N9AsUZgJvUQRuTyCH@SM z_VZWHC&uu)N)isSdG~)xi@J$rD6S|Ps|=>gS|v91 z1{zH%FU>2? zd$5kI$;eVtv;X8afd|?cYCS9vcu2NUmS!J^ zR|II?tUk`;C?NT*n=`?*e_boOXkLlNMZ}lk?|9%X0$;c(d^2pRkv3wx<^lFcViO=} zh^@QER5XaltL|>A26sC5;GvnQ#VhZAuPbUrP4|#fLrY!&rQ+w(2@qjb`?q~aAOA~D zqiHliFa8VltNc1bS!1dp|JU-xkD1t{fN+!3lNml=Hx&$nSA{^y3^G-LzP66q=R?ID zBVtlMbKo$Ga%JdPWnp zKxk2S==x(tYDcM2%)^zfAXdZWtSCHe2cc!MO$>$u>pPwM{EI9zKs6fl9gU1@Ii1Kk z?TIBDP}?`Fk@%|d99yk+oN{GBcd$g z;GNq8RI7t_>`oKyb{yKze^pE(`2$>#SOyKG3(p>X*3DJM3V_#z*2n~Wyg~hZ*5keq zT+!*ebF(9W4&u^jl;D&AajE0Tg=SHAk8z?oKXP0^t72SXtnC0suR1+?{q_LzQk~{% zoK~7+m0@1kPt#5F%3fy_)P11i0T@#RXKR)wVHEbtPcz^o#2_f4iNAv7CHU5Qc`owo z;P2*3nbrTz;p#U$RoeAVl6Rm)f8Qp_@jv){K%vK_fEc@~+pn52v0LoeeMRKO?q2<5 zT-;`EnAocB1UE(#P|aUe=egISxzaZB5rlGx-;jEjtLnIOQkdoe6dgy8IyQHQH04+q z{rHMvC(khpXjswpYI_);^ABnRH6gX!I|5Lvo+9d-6DiEIY6LnrHdj6yj9}GuzgN?A zZ3KxJDmHHtFHrvwEPZ7+Lb|Ar`sE^kPOgqbn@1mh_u^a ziILJh91PvDdY&Z?y%9F5c=CI+7u+!aXY2~HaTLX;)n0#!Ebt$n1>ayA>*v^U+^UpSt=55X5NO>+YN;fOzW8( zLdaU#2qN^>Wlv%3dhxe6Ps#cc^D5QcH+GbiKnRyLexHc2W>LApzzGY_MG&kl(hcZO z9bS6fI}aKjCo}IQSTGw5*d%XO8GXp0_hZS9r1y2t=Mv8`qvez`x9p! z_5Umr0UjB~2m8-Cq~+;&rCqTeF{$C8%abRR;=|ynSHYgP$lODhc%P$r0{}Zf#J@W8 z{Erd*S}mxhZ#I4t7;1{E*NMoZp*#)7#*RP;Xx~Bb{1Pz>s|PJ<%{!bNJ5p}I)9;uD z$UE%#@@wCRoizz$zFcb)X<|442Mv|KWvWQ>Fu>UonfTvBv9g?F>Z~^P^2kwEooJ3j~Jc5hj>UW5M^NA|PSnr8w76>8^&Sy}09%39&O=)QxeWnKo3jJ72%N2 zq8Y~%NcGsBP@e|>2ce+Hs$}a7MTpm6z3Cj9zcx}^3u`7$wjGDT{4*<}TnaEC2r(S9SrgJsR7IfZziUB!Xzi%7qg6eEpG3 zY^bHi-MRjeNOuTA%k`e^Z2P$tvR!KjK+EJ911RSraPD@CroZ0H%-Qc__MG7R&i4w& zj^Mw=+UMhwfg2bx(3oi2EEFyB;PqrT+- zWd#Lyzt*Ls4uV8SUbZ>bg={C6>Q?OSoyk8>YJ{BS+k5W13NjM@K$F<9QM|a1UN=~1 zJJkTKc?BEY3uMiKGYun{KXyv0%pQ))-n40Tw0;z#j6bE;hzhHuRi`&_1qDCMob;RR z-%yt8Cb@0F-g;m`NE}nIegs0MqqI*SH@~3Lx&tn0G|j@!Emn~5+AD7Dw%-WX(~lBI zOvhArFz^4kBDF;Y7LH=9Ybd~hD4{z@(k%fKJ<6N5wvW8Tt`FHhxiHMk7fvmC{!bw7 z+_ati9li08=zwa?k|fZDDaX8yLz1aT8mQAZJ9U$)=<7`ethE^i7hU{gW zn>jmDnTJ**kVXspwcM?(H@Zdyb4N|<*YG>hjJjn0QQ^^(oQ*h3;Oy#e#hOLa`giTA zj^1DTEB|9Cxa~M(deEXuBbLC~wfZSNv^TGuf_1Xb6Fh-6fMRpSq|Yl7j#L~WbBkrr z7F#5l*t}=Toau!;en;Weq~ARpGayO0&Z%LbMPsDK89)(!|E>z#HUa;Hh{oJYf3A$M zgJ2v6?1(B*}@)4!s3P7nEx}wh{3XE`+V~qB~$wswse42g>%&KzcVKul?@zheV zEXd`Nsm(rj7~i059RCkJq&LUdo)1UUvxnu(`Wsor580fIJR;0ddsWn zI_*HWTawQRZ-s84%N9isdN}r4tSUp*%BLRlNM%|`_5@J!xkpnxMj+d%VOSaH$SKw4 z^Dod3gT4x~1)P2f|K=~_O3Be_9b=A8T1cv-oGU7FcBiEbEA5@fzbKM3qRttt?uM>} zntE|s*-tXu*N5U!&AhfeU?8i82R4R}sV7I!!KwOku^5;x_-9LC85+(t^^urT%IfpZ$r7i*8K$@B$C^W;I;z7 zz-#N3mKlRqirLnIMhR$YMuTB~MLVvR->HxU$(s#rqY=Gg1P>f;tN6hDyAN*yTOyPa~efR9B7_|Mbc5Uth#$Q_T714s_=8K`{D@8SRKf`O? z2;nW6!Lz(a$DG`0-}4 z_C?DpJ>*@3cYQ!Po_+o&Ec$PG@wnmASAqxKnX^qGraqr+(t}|oJPz1ShM&Yn)U~zX7heMI#T7I(T0Ccom>#?eM?>Y3g=~(w(rG6Or z=cQ~hEs8lkFry)m8Y(PuLp)Dkb{Y=?TF^zNA6pBVeJ^;R`tgGJ~r zPbo^1)7BrI5%|=pxD433`dYDx$E? zy`==Ni_iv@5NPg&S*A0?>|mm9mJ@xoi0xQ-k3h{+ZVDOveTg%ne#C2$z*S}73>RUt zKg(}G?r!u_Nn`C^aJ>KA-0C(K5Nq3{T75n4@#p)Jhv{(vqfC58D#+g2jePXKcIhLU z-p6$KD3PQztvduT|BE5!ivMuvw3bR~6r^tD_Zy#?AmEyZLiMt40l9A%8V5LtNh)W^ zV4F_A+_Gk3>VUGfRDrh&U7#ZSHZK>KW9Qy;<{9WE33&;kb`lRGGcpyt{X9lGok8yc z599Ol*|ZxhP)I(=F2J(@(JMvjl%^iY@gQ6mS86q8r*&R-{AfZ#;wuMeT|GnpV1FR? zRTOr7RGIc|=hHN%GEINjJEfoH+ zTzC-ngX-q+@g1ZVu0@G)|;!FR4tiBKWehUj|+e z1o3x^{XYLQIlip^G2#d1ykt);dqDLgBx`=uY?1QrFz?9>ey4|KZDybGgG&R*@D(yt z#)l|4bmm?q^R*ityKp@Xw*X67U%WfpGS(}V_&S(D=hKK5a%OGM;*KgSD3>RSKK@Ly zLF+h-6u>j|fU%E_#tMtdG!**FuiAxSKA<5A0kSEmtDJFe#yD21aSNF}4>X-qSa#6~ zZG={1*cSw&9(_#nQq1J~0YcX7e+wbP67N*Gd9v zdeqAR!nO>b{{%b_@|bB|r+^n^Xh(h-=DwC3df?F9$yfM_Lg$ld_$^FZWqwZRL6>1g z5H;4AMjnubC?X4UmYbM3Pdz|{KXng)Q_5;H_8aNeyFa2xv6>wiBFbuX&;|wd#%44H z@U$oEAYoO$+!0K`4PulHOD3q;k3u_gCF_^ML?3cObSCUm=1KLM9-RNGFJO$b2mn(u>9mhsdY12eLbWa4}FIa?ul3IpafU z{In1yNz4$Xh57L=adl&TCqwtWi&^Dxo4fO5?-2C5ZWO=5!`8bYw-{d=eQ$ZpV#^Z? z>QZhJIfmU5bNHhk0fYAN>T#((KmhmDYMNVY3yeYDAWV?_#A|^@CzRbZOCOs*bS&NJ z0bK4Q;H0gWMP_KMyHz`Q=>bShR zgHjJ2Obf_8WNh?DFK=>oIN$?+ zFZKw0IKPLN=TR%RTd7}H0Z8R$z=^w|m4uF7{+8#;;vvI54u9kx}&L+i#iU;aGl$s~s@o+@PTQVlOzb)5(h$g;4S;6GLm|2 zQTo9dL6c&U02G}FbSwW==yVczgxCR3S<+bZRO1i$sR^hC6i0JCew_-EANK}{fkiQW zr^np^E+Uy%O!}ESphs=c7{&b(PdT9f0eVuO!Blic7WHLbzl;%01;SfF6@cuO^>UKf z5<6-a-+iKTq>+-E=be>bgf_$q*&}Y_(RJbnoskHzGr}?1aEQsY+)Nu44NZ)%GZM%5 z$Jo|(oRYIKyVU`Ik6SmoP%Kx(0AvQY5vVNQ_8!t%L?(fsr_w7b%C|EW~n{h!Ss zlo?SxToBtbig2UJq}eo~(fC_`=Z3ztxfX<`h987E=+)kkX6ty)qG?ZR;wBz0IE#es zyqxNpRu!+jYm0Uj;{7sEa8j21U_z1b=(%uSgu{ zDE7w zg?9K@m#K*WEqaj*>|m71MT|>q-c%ZBZINayObw%uO<)OkswO3?WxE9Z4GC8XTG(N= z_;m1xV11>+o}4RvfdLG$JRSZEr24@q7(RNKmfvY7Ctr$dS-46yAxzP)Pg-JWqn@4k zWC?2mp$yd`L?Ht4+7%tTXIljvN)LIOzrZa^i#o50O&a9QMR)M?+gk2iVxL0C?|fci zzkS{?P(v;1B^(o?D&#|P$qp1s4n{>$Gaa!lH^KTzbhEBuQcQmHpyW@T<#R9R)x@*f zkXz9I!6Rl%MbfG}Z7$K3v@al_g!ajmA7Oyz`ASXWn z7$=6WS&GeaZG#naxD=-h#7x!bREf~oxnQT5MC=h~9sLU4&Se!1` zp5qo^@iPGSrWSZ&$K%;j{fc%)^RRO-C~ z3eK@`@p@n@Z&qpj&L>KLrShvquV+r0>73A6$mNce5@kkgfV5Ch0K%`ka?Ts1LQaFF zHr(|&;Se!s+ZVuME>^P#)}Uzor>@tFY6)FGt*df{*Y}<<)ZFYldt>?uTkb(L? zyHJWoeA7fG#iRf~#1bm@)pc!Mx_R1mi(tiZfaPlDF>qvs4cK@%10afgI+QbtB4q#l zlf?3C5{07~@Zw$yVq3fCiXcN|VoEquD>!3JqI+7(1&VT{ZJHnlewcHL*F8< zS9l(yPzTl3ZoH@Vsz)Ng=UR!ofdA%$^hyl-q>#djr_}ml_H{T~akkzZ`XFY)@K>>{ zE@w>diD!gi9!Zn)))xQB|! zA+e{20p(0AQ1Wdxn^l~^-b1T8p_pZSO%S8{D&zP6Sb z>E%eENbdj8U6k@~D?G)!-+VS{@Bzace(|NCe^SDUDFlC8Mqf5%Q(@boqGyfi5;M(2 zmlfi*XF<#QxLL67l4}`v&S(7D0W@v+S5x7Z_T7 ze!nE-0soaUsf*$F(G0Gg73R^hT5k>;7bk+~g9~wQ+Io&@)rCV*v~O@^@gF00`yvc| zFH}Rg@kHM4aS{0L6K^w5V>V86{$NE}-`cL-e_sf^YI(fGw6k z(8t23c>GF6I*#c+P>$7JyJBEN){v*xR8EU4vt>%i3tyf&eFGzT*6Wl!422otsAUM| z%w=68&RKfn;}jYp=}Ho(fNNZLW%6WZILSSS)QZW_8cvHr%$^b5 z0m!OF0>8AL4~YT(#7)_Hfj03GyD`(RMw||c<#F8FnxNIN6&jMDMboa6it&&iUUo8D zg?lc>Y9=v zU{0ty{055{{o}jju=Ss6%@au#{~?EJ*oI|aMYwkkq?~-y`gVT0cBTRb*F(=XO+sUR zc+C27X_ZZAjl@NxxZezeueyE{U{{$X>PtrPYab+7(k_Sq^?Fh66JZ4yRxx3_LlO2B z#(`j?V-@M(qOf zfB7wmZ=;+Wqk&B#^RzUsZ$)TOLg1SFuetbT%=!}~alvFv%E0%4-ZJGmkpeMhbzmp% z;Nwpbgv)n+8};37ZB#|eH?6f;4@Z;uq4ocI_dc1_rj%r@+ElRC)Oxhze0z;VxG}if z_U=Kg2u!a-qgdm{*VE4JEh}}K8CHXT$4Pc(=6su6p@;NI>5ee}&6ebx@_=ou{_zb@ zTcg;bm3a72L&Z*cOK2tJSxx)>nfkFpy({O7Bg{LTEM4 z3t-zi6q|O(0oy^v!aI_I`#g)Ip-mLXzpLpwqL3}?(>n#tEu8p}o}s_QN&G!RRC%SJ z9d?$&-U7P>Ed5_L{|I|K-u694F(q?rao^$D)HYXx=>yeCWTx5vc3Ti4#bBpvx(JuC zTU3f*-|N|cVyz;y;u>KytiIt&`ir!oG$9}w%7s@M5uSO~QZ$-tB`otdmYhSb8!=3yU)wLa+jS+ms!-kUV5 zb*UJ|J?cR|JMt0&@(Hy5KBU{f35cDkPWWxxme0VzmRB+i$2zi($Rh81N8yNiTprY6 z33eF{t*Tg`m#lb|GB^B>YtaHOxhm4xdFt`}IMVA$;WP)WO_ndTn1Y7J5;%Amv0(jLGw}xtd)$z(58KiOnHuN|uxP%m|mUh?>(VVzkH!y7( zdZu#s7%?smH#8m&#rnnLG~TnF-i(c}6^nxsWwDv4UvE9bL)K)gY8#-aou6r@_+{?BkHVcSf@h_8$YnJ@){}$h=r~`iU!$$6vOr{^ ze29!J!N&XY#aedJClw-!XwsY{p#iOl?sw#V8S0*Ing2H%4UeyiLp86sh_0LQR*``< zBV0;2HgE-MliVPUT=S)=%6u-*v-tZbhidq5%U}kaba`Ywt6p|Y53v3OdUO0# z>8~?9S#g@GOVAsd@YBpDp|IXoV?Fr6Kn!L8fpr3VOLVYxXZg|uZxOEMf+kwV)~nD# zWz9BMeW+d7fgI9Na!)CDW1wE2r+7CX6wfO<%|82`Bts$!!05^MNzklafSzsehF(5g zAOS$o)|rlpaXEG1@(Cy>3zwbCvp%!UaSwP)g6beudUP>Drn-Nk7h~fc(ViH z#=|CVm$@+$BpN8}z|*kjdz4^_ef4KoAd!v!zfR&qu9c7ZgJr+pw9%uCw8lQE;CuV? z@w5|mt*~t=dxZVP+~a4|emlJI<~mF4yIT>buSB!Z|ApaWrBjfRYwTv{7;- zOU&gGId?c^nO;PCd2M3@&cUelZJ;0yP76D8mWAy6F$lY}{UWa=9&NBsuv00SC+qZ& zFs?6)j1@!v6D*Z7*RWI(Bj~t2#9d6)v@wR5Ddh`yhAwb-<|FHtBA05tIZk3Wi%>z@ zoZu^A=WMy+&=7LQKtxSwKl6%bB;iL15bEUNuVY4CM`BtxRqL!%u>pPwJ$_58v9*o( z_vCDgAYN*HG`egU0f^dU=ku#U9RtF-OvZ`0px*G32eqI1Ao@&qQ6oQ`8u{-*MDAix zuB*;|z3p1{0p5*N;uK^#w!s=S_~;CH)q8fx?5gcAeJ@trSbf<#yhl=8(&*ix0--_2 zX81ZZVV+*vN>hvBJo;wHF_{JTFrre%c9V0H>wfnW#x9gdKi1ElRG}$%?C4c0I zu5doKFywZ$t=GIRxI{^x_cuJByTnA&GP)p>NzT$&abwE~2T0m}(xFIV3o*YpOIC&N8Nd+sb+erDKNzT{D`5j;^%L&r-$;wFT^<{}>7A)R0G$GF=p zh4IWgh@K7gzEVZQkM%? zd-A9g&#s8=??dEmS7+yH8LwV`d6TJzOYO!c4No-IC;MnnwrGQp!(vG_u=x6D2`Qw=a-1t4TucP%sz9* zjTPt4Kw1Dnlgu2t$xgbaEt6r$7aYu>u;N`JDxV zN2mULlSZ~G)CF5 zU`V7?ng*wUyn$XF`$((Pr=f)B-<#jd+BtHL*(X0KDz70>)F`)ldo@MWp{jF!DwCF8 zEc?SPva6R~O*y{1jjHg+2OxFzm#y=O4DzU`LK4dSs{E`d=`OMgH$dmg&IG*_aX7HB zI8zysiWA8g_ZCJfxDZS|+Fc|V`&V`qc+vN>mdyw29Do}A7BIt;++7#PvkKJ+z`Qt) zZNgns4AozdV*|8pW-9EDH>Yc`Bbh9NQm1ycovBuzj3tiZ4HiO_Lbg}IY}PckxMupG z7eTcK2OZFTm+$rb+)S<3f8m0;`cNG^Q6k>5SJprPysl8L6B5nxU`NgonastID{)LG zZqMi?YZ)y>Kw~FS>@@0J6@7E_5O;1fh4w|K8T6%Bk#Vd2JVuI9QJvU^_UkCm0jB_d za390FD%s7;oC4`_5QrVO5)#2$%D8fbwg*Va*V_C4IoF1zNJtuI2PFIR&*I+?$hQWZL-Yd9Eb(PV@7xDmp5 zpv4Su4b~Gjw-uLV~Y~1$~=A|cIO<-&dV-XW#M6eRv zXPY3}=&uw)N6vA7+3zbojW*MiY@}aRM}VB_)eckFpeUVMRpAaY{z0A!g-7tE91l4O zPpSF^@ymc0ZtzIU`{bvaDk!DQFe}&Q=g7AKusT;o%_G8iW2`U;xM)(f z#emBJ@sm9hKeolOZ)Vye_8(()gc8lJK#-wG(a=*34E22BJP=hwDD7(_xK7W+nDz;s zxL+W1qUevK6uwt=n|u{MHLMdN^fjf%0RkXj#vf%K`T9 zvZ6~0g>@D*&=bLIZ|Tw+-J>*F|u9`EJf#&-kUY-cTBoEyiM zU_oEyL;430;o{1%Ma|HMXD7x2LR^D<@cIom(KSGm$y)qUd6|SAa^4^Fw%Z*!6vgRW z-^>jVqu_ZY+=ZP;4ZJ9eWa066K!W~}Z*MluCrO)|}ZXOLVbWVznc`bhDGJ0BtpMvSmpjMNjGmdJCnv04?sCK8ji zF#WJ$1qRH9@{s|UQGq`du(>g~Y!LohM(}DIYwO*#;z!Rzw@3X}5UqR{-Y*=_L7uoc z+H1+s;9ddm7h+?);i}iKt$?}ySXMn%YwwiD*~-iiRcQFDm<_qGq&!=d0^H6X%V*G3vo0BK7lW7uprIqv`J_m zj3KXotSRld2XMQnl3pQ+K6t2o^+gvqm*?Ox%}$r&uXF3{Jlmc0$>SYsqt20D!efJ9 z?48P?q|0M+x%3WE8s>bwc{#SdYTn&#im^JzSL;z2x9ytc?&mIpgU*J)!AXo-ZGC2y=*j@wfJ{iOGr<)OQL~z2DY6xOcAdXB*-n*97Oj zK}t)dEgkX8j5ZKoAnb_M$xXKhk>aV>_#um;J>$x4?c=8(;FWkVHZ43Ya_Fti0?NA0 ztjwxHR}=b_g_<)sh_roPB3h5lpu!lYCO9;dXWe7!_4+*8f&h!J&$5egS*79#<$rU&} zc|~`ho+spEUmnVLg96Y<;8eZst@IY`g3|q{IyBGSq z&hSx1+x_0sE_kf-*);Cpore4k7rLIP-AqT=q7sWAa)PQpVcpGMa1(eJ1f5&?( zS`R2nuTC@kNb(VIdT9pID$>eAmbLOjHoe=yK~sXuKSxw>0kG2;_W_}4I|7I%E;E0J z4g4;BvVS=@|4ay(UN=rp9@Vot8MIFawj(vgq=WOF<$uFpVZq%qoT5qG5jRR=oa1p> zp(FC>iY%G$Q@LfhW{+}wFbV!$=?fex;2qIF3&dnQe(vM(F?1#_2JQ-{OH=ocyG;Tj zsYssPOU`}c_)sLSiTLil##7Ivq`XU{Db4AtRs+AF*a-=&aRADukko{R5etuvr;MC_ zh~AEn4ZcI*b3^{sxvdM9n>#c(0D31d8YofFdIYCAb+QDcU-;WXleB&yaJo9wlX+n2 z6IpcStyUh6c5OckQ-_8Hh&3G#KLWoe6$heCd?0S# zU3pLo>{qn3ft2C8eb%^y7bnf&=?~D;??_tpW~pqKIz>K+<3IqNn6dCyea8#U$Lj@c zGbSUs?p_96!$kQ9N$}9rP~Pu365~Tr?Md&8@D~n~w0gdd=-2*SZI{tAy6h`&zq3J7 zYE02h{udT+V5|u1#w5<<-c+m#q^1R|xlU(aE1r>}{xwnQBXcKKo>fOC#!-N}7U%CM zfLya@N>}irQ2@oN2+v3_T`*rI9ehD3@^Q|7$FiE8$s`U`QB}2qKCuIMX4D|?C7!Ls z89UAH2qcCL>CR4LQCUER$ z>L&9*BkeL;!d@GJ=ngWJHrQ9w2%7|!yQ@@rEhuGpJ?}sw%5rAlN`?#t<_%)Az`e2H zT^78Nk_|n#r!Kzraz`@jv5VwHt1-`%CI?#h=U#C;WIM(NgSr`p#FV>%d`0iiGhTh( zRj@e8z{mJ*kw{O@9#662!a4b{mK?W|ppAFq2Q4EX2>#X_cKMMfQ{x&Gn{R8@MHC&; zWcpwEx@Z1Zaz%Yg5lJ}{0duJG>mJU+ixEP5F3z9Y%Gyq1QiNK)EJBrg1s6k{*}nMZ z60NulBiA1<1(%o!-?E_efNPHI5yyh5U7F*ls?6Sp;?$K(@$Dj){>E=Nkgx zuo7yfDY4FTxkdfV80n>i{^4@G_BoG91R91cyrYhW;zYx49T{P+_QW|a9xh1gg&q96 zRS5!~Zxf%+hV5(1tIEEs7pSf`CJ9SkF7*L>@hm%*gyZH!1!{J+uCtew zD}xPi!F})5o)rjY32Lc`Qw(srE&UX~C$?%?b^RWKgrtOM&HuV@dCNCda%-;&PQ~K% z_{1|+qqk;`Q)eUFi4u*2iMmGNTQz8kGTHG=xmKT&C0tX|%3l`l8FpJtcF+gjQTr%t zy)-H>@kVn~uO%!-#O-PCSW#g(#9~T+EM2|C;$EiLRk~#yTD7n4lQx*YCcfH~u}b6J z9@ci9Y3Bbdo+*N@5Dd23{@~ZS!<_Bsi%vb@#+t;rdeGD)m8VOM)Rb7u@hs^vn=;5uaJB_@9uiOlH0wCD4H2U#?+dA(+A z#2xe=Nd*2cIA65&d>R2>wzCK&GX&=i zr=HPF<%m`?Kab8Hr7f3P5Wxw?B%AQTFHmjNYSRl^-4$2O2NpcT3?GPvGma+=6zu7K zF0Qkw9zCjWs1LtixyTXj=LbDc$}|bF5UVX4yy9t3FHT3@JJ4EMmLJlty2ABMXJs7h zK#L^=p25s8?(|%T50-S{uS$2|!D4DH;GJ=Bh*!#2W=5#*%86{``dA%jLMnyL;bG(> zPb+Fhxj^@y@1Q931_~qh6>ZEd|utw(aY93PQeW!%pvq|Z8} zAM58y?Wn8K8g?3N7zYa1uiX?c?iL*4a5{l-`8Ak!>`5B7MESxrpy*EOy7vkyP^Sp` zvr7jNMc0mHAn^I*&&enU>uRL7S2?~=K@TC^R&e*CqbsTT_**%>_o>toXLWh*$>*|n z`8Ew5!zZqbzjyOiU_+XR;PHXSi*6I9K3*+JvA*rA(hprFp2*qJmKH;qK`e0`I*t}^ zEkp+Z76VKWJ@tY2R5gY1Rzt%5*MrOQ*S|r+(ZR&N(?+T9W)VQ_B%9&#aX&QMp;2dd z8Mjy84<}cVnL{IcGwJiz*goi)shSranb)6^p%aKjMZ2r1GNKWqXJdw^wS1_yM)ZQS zkVo|&k^eddk*uAot4q75e3N<<7`ZcS-t=%PO8If72qOw@e8>O4t^_uiL59T+%Dt0N|HIo~s$xC}UeL$H>A$)W_EUBtNLJG* zREueqTfZV~3g1rPd0V5LyCDO)p#ptre79j$+0E^klmthR25 za|l~%>!?5`-2=zDeF%!R!lNYCiG>`03Nb^_bV_IcSLHj)a%cvgrE^7I^=y58R-oVLmi)r{b03T%^K-Zk;7D_|{Xq;j-`K zT_lI8y-rI>Iljj&a&i9^(nRBbMD5Jgh>t$OC5hm3*;BiZuyf>*Pyl_PXoNu#sO@Fq zskLupv1?msOu}q$6z=-D8M*_ohXZ)mXH_cvhkv=BXPWknPFZ#zq$>4zOBL=(=0T*n zWp!L@5yskwi_s!W6MjFB-wMx*l`APOIhbKp{>)aB7VqVkVE&@Tfzg)Kp;7pv%7^8> z9|5w=qUgrey`<_|eXQ%chkb|g{7Z&8hCIp==}(Bgkbo9;oBu$uod$N@y`OB@AlDJJiEy_1rR^Q3VZ0H>ctg<8 zATr)|%r$Z)I4aOmKnxBpLeS#k=L3^!q|k^#V{I3NQplGC_FUq4|Gylu$gn>aZ2j1|Q0?6t}Hb92RbY?ZRUDDjShU?bayCU7;s@OVIq9qj^~Z(jco4(SnYb zuEl@9(QO6F6O4(({*>1aJaaB<=sxlZ;rB6~hYa zCe9#})Jc_@YI%uG`wVM0PT8#;3#>T5-8e4Yg!2z5w&-_FyodKlxaDKo))D%iqTg^? znHiL)`}^~rpx`OW<2lnDEL)C-0n+1d>}f{&u5DC+Y5|K-u=Vk|N;m9|+Ow9a@Ghs` zx6CUjm|Cf-VMVceOx4T6Z15#)@z(aIZ0>x;l&8b9js$7qjSH46^V@Q}>pv2F^9WTN ziPQ9>i(~~(8SzBNz2g5VfFQIRVRZam=<_8mby@7XuTWAfch2T+L)L;e7C4xNh&9w) zHIzL_A`GUzry_Vcu?j{&0FGBEinFUhu;#Y}Mo936gLiHC1BQ061peCZNqaAH$B7zxtLg;O zevS+q^HSp`Z)tNq;i7`1f{1p5VSXmgTL`f0uDT(!B@mXXUkpg@^94x0)}7o<5Rn+< zluRq^7wR4&%?M1%G6P?)aFf1|9=Z;ss`IbKeDtD&p7+^>PQLqy4m9(hvXispwz0~{76a|j(xh_+nVb>^_j%!azGmk&%@<+&+e*8rn zUUdtaYqet5pJk3XFN14J5Op`d%$ua~ieJX;vhL`~b84NH22dFcVjT5j0Xm#12uLmN z4l8s)T*<{tpFe6|lshjn`pAZLn`r-hrM66U*26k-?sjs(FZD`TsAA)Ul#?_qr~=1O zm1(ZH)~$D$Gj-8G*zIo5w2>&9uiP~NEp(O1onpzJr&RG9l90R&@69@f%w|Sd90tP- zg$uTkp~ZPBz#b`%6jt|lWas>7iBcb#npA;|Ly84+)C2Q!PQ|@ugo^$1avc@x0Zpnp zz(xD0OV_LvCno?7#2pUbu@P3N-HV>~c7XOm2n0xD)H0yrP(ou*swv}(!mlHFYPd*f zL3G-{#*XtPD8Ct+0?tiO;@cKLBDk$ksN9=Gv{%l84MZ^_%Qrm2yo@0s=CiHpi!%b} zRWDKxH=T}sh9tp3}Lb#cR`bi%(Inv1sZz#)0=aGmt zluv7>q?rsI&Ko7U93IRhY?{Qnr(%?Iw8j(d`nz}18*6W`y4+QYGv7@($GB#lO);MtOup-CDugkF zPcw;#b`LcD(}FmhLFTu~Kz#zZ9`WwLR_jC(q`093JK?p)wWNs2aFvW}aB_3m*E`fB zdd|sHT*#EadVTM`6d~PD9d-Pm7v;aN%@~?9F(FjMO7y@i=^5bO2Vu7W-l8(Jc_j>X zueN9(pYM5~VFftB?YPvLo2(Kp@G0(8FIy0dL`$23_ZkYC`j$-S+r<2Ji^uH<>9z0# zrfmwd@IGI>7{)UPW1W_1nig(wyrJtcyLm(58_^qR=q5EgGWglGRU)g;YB-0$L3ZnUKu^iQ|yktn><}^Xh#L|&L<&7D+Qa&>r zGpO!SJxWRN#)0-DF( z9%Vwqu~wTICEZL2ZGzWg&>sk(Ysd457CLdoZuW^$pPvy?%aE`;yk@L+HThCYmixPG zKLXJ;u2v(|9MEK~BQ8%{!BN_BtHoVzulwE=8xMpIf$Kego6Iwo0ef>JyS}Nyj|tm% z?*yuN*aM7=mkKxWyJR*dNA)_=0`XDiEKPEblbP?) zcV>ZftTrme+kJ20Sqb|F>mOY;U!|c=4#(T@wpLR^V4{ls^_=&S4i1Yrs~&2L0%2+w zp+owj8L2RsJwbWtPnd}>0lcLMVz>CY zSDM77qFDYR|q%0dxz*A*!8F;*mYNueU%%t;(9 zGUfZssY>k<`OB{i%75_*BdUqmiQ66uWc4wT=}Xbr732{|6*-srO)sl|&inp zafL%aoNkZvK0pa9!L8?E!D#c`Z>FZSHFRJ%o>O!77Zuw|#^Rth!Xw%dYIU#3 zG?Ed~(d{AQ)3R6U!$7E|vQeiIz2f$vgw6+13!?gcAqN!!_@cG=C_Pks;D(SWpsb5+ zKcj`C_*!|h15Ob^mbhl#7(#0-f^R*~BuG@M$&_y8*4oEXSuf)GiXNY%ZUF@~@EJ-bTet|J`QfegE5zOoq3evTB;{)5=q50F#rSPT39p1ob9 zZG8@2L9ip{QdM3}iIAt_m>2R~pU2jhlczzG zz74kzVYzPRxOmzR2R#|5$vOH6jcK0iv$&o;jBp(~|U!3{2m9D=jx zUQYG!s{zyUsA1vX?Zzc8H(`qX{HtkZvcL3;4{tVw#eadl;{90rX=PtYXY9pZHgU`Fw7w|Twmb($VynL6 z+3A1#b!3naE~Evi?(l=#r3fgg*M7w@-3K=OjnxS(bU0pA+hl2?ejIR8k_Bt5DDBDXNbv#&ql)vyrLJX%pnOpBH$t9tk!)S789G^Km$|EXdU zsc1WvsanlVaW5%vH(bv2U@b&l_f%z>KV9*IRXeNp*+`5eTKDqoYo`7A$XN-;bOKNpV*A{c7*s&um_-D1!-;Fi_G-=5RNvP}dPiWQ-h8s~9HqCP$%0rsyHzeN{RN&pZs7G;I7FzF0|ULUm^Zo+MUC9Feu?QLzTGliqb797aOKZ&)+rG3qR>z z_P-qQ>%z<>76BZrYog7^3T?(8@yj`S`fKdCk4uc&=d(npSWSMJ;oH$okfqNOo-q#R zssWlnHIA6MUKaAK18oY?(Vv1jq7uw&g=dcx^3%MLdapn}!$NpeG`?wJi`@~1pD z`|kx2Hhu(U+?fA)udjf1im?0f3mGyNcjHJ^0~xgpGD6=@;8r@V-KxV9{w3qpAm<-u z7cqv!@l@`;)OK^YyGef*XYW-+x5V?v2DF=ZGu*?Y{~{>LOIBYcfCzZx#xuzjY0e$F z&`kgZ4Y}JHdzU0KX?NiBIx1{&bqXeckWBz{>m5~1=JRmSK1Tb#s2&$olLrc3B$*JJ zl7#K}Fm>=W-<0<-rxfJRlYs8%3mo=YmKrW6Byp4`6MV<*AZ4r`qqeE7M@CeEc+FPJy^3#P=GpED#9KQsa@;del}OPT+*s;`w-Z!xZ3Ty7roB@}SwMzq^#{g{{HIyxQ#XQ% z!m)I!2v55!=ax4P1XHy4ich?re);(!9<*xgGQ4qtnDjsxMJ;X$$Cm#Xp+4nV(U^qB zR%-I)`;Hp78+Popp{04!MvVs0oI(H#+h4GIAfx`Kd%Zpp-4o=mqovT>jeL%*S}b-x zm~A`8-<6aO3JsWX0BNpEG|H5_p+_d0E0y5gP^}s*d8Xk(em{Yt5x}10V9dZ9%=yCT z3!uYbLYl~S*yXKN)VAf^&|r%;eemCQIX?x`6>We~dPQ;B0LP^`o9q^Wm7P1;2BpZ( z%74mPR)Tv-W$kA*8|dO8kgv;E+x?stN6X+m<1ctzK1midOUOuSFkkV&GRF-=ppyjY15bt{OfC6doAHs5Fd{xtaGk2ix5pm@&pu|vh zm(}UJ_CHPdA^oogI(8ziF0YG^^H94`J_M9vdj!kEe-Q2c);_$DK8(=3SHf=KbrGO~ z8^xkWcJ8&lYI7H$lj~`g9Hz@R+E8P_S^2Y zy6ng58YU7Z!_Uy?bjr<#qD)Mn8ms-sXXmd~?YuuqZ8!i^_oI*Yki!Icd|3RiAU%@r zXGI2ZmLpp?L%a<{HGc%P6;Sgs{KCO+BTUIai?(h21M}tA;Jc8eOD1j*L+|XlcsTdp z<6n5dKj*?SE0)wkviKtz`RSDPR5xc28mj7lwESgkVV$1Wkxj-)!O-f@N%<55zratm zz)p)ED=vX`_jgGwE4CP{7ln2iF#q*`aJv00ScQ(Xr4fTOoi1u|D(b4t^!@ zdC?$D1#{wUe1$qXAQVd#_O}4OLTME{e~f3=99}L=MPba6^pLy2fr|^mbtkl!fk~^H z?GLRgS7{H10uFR=-C$S*Qqc{|jdI){YUJGmf9+DmhbdnHxK7hNw0A%qgltFTb-zOq zb|xI#g!jJrF|q|KauHsu$E8T*YqdK?l@-){1Hi`wf3fYMpfxm^d$1WxI)ovVV0M;1 zKPaW8O+E4dM^7tp19aTOKEaT@G^-tQpNm@X$Hec1<7YD7>1`V}kZ#X~t}caHqx4PD zLp!v1VT?y~LeM-U&rf)5qHhM`KW8SW-d|@flVx(|1yvVSrsz1?{wY&__Zs7w#lRmH z|Hd`du4gUx)A5pDKK4D&3s@oIHt)}SDVTrz3K=z_Fbl1Jeed5G23)xA9$CJL2ryN>gbZ0;~Dqw25TeSc!=@>B6{S42N$v&Oy#4 zRD`Lzm^xedzKy8(5+qm9g#A4bVVT64M@$@^f&VK|Lx#66^BSq|jjMhHEJ4#NW^Dw1 z?}di+uRS>erCaE=FBX{5+M(UQQb2rsCk~qgb%v7vv~XQ3;QFdDoonF$OIsBLjn-7R zfXCdA#VBI`v8-~l6Z(PELtd$MG=SgH@?^nncp5K)9jRS&=g&H@6vm$ypaa(^7p1nKT8&D2UjwT!}mO z?NmlGxiySj8bMN7a|eiF<>x5b+GDQsNT_`|r`62{M&uXvp|0n$fZeVR2Q9way!#Y$ zErtRouU_J35z@!0ZadLLNQLToeLnA^9WPRXpE-bAw}eQ7_n1BzUUS#cKUX54XZC+j z>1i>xS!nvoqF`(7NQPz4+|ILwi7hJ*R~@9H!VPp42A4#t&oHI{DYJ?i+3-UTHXd3| zdm(3brNbCVQSi6RO+O%bV_@#wBOI`8m@!xp%kFl9G@JAWm(e+jaDrarGsk5R)P9c` zLC~XpTnUAh8bfc>#&|Z2>ILu5`8kxiU_yl7IgUOZ#~hs?pd^$-^y@JFeQdo zwg*{P>k>&KBbrB!`SEG;$|uwQclsE1rkEO**%?u9KSkXAA=-;4SF@N7jYw*uX@JkD z_;(T1^rI)iG_I+TysP{u-vvg6E&C8NP)mZX1@yh&@u&fpFtpVQUCv{4xxJvmL${iofl z(-R517VebEjnxva_F`$`f|?vQc>o|dR9v{j)Fl9;@xxK%*)pH2qin7A3FzM+Sbb%jQ8sBxYdMkN<6C_&%OqSngy1M0*!-X-%kdQI2ry%$pbWGBh4X+G}T@Kjgu#V3TXX3;yP6{ly-*~)- z4#ko$m5UYNmil5`sc+2>BOl?PD%Ony-y5ROvf|ozJANpp{c&$*GWNM{o_7%Y6nt7{8;-7-1t1|2wxttkI zsjhu7IuZVh-NZndWwzfkwiGv<9($zhIw77=RdF79g@D0XB;ql9M?;FpPjg1(+xnq) z|1FGDQ)@&VlH7XQv#DeeXI>{L%;30MI?_y+Wg8IG=w&Sk@q)|GR<@ecn|L4`s(Xi5 z%1}V6?Ml6z+S#i(@Am6X8nMm&58I=zW{Uxg8kLR304qMEI`xPsnWPu8?7wJtl8?yP zGV$+$htW&Za#W`U^#AemQ;4W#1q_}x%R%QOul3YC&01gNWk~v?# zgZQu$iX==xmbZ9z40+>!q4pUV8i`6yx^6VmaYO5j?lu{h%>jFsYCf^uV7UN-mwJpk z7VJmiJfiGzffelY5AHCn=PM2n9|$8^Gswv^29dw$pxy)Bp!fm3v79LH$r2V4;ZqH3 zBkZnm4uWO-OQvYuP95r)LLSnGD|FeJtahlwO2{TdXO!TZfjhmw@omFu(?}Vnu>VYh z9z>V(w{*U`()3&`?Tg(qdldo~L@pk-V6Pm)Y)Zi+znZmv+n-8dzCSmMGPUHK zjYLeSmXAt)3;%j1-|YUY3v2^Qx;` zRF3&43I%%h=+l0hr4Qj`%g&mE7ARss{YP)3#dlrkbHdLSOugUj&4pAYj>BXqSw#N< zSu&-4*fUGI7$-y?n1eWU`&`fv(c;s7kNm4CAr@GRJ#NC>P%GQ@epKKM*~UYN0VI()^iLnt^lQ8 zqx|({K5YBzX|&`~z2_A+dG%QcW0RqA@#=u|a@4z}nh*MDbI9`_bADn*a=UT%3c{wI zW@?e&+oXfusDonw;`$?dFs)7^L49b4FRAlRPNS<1EwLwO?cqmmwdlSD%KWLS+*is_ zkWPJOp)cpvKiUu(>ug$tr{(QpvVgGezD?KUH8*0sF2VOo_<7F@6;E0`3@wOQu|FKC z6PB_6A&MOm?NM`RCWtUEM6(v;EGisx8hY@;?M`msX0#U=dfPqo1 zpd4BcWzHaXG5^@BI4=Oq5FDFT(Zg^uc$z3Q;*4`ZD_B6sb@+(M`>pYmEfAvx3B)IwUzpX8S*XY^WTj1XdKjHj*b$-FIp}suWQs@95;W24{z%O9( zmBDv&a;0SpJ2z%W1{mSXdYRsex;N1!xGi9{Pwg!ZTJk-Qo=SlryEFD4s&$J}7q!^D z=hm8?hMg0|`k`?+&v4>D!v_9w@6;|9%gEfLc(9lBY0qufITE^-m)(^Vny|Z@{B(he z*b@$KpNG#SCgz*E-8DpTzagD7P-mO{x~1cz&R+LwN9`NV#u{UP3c+o!Gmcr08FwKr z9R@kA`c468{cADspGM}5e0fh}wk4awt7UsP?%}cF!Tx#omK6D=_!1nZ5cW3FC z&T+#;%?Kqp0-&Z#uM=X9f!iVoeL%jY|DR}A06kOnmb8{6r0$&?cbnFd*6k;<8CQ#ZXNF#*{lNt)+3MGmy!p88Wv;sr*f zM-!_*`2)M8FLyKnE%%pvBqIn5y7Gn{?jXQwE`5(z7Bd@!u+3Y6HItZ_bZFV#D`0hT zpMHzw-r~(ybDqs0yirF=6J!M4uYmZEgHNKo-JBI3Vsi_F`wogW*uLyjUqBwXI&GUM zmjjxXWKC+>_9tmhUOlgKuoc@(&O~>_4z&g&4cPn;0N;&;o1*+K6~FUtQuM@*v%TLh zm@(FT=dXb$!~kE)1uaN&W(W|2bybH&)e9GgAm*qli{K>2d4Xm@G#$BlH~q3#SCv8; zZ3_Z#K4&2H%P(f^OvW9^UD0dc)f=q5DVr3p*}G?~3JJ+Wsg*@44bva^0yE$g#=P68 z(f;-Zu-TP+?$(l!*pad!!`lB1B{-i%@g^gGIW-LgUbXr(C8b3hyh^THFJ|RWkJR_~ z0e|5adVS&Nh4?0@riOlHzAI|H-`_;2B6`yw&0C6&P!0on2YP(=0$=vvIGN&Yh_%=# zRRGJRzHik|_LTD(>H|$vn+qadgAkDMUxEfF62R?R#XY@v_^RLNOqu&M7enWCQHW*q zy5x^Lzyzb#(;h0Q`HQGqykAN4_5TXQ?{aVh>yy7vgq2-D>9cDx$dK94Pc*%~TSF6* zYK4`GfHAY#bKd76NHbCBu$R;cL{ z{%TYCXXa;!y-Z;P05rn>#}bfhGD)PM&ympg>~b*@4aD|SUf)kgI5Xwzw1^Q6XZs_B z$k;k#>}&dKfDpF z5HyXgy?wY83m{~_w7P^3`N1r+D?8!+qKA}*H611s+!#CnY9~2DFTUW8GcGJHJ>9$t zxVuI8`)o-t0*GX#l4Nk#_^YbA93+~?JllAFKhWVNM#e0fdkhzC)l%*qd8_uP^Q*yf5On66%YE5yd5xYe@A$4RC=zXz`}l&sw-4yhlj?oz;IDeYUJhS% zJH|Ba@mhCxqe;3>hC+l*RMP&c0c#-NZGp<9uD3SKGWRpgnq`{pa|MqHgh;f{Q3DBo zR;4eksKlpg_-=3yo~U$nsfLz{mXsJg(z{po9N$b9%VMz&kC9N=mvmX0UdZ>u0-cJ| z;Orbdt`aX3&#y!!GfU2p#htbH;tSsH?N4SmHjN?eZPBE+4NfIh2f?fI6#qJU>s%n4 zzMC*g2-C5{<$TN_B!zF*^Q##6_+tZ@N(#=9i{WAU)2KL`P_uC*+9{0-={7VRGqAtT zcNg>p=T|_hcIA3b8^yX}(%)=%s3BTc-Jb|I#Zl@QwaoA;%f`Q%&8=?Sr?W%1u&crI zeCSNq!(lc>`cq5>LVE>@$$f4kM7IvDq=dM`$Jjg^m;V$V!1I1*t80?p#q z2C5FL(f&LHm$8E9C@Y(Ld}0*-5!lcp`Nhs~Lu^rM;cjrQ5+0+;yZJ-`N&etzj~z6aiKLf+oz&i`kosko9cGzn?%kmpTq#lGZ0CsWi??G1MU)QZ12V zeo{h1x^(u+O&eU1dI}&zDF16Rb20VN0!a5%TJ$6RwJ}1iX-|iAs#V7IdPb^AzP5E$ zi<@$8%#Z?XzlKM94a_HmdS(GtL+r!dM1gW2Ljnpm0GQEy;z!*;aM@y-Eq9UeTypc6 zIY&nT-c{0Ew};>v-|!6{s0Tgm$@xaN@Mtm5_gd%x`l_2O_d1iuiLZl#<>%F@2*#dD z5-h0KuCHdf$Ed-Xc|Ejn_8O=q$c?|iKj$3th}vQh9o)aPB7)9#_KM$#jx|JuSiSwK z_>-E$a5sD8{xL6GfIpdMRy%hiydHD_!M#jeu$^Ll;quFoYR*)biY>@__OAJ3u)2vF zl)i(O?ZshZ?^gbu@IeI90(!0nNh%TZ3;FJl(@|c51u?F* zxAJg0+_q$-G;*hV54EI{ZgV~>8!{V`w#Fta4>9HVPX2M(e+e54wwm-YH4LM41=E@o zrT0KhkAxg9P}7Lk{rlPG_JaYPIb|-7pb7X(Mdpz%VoKRD#_I`0U1@u(Wt%q9a;S&4 zNNyY5JjA3_v>g-~lDIdm$mE3s8af`MA7t7D5O#d-Akwh6`&y^Y*~`7%d&5!Cj=N@f zF5s4_(jITYohQ(%jV{!gLG+z!y^Yrl8@j`;ypNz10XZSXHusq>Spm((K$t!>7mh;A zK5X$Zp}NiQr0Zi&b#Ht*toT3K0dvyYQuoX2r`=e$Vlw;E6ADJzg5QuVp~4bcwS-ZL zIr}!|761EF7v?~A&0f~cZ%f$!?%}|8R>wZe-<+^o9bVo)S^R@UL#BR(8$^wtAz0`B zWLlZf&j^7h4+#40u7(BjGR#?lXcVMOP+nRKT%vm;oeZ&8}36Zl=IPIFKR!p1r6np{^xYzG-;jZ{Ozhb z_8I`-r&gSIhdyn(aL_6t>J&7)oGocAd4Yb~bVz%S+yS2;o<$$<$)}~A!i+IGtspYg z%P6iB?u}pT+8*CB!b6)RkOO!7lKB3>O0-R1N#N*znJAnTyt-q@Na4U#KC7 z)$1wj%6!4A-THA`Ckj8gx43(ER3MmyZSr+hz$lM{%CvMAWmaXax&aLF^M=rvEQvGJ zaBU1+B4p%+Bz#~QAXA0$sXCHbHjvJH*h0HEi4Mb|7P1RmVO*4?==Iem5Z=)vfYH$*ApU$Cp_8Jz)gDh6eox zHL-3cp(tr5&PEaAC%6?9oDcl-<3%$0*+j59PLN7t@E24kQ5z!SlGmL!PJJ~6xlxD@?rI>pss&) z|F=s&%uutv_Ad$zEzvK!!_0w#bwKZEPAW1>TxV9kq(gI{_K!GkEb?c}(CVz*D13zq zCVJTmJCe2ggRk9f)%=&cQ=ouuss5eZUex?Ti74|SyxHNkcsEaj1}_ROb|<$4f*>-y zR%na>7YE!vZ)Eq^E0!|Z$`Qp)MZ5gR={&~xIH4; zx%5V=^|fcm1YCaKz4;T?m%S0>PicN3=|s`kWi{SYC7X7sGJXIc!vdq%OPBn5a|mlm-7kccIG$0G@O z5|EdVC<7yTh$m3e)r_+%VkD+>qkGcHVtH3YVRowRpyT9}NQNI|9*d&dYFOHj`>y1y z$8^o^gD|g|xlu#G2dTU0+@8vvyM!%XZ~|X$u1rv}6PMI|!jC4 zNM=W%8T{OJ?`Kl-6oz=JPEpYlpX6siuFiq^JEG8BImuXm4cBzf3@c3peK%~Ry*@gR6`2cdTKiAASP8U;+8jrx z%n=FMB#t5aJx5P%FGzY(mPiYI3N2lgk?Q|kEgJOZzX)|+M0ur3FU~P>Tt@|{h6CjC z+i+5_$%w%5Zq1-XlR4~C(eK8Cvcy4i!@H+;qO=oqH&OLSUh-P6U(#q#=H@hL?>{03 zFU>YQ6 z6Q7S7gSCY+bD0lAbMg+oQdl%0uDryH{;I=gAP*A`gjSNu_cfs>zt(8XNN*;e$2sv0 z5ey{_u`$iW&Tafj>XVNc&}6*7VT1v?G1KZ`+7Mc*QVNXj=a^e%!=-V3{Q9S~@OV%1 zt722oAXXTa=;`)xZZdL(5R zgyZB1xOK1=@XYl+?jM(W&>q%xR_9U^-qgf56a;U2N2F~Z)$&>SLR0p((%AJAzl!)c zD|t>n+54eIctLmPpV|A6dymJ*eu)lIc;S$q`sPA}nfGmQs0~SlUV?}TF?^bzX5BF0 zza58yLs>v^A&c6|nvDg%v9pICA|dHo-) z*u~ykDCv8Dd|txQ&2K%r)gK&*^N7X%Rc@Ulk5_PiQZ|#_n%MUhe5}_jR=I(~W><=@ z{Jebd)FA3ko8{vSL8Xr79-ncM=p*9Iitg52stLh9)0xTg?F|5IdYaFlGrh>UzWmR; zHc~!upUSAfM4GCXH$4uKuVw*{jnT{T2+AniZb3XWpL5K~=X|%mbyc+(W?g?YMt2*T z<>{@{n1*>cw?YBU%dHxkHsy#!Uo* zaE8&2@&8h@T?Uqq>Cf~`uF2mwnaL#>hOS1MR;<3iB$fGL3M+(zP7oGG%}vY_Tn2&f z+1_jKWOpy}7p|75%sV^j9Y*7e56cx=`H%L-Ts#XvX}?S}(kkK)rpFQ{wLZOkD6|aR z{lt4ynoZo3;(WF>_#!e-)5=2HwYLh(JBt061LYLyW>q~97Yk7nr_>3F^ROwv3vJCz zzl5OeP-;=t`g{0(@io0W5%XVBLqXeI68o$F8OS_9|G4I`P!_A2ctw2kf`kat^>kEv zUtx|y9|W&<4ErqqP!_GTEx~QZ{@}O59~$>~ld7j1n1fkjc1=%!&Zrh=tyTH-81`_Z z_RfGHd(0NMz4nK~M`xnlL+yG$R|t;dbTfOw^xdx6)otvQl_M_H#E++--X28_=a_i# z9~VF23n}3Z8Nlp*v@OHrc@`OSM}%|=$U=4#SGMJEOCL+@+t6W|U83?iScp*w&#B_; z%1jOAXi@hbhMKzB3rxxk4_WjygrnJ)?Jw+u+Jou8m&ELb&Mu z;cXqr5ikn|w$oxy)$~Mx-95}OQQ~BOT!yL_Dd6C59ho*ubBdxLEYo8=fSYxLazK`* z()NP3Nf<%kqQLCJE$^?@aE178`@QTu0CHuRxyCG{y<-SjF>Ly6CiqOo+IB6-sQb6&?yo6iHa>2Z{I>Y2d|4{J!Qf(fjPu6< zNznW)KZrQUlqAd*)a1shs_t=*Zmy;!0-b1{VqFZC7ES5wruQDZZ@4^B)2(S+Bd&ki z32d+|nnqZIQJk&91tB^dVRq%MYUq}W;jh>vHQIjj`v^QCQ)apy>1$_)C84&yryx8L zEV{N9Gcuw^!4byeVJOGYY!OuP#5E!@s3JV;3kINw(stL9(iOXBYdQ-Y^VS}_iuVS2 zlwWYWB%z7m4iN!)-oRO$U3e$B zTLg3y=1M6tuSFEhXO0p>UH$9R113jwFCz)hj+SNq`LwVbR6HUS?(0@O`CF~FKdZTB zYYZP+2u`V&;kwquq-nfgEpjAtomz@Q4mpoCwcj(mVXuUg5-Q_{^RGmT7U7aI{s42~ zS$^<(X&q~v)o-f|hhlomf>GJJZ_YqAd*Eme7e0DqwcfT<^sm=tubl8jh0ihS)!NhE z7|O*5qyt=z$j2)OYQq-Fl)YhVN%5caj5-!a7|QzAZW+6Ge;)^Delr=|8``v_$LJ++ zz7ftC6+LFG?br0ES_uq3K}qc|T)DSJV`01xt?t`*M>WY@c#>}A@3QlpBxtDV+WIvW zFyy{2ndov#knn=q8!YdcZG~PChm;|p?BS|>qu=Xq=s*uwb!HcwCQit>bh}ZhX3n!j zLTgVU?9o@g$IJBPFZR|K`sx5r6Cz5L|4Y`g|Ko(fwjB#^bR$4_8{FbZQ8moE=pE(= zO~u=4e#+wuArWFHslcrg{+Au_`w6z$X{EOZ)%vH5rFG04(yb{)^CwRp;;O ziqDK@{AGMHySV0$N>{%gkO`@)YVTx)=wf&i|JuwY)PwQ{uItQ-^1G4G`>Bm4_VM0B zGE{TGY2Fp!!o8xGViY}xcfM@~wB1QV`H&9E-}|~RxN6Eg_}-0MBhx1g{M$VN$K39f zDsA+G#%wrmS68X|=DSABBrpzfte9FME@@pNc^QQIbB(oY!0rw6or80D9fAK_-WZ{L z{ZhFcV+Q3PwzIhtdjY=txWaIIvmN^Ts-mw*dmcW~j4RS`%C+-x#bqq)|AlO5Qpw|T zr)l#pT41Q@7vKcE{}1-{+_JEfZJdQ8rpbZfSg3)sDFxv`TMtL51d>z*S~~IL!L&X+ z=osA-UrzU1`$YHscv<&Gz=vbn82=@gcZ-_<>kFAqxnGzhcixC6tG+P&_n0Bk0!vBv zdieT|-0p%BJCY-@i&rCz9@}L&jd*3jKKT?kOEvp_j!~(|Sj0cdKRAgr>%YgLZ&ZGP z^PF@JZ$dV9UTE!4Z?n6e`Za+g98gY+-xb9cBa=Mjk7u7l?b0w#hAR3!`Sk-YNlZ#b zUX>YaN=7L5-I@5lc<}?wl5K2k)m%+gc|6X72kjQJ_pN9X0|EPSg;!VJiFKJ^ptsoo zJukuV`*y1T7yf&>m*ANl*>n_t?l9)L_wK@HoV_{tg3Au~wPWek9owD=9$Rhu$|?3s z1n!!8N`8*;>v1D5Yq9Q(yy_0zv56X9)Sp7fr8uwR=V16O>=&4LetuG9h8Ll?W&q!< zN&3H5IiGpqG0%r@CXMF(?(-9Xt%|>nUA_;a%-RhIJL*KJbu5~l!8B@M<0bQn~Dl#O~cK!0MI_c#4)>`@52ke}E#UN_8C96TC9JHap zC_H{CB!%Qwi)oci^%&3t1DpLYW=`mo(AA@!(^l2NiZD_rfKEof-Q2r-8x*Oi4(%_S zBak(3+0R)TU3qg{11TcjSA{+kO8c>FKPl5<+V>n2582VN?+F?QDNlAsl_&1fQ+=5TKoTQCvrC(gF z@7-3jRa49zlvz*lsMP5<`}peCo|yb&i-$Q?H#7A>*_%3l^|Yn&(f8Ia0KsoD+ce>`_IW5|A=_q zG-3hl-KP^7Lf13&Mjd*$2)mZ2r! z26x`Zh6jqm@rl!)`Dv=Eyf_Xyu0)4Y)_|s6GzjXVcq_8C*1APK4@l?&d(P6O6?_EV zxFIm=dd#b5Fj!^%h9%J-|PbnxEjs4e?W0$jr*}6HdDL8V%8QIBGb1 z2yJcogO#RuUvO&Y#5iBob=1a$bfrkoD`jKr2v zs_Tc3o3^*e{TJ(j-$TM@%^kdwakWG(fS8Q;h_SF*Iim}YBQqWjS{}}~eLrWW{+Oda z9{1bATuDz)8ircm=0_1q#gh^Eon_i3hc5U1o&a?Jo1w&JWb_R`Vb#O{s^N<$EL-0i>af+aw~2(WlxH2c?gAntDzg)$kW!g1ofKTNplwD zjw<-Ih$aX-uy$E6_I^%z<<%rP8f(8XwlWV>3F1jz zrx53IJesOTe=Ee$Y?8p_E>+>|DB%NEE1cjlv-A$1+zi@2@aMa3191x!2&Kqjpv=ffpF%5RNx)wbvRD;h}L6{8riOHy{FsOzf?)t zJG&^k2Yy+2L;aftI0(Bp)m6`xNQ~gg=Fx6Gp%{galEHj~WkCJvI6%|J4nqc~^ivw` zhl@d3Iqb3TXQo9l^Y%f5Qf(ZOJF&C*Tm|jBsi%HUf9F(^Ou1zcehh9{{#(Z;u z;2R$#5cV<x?t(G24 zqYnUVsCBsQ%ALQzg8MX377%MaCk`FKV)HCH_*Sw10ejx!(Pi-vLdEbQqj;F}%J%x2 zD-`?Qe&~xGP|b)ZN7y4#PrSA~+FwYWeQ*gp6 zLB$su=)|mYcA~Md#Y-Jej*D_5s|QomFVo+ihH990L_7SR7)XRiO0e%ReR2IkS%2^Q z8t5$0;3+DCInok(Bcl;*^mO|%Me~){3t1-Xu zp7`pe6#9cHAmb}ph+K!ja;?U~{%L0lX-4ih<{njF% zs)D;x7s~Kvh8H;g0bY>~&DAPOeiOrZ%7O{vnWw{kc$b%Z@7@N!0uxYrJ&OkPCw{4**b>|nnLGuMl>~)>8y06dWjG5y#g>I&UhV%g%2@so9WvQdm9AA3Vb4mN8 z4sV`OZI_L$5j3$-&P$45?r=r~Ho*|Qo?RN}YJ6-iQcC{8ujZMbG3zln!9(`9FC3Wp1mH(J6hY#Sck^C>%)4|*9J ztcTPC!sT5Lxk1fexuygEznucfeK7A>s+Kz0p$(oNV^WWcXtN|4l$z^UgIova#%>yV zt9Ofe#iX_V2jdy~FlW^2Y>R8L9*KHVoaR+$y2>)PRfB$hYBC_9*s+6%&uFTUo)sRJ zOk5GlNTqzA>JsyMUxb+IbWgkpQV5}tb&WagP7nnqeYUZB)7+SRl1#FkZoQ-Ra1PE6 ztC`*S+yKLe&KUe;dB!1!t5fuoyw6b13^#H#M+0;P*idXNHW*C}gE1)O^nEKR5 z^!6qZr6X+ETRnap5>OFm)#Y9))Sjvhmw+^7b{P9HI8nexB!+k+z97^1+x$|9r%s+t zAJ=d}*7rkvmS8Z0IcF6JjjhYFjIa@)?4VzzqFwiVG!Wi)xkMlst`mjEWP714SoEix=skd&MP#cRy$3J`OCA5ug-*-o3IqgtqkgCTboY-%9 ztPp3H2}qW*S3X;z5w#ivPWo9W;OQBjaW$l^zYu%mZOq~bgX^RJD{%>sjXB`y*4>#B zU^j~&$&S&V^e?_DXh~GzBQRSahaR_av1dS~!{GpRO|uuBm;Q5az5C_p`1Ub(B8A9D zBP@V^3pXR|di@-M-V&H)HJs!?alX}pWH?n1?g{m#q8L47(pX}nFe{QFNi^ki{neu< zx?AKMIkjQFWRlF}gms3|lEZ+0$a=*uF4bAB*iFrCP_WoVkh#QYrm_Uf<6EBD0N$dq%`xx1jcGw(16 zQ|F&gFBT8oa`Z~RlUQs?;diq_0B*>_wG>EPr3Z@l*yK!G%1PU}&bm!3{kDCz_HRGf4%cgWnzMs-r(8@J_3 zGhHSemaAFJL!ds|`2kyQsj(Dr1zzi3atsP8c_5_C5J}PTES29*hTP`T53Sbi+Ydz! z#-F&?2jp{lJdak;EtxE!Lh71zIzIDo%Dh9d=V$zyX?G`+0E5cM*l8psFu5KPiX9an zOCF2&9#kd(5!oaIpQ{8bj@?A8bje&+2mw@_k@y_?w4~L*J<@FsBzXJtS0753S$ues z?U-sa?jCK;Tgj|t8$ZHFBVXA3djCj7s_%!k*-$a_&%gq}EKw;Hkr#fe3E40az zR9%1!cI1{!bkA%m&Fm`jSo89Vj>9#F$TgTPU~M_uw3|quHvu)~TsuJZ&8Ue>;AHTc zsKI*=%XiUf!0m(KY3}3sibT^mNhBhVV^r}7^Ju~_{!PSL1%Q2hqctt-Io=dA`jurc z_2EA9y9X!v&0~lyBtuU2Wu`th;&4-5a;noe(2-_y7R37}aJUpgAGrUuh?I zLrpTXij%<~9Pl>pZyuY+3Ejbe`va?LFDn31azwht& z5Bxsodf)SWzuvEPo@czz+nm>J!62FDdmo9!sy$doRM+2uoXnK^JLg+>0Z&u zxz`3YH>`-Ml_hE}ri4uw%oZQGDVL4D6Z|n`?D6SAewK`13X8^Ehpo@*h-~8K=6fVU z4(jE*-|QDXsqwg9yR?6>Y^wU=A&;XhR9pizQMY1S%coofF@lo)?S;!$`j4aP6Zl>h z`gAKPws>q_dFb}7#9Mch*LdF%HphVRR}4Hep*J+XZ*G>lXOlKnHGO}CJ$}DXc0;GX z!0y{2wvtb=pHwbTDzB{NO?~agRy0N5b}(!~*upfZzf^Q|ITk1KzZ+R?AXyWjdbpVxQ_Zj&v=#CUzU()o$r_lx?(&1|B%@;HNvE|ghig}heC1%qcJO|$l& zuQnWX_PDahinFzB!H(8lZ<&qWe<|pLcc4<6>wIkKK2kw5o8*g)SwwF=6IVti134$| zm<7tZ4aLLy{xs2I*gWMUceg1yZHfbh^E(=p3iI*~_7txsW1i9LJ;~=zDybLb2u9rM2ea^28q7pPM!Hcew*^ z@~-n){fi=1 zu>3{(3t-74^vV}m^V3EJ{%C40&+`k82=mM!^^*8%{^w5@w`iu2-mG5g3kz?$V;v|4 zMUMGS+6{e7r(^m0*XLz?+1?R!yj<$bQnfI>O+dAOqXUvD<+Pr7Tme< zcA0tIW>r$2^T%azmq%-50qhor(cVf7&UX*3xxQ(x9(&Su=lhRIagJ&=<=`B<5AWP7 zXKD|QSvcj?zL{8M9dkmZZrVM5sOfZGJ@Of&#bt$x!17QB+~GaT{d<+n{}Em_I!^M zBF$Rr2;!=X(Ejzof=RU?r6|)vM_YZf5Z_*GfbZ^ijTcn3J({>>e--WDU;8Sykdfh1 zEB0{4Na(2->(beY_N2#URt{M5=RKw27`A!Vx-fNo`7^FRXh=~jf8FNAgoL`JG77Wl zs+&N#Go9rJGL}{uO0)CaPDt^c%@+P)ni5 z7NwCyC6Y;RScI$_!}B=e#p*R zdblj(rYn||NFuCLF0!6dH{}f#+^cxr5qXVZD0|pE|Tk@0WZxGjyL-c)Vfx zn5s?o1KnrqPm=h2gUaq&D;hJf&xGmSd3Y^qm~U)Q=jYjx^S6J^r ztWCS{EX>1}$-OJVEfL$Addlv+t#RE_HOa68TG9LB+=6*vLgrFQ)8)!4ykK{RRnq~KM1kZj`%GRvp45}Z<7kO1XF*@}=;hH0csJ~=_Qej;yo_%=zh-) zzZ*SXvksoY?YgnR@M~``mxqA7j2P_KOwvY|%wk zPvjp;HTCuAC+i3&+C!CAxm7e6ZJtkK;`_L8{`;wY-tY8gt8b+H_U)_pd{q*-US@)N z^?*+P(A0aWvotrSzgvd%P2(qM^Wzq1)_6NkkRq%#H?oU9rrqCsxk8j>kkotqSZVOA zpL=2|5WQ(w`bs~nLm(#jS!}1=y8Tdbxb4Nv-sl)Y*mR!Qi)QsVZ31s%bii1 zrmn6Yb+E``XkiON5GR_PpaM;vFQb!jI+%TPL!4_bz-Yc9<9nyp;yt z^`DH#Map_Ub-$`?F~AyJxfZ7&*jo}GqxFRvS5SuQpO_o(ZWukK|3c3|%~0{1vo^lH z+N@HFzp>QOq{++%euv*5YVP{5BzM0@US**~X}(7~ z^_Rdo-~F?ki8PiC&9`ww-8uuy9}^xNOa$5S=)v;RK6Fp2ImxN;gSx@&KgUgF&kPwl zG8xX>&gzdF>97dVVY(PQK{~4I!Rf!+-Nb#<3+0#r=578vwc`6Q_fL_ zFE)-w;w+*>7H)eYB#q?B%3T-#m>^LsLM3A zmAiavLl^hGaJChDCDL^S*Bs`{=8hBUq2{{v#`iRle4gc~u`msM9c9c%wvncD<#eI< z%F&JCfES^glxWVeyIAQ;%6yXveJ-J!xhg!^(XI(jvn@|s9(&?M4$Bv9`R4asqGVqT zpYaoKz;AGxA;Nnf5Pf+oQgQKfus67JJ@T5UsA>BeckjC2y}j*@UQd(Ty4Q#dautgb zgDOP*htJX7nocWCul_zAaEML@QJ!SJoW#Lq)H3OUTlgUJ9{=X?b>DuA7dbp3wd%{~ zsC$^R1J|1dgd}cNE@v>${BjfWy+4#Cj6?C;O{y zUs1}*r$yZe;wrRfYHSxdm4nU@dfL7EK&y4uTA;OJtDA!BlB@oyTw%WJVntZhV?E3- z=jI1aU4A-TG1gZ%fUd9HpN9z?5HWwm{=l-4!cTdAm4{L3w=J^^-s@H24+?1R0R|==lsY>5d!>bH8 zNGbyNJCv+_d%+8n*9 zgW>cNa6Lk_Uz+^v(UUP3(j4;GlNsp@GX$xc&M0L$1Q+X6EgiHn&#XK3RQFWR-umH* z{f0$G#`d6Fw3Gy&Rp=adr7L&;;8Okzxh}Wzw}tp&wzwuIzSd7)y^bgqnfOI$QQcb` zHW>C4=ykVMZfk#5TOCci$H56Bm*%oAA$VWh)QV$|^zAr1kx_~!{r9U9`_vw+KMpHI zBp0&-H>oibCk@{`X5Tm!gH?(T3-DvM3XwS4*)e#IA|&aTVrS6vwz)nA?$mk>a$o0- zkWXQG1;YoVuSR|>keQQm?Qv1=P@(O){Hx){d4CgWdVx-2OO#AwC!g_WKVQxZBTgSI zHooo_{$2}aXXH}1{a2ydg-V0;&N z@yR#t@mEJ#xbOEonmfJWi0kn?cl?kS{8aW=5+=Xg>T=6H9dY~)5$tzr4m$dk)w4W> z9}_Lsm_3fWlkqYet)$ucijzAiX`VIjXtL^giOMLoh|ZM-+O$s|w5*33SMB*d4^-0t*OG;opO@yiqHX^U#rXYN1XijP2$vVaNQfx zKRH{`k&KsB-*eoIU-9;gert>4WFzAD!Yc25!C^CdiYd!M$+ujyELt0H^CM-U)ctHk zz2q~ND|}YdtSxS>ou0T4H#X#s`h~vddq!%t&;3oY>38nDy3!irk@reYMF%PB@*R*% zYop=6ND{P;6Q4{lp06I_Xt0P~FA_biAR4I?oE8x|S$v}T`mZzBbdL}99T6{oS?>9( z=qB+mUoK8+W?g!e-W%KeZE>PGlGaZ?uRpp;C%8=PdJAOfk zXk3ixYvtp>jU%tp1fF=OyT3IZ^?rwc=un1UA80=5TM=+nSvVjVhG6rn0^X^SRx#A96CIw>HdNGkA@koFfS>*jJj0R$V;R`L5o`G+pfZ zj8sT-`vxc zgWhMXe(}xT%rd=3X4vzztEu_Jql(TicYe%NaA&rTGJf(r*|W8h=A=^7OMLt+{gc&* z$;;Ttqx~r&9ef!N*J^(VQG3}7(4giG;uepEHu=JjOo~%zezPj64oF)l#m|coYmQy0r`&`3##aZ3bp+)1Qq*&= z3e^pMiaBf1;=1Wj;BwY_z-r>GDEZ>A{pVazH)7t7JtK;1xXk1B?#%P~hhER(77crX zGKw1RqZl3f&!jw za&2z2AJ5x@3kR;u4s@S!^+rzCl``@)ku8VL6f?`>xmH3HLvJXsM+@jR+xkTxNE~c? z>Q^@HNIjruQy})Kv*x?>>s+?VU*qKkn)Lp*yvH4<4&+=63T01=&q2MG5(xeI=_FHs zpfS^m&d;dYgSTb0u94nYs%i{6B5O}?ELCpm$+*~vtNZyf$%^u#P9gR#KkMz4&4epd zw~e$#h1~Xga>-HTA}?-Mk_&EV%+Yt6hsW7m>Ltf*SgvI095~1Oc1w*RUH2gVb>s^& z#_Mm@r*Pk7rycmOU%NSXO-YP#JRl;nU5EBdZJC|$(|sPi*S(U$SB+B+#j<=4&p5aq zRbP#*^Eo7YLd`J2A%tJ}#zc-o$0(Mi%{q{eBns`ept|meOlej*dOo z6uhclTk$+uPySgvvAlWG<^`tqiv4OXI-I;|VeHnew>Ukocl)I+4mBGENV3;<3y-u_ za-+=~Mc{{_(x+`@*v}D_yt&a@JFCrX!urICcUghdkv-h%U1yH<^kPXTxzA*UvBxw? zZP>{7X2vWw4l1k4vSg?JrDXB)11EJpN7L1iqdy&pS4%h=o_&?2blp8ku|a;{kFV0! z#+qMa4SlWMqhgMHU{f^V+#9{$xWK5qo)@vd|9PbUOgcmC6e)R(jK^P zC#jz_>N*j_#QwN8u|p6^p4vD zr!!V~NK`C??fpF7buZ**Geuwvp5j*m60e94=PBCb_Ul`m!=l{I8oVYmS9vFAyjn!o z_)&eNB9-g$L+V8X%d0c)f;Rri(_kGhO zKVwd~nT|!v!Cski`{)k`!yO!sMr6MmpT83kJ0b9CuZmPnLzpp{u;!QG>k-O!Tzml^ zho0PYXlaakqwYRnS(IP0z?4jsXW;TS;tR^Vb^S=qTS_BS=9%yHX4rgR=7tFMdOKPZ zn$sH#tL82$`$FPQRnEkz9k!&W5AZjW-rM8Ud~`^aV}JAITDc9ga_O8tsY$N>js@P! z@*V}R_3dlAM-(1;ZlM$%s3s54S&B`lxpUkR;v`;LKdZDZsxFZ1c9+-rW+8mf&PCSl zs&R4r$Du4LiOdrA5N;!;YK^$+i*dRPR{QWY()oG4e7-3PYUpd1OnI})Qaa9~sMHz7 zG8y&UEzQ%gCDFx)6j@9m%8=Y@z>r$L2ZF*#}?o)WjYEUx<7tXFySp z9nWXZ*g7fFPpZo`!dnMIE-=s(Wt2C(y)z=L^Ud^@j88+fm&US$-B|Ys@fmFKxJj2O zo#ZOt#D;MtiP;%lnb6x2d}PmxUDet@2hWifSlLwHlMYk3A-h7+M!mo*eWkR^>f3RS zD?uvrDHhMK=Xgu=*GKoTtWz0n{yajd+gNv#J0R-uC2N(ZrQA)Wr%apo7+5CJy^58f zJ*d@GdR*8e?Po#&vAO1t`XZMN+@>yFKw^7zjr%RvAU@l}q??H+D;JejiApnBIQ_rO zlU+&{cjYgXh5tP|%6h)Bn;2=CD1A7r_fP#n=9t8-^Hr@wu8A1n$V2!{B zKv)6EHU^*$VcW%xh~OU`=m8Pmw%r5u+7O9t%m8r@qPXjG5>W%hzx|*9qW%w#_u9c= zC4p}TQ*c6Epz81M;|9EpJn?>RXmLrjQ6Qcm)`kbn>~}3LD=H}}0e}QXLP{PZDKCyi zi(}-au<{tG|8998Hftw;)cM%!yEr9*`=7QX2>ijW03-uIXcI9;LQ*1`Xs2DMtYqR{ zT$22oH>ihtkxaWSC*YQ3x?TJ}1pySlb4K;2pmyVqrV#DQCsT-b@qEgjKRH0=Q^@~d z8i*-&ZP!v5w&jphB2-EwAy3lh5L2XF-i}KwC4~hkDgWSHO)suKdi zLWm^?4~jj5B%@^cBx2j+3+-iS3a`OgAqzFg|L75B2B9C}De4i-4r1U5hr%Ps){YJW zTfBqs!&$V0A3*ILjKFzD=zBPyNZ0|@Hik|~uwd`54l~%divgh7#Ry>7#Z+KFyt3T} z5)HtzBS)hE>vocmYZ86HwIhd`=xsS4l$(G9J7bF^6!2{85ORnHe7ip50spQo5fIqb zPXfZbelmf`jt-485Z%F$HL+dn4KTa5H9&Gl4m%6GgCT2DyOsuK5@FIN3Am{)wARGEI0zJS1DF;4~_k7R^d66JGgq#E~ zU z{0$)e+4?{DFqSkHH z1fB^VX^>ka6z?J7GjQ7LFe4LcRy9RTVGe1Zt>K?q(c zKEUT~`C)>bcvn6L5h1hR*^zF`A*LjQ>)an(N*Xvlwr%wYwtIJV1mTF>mYWgew7YT) zoRa^@nRn%~aGDe3l<-dlP6vX2LM(lPIV|utvz-U_ca3@jYgc#>YzX-={;4Nn?Fvvu z768ywL%ef$k^Xc2k6(C3u-nre4OeT;o%)|03E?Vh9dzGhWnhG!fnF4q!~7w^Zoz10 zHxDmA9QW+gXWVEnR~)yclmW)TU){~qOZ!Bio9T%oW-ceZUF2N3m6gznVe(Mn1hq4~!a zp5eGXgMF$oC~s38&*?icJ7CgK;wv*SSnE*x-J z1bgBA&;*Z8&iIgE95;;oJ0)NLUAKNg@LiiQJy93DuUMFqKO8w2LWXHa2%-+qUhEHnzDNypw&Ndw=(zx98K-HQlFs z&eSP>t42jyLIN8H6rd?CqNJh3r3DKB0KNeC88|=>5|LEzBt?j|v~`G~4gny**T2o!)WuO)NlEVW!~Y!rbLD^DAD90#c7gu$S?6y*}A((#|P z#ee9+Puk=^bnCw{YAT|@F_S==*woVaE08`1(sU;O=e))Lq3vwlKEL;K`~0QwX7=i; zz#}?v#|MZ3tN<0yqQjvjA8ET!Hrp1J8Uu z!3;=C1MC5&00saZkY)ie0e6;9J_GLsZjVd<e~$wLzJr>Z0|2)r004qE0Dv|Nyhqo?oR#I@br5(F z003g^pkTmTr%zhXJW6HCddR|X}-y~E==n2B%_! zn$UY|AyCqr5fuOmR`R_$w?z)*UKs#7dW1jA{cmdz5rtaMP;h&2}PNlB^n>i+uV% zH1LDxBj-Zz%579qYMAVK$wQk`$&3xfUiYd`1<`$FmD|6BmU#lgT(e_xKbqT@&=oJP z5J1Y@^4*Z)a{oZxqLGPU3pktqnQENL*zVQu==VJrfo0vjCS+d!B_9$H4V--T@!$6N zwHYRuWMy*m^iH|1RJh}jvf2TKLt0Sjk*u&YR_|oN%3aX#_Rep^ZFGa+w9Fha9ZB>y zf5%-XZVq->d7YQ-L|tNZ*Ox?xz*(T$hsv&-D}C>w2gC7H?tbuyJ1qu+OZ-s9JoZJX zwdrdEi;uC}`9~KZe5T+Kst^Xd++vJ!go@b^0->?c4QzuTv~T8tRf;o>kk8XJKgz!vF)!dD#(psh ziB0tZXVDvVQP(~P?|sMHU5dh|V*-2kjLJPcV6{QaoLD4ujqqfERm0*VK;%r&kB2Vs9tW+ZCi_|T00<@2W z+Zg{z)Bj-&*9lk2t1t88a3O$#7l1kUeeuQu=`KA>(?2E z2y;+oLPPgZ*IMX6F@tM?yZ-eW$i3>w*0Ue>Jn@PWh1^U3Ya0li%9rW?*@-mhn2m;Y ziY2z|{zGvk@)&zv3&-nrGW*)vKY+iQM^8g6tBY^W=MwD<lf700Fz7>(f2%kvF1%egxX??Wm zeur53x=J#B-!)kni-~TE9s?vyQ@v(^Yyw1dI@J-4mt6pb2H=K& zAS4^dKav!F#)v+tR@nqThZ^>EaBWZuL=8=RZ)Ft!v{qUI(qTT~!T!hC>GAe~ghA#N zM2SlrJ|I|XfO)a0z2tgXG6oVqJNYfl3gyovU`{GaVG!vl;02~Q70j$g(iw%#riUEM5 z==e>_p28dZqLkVQq5>A7KAn+PS=PjLz}$i9g|Z|)Kb)Ko+YGk!Y6mP#DLEuY|J0cu zU57#mtwt^i=l)kjbBcQIe=PQY&EVe8L_gdA^(;gbz^m!r;DB3*ojcH?N30|CodlVF zH_nS)-w|+{mOfO*>J7@T5Y(+V!;tzNU;b_wZE;<6!JZPwCiI!X zq6EF7d(Q=zc;)stln`}*^Gb*d_Tm}e zu@ueb>wmo2|7!QYwQ_D30(HvM#eWEi@wuAX#;kcH>FWkSo9|Q?!TE4SA)WPm>?0PR zVa`_oRJb4XDA9}i28p)w2A|m9z)E<;G|9b=z?eC{u1I2!{|GdV92vhID2a!~n@-yE zgJ^}oq5hUHQQ7k$dVGlSb3U_hD#+t{q0?e&`g3j2SO_=?6f+Zc_{uBqir=qN)bk|e z|9RnmqTK1U7=tqfbh3+cx-$u+Ffe(O7wlNg)aHiM_~FrtY0G6aBicuzx#+CvNz7(% zVCJ=t6KW09U_ZXz@@B7M`sEpFwh%>hV8g?JlMiFC?0~51pui_7H&U@n;WL7g6WmrX zN3uD2jq=WYv#DTA28&P&Y)+8Cfe^SWSYW>*OWiu8X(sa%Oyu%5{> zdW4Q^MdE2Lo}P~l=J&|V!V}r?&?lR=GmsZ?sP~6Xr#ZA-nB832G(Hn5UTUi zUJ*8GS`n#H0qs*EN~p}=xC)lKP%oP~pc$E*7;X$NnRK_nZ(B&vN)X)26B-rq0K|1 zlo%*^rvb=MpAt#p7uPiWUL+fEoQPi>jGl-@Wp})mE>BX^Nsv2i z8V|l;>(b{M#wd>+EI2jZek(BY6{ymVt9?CO-S0qdc%FG&fBLFv4zyCx|7!XtTR!Io zvOXd|DM<6W?`_a85dGWhNJz2TyXSIB$%5!kU2tKA`*;Z`|A&{+qZezb!m_iz)ihD# zk((`VKddNY@i{~fqsQjP;jHOY5{w--7HhfjLXE{o1gR*Eu$$@BwGX_kEG*Q6^fP0u zJMqeexx_$OIF4as1puUJQf(Omz_1H!He3b91GZileT23=VKZ8UcU@h>>rt*)D(nK+ z0V70$lgd1=44p9I`?}uD;;RwQZBi}VX|fK&i0Xk>hd+b>NNDxLFGf>xszjI#7e+{n z0VF{#zwgbEm)cOMyC}UngRbHr>XwKPqra4T9C@5w$EaMxE4$_JO3qAGK%ZhnhD0vsDc;iLk4P$fv@28aLe+AE+H`cr7DpZwq$Agpob- zpQC0X2+80l?<-a1G{UWcCKN~Zci}5rK;Ign++@k(C?`eiRSWaKaAUwlh4fl&nz8?C zoY*HKAL?yiuAw+(l3ZDqbY{}DyXH}~Z$F?}`Wd;xZL!*uZbSA18J6z-X^O2o$x-Jk zDJ#a!yJ#v@pi-`&&;-=W5^sHs@;pF)4q#DbO#QZ;9U`Kw254Z=6I0!+Qoi#XXT_C_ zm$*jQ?gZOe(~Xn^AXRBWw+HKdPuR#fJPtd{`CNlN7|lC=y4_Q)G_@)=si@*Hz{uyrEFgn2_L2&~Ji*_5XToZ7Fg=6KmksaoC%LIv|+x?0zc*rw6}VY{{jt&R3()GZN<( z$WXrq8WPV_XnTj0Iw}xJnkou`AMh>XBWBbOt1x1^Bmr7k2C%J(-U9g9Jde+SC<8>0 zTgrp+P>Aq~*tqX;+3oN!7=q~IwBJ#_IRnFyG5}WPQgl?o@ZceP5_)sD=BO4 zwb$=x;{~Va7Yu%^Jd0M~LtLHOUQfao3>|c%sZ{LX{rMLS z{!F!shb14gd8 zh;3g`7Y;7&3A*F5zH=@8SV;+@xvd93T~TI#EyrXopxs_qrldE62PNRTAX@?&H9|f- zLfU34R+(=0No7|#w90O!&*);svGKBYyVBdOH#||+s&mC2g6BuipBj{xiU}hs$VgX+ z6u05wOmd2?!1}R%8%$t;0+nYa54-qdCXjEB2wo?uc)A*YpMV4tvSPX)Y05tTq1x5q;*#I7s_h|OtpYKL~W%D_6lAwwHS_p zJ;EeE4s!CvIfkCDv3-7)0o)6wt_ngssM0n7t@y21;6*6O?~y9$2L{3bAFRuRcB_!w zHGoT#H4YdR1AmQ(=!T`Dy!gv57Xo$Rax$*<^m{6VjK`fLnd$HGNYq*^4+LaG?6SZBI`Jw#?y)k<4}R){7ya zz-zxCa7B1Lg|8lZKFW~Q3i6eq!_f`!gT_#Kyidqhc;$gvu`vzU@OC}>>|bXJjMRK^ zhw&8&F`qh)xE`@6{L=o(amOTiC!D(LOh!l&C@}-CUWHC2*p|55PJC#y2uqdI7Eq33 z7*Ssk+CPZkES0qtF3x2%3%%2z_QD1~cRAO)q{YzI!VW?$jH3fl za&riKzKhX0oBr&xqp9G#40R5Grd_0lq`q^$?sI2!Nrk}+`?bGro8je5?lPf)UvR@z z9*uE?OQIWB{K)yoqO~J_idSQ+g71$_*On!k`B7Mt0m=^0xn;PAIBoo#!HZ0@HU8iu z_RPxaYxmc=b|gu~$KoGU1GmSlMBP?NY{Bvk>}Hkt5xfSzK=&V$|CzdB&|e6l`~Oxh z=NYe#lg&#CI1!=ts!rO_au@Q1nU@<6aiS>Lk;3##nZO>L$=?{53!1kPt8yGXAg=JO z45~8H$V%O%_GRH<#Qp1H7<603+f*$ctY?15GxM`}uY%`UUy}+vjjFB33MHQ^*ZHY{ zGBiW&=SFfrtS~*03&%na2K8@v;8<@4z5~x|LS#q>&btOa#0B_I4b$b(E`3q2B`~42 z`hyvLHITtHXcW$^2Yo;|VO&~-qSDAS+Lz4n)1AU>U;vFm&!is|LU>{OarF)wzI`4A z{|M1fYw6QPo=cy>ewJw6!l1h=Je+&#itMM`ZP4Wpo+|QxQU6tNcd*KK_ogsjoE4qQ z3pM(&Q>oUUItkql%`Abs9ks>AH#&(|GZ55iNyfT5fsi7!?`?H#726ZBnlq4*&D8)2 ziA|6%4h7fAe`bWO)GbHjS!SZdf*N`Pl^1@82+!cx3d}ntSL!?$Sc955zFs#Rg7*#{q5_o;5(7q*rqjg zyt`%;{!>Pq7MdKW39;T?EuZn3fl2-bx6N*#FTVyxL&xUtyQzIl3f(9etdRu>*l_1a z)rKMygx~Ve6}T|O())%WC9A1mNsdX=yL6TnuegXv)q$~;aEDG~`jE*ld_Z)UX`B_% zC&0#vsXTwR)uPx+V%)2s>DpB}+PobMc+ze`v7?)Cg(+%`&(TK)JBI7J{`IgkA8c=m za;V9EIu1myKI7(TeX`IRg-zVb(vVjR%^t|X)>rWnviuDAzK2#U5h!R5m{|CCQFWRM z{xU=-Jk}5cB$_Ty2B-3uc(tGfR{mTgFq%uaD86kO0UX z7jHn249&S+wDT(PAASc#yH}#UTM{(^4)GetZ7hJ+c!1x$c+|9zz0nx=3lW^#Lg|+E z2M07H?XOm;9T{{evH1!CpDQOiNzJ@i8tG7ATJru{75i>R?Q$(ZA79%v8fS`9A+1=2 znyaT-G3VtIFx9|d^}T#XTBKrlZo6MK>w_k&HbC&UykQ+1TFXo@hj#~;8xB@+Ku=@p9o@q`k`;=0!3-ZL4*U7lYB+9%uoRI0g37uAa#v(({yPTP911GirF;%DW0HAp~>_pV7(|c!_M{e_=Okrm&MN%_JB!Q`%NY zTQ(~bFiKVU*#KOB8L;w2`k21cn`Qa0dnutJFY0DrZ!Ki#sWW$x;i$Alb2Pj`wJ3J; zza3sn6U-yD#u$!|=uFzpbP{?RL!bPH5^>p*U_8PDcs^2U{lI;|YI%vz%U`Ll_{A%D zb5t-U;GNiU+y>MSwr*gGegLUb-td`$zDV}r(C@tB3+Q~;Ao}wV;q*t;@TLM4ETea~ zOiBKjfp4jwKK;SaU#A&aVQwgt&_4KNu51S4UbHIVVVrJD-}L}YU5E3A)l}8h{}~Vw zM>_UQxD5^#o8dPw8`~OfrT*!!@0Q>&AmHP9XuSIoT&tp!W)-S9IY$%fRa>%QLdnHQ zJFx}FH~$MO#Q>~VFtn#)c{SfB(k+hoTA~v!Kk6tx+{yD`HfFeva-a@ctS^?3Aw8g9 zOy$@$18TO4f7s4U>CVf-%95zYYgwlg1=t~-i`;hTqj`YL7dl%xpm-@N@CcAq$<(dM zcmNP=(uCCPqjE||!!Ovp%)-f-9ppuRUE^f9hwfEv_x=GT;H2Z%&!zVLzLHd|@1-Tc zh28>$!%O=!{b%PG%#Nt1sfwbD79GWHN{he)K3*HUK9IYd9+I+BDcF_!%TMyKE*vy* z_FbvdKw`>!+&P!III|mJaQJmUXezYP{le`b?J+EyjsR+{xV0!A#hS$eAwlpBjv&2| zGoD=P76Zj=w^mw!?b&!U6faO5AOl5&>9*SPIgZp}6CkbiNk6l?S$me7nJFOfL=r8g z_R~%Y=ZV~)$|Aq5;n%EE&ByjPvspevRuX|tESqEWOdM}$%$`dsU-P_=lO{@VL_7(z zAJjICgQS36&2_(@YeCzNwG8_x{4&0#%W;eM`RKPRp`MIAfdr-dJGMVkc(uBc1SRqS z=t++##3 z&zmz`_tRmnRZ*S=l0z8FH`sA(FqoQnI#w5SPeeEaP~AvjgPzeK>NSuLN(^5zK|ePH z#*YR8u~-R>5d{l&M6_$_b@qLidIkxjr=&4R`y!`UgoDwoHDvlUMEUU(kheuQYt;Ix zuukhx@or6c!pDz6Q9>B9+nd|L!DGm&L~DPb&7}LA$p%c&H4ib_>6n9;9eS8RY$!;u zVpq0Y*R&dDSXNNe8z^X1%86ix@5xv+E7D&KGZB0fSj77U-UMR{+2=TS=I)&QWlGd5 zi<`3mEC{hNBUlcXe(y<~eKxmhA*cFX?g~Rp?zbByo|vTRm^4Bu1A2awM^dFu84vgK z_VlHh4b#a}0mMKEpc0m?jQnz5wIzTQNM4+y z)qz^{ppMlG!p$NRJb!DvF+oBy;M&Eep&UFp+hK1H7!A1OD+C0Vj$W%!dNw+G zw3m7U4rXvY$Pf~87yHK_Qk_3d5R$UZUgu!pG9P6QMq`JH?${r0Ep=fK{@7es&%E{s z{=BRuLnafy2h^iy;)jFwDD~FMicKK;sV&WPbL$xFjJX5h8 zueu@v)Y|8n53O?1+c$NHyuoJ-I|&?cKTf8GBc5SpGW**{H$IpQU{y;$=zbhAZfoKp zkmBQn^?|j(Ee9eF@!8~*tUF1`Uj@QQHD|^jsplpw*)Z3+%d{q1X#=y85i1j+zS`Ar zMQktwEl2iEvGg%E49G)2AP!CpRJ*>@Nh2!O4x#Cp4AbJhGLSnWU}of7FkOakH@L+R zuQ-dkf%60vZIdfOf2d}9NqksWxBe)dN7Qzz#6In65zrIbWg64S33K>@Egd(gA9aV1 z&|jy70LqD95i@)r(;xA{_5!p%6%=0D!Y{M-T2AFNLegLsqvbouC;lA{3SpZVo#Cc^ z6@XnHyDlR6s23TZTXI{S+gb_~S;)@K!%df^fV4WYZrI>H3TLb zrZB^7tdM>2G^;IBoGvJn)SWD3yY?S>2-SAU{<&kg&jv_`92-Gt9MG(>Bb1)UYI#wa z?6J>b#Jx%uR_f8&7>q`7Ven8QW7~qxVzGM_7lQL3J3B&TWcGfq?ZdkGs(hfnDsr?~ z#auU(YSW0^7A^iq_Ii$t$3f_fKr@`UxRr}S%?5W@9>KA&0P4^O_VE>n??2Yuiqi9JOPuSs%;nqE}xL=@F;=-p_ z)(rJgCs3dHe3w@=_DP#Qac-;>+;30Ro8=b_UF_Ku8ttdzYxBpE2SiWr-*%dzJJkH4 zL5?HjZ;u2Gh&aQMlYutta?xqc|AE{S9%C)<@;5xsb5}8!&aR;RH+|JTiPMJ67mW?l zPrt>nKcxt)H2rb&XR<+lc@BMCKa&m-L#E{ZPKEDPis@)i{Q)i?lE`^CtftbZt^srZ zPW?qPD?XeOCY+pbLBHYKoW&YH862I$LD|YTaLMXzXopOv27Qe*a_In^W3)#Su zbR`xVFxN2_U)VE#c+~r$2l96V#7;;mBBK{dt9Y1q;VfLbD*uxo!4-PcHq0#o_puX5 z+P`fjVpLSWq{lU(Hvq*rG?k}}KPTQj$cdDnSu_IfR@oMRYuJhY#BXT2_a_UQy8`9G_!Qk zIr1%v5n^v(*3{LkuQAd(0N zSzNiwQ>0YKBv2 zhzAhg7!|pDIl^dt0eagIj$O*XAir00tLz)x!<9L3rSGuJ6)ZR@07k1!y{9b z!7x}=dAue^^M8SPfGL?VIvTf0d5^4Dw@QP=5ee`!&tivj+UDyh6E%u6sRZR8V3-%OK%-RDD~RUs|fCpX;`RYBg(?%_UNMv%6g z^T*1t`(Ga9x~|)0`0d1!eZ8a((sfV_26cA~r}G%(oAeIMO2xOO{(@2UOc&ew3D@|B zRqgpWAFYwPrwjA1Xfioy0OWWfFXv-7gKE(4Uv`#&KqwHok{;uau~gZn?K_LrJ|c)# zch4(VRB)Ckc(#?=g2s9sOUNbKi>jzB!=U1>{Cm;fgdltpuC^d}O9!DF#RLiyE~Gn3 z;yB79R|XXvvRbpdV>u-16y4E$=3Vo{dEz6%-T+mLI_R-&VCzU1w@kp3@6WdV#w6P6 zGBzS{O;cVXnB~44prPyUi<403$1t(h9g%uRvQ z{Y~Q3Q$^jA$jV1}xW6PMj{XDAN}X-t7?{@j{i~)=I?wPRPv-QX-`+krPDheS<3>cQ z=pQXcX7C%;IS-3JhTp0kJR&467`Ll;C#ojwCA?@x0U%`@7EzK2TA7hDIIsClmYI0) zQxp@kf+(Nk=gP)g99fVM#ZG4-JZ2v&roIHke9zzTprWa$8;S)G8DP!#2`nMYo)?qg zB;f3Xm2j~#xhSK*#OF%}+jKu{QU@EL|H;O|DSDG8}ZEZVZ5x-uXposqJTaym0>uHy+efjS_0Q89Mu~^sKMr-$WXA zLdi5Y%zck>V=jcfNfX))ZPvtE*KwpW%Ww`#w$ioY{jtH(Xye9S?>gyZ^F|5>*`7Jv zmPAgPO}(lcflb8Ey6uSD%|8UxqNogZL>42I2CyYV>!IazRitG$J!YpF;@rn8(vyg_ zoL2al=x-N7S_E@KkKQgS_h^m#TEZaC?WnQi4*K;0*4tiMhzW{fJwGWp#d#$Q=+l6$ zPqE^#&CkGo2LLId8d%<6%rSs*Pn5N5)4Dx~X_P&7DEfMIxMHPKRy#2%vODDaoswGKRmEysOIG!ucb1i;~=e@Tj$*s zs7>7}ezqKx2cxF*sf%F1@VOpT``#$0qy3HF3&!|ue&mQ+r+WKLTb&~?F*zbCi;(h2 z*t&fv5aLXRZ!38R@|ioTm5+UQ%anbv(5PV99|rBK{4*AHF`E?KyLJ9Fr*-k-CWQO7 zta2s3&h;m3N@HBFlW8DOYIH;Y$%#k)pjuJc#P122kRr8E|>ELMVlqQ52w09QxE!)g)CKM5?5S5!ce>eMpbI#`IgQxb)K^dLj08NA7 zDycKi%4msU-ISP;`(bGuPxl*uZhUiF4_S;|Cn+Fhj-TiOp*xYxGlA!T@1_btzGJrt zB1N;6QUh#BlDH!5u2uFQqOR3foHm!YYt<3gR&f0?rsAP`QMEFU3aKO03y@&{tqZP+ z&s3(Zm7drE0$zQYRry24Yl|3xFnn!e7>{F0sOWM#+#fkK zO>lfKPMCgEgk|iz!(JJfnqWAR6$#F86*_dPJ@dFK3y^SlSg1ikZU}2cFQac*sb8%Rwt0x{TT9J5Q$@24TM}7oX_y3h<34 z&<%PJAuf(lxk{c{NeB&=YSJ{!zS?(o{C!}H+^pp5xXLblk-2M2kvV2aCY*tztvI zDp=&aP)++nw@?XE6*LvcVsKT(_;xupC7MNcM4kJ&CsaUR&}qK8G~vQJ09^IgVf)5r zwFg}SC2Z{|c$nb$UFG^#V(wGj!iy@icTduXt1h21d@WBrVjv_EB+WJeg}(65>XM2t z`K%s77HoZzu(0^l3x$4EZTq)CW?miGl5(3Ss?J(1FWc>+<#L6s8bml&ar>&Mt8(v% za44UYAl*l@Syl>}n&39$7Os_-9(trEnixmQq0(@DTsCk92%dO&0tt>)RYf!BlqzNA zCPe)6OU)P_!AwxFJneOHn~}~FMa8Hxe${tN>({`cO_+Q$62kLLJJb%x(k=q<0D=Y+ zU0w~bD&-|dU4@)$5Uv7bX%M3^ob{EK1WWnpyS}sY-^v`E`SCkUkE`NxrpWC@qSot4 z%T_mvB>g!(RC-!_ZQQ`j)o|Hs6a7XlAAl26$tLxlZ; z0%V*robq9$j{M&{9nJEZinyu0D{&l2z|IN&oxPmSWCv@^hSH$PG4jDPde!EeRR~Wl zYk#SEYbwBIdTMZ;oAC~0>3?1JKOk9HpTeg*vW;$5_9hiO^Ct-fof~u~sOl>u`FgR< z0km5QWf+OuQgI6tY19Dwxw~JVB1Le7hq))bIt3p%3=AENxoZ*3?AqC4ej~Nc$$Q^5hWQ_9k_|v_}h_G0Q49%i{?eHkqOed)5ow^7mSV8u6WdR zgd;e!>d&ido7S}Acjl+tYtX50&d*u zjPzjw?IMnhonkXU$-DbxD4rm=nu*C|-qBPllHLd2O1epgII{}z&;9XNGpVm_b_1py zc!HUJyF+?@Z}nr`Vs?;QI#l327E!Yh!jSlJ1yYDSqU1}aCNZib#5c)x5S3lrk zJq4k32aM zo=o|FTV=6;b#7ocB1EGfC!^J^x~TJN*~+L)qnB#M7m> zBuVWF_QFO`LIND={J1Yr%%GxKgNWYI;)NT*M|hNj?3wg4H!9Z6CLvVJ5a1I+9qHa* zERPg`WsU##zLoszJpop8EPgZkoZ9;4=}4g(JNvTVvxN7=t`%ZvNH4)28p7+0&YMe} z2p@V>BtgjY{wW@9LR5$GoBE!&SPu)>6+t74N_y%=5noeyf6Tq$c6nkpvXYFJv+igx zoF{X+rxtc&DAdwgOE${hL&k$Jg6%N{uEu;E*`f|HfZWP9U2C85X;^3qXAVrARp9kO z830CM>Q=kIw}d5WC(6^p@Ejg2iyhkcj}6Lw7BA@Jud9d6KQC_V%Es;s!6HB6z*5yTre`<2-DsYHK<9Y;Xe3OLF;qQ`s$g`T_ig=e ziJ{0gn_$Z>XPytJTUl3YL2Gm&khG14Q3Ic5MAssG&QV zNtBXI%gBk#_qAp~{$}mDU6X+Be@mVRgMc6=iR}=&3G6)Hyu$BEpkz@zgOMTu7U>sb zVC8>b{h%`vd`+vTI-dHtcGBt@Rk4SI3a|7WI;%~Na2JCXpX4H}$)0vl2LIO08>D_l zP`i5`G|UsqAU&rMrE?Ql{^~vRE$VitY4GwTgj6?9CBSm8tso_(o4BBOz>D5C+HM!- z_sOo|;Y^{f3^~l&e5JbzLFfp#RdUfU2H6Owig9mNN(!x_pKe43ZgKM=MjU8?cuIi}T(1*f%88O66 zK3RSzQ_!1W?LM0dLd?m%MxYon&t+z`Hg0~WBm#)~mP+bYFsKKPOL!C4SRbPp36lBI z!IL_!lLlx7$HFa*`AMu^?i*Cubxf2op4QVNeE48{R^|7~>a|UmSUn$XziSV5-#mwp zot6||9ewzqqhkj;E;?vsvfy?#Rp@gOd@-LTmsuCY%>>@>Af`9i5$4$cm>?hL%aIRt z$8*9{y6)q|gBruq#IqS6L`2!Ekb3qWAL`B&bBE`{axZj4T=m^Z?>iT#8dIhJ5MXF* z6eekCpy{I#7KYEXm<>xPD-*=ByN&P`|FM_kJU_{Fe9C>{CDA1XHfEH;g!6SDmxR{+ z>s%E)&1&B$3%b-vk#zl~5{_+JJnW8ijDn}Svd!EW>3+)a&hEaMm~Fa6RjgVbxpu!0 z)w~8lt?v4rAxYVpe7}!!4B`dbD%TkW{ov1U+$@(>F;*=eJjl{odnaV{Cq~qyN?vEg zFE-8b?Op@nE3X+AI=UW zo1D%4U0syCyQ-N1G^7luG4oD1dMdyVWJpGHQ|vREf~uqJK1DBy7{^bXdj1{<6MVkKECM&?&Mnl;NH{s#mpWkQ}?PpV>@N z*XyG8*G{Ybdr7ZSZ_zJ__0&|8_c$4|4u)y(XJM6uS(AEFYlT^oW-gy}@%k_@3J|fw zdY2TRKQoplj==w~Z1ot{j1rISdtFlf-6b2-c&*v-{z`AyXWTik!j3D-?6>8C4ymaC zAQ}43VZQP+bsIN;xUPSIfl|)<@6|zf$T1V5KB6`%gs{(b4-0(A^q|Yje(iceOpU!4 zRy$8VqMcsK`hkgP28FI`##6LK>52660Do~ISSd^kZcl($l%9CEaKF7XK%*aXU#0(7 z{iH2K1P)!51x{wcubg^Dsw^1SuRlB0#%!ukwjZ=R*{>|%+re2K|LYcUT6!HI6lFxZ zYj)He1~Be1u=Uo9ys?aGo;mL z+mME-V)eBM+J0iO6Fwu^wQ9!WhXzsb7o%OLihr}YdUPf#mAZb6OvBj4NHhILtDXdM zm4D7Sw~;}0p$TzU3ZCBl2j3b=3CSK~=zB{yju>zEnRZSV_Ha*_BxbBiNADEOPPyzk zk<+{H9vWgwgs1Dtw;Z@qnfDNg|7S=7k2|O6f5U4ttOqYmI84T+FNlgDH zC~`7mLD0T_9TLuwva0ViSUek3JctSLRz+;6)a5CH>KHr%_Qs-W&B=e)w;3c@Xrm;1 z;1KA!5!&bdCWAL84z72klNEZ3tyH2+{z%8-2q;wo>BK3OMm2Y)d6BHp5dk;LFWJT^ZI*-n~DZt=&Av>Yh-Hz7sllacCaRbHq0S5jHT^rD!x-iM#R3 z13@;}C1iahim>W}Reskd31xAq8YmP@$55D6TF7$HR^-xDWmzW9wx5d@=7`mQ3yiD1 zPbH<7zGe$CESI9xX$4Kdkes%mwdedaG)0ejK|p^$j<}K~m?C?HR6bMOg*tOOs%FPe z3IuC_BC@FtjCB5sxiA6>pPWC6dvPtql?0QQYj*f82HjlUaFaJokNd(mr#vh6Xg`Rp zs|wicP4veA&Qt|}+`@Ov<4uO=eVurWiIaYjmQ6L&IkQ{|*pSC}T%&$do*c1MPxcG| z3slG?Uy)E61BZqlt@OEzbW747*Lt2h_!jSm4T#JWe7H5C%3Cc{s%XEU^!L4J#{8>A z25&S6i(}2Pb7RQ~0p&q87YjPD2N2em4*(2Q{@`%;3m5;vYis;7r$UBLiupKTs47Ut zkLQmTCr9jTpmVdc1#VPTbm6VMe5YFpUQKA`ijdmR#BZfX^ll#9@9fuQ!E?g4Aa}PQ z+sj8+_yePO1mDQckY5vW5Ix4Rj`4+blAPWUP6vAeo9QYOh$& z9=!mCs&zeM`wu_e|W$*xeuOB(jzkyZbmn3ey%y$rgu^%oRz8N zbfPZg!P^Og4(Qm<_J<}>#IJ?4%p%6n{Tek?;f>m77$R@N->3h z{VC!KZG|Da(9xCU(%GnJE5jQ_Au~BmO6Qo>8M1UWY_hKl855?}UboDDJ!KPwf(8)_ zRM7|X`ETO&@tHMxC+IbWMbIlU?&N78>qFzmiMQK|6Nm4lw}QX+t5!{|*^+QPLvMWG znw7V5Neepjv5ZV3Q2az+t}kS_77-j_#d; zQSG;ZyiQ`3@AqMi#5|EKdhDHZv;-&so{$Zk5l%w$(;JDAdCov8bKph0dL2DxoSx9z z8m~3J?j{|JTls;65>tUs!92@QdyP2;Jl@lZ_=J*Yf^^gwW1UN`@@C&{Q&9)knK$?F zbC94ngOU*5vE*9O*5Gu8J#%?EQteirpN=!>?NxKPdHVM+rr9ECa}AMF(>i+1jDG#f zsLu20CD6glDHjnNO7kYMVpUmlQ#$ zgylC$5*n_>keq)&2^+_FnDNr_{~pb(S<94Qd!*3Uh7Khe4L#iN+)N|LMPK%q%tEYm$rk-!M83s zp=Z&N{Ujo8qQ{$D&=w@_c3g!>YNV97-#am9;Y2w#J3U8ts4$3E#-EA@T|0a-7WNd% zQ;r*;n!u#iS@dsA$EC?B6^(WE;x0vpYu>^;`$>K(=U=Ws$@a~Ow*LIygUIck#(Lf@ z-4%XM0|WO954dUXm+NR`O45oGKNUqMDsKYWfE>pdK2rlQjX%79kP@TnjF9mk+>Un* zh#lsxzLi_57n&Fn9pIiLOl?TACQ`>WcC@jcibG4_LqR1FJ%R;=FMSY$*Uioshdx8=gXfpp;HABnKTyeH+VW*+aUtf* z85f$N!4I9(3N2ZASx0gq2j!%&3()VG#^W5_7Idi-RchQJ{78ajE&bIlrnS@ zAIBLu+KQp{FKUHI(+b|hjhtY<5aKP}oP$EZ96fW?7t>&lr?9QEu29ZBy{mvvsM$qv zWyJ3Y9bh<~PGHE^zz|0Y6L9LVT1=9^w{UadQq5!4JKb1^%QP#_uCy9Zf36N@K3?04 z*ID@6Tw_m1>wCx1%0p?sd#N5l)7Rb~_9b4^ZaxE|YB8nUAxK{!%?84q`=M~t+KUNB zoeEB5+rCGQ1z+$c%dzkVB*Q^$ho29-OLj&u!mxL+YF<0lU0KQ=R^|nRFmFp{o?qsNZVIaS+S0*ccj^sKK$|nlO>~zU^iu%;8UL*kPw1GjY;&=T6I<3cF=aH(i8^UT);WU!}Y zD-&Y2m+oM=x%ygAF}(47YKH2eH=#0&`)U@k%?>yP`fLY;-~5oF0~gs+aNdL!Lhs?J zlwCH4<&i7Le;HfG$umQUlC=Bm(9L z7Sw;`P?TY$020ozJH!U9Hq4tAI=XZa2k>W{ONyDSd5u+)T&T&3TvmMP}Q{`R8uzU@*EGu<%cPlTu`vTFlF*?8XaGJXPb0z<|KbTT{H6c)I~F}s)N_TmqiM@59;f~~4%-ta%}t(kid zrY}^FAXmSjTLlg(Din6j%VW^jSkMVEIASsq1WjEJ^J{n2VUDLq=X4bp6k!uw$C`7w zy$K0uVN`=OBep(4#F-NO1qGILDGR~RU6-^yTn#B+A+~sNwt|SE(D+#uu_?y0zy-Lh z=}Y%hO&|^1q!AI!<(=pK#mbBN=boSdsE(xmNdattdOO5`HS!8Q*uW8SLLVBl0sy$Z zNt=Ux+`8juvXB8i2M+m;8*oe^32>B-c@t|YD^9XP>S>Rjpx;rCCtyp;ci=F6o_E!n zl4nb*_pwYghxZGpBV~0$^9JFH!tk~MWv_wsUW8Kx%`L)~0<3)ebD6l<)FI(wG>10( z2N7-Jon(us-*eFF8n~R>^}-?_KwBT(9Bh9&fs+y!6Lvv7+3rWPmHO=l5T9Jpr;ClB zAI$I(K-2&gBfB~2;MetnKz{RZ0+>GxrpRD>(j#9XxzB7UgcAdPncJ7e;D(>Wi_DNt zwD!<3+&dvwJ;w8lEHEkeLZ7=HM&m(kgVpdc3rr9KdDMD z6=oCN1q=SvBlKeE{A%mzqfv>e?dJqVhV#TVA^;;vv?%d41{&%2=xk0hcm|S}05|uv ziLwe~P2cun*Wv&lR+l;G&*b%Q{h0Tztl%KaALO^%43z7 zX^o>8Aq!~FN}LWXz5(|KPjIUvog1GEQ!$dI$$tJBG@w8}V7lTjrwxBV%bceF5s#qU zX9!nRNh%7jdgop|N0LffooEI=Q3FIUFWP?3N&^Qat5_Sm% zFBC7_U{JH^3I~7|$^k<;G8=D}c|ZocM^3(8+Vsv$f!knoM(q70w%?}PExHL2Goo`t z&Sp0tZayZRgzIxql)&lar_?lg0 zfoCo#n^14vHm2qnQ|l9V1tGXfAFtc)(M%_^)SBRtwIJ;cn~|?&Zz)g7pMFircDqQv zlAp%Cr>%j*aOd=mV`VK0706)V{K6Ly+u80<^XvKtTsvSO#}pJWy77ssZDEBjK5KR^NyH-QbY?pI?uv|sj~yj2s)6(_XCOqG;v zs6#bQwdgg<^!1YSpvyd$-sjK9#PG!kH^QGztszm}V5_&c5|(P*nA{->e+HWW z4_c24nMdk%ir| z+_noRVq7i_=m?<+WT|(MV78i(u|8+Ps_8bl;J81Ka}V6N(k#2$)+O=f*;UPBAyU z(aNreu?a4$Q|6n@DCpbx0GFqG7S*6Hl_#HYl;$VczIehfpBy~Y3AH5c157uJf>+%F z=xw^Aq4Y#KS-gmVX_nhN?#bi4(Q#A1HFqD}NAf&3kBwSxhA}(@Yj{?OB{EGlm~`Ni zJ(lC@?1LjFG=AdCTEZuOCtPi?aWdZy=M)Wp?Aaikr$p;$6==zgiWq3jN2L1xk!&!u zOVarf#{mj(FjISs0@331l_B*8ci=Ys)?IllnA$S>fC2CKq{ZnuSbPGe{r~KuAbv@P z zab8;3vVs9uet*bk1$qaDTp#(PL3~8%F0>*j5yd1n{kY(WAzTjeUiTL!2YL)b zu_#ku+$ULXZ29A*P)rHYGV-@_>L*T7o3vTrp$&oz0u{iElC4iR0T^US;WN*g6#o&t z@+1p&SnY5JaCU^swtU#L4KSmsP&31srC~}aLFX8`E`-J!D8{mjXyOCYMBoqG` z{Z&p7$06X9kus`jCnzT&eZK*@PLGp?VV&`=mlhumqput5Y7u$Vx)_XG^iP8W)Ge0=|!HVtSJ$d#woH zZ1(|dt%vJHM-`jteqcB|i=VF#2J-PMDayxjhE!h02 zzEz0N$B#pthGXTG1%0;!(|&dqnv53_)zo!YW2yt8#@wFPZKr+Us&a_|+SLIjZkei< zcVA4yV_PYj8ykn&d^P1pG6LwTZ(6LB)Np=Z5`N>{b$S0hTI^Gsr${UCl51EErp+O; z6#v`Uceo~7Y0zs7N&ZApQUKLY#VBV9>h~iEsz$w_;DodxdpL(Ji@4AgY(rAWKpZ?J zds-grFbg#$HrE*Xk$rH<{ZeSYx&Gd#(Z;b(AL0X$N7O+*9 zsVrjd%bW|twK{zWf_B8o8%Wf$nd+Atb7S(Inl|-Zzc!*mhamI;VBdGs3V&)Fp+pV~ z&H#B3Y?*K?qL>^w_|9y#s|~Hd+c^$#IzxBtRagQDc;wF^g&58U=*zLU_(@#iAfE=R zhA4fE9D}d_y%r1g#5N@9q7*{oMMML1R{0>pk-Rm7plT^GD|o%oawU-#w4KYkox{~9 zc-AH}z&6*T@2alOkie;Y9!-C6MK)p?OQn>;VJY!TwMl|Zxhj-eG#c24bX8!W$L;L(6;3gBT|CTc4)1~tJ~mq!_|?r{Tb`2ZzsEvd>Q50qU9 z>=0w^O}ai{Hx!84f`K_tS+Txwa7IuSOLO$R_}0EO3Lpe(<_(15Mzuk?h^{9IkL?XCQ`kO|d01-Kh*Pl~aV7uraWgmK8Z6~l*FwLTprZ^2+^BQk1HSXZ zjoqtmV2~ROM)tiEC}ei^*zrRH)1|a?6ZYt?_o1>p{crl$Gi!%g;_L|30S8~Z7yNeSZM`5)g%7|<91<^jW`+kvJKKy7D&C3`Eh*X>xRNp)3})U<98jFu z&%`*^patg3`=P0Kl8H0^kHD2ZKc1x^!LuKgvdvmQZepJ=;}s>iigbN7bLF6Apx8B5 zXO}f`!2iBD+K8jKORQ;qMF>_88A&jbjOz_>z<=qU^gQbHx6AietJA%2B#) zbU*7Xq57stg7c)D`m#|d1671f&^t48|0TC+Bs#~r9rrstdYq8EUB@uM0=FT&MesJ| z*Hf-X2-8+ybA@Z6Dp8fTX}X|EnyLlw-x@bPY7-e(e@ZaUNH*v;x0m=;AFGpIgXVz= zz3<^($XJVMyRaPa*i?P!1Vt<<>_AXY-eEi0OW3*U1ZVT=S{MG;S*Wi9zmrsHFydlX zZ9Ns=M2Q(fgfd}bw{7&j;7MVSQe!?eaoAQFtK6^ zH^?tL+>p)}x8J(&*_IszL5fq^L=0Sm3S>r-UpWp~HJ&IIbl{%z>4=!ql75 z%rRvv*N`I@3a=^VCARI23X@mm-gy~0f9%0%g`bqhx(3%>l?g#B&E z6)La$N~dZioXq+=VyOC@I^FNM5~nnS6Z4;xxUpoW?NKk2P?Ue+-e+VjSU?*y56Uy} z@u&vC#&=pNM6DK+J|gPLz_B785H{e5)Jm85?JN?Bc$W`U2KDH=ULg@e9wJ)iK$Mjw zcU3nRu^7nI60NQ2$q8~6PtPPDJ{T4Yl`uz>$gS7q74dVhg$mRl3Kdu_EjcwCGt*@w zG-{Au!Bsab=tn^vLw_y5uCSWDUV3ijkfx6KUKN$Vc z;0^d&P|0e=kxMAR9(?(8$(+C8^E{ z5220T?NTQPUHcF zAwnOTHzuv<9JXVA#%SP@Db2PHv|kKFxgW1h-&RQI+v?QVzMM|AJ}!`T#ENDt&#F9l z0W36!XgjqUA@k=BEnbtL+=~HM%;klHPpqks$|^b^>+4T-D1K`z~e{ z+6?moN<|6&9iin-7WkIv{FKxph*C0w+cK3M+5IBNL--cdx!=+boJ&f)mse}CJd?om z;shhEEV+-MEUOly_+`KCk&GYA@AO(a)=m@m_>OuViJ!2z-+ctgFF$-SmEW{mFM#f0 zSHk3EuZvm-gsdS3@JLI6pt7PMe*B=Cll89YYWdkuwWbLXi19bTs5A)e`G0JstKy*R zV^R4qwc~iGNS?^@{D2zc814NlH}$NICfJVP{D4``#?zY4NQDafnS#S1-Mu=xM?F4P7iRs-nE zZ*D2hfIPg+ThDkRMXD1vM_*Cb%o?vEwSH|XZ>|pl8Pz1oYEyuCHqbuEovcR+ewyzj z9U?h5NuDm0bsXO^4;m22)p%?bo+LhjuJ(X_H7{69x`vbw*@ed)grtWzNQ$P7>}K&v z@4Cfmv}&}Jmw_Ty^7`HOgK^Y;JG6&E$^pFO8v?|5S?qHDcQAY}a+>#yFWV*6&A$8RT<*^R1F|!~cG`iV0zu8jON*X?xHQNP$D?3x@ z?H)`!SJ8{@bHHi&YG=l}l%7Ly?ibd)n>AX4Abus%aIQx>w(YdWPUy@npgoJ-uy16* z(HiVK8TOIV-;I>m9ABp$=IGVr2yw{xG|mXnQWAR5(XOVttSy)3wi$Tz(5)Aer-nHw zkuX>88MMUBG|pQRIkdqcm3WnogyS>4%?Fi%Jl_u}BEyVfyqB|3iL!!dwLm|C19~p} zlHOFJ@8_w$>uBPjye7keYurl53j5!>K7cx+1G~XDeCBe%*o<>jO_O+^NF-1!2D`Kc z>3L`E-R_mH3O%cDCclL<14`!!_E;O@e~}av8oU<+4RP08H(;;q9mNnXDl0;T!4+=z z$P{a%@GU(Tu+*41{PYH28*yaA5dou>HnP+iV%&8ZieeOCgl@0L=sp8*?*2h=&HVUx z5KRx({+~%IAjlU9TrNlm>CqDJ9&Sq5u!C1uG;9{~SwbE8srvsgn%-GNkV8}Gvqw*O zn;`~B{LsK*j1+)HE7||ctBJCK{$Zht!s1z1J+Q02hGz4nU7)U3<+@L#vO_;5Cn2@P zT#6Klr;BwPl3&a4U*WS)@)dlQuR(JdSRfI0HJ-ph**_qk6ZG!WF|-O+#V#`h0`0#K zp@E_kNlfVWFFE9kYzT|KuurNd8bteEof4X=rBsluweNUjxn`0g7i=^<=Y|f()(NfBFFtmW21+s2xOf+xm*_@Ve+- zPxTa!NG8~~KFG)+bUSkH;i0_f>K}U&M-AobzkkMSjMwd3JkVx2NXeGj@d$Xo{oEey zLi}67r1t_ACh3;vp{$1)GO9=z#gt%fwHanj^SEn_o~RYpLXmCTPQPn&&>@y>1#n!eSSP*+05q{0&Tr-93Hc}DA}P|3ar>Cq z95h+O4|j^CB|SI$2G_fj=La5oO^yJ#d&~C z0h7;UAe8a}G{rf}^#IThXepV7-GcxA<(7S~vZ0$_{t-e0_4W{b_yip&?lcBF=Z!z2 zU(#?cHpek@O+n!r85LqVLyTfLg&0RFF5JtAvf=k7@AE*3XPq`<&b>}d#m%3OnIf$y z3iKt8i2vu}1uXyP)spYWoa$Zj3CTYLPK}E}~mu ztyWPcN&%F_ttll)jk}?N?P}WQOTwlFj|a+~0I}co7Sk$JjeW;AfTC`O^fyE~V?Lq; z)T}*N{U-+%v}l}}g7UOA|E=Blwjw~@IHb#a^;dwz*38w#-s0wBqQaA+=Nk$pX{s44 zqzlgddn;A67t)%83(~1mk_XL&@ej5=>`!rd=JO-xfq1j>Y8tzp2Zoz{M`v760FNFF zao-$5h>MNq;O$I#VWWz>aBFE{-)~hVA*8OmC}(z^blc4b!(zYlw+fonMY^gx`P-jQz?W%I*CF6V_4^2MQ_yvf zov`)TnGebcN#Sk9#3y_ww2xRaLASH`I#d-%Wk@UYC~JU2arcf(#HDd}r;;DooKbd_ zbm}#O7ONp%eID#A#K-Prnugt+Z--G_7qR^OjWoSY*y=e6jHlS8DZ45a;y z2#jj`{NTX2Z(@02{4oTG!{q8Dn^lD+ves#c*(zQWRW{AEG*}LrRA?$la_GUbpg-Lo zkF=WkE~PQqn+8?o#;W*YaukIAoj54tKDm_3w4`AbYAdRW1kuDR={&AS#noxY>=h6^ zqD-sq@*0q5Oh`>Sio~ImFbQ@djz(}tr&y0UBV}zCq8mZz;?7o6$|_Mcg;h61(n#Ke z58mmGAew%ZBun&yR8sW3!DN-1v7HW6_fF7?nBc(cnjF%T6Qt`9O<%WEN9n9u_5l@q z4~G5pY5T^;o&U;ofr*}qkOu$|C=Xp!Z@0d$ehb9UZFzG(vPJ3L=o#d|C70l6SBUU~ zfLH)PXWa;A<6Vit$9>?n(zZwIasBt|e*^U778$A6-gKF0R>Ur=Q8=jwc^@C;QYdtK zt?&@l8j!D_BlIXM9AQr=)IChLlg5f>_y_!SVHJ6ZvFQ<|(u7_a@m#+*s?GzfeO_4I z?xYjbhqgqpoqPi(c4x_wO*3SYk?bENoJsj8_qC7-qZ@*YW{6Oj;N4uhx->^r!Z>#| z9SJpR=~QWa0eIu6!kgdkta*)44D?2lE{f)vSa7eH*qT`k;>mdT!IFtB121~c6r=yd zYXZ{mlo}VLzz7?oqrhta!WK{A2@O8xj!xvpxZT#w4>|E%hMm1F6|++C2L}45{Z{GB z2aH;Sn2IoHT?UqfErp~ZB!*;6o#;8}{&2-|nV#`fT5}Sl>GXbh?+4)CZA`YA^u2Hc zzcQQjaK|S}P7ox2(0WI3lEUnz_9BhosC@Mo>GMt45u6v(E2CJI>bbq^v&dl+$Z|JX zHvklWnH>$rJtjVXOnt0UWNwxT6A|T&^%&z?qs|Q!6Z~M$h37Nl4DATPUAtM9bh?I) z!b3~2)J0;mo`ioDx!RWjyO&5sbx^WG^2!%y0dY^>m5}$eaDmyqFGb?`Nllm(hcLEe zyxJtzUiYvaQ6^|bK=7FhUVivf{=aE+f}w5RCBXA@ygO5SY~(Peu3H`wA@ao;!1Vpe z&1kydpyTa)HWKE*n?@x^Ua6;l4#(XqMJI6GDFww#(9I8SHzB^~ha! z^=lk;7*maARzxB1qk=#gB&hZWL_AJajq{j;4u3rD&{VZ~!XOKv_-c|)#4$oW-BF0L z@~?N%f};gruD%`58kD!3fhJ-^^RIg|C3^XYhy&^@mq+OyhjR0c6)9{yQ!5&USk?zo z_DU6#VFDw554|=Dl`Xdl{NOP;T?c!2vS}IFLf@nbKMnL_KaE5OxEsP)6HJIVY;YPE z3UWcY^x4(!{9!ds;8>SJdl4k2zWyN9qbrc|uMsqAuMS8SP^>h`5<14Y9u3CFkR)D> zC@YVAV{(ZP0H1C=kd7`0?JyZF3I`SmTTR55Dyx_>aTk&D0osR9>q_b^X-swQ9#92J zHOPkt6z#wtBCumnhXYlR@;rqE`G*8J-+uO*AqY#b(&e0AW^s!F1GUIrJXy_ry!of}_ zs<_Sw6UX8R=Fab!@iSpmNB$MOR~oekJ#VU>TE#cr zHkIM(n@X`Y-#+}rMQ@Q#yK0Wmp>!y9vC7xislL7KZ`)li{H z)lk82E@G^WYy>FCV#Ytg=ntkA5qK*3{CE4yWq3j~; zI#is*R`Z|J{1|CcVmvTF<`O7OJ&>FRyx*+VY(;@1Ujx{1CmGYRU^=(^1}?E>`MpT8 z`SuE)Ch^w@q6p|A1X5Boy$AyFzIf1_aKytp?Z3_td@)%kOy-6r2Nzb$*WBM=-2b`2 zSd$T#iwSUWhL<@|ij2hSLP5(n7}?VET4N!P{>J;jQ1Y!%O_YB^m}Dt9B+0HUS@v%ljG>UkuE=j z7SNn7qg5Y_-jb~GX2#Q*7g7vVqG?rJ9#vZKUfgyvO^B+GfSC=zr|H(#LkZS+B|i>2 zng+wkDSAqRfp1?Lga|PE9DXQhL&Zb?!E*Id82S;w;0J2&`ZE`QcD3Lb8cktdeNBM0 z@HWB~etcK@s2oF}N8mO_aXCSe!;u#}3m}ehQhLBl9=_ar`%>O?tA&4pYV#qKUl7dd5!fAukQRN_jd_YyNzcHpDw1LnT<<6;gjr*yKAjwVcZFE_j66a5 zmxI4~4BToAv49SIOvd`YS)2Y%-H@c{TTRBle4Uw{tO?YH+;t1YHfAb>Q1AHQkBT7` zmMRdsz(g1zv63WW%7uw@o{rb}%f?|;F@Dh}yl0#Q^z9Q@aSk z)_rVhB`re%PM_KaB|6OY*P1R8#d=Dc%Taz*H7G~Dw5E)rS3Xq^B!sd_Q~BG<;09J) zH=c+HgJw=rfA z0YY}D=)wy|3Jj*1ru>x&+qMZCVl^oWy`JeR$s6??)t}`uj?_b-R0!s;Z_;!=a*eX{ zrso>nIz-Z~-ED~uT*#z`hL06yVei6Jji;)wr?L}YL?v_5+Mpcd#t)Vi1Ld^oy{U$K z->iy(l2ys`E1n49jmc=BgyHHCrx8)JMk1k8BtGi!9PM9VQN+lK*#QeNyuAVm zev?mkozeUdFyW{Q&SmC^&HY8L^2saW2)eZS0;}2AtG%eItuG+Z6b;rGk5CeyT8UIZ zY$CF+*PJ5{6sTb&LPJ#QS_oz8*w|!6;QAYUp|W8nQ1ETn4O?nHfGd1LMuE8iWeB>K z!=i;hn7@XmZeT3>EhHx(?8IJQrLHSm@q-y4zVs@>fYRg1Qh5Rq-3gCRGL5cF=rQ|| zP&0ql&P20DY2(p6`=k44MpLU3J18$i7-6xJnu7?Qc8)_adc&H7XYz`9gP(*(szDGlDHV zO%@;y5{Apv4pT~BN{ZC>35lad1EWfJ;!HS+R;T%LTQt6eeJO!eOl6Vn(M+{wr@h{zP?q}7c1A*fVbq;Q z!;*#js`inxT+Q@9;M;TG%|ngh<+(p6bM3Lq!H<8260CgjKxdG6{+_R?pS}(c)Z01 zaH6`qZlV1%i<3l`jGjYHGohn2FGJzsv-pv}T_PdQEq4aCY}LC6X4YLo56lv>isOFr zRKgw=*N<=R`H6gyQ8=+?_^;b6KD*U|eP^I0cqRHF%$S(aMeX6IfGCv&sS;N@iE}+eF;)&o_9RXJ6K}j8Nj7XIfvfaBUnE zIk$qgSG31-GzhNEWC6yjc2*o6?AAQ82Fpot&(GBUrNg#g2g!O!-ykdW^WYrE{G+{H zGI5z@;JDW9TjTVnkp$F>Yv$-WQx@;g|L__cB`&BP1RZWJp}X_>v>`Icj!HJuF=*Fa zILTEfZ=xOnw3f>C^14O*X^0`}4~cRD)RuB~u&33A^wxOD+_C5$IE4yERZi1CNc=ZXPFxXe0EeJN@uB&ZWtDwMDEvX7 z1i0W{tL$M$IY=*w{E0J?O@P$=mDN%-o!-7bA1X>?0Mn ziT;jpa-*Z`S;t*lVE(OYr<>8>X>SJJwt$9soJ5WewzPQzbgyP{FJbc)q-v!sPqqv7 z&20Kaz<3bjT~6{_OrfP_$1#2{R9E!pv~2x1IRw2Vxod0T&Yz;s_$a}Y_rvSS6*$de zypS&zah(8KFGuP6R=Hm+PARgGP%tV)ekI0BgkPy^4y=?xkQ z=mUdWd!%iw?Im1&+JDn)aN&fAY4R;#9N(r<>2ufnO2pi6j{DYS$?a1rbwvo`@2{yP zhR=F!A1%7lc`ZV&8v!(2H3YF!e8bF+p0QO$Mr#2dS*wIpGuFR6VHjzAZHocI;(z?Q zT7L0>`PWZ3vK)g|Mt%ew#wF#9w9Y*;IbH=rvpzNgg7hjk#cfTt4#F29>Ud=L0BMh&>9|Y;Df9 zt4^^&VvleSo7^|aYwGf^*wOO}lwP8M2;F`}^x$dewD*(V3u4+;R-7OGlg{)#e*a+KzS}u# zLA-OAgLU42iJkiFS=iFLaj{7u9*#^N`{-pd+L1jdXGClBo5LBI@_sm#uzd|VEh7p> zMK4bPa|7UB*nDvA;6n;P;C#y?Aa&TYw%uZ$Q-f=QsUom1#>HG}(ywC7sQ4}QxzPID zCL|`5C2T*EK088RkpMa=mqJRPXM!f^Om49JSr^D7n-dkwO9pTsLfnDGLRoH{`}2iS zv2U>s+0D#6teZKA3(04##u%zWjyrg-9N7q~Z>TEy5;J+v#1P~M3z!l#LJ*@7W{zdy zjqzCbn;hnZ$E1ua_GSuU=bax;2y;-ROa|*_oIo2#7f4+A6P43$AG-uk0kedkba;Uq zI;vQ@^{T@`HBNy+F5uTI1XbA8{Z*y!i#S8UrgS_~T$r8#1a#A+NvjaVV_T5D5b1KKzI0GYaF zpVX2AjpuLoKtm7e!n(Ztf`2RHf4)bHxG%IHVJQSjRs2gKd;+(+cQSShD-f<3vL6JL zyM#o4WpQ+|4HHiFu%}qtmkAp1gbFuiTn{|j+*c$DEi@T;vthXu`T^a!3( zX>ioopCSg;H`K}|Uj8C48{~$Sksj-zC=M)Gd56#`M2y~a83kmfJLiio3HITTg)?Ln zTvq1jj4MV6wR;2!s}r{Nzz9V1?)*)%@ytssEwD;m=80J(w#iA2js&JDp_o zy167)64ZQPUy>vss8}BiqH1(xFPouy1Oq^QLJ{ymfIcNL{JfAr;{jm2e=WpxbV+`8 zl4%%!#;TIii*LE!;KSjGYxttK%i1X$MUHeuJLT1*UWtrAa`(a=ad`HND|@pSR* z7{{LB!@5Bnf?fTJ&^lrNKo7DzaF zX<9O|b;^u%fi?MTaolpkcCiu%_H)Sru*|29R~bYb%%Zit(LNwdYjkn|g}`I*O;_RRHl!)d2Cs z4AJ`%&r|$eG}M5Iwv@NDiEb&vLtC@(v6*v4${EtKhH2@q-T}u|n8qk3df2G@l+&^s%62X1mj^JaAX~^R1hm&<6Q z9z?35mm4H<4m~@D;ERCDqbQsPt+UB$dPT1W zh5mO!L2^&6Jo_UgxUETyxVmz*?F zUm3LdPnf2Q>Ip@XaU8&lAnx>)<3~t)KNHOzF0U@qu@O#Alg7eBsGDpRKZF`<1+=89 za75$6KF#+sNwY>Mv3z-dJ?*dErjI)2y@7EK?C@odI8jTy?ymff{O#& zfnibFu1Z9^(ps>DL+MZ8qvX>KD#fFid|Koff*%h<{j-p$HvK0=TH^iu6Ge z{)`IIAJ+r$tRGEHvOtYo1!1ceJw-KuQl(Cf{_TkWf3}q;vg(nMPqfBOwRBi8cNqp9 zTm6TGMynHv8l5Lvj;$F}Vo=Z|A_u%${k%UtKAAUmJOMH=-azfaXL4fOt8Ytnws*=- z46jjlhbyVsp;R;n_@52g%uzth$8ke z0)R+X(7SFp=f-NCqve+HI+fMxvMyk&FBE2(p`3?0tq+=1dpIc|US2v0S+N8EQc*vH zq~+k_t{{A87KQ|1E+T@PBAp6Ogd83+SI7V&TlPMQFSJ)oKn-g|9Ewkb1Av~9%a;P} zg-0If>~+cu0FrJwB9z)R@dBfU87N#w%%bvNxpxDvUWX5R$v}9Ue`LrOyVSY{+`!`c zmlXl{LAS4q8p;g&rdRbV^oQW)hSY0l3r<@koqmvz)q6|ImT1YnLovYb%!=4OQI_pJ z7`EKvEwk$zg~oi0y*3Nt(y8WA=%GM{K{7m@^%5d55NYBmE}exhZ09Sa03$sY#*`CX zSmo_UnNmfxn+tubUp-8Gv9wSbtwA1CsZoq}w*nz@+TVg-U?-mf^foz_u2upf z!HS*XYZ!NjrEo`v^U}h|aTw#t?AO#=QEty;5vJ9}eK0hJmCc)?g2=&_bw<=Cy$a}D zlWrumlE!u%E-Yn8j--(Dyf{cR${QCgPP>8sU`5}=NEZw6;(_;4`ch_C^hjOv90ldd z&Ud(LvUN>{WXlS(E-=4Kgl}Dj@Wez0a)G3i5euB8$oe;g%ULj;7+%US0@X)Rczpqy zj87Kt&i7=NF#;+b(4ACpvmN?iA?W)OW|=5t6*m#iJ6UfgaX{65v`A`im@HNqT$OEB z{kdKi4fVv*HA^EVqS@ooINJ&A0P#QotSyWggmAQ;5jA(bsgB|xCNQpJ)NvnKG%fvF zrBJu7)JwY5RI5e-7JOH+((469e9^V`e)h#5Z0v^R<`vT9dNYN>`Xx)O3Vsd+3jVkL zu5IE%#MNR&1xqCzkwBg7)j0Y*AX%>rFKM{?N5(zKU;-bSq2L6|P%)Fkl%VCS)C|lf zh|(A7HFwc8*h_D8aOYN%wLs5OVJowd;xahb_kE;QmpkJMYBBmA|u_6>+t;)Bl~S z*AzA>#?-Y;DmKM3GZ{M}!L2_gb9zE0>vj$*@E*rY3gB(i5#tkP5;Q@%Aypp;DF|b# zi+b+28UazMRHoM4=j5png<(CejB%Y$gS6Q;;v?iyJyed(l}lPVkOHHU8}pwOPcba3 z5b~Y!NJp3*=8e<|WNZ7DiEF{Q>OcZgx7q3d>@oSGtl5k%O#0#zUTmjPD1%cOG#HBm z@dm%#uB6&sOcPfqPsJc7eCS(=*9YTMgEg&L9r8&7E0yRtv1{}~WW%P+(2$Z-A8O(p z$e<6X-Eu@GS%zCsTpF&T5i=nH=sTn}+x0_wiaIyY0fYAX(xl+`C_XpRf+ri(%$?nH z87e;Oe`ATGBIP`j$E(GhA7v7bZYE00wVI%cw=O7{D@KuOE)_*Iy}wR%;5kaBnZ^6EZXtJ2`!;P&51!rdrGR$dU)pw zQ9_3-x;LHu_|JjF_YxMHHQ8|G<-n7N?dy{;d$_lQ<5buIgxeaCkD#;_E+&dBs&QWs zB?`*zIxW5?JZuod(jTwclpWoQkXV1XNk6(|9<^N*Fpi$t|CwB=Zx%|zkCz;d@zh(( z(D?L^te(*3$_#^MZ44|Z4DEP3)WUoq%2z~-NFEy}y3ti1+Wd1XoTo|^4(mts2mha~ zz>gADtGHZRI28`>FlMZzc?}9?-UQZ~BRJb~NDSS!@wFsnbc!+_O?JC6)AZ)L$82dM zjsE$@8;Y#>a&A0RB9DTQQ--bdb@2(VnI$msCS(^?U9bB~@Bar`vl<*sXp!M*=dN#( zKQ)FxZ#RUom=imhv?u)FC?2m_=WG&GqAxR?lCLfAn%Y0yfITEdmk{b0Wp7_*%H!8p zPxhgm5i*Gr0Y#%wJ|OiR62D1MP64`e_Nfi31WN%XjARpYgr9FO$)8S78SM)}CPdyhd0#1!ALZs@ zZ9dK$TM*^p8qPPAlevU#XcT%HQg}kDfp0Tru89pE?ipi=Jx9$mNmsd;?;K5}!HxU2 z1+?bRO&KUq@;7r@@QaIEc=-ipz44d){?M?_AuB|z@sxg!G@Q?;MT{YIQRpzDnQa;| zb1qq@EdCxYLVaVP+^TDic5j6i9rQTzZI_4Fpu~y^!$i!|631|i3mD)Am211n>rX+Z zLdJo&%zWM*0cY`HPi5gQg(sGnd-^C#;mb$k(3>qmdDTG)VxE?aj;zx23p3o&;~R;vP+m$ z0OP|s{X*AA@GfJC>$2xmjX$aC$$$NAbf(C_heX;^RKM0t69E(dffW$94u>l6ZaSYR zz;FDZ(kA=$>MBOB%dlf6$)u4K5A^`FKuf>0lqKUOL!p~>6FHTB-4>;YPO97{)j}|6 zT0o(-95q28?&D81r5EC}Vj0!cinRr{bYcfl@%8wIHLiv@FyW|x*RiCapc5!kioSP+ z_mDMUq2q{vcUUs8K#It+{8kmhC!zQ#fnU_(&8w;Lg#LE4m>dF@t+z`fOZ0IQ;{w1x zDDFo|PsStnmp<_hB~ysYds;sZ3G;M&QcSQp(UVSbP=uK;uBL6Sd*p#`DCdh?5BAWf z@}~E|62G~j8x77aTq6|EMm<4R5hxK3h&famSq*F#NW;5Q?Q0}dt}-fnIET<8eG_1o z>;efuCIj*QVAO!B-o)GV$%kD9e%0}JkAo;4l`y_fYJxI0YOKJ{Nd^Mzdc?|Uj|w`1w4t+q zPV{^-ngSzzv+4AdlBB)bO%|kli<nBT8J8l41j&QoHY z72N87S=66|u)p6%XMIT_XtaIrP%EcGb=r%hUbGMG{QVA43Boc(&MR}(Nf-15p1%mp=ZHyF1F3;y{$T654hKXP8aXmH z_i)@7^}u=yYy^$3(+D2tBl;!FWeNG$61>_c+)2xb(|IO>AKJSdbr?4NHGm|L*2aD> zwuDz>N@$I;p<=!>Eovi&5$|;hOtLFKxPX3k*>l>2Tb8#U1uubl9Kpo)%v_pC@rGG`fMIjulxSoBxuGYXa0txtTIK{6$_ZL0-BcC%aB5l@; z@-Q3DgKuV;Oxa83Cw=^n1D?}IYFrRJ$yG2gRj z`l~2>dt~N=pnCtzAhXfn65jYz89gOlNTAHRR9q{h{smd&CEu8k*PHbdN-}XFHU~Ab zhWqu0MX!|RKN~B5!OlfZLdMPqkYyZ7i@`7&S(=$BMq{NXn)rB~#<#jAgUMb5emL7P zt{a*&i!p5V7Xgn-x6oQN5|1(~e`BU!#Y4syBHAq5QWZN-vAJ|InXkWO2J)|iQD}CsAk!d$up?sBt(@p{IuePEH)X);+hhYKCFQ8Jy|a@^%0)go{j|H{ldNt zS0tgNo?^oyNtUUIu6jxJCmN`7b%WMVQw>F6=5l4ZPnDOBheo4ul3af7DW!g@&e@1!{Ba;J|719(9n9_*UZnf-#FKVjURt z?(!d+TFWKe|HQ$eV?AzTuUB20x>|6I{64^O&@bK+{@>KO`=X?6Dls8g3u@#^=iLRP3$>9GPS1u7|i}BS{xa;6JJCK0Z)n0B%UD74d{Ca@T?@6Vt;v^YR3BbnWp`8kc0^=!|+j1$VVJ$P_=p9Y3?J~F!Y=KuW z)B!*3YwmO!UeQYnUcrD7@I!e2pm_OPmm)N=V*vhfKt30ytUHgP6Uop8O*pw$?B6mE z`kY34l(2ZSQYe|ox33Im+4kH_Ma;Rlwp|FD`8Kq6J^Ej+V^x@~BUU;fUf9c@N;?r9 zEB{V^JIjDoPlEnj-Tk^%Gew(-*!J5K6YIW0yTUzO@L$#l%qQwd&)<-B)@=AwhBjAU zOEkmTJ(Jlzli7S(?)FCAY?y|-VCyH=9g}G;pP^?S0VGqgV%R}?AK4pcYJ>XT6ffm3 z+k-38AJfnfq3B;CMs)}T0>>{>@Z!l$Yf6UJ-1BExDNt6P=>+uyknq}8lAfS>E&xPc zK%26>JlT0RdgrFhSz}otZ z$1Uc`=RXbzt@xsOr6oOZMFeYc^T^K~r3)9y$vsk+>BUz!14ixz50bq#qv?}d83$m> zRs%}n4iC^8En6F5e$N9j_x#N}_M;%R25wv)RZqZQ$dP~_8N}8NHc2J5`VR1LJAhSm z+iuM_O%vz&H@}$1-a7M3E*!Y>{r<{wbzbUI$$ROD>!Z+dl4%Km`Gw9dK+hAnCy(0b zeRuMoL${kgYys^4_V-T67Qv9I`V_jikr2P+o1C-f-YF|aM?3r7BSEo}{rm$m6+Mr8 z;Ux8oKtmwJ9qa-srRB|p5A2VS6y!`5O?2BvqOG|u=C+i~DDS)A!#W^C))IRnS|*IE z?ic&n`b{&OGBEnZS=H~;aQtjX^m$2Rxi=$;yzr{Jy;?*)1&Pm@8WoM~jp#&;a)+5^ zi@M!)N-NdF40Bplk~-sO>6n#E96v~UF>YDkf-$Hd__=I`75Kk{Mig8!Ua11_?+eF9 z=ypxE#j4&Ra1_oBDai%Hl0PPg48{kI)tHgs<=Do`O4+0c?Ks)F89>1vcTNpyJ|S-n zsZs`n0i^BLB7zKmr!$I(hm* z@+o0L!(^0jP5=s%l21Z*%^{~yiC*;_K=1fDNwX<;ZaD|~&OoKxIn5ckww*;54@phV zz?Mq?Y9cE*?2TCt6U%Es*?Qq2s1Iqclb5`-$G|N z;8J?aEb}AV@seu$7XXD;nZDIvu==z@)PP}*N!JG!5{Ci@;xmQ?w15!(hG}q$ zC7J|wA@B#3&E5qAwATu>l|MpLA_hCU8PI*0XpG16md%%n`{pvIoUQHZlG)N=C=+zc zq5W3Mu-bJo2XsE7<*Mr;^e1(W#bE75}D4u+_T&|FhHj$?g!LdyOip(AcX^iP||9m%aILNoA1Bi(f(AdBBAAYQW3uz^Uykb z43)C+RG{fxepymTxS<^l4h({Pm%o;@cAOR70mCTE;q8Bvl?PDmEkDVK~ zgL-S;lT{f0hoMB=a@7zMw5Xdl8E^wYq3o1{Y8c#v06oynm$jKkXBb4>o_{7g84+$< zDxeSnrI>6oz|OgW9&5nFTa`k2XL32PR3?1*cD)IHqFr0c^+F+O{EWxm#-iTESwor- z0e=kN%M5y_W9`M0CL=DFc8fKb{>3<+EI?eI${UW7kmI-v-X74f>gB-oU!X628FvV~ z^d1)t@w8iF(3n4Ltf>=@h#AUOa-6g_=N<=YyFrNtG+-GT>(Pr5)N6cr;$nXlFJ)}4 zNS1^F$m&j9{vgv#Gy6ff>O@kup`*~g1w`ZzXla1Pkf#@}ivQv0rP6VpTMQ;gZ+Cd1Of*#>K+vjnyP zPn>N0mFuL4((8#BJXtg_gP>pq%ugo7a?>=%s_#*8+oj8)FEJH=UMUfWF7xwUUX*|+ zn`bK0%#W*xX$tD8$#Fv_klRmlq%+()JZ$-FG~3@+EpgQORZ8DF%kNN*Wu!S%#F21m zdX)PwR^W$|&HZEbxPm2(4C*BYHKhNh9*;x8ZapLHP>Fsf!yQ`cq6}Hk(H9U|wsfR% z79F|I6MLV6Ba`6{h7-hj6!KN4R`xgr?u9Je}7zw3lIi|-^gLM;sD;5;P z`GY$kHp%DfCaLkMliBk`e=S^LtRE?OowpN;Q6p!oM|AQQ_6&mHH@-h$huV&%s5rMT zR0wdbJ!R&!taGAi?pT+Iku^HOaUeW91P*Mg?fy|l z6dZR~g&1^W%W!6Njv=dN!&9&zrS7L528|FrkZr?We4wB{M_2r5QwqwXf&zhh3Ck2p zSux&O1vjmm5>vOZ6GLp!fZhF7(w5l(m{NSc;G<;nYRKz%-fAfS*o?14B z*`iiUCQNTaYY~fZ)CIBOcNg6fl3`p&(~zA6+ui|Wp#7+`@g5CpF%tx}b76|W5i|x; zWErUZ&f^d}a$B6mF&wCol5V0X!^}hy6y4t4b9m}q>pov$6b;{|41A?vbsz!MSS_G4 zW+AaCjS{Ad8XKkIMceVONM~u3b8T~yfjz7Gt&hi)XatdA#RUZOHWij=0>CzF#d@v ztnoLOb^2nmjuOZI#fM_wb*)FfFXZJYdzr@S4Uz0plnUu=h`Gx$UEq55#}|o>iXQ_q zQ8uxIkqfa(qi-5PY6BW&fY6_@ zLkEkw8l5FK^`BrwD4GlbR*@wEi3-gg*W-JfGvFu5x&4y7PJ)AF;lK%5zztzU(HA;G zf(m5RNMUMmb8N{xK*){4YmRdDzw6~bh@_%)r(p9*C-v7JDT~^&;yuHX4>b;DuGA$R z)nr=rYDL1V1wk7W-YreIEy<;gX#8+zrKRWz0<)J6%U}k>C*VZx&ut?I{E;+R%H>j_ zVP{G}54=p^?9F;GTnvr4%rx)p4Nx znQX;ot%bE91>Mk2f`eqhm;aeS=@HN5B(w^(qfXK<>y;UW7zzy-N(AdKZk~5U82c~k zJ68rp=}|*l@+5znfMF1foCUrkq2ZEUH!FTWn0=KfW3Tc}KoRFxj(M&+urWOl$Yn~D z$XtcglXbx+l1)*RcW^#S$PJ7dtwhq6F=aiQ{Ga^s+%^%j!JiZwJ0Z$N90RUJT7WaaX$>Ht90T>t+gC3ykX~{pC0K|sG`lc2^cpRBU)j$u8;?Y>0THTA_D=E7`546)9Z%!?{sx<$E$8|8Du#cdHzb;K6#<(ATZT0x zH%AfZIj&_QMFvjenu8FGW(*%vK!QCs-QBY^Q?}ycMvVJ%29m_afz-qg8DsLaYNQkS zp~|MP%pJAyHI|yg{Id1!^JO0eE)xzaM)l2u*Y~qCrH`?s-_;M{=T%C<4YL zEB_8`g1B?FOo@@Y`0uK8b6lRfe=l0z_)X--*1Mr1F`#c9L_K%=S@pz}PLKp3jknNu z9Ss!KDT`^?2T}kMkfJWH8n{;UQfa-vowJq|C{K?|%+x-AtQHWgY$F^-1N}GvJNJ8s z8vW>Kiv7YvRoK7EO&z}$6%)~NOYIgpHXrQz9lscF3*^9$=GDVGltki2@C83AKAwfG za;gc19l^b^c_z;L#W*G~%V!`6N--yL*B$r^MgrpR@5Os}s%m(9*q!k1R5*mkahTAG z5X#zizZV&=j5_I|TRtX1x0MWm2U=)GE9zC4406Yv?)n-`<=rz&s17W5xUlfs6Yj_@)mvWj9|$ zI98FwZ`P5`E6-Zs!MKD0Y5-vWDg$|*qp3xtX(N_H>MH|=B_kysLN>f^=Pw8wQ^CVt zRN-XMZPoQ`sNT@=or_abkfr_@-wg!cZ;A{92z zI=IV8ZHw9NxyAgf+jPJ}MzXRj%_N-!fi14?YhkYmoY`ntx1Gw0V?FBKl3b_T7G7kv zofTmJVIm7R4oIKJtNNl0Fiak5zI_{;0YX-Rz%{?xQ`?R~DIHlQJkiNMkNqtD~0PS_|!Gkb!M6nwPE7_W>w zd7}z6S%%1U%@zQ&pc+GY+l*3a>1ldn|Jwj}D?q>_TI%V_?GZZ~^B7u-!%dLCpkQkd z)POnL(oYh<*Z6$UGpeKHTdrQ|59Wfl0xf}4G^!~{R+z*L0wQo#VkpN!iGaRIO^Q$- z?H`N{V{B&s=QS`ZS(Qph4}MYr5f_hNCGMmJ>wbJ|qHiM=?%D6*UM=IG5xL*Czve!? z@XPSy^L6nf&ts_AW6)z|`-PvNtwK*2i=d4Epm+;!l=Ps)Q=kqzcOjvBdX@?k_G!Hk z3;C-`PY22wj_hM%Ao&#=ua=1$(1k(~aaB)3L<#Q^5eo78#Cg!AD69vJwB@lD{84{MFsm+I1{BiU0;Z+t0#FuG3val47WIl&KyC%P zGaXytiddgRx8ua7zIWAqkglCy=jMNkcPY}X{0S@+{PBleTTJ*t5a`g7!3E&*Q`UkC z+JBc_-Fu0UG^>faC~h~~>(^T`Wlf|~Y=D}X-7>i$?ij%aoXh*5h%FFz{*nqnMFV8w z;Rgl{y#`8^eap5-_t$OZm0l4a(t6Bdxh0--8^IRFqymf6*z?D}t5OmMDZ|+9FP45N z!QW!ebg#2#9#q&pp-ZSwk%?!ltm9hG;2^@Ue5<2ZO2vrwAn<959c-9U=HkxHaPY+^ zq(8XTpLo|LRqGcCPj>5|)@~jT-iS~We(^ou96^l480S2!+W$H8o>qae0I$syz^2Wk z&oMPe+a}dtp-!Yq%E$GU|MPO2gb#8+WI0t}q9Yez4Mz#fYN+sO2cs3Pe!-}~PbP59 zi_MZ(SliHW4^-V7lF2Od%z|z@sX#QPZPXNX(F3gBs#2gWm%W64=e003Us`P3y(lYF)V`!+72NPbE?J3f%0F`ic3of=#y;ZNwy*vC~ws>!EX&W zn84blt-?{dAVPH%N()mMca_a?F&m^Gd60iIIz;&aks3Z(@MBhGV+iO%ZEy@|kWqEB z6k-SSa?MRf4K9q24IK>G@W^BvzA;HO^V1|Y9z|EuA!-oC*)3A#{PIAQh{*`^0d5O^ zR%*jMHC#LG;5C&*)IqvmBX4@iGkf!()l&}IwyrXkUu~tT)$R;ixjsT8m%I@|!b2A^ z;(8C-Aos`2eH*-b_rA6@AORAEJOddgm$0K$C}WcJ3kl7>FvLwq8eQ)vTsB}HiHsp8 z3<{HCB4|Nx_&a{ced!lv150kam@?OMWgs{5O@F-op`*0>zwu4DZ7(V(;!D zu?V%*yp&0r?O{U|10^&j93-}&+LuHqnCV-tw_O9@0X8!c0p~hhP&=REZfGvo;6MxB za;)0;2GSE>Q-$$z(&E&VUj{e6j1YMSnwp90^5o5a!}W5$Dc%(noGOy*-qB9FE4YdR zQVWUhFMtSJgcIrc?@CVUjfu=8*hz**Let7O_}01w%kF~Wd(@bHBOB zeor9D%ZnZgL|==hFwD}lI+|(9X2>ci^U8e=#ZsG$$c;?3uzJID&*|1dD>@ik(2=`o3QCMNus#sNa-q8XL%vLGfQ4q05pcEtPAD6*b`z!anxdHqKjS) z#=m?JTS}_zaiBdcpsXw(!k>Se@5R2?a6oRNh;Wd)(fQTnp`oyEI)#m^rGi;LRiEW60CgZ8{fNug)5qOT-x}<$- zeKo94x(XuDCJi?sSg_S|WGZs{MyQ|*F*xJG_$~a;#)4N5`qx5>uQSh{T1Ntne`CG! zfHoF{6vQTvnR;NU=;JdMD`fYzC>UMY!^B@gvq?UO28W3wqnr&ffk!E#f$F%+up(H) z+{lL0I)N7!fFG68G-6{hsfChpBpbGV4Fuu?ssBrJCKp{&VY{Ta&Xp&5Hw-k^W%WV! z#Ot;-ATaxh?${m8kIp)uFO%_`mU-qvl2C|)yK%=;5;b>3jlRX~EPdscK(8onHe?%U zeQUnI%7o>R<3A{rh=L|$`zH|aIiRD+cX3-z*_;R3pIt z-8ZFC>hsCQw`_me&s6gETYyPlQHo zjk=CEqf~)d%3En^BhH&e&P&dJC9UHd!#qYw8Eu;iM1HR(i^nU6dMl72j6!ddBFE>z z!y$(MVt<+xfI@|b5u!sj_`Iri?NIYU#xuz-v!Y84{s|TXXf3bFe|-@=$V|pHZcE)r04e!r8H1#b3B`=8 z@2Khl=a<`?s~Ha2SW&ujd9?Clc9XE-1B*kVzk^K!fPa13*!=T1ow&s{vWK$8d!h6I zLjA3>C)jR))zhAV^bf7Sf4tVrXpQAQY|F~v*0C<-K3EQ|QvpAx6_~azhH!W_93EP( z#BC%xEq(*`FUdmB0F}V7X&l^anKc%oTBdEnjtSHt19GYhBL|S{;NwSv~`LNdZh@>i} zU`7@Q#mV)4{KpODGUHxCc4@=lyG|rL0Ldif5BG>>`?!&o8V=+$R$mJPgIFQ^6bH5b zCP+LQ!PjS!7-gX6~$GEY}^y9BIFN)t~!hx{G|U(N93>b?X;gJY6v$jmgnr2yosC;Je zJb>B#F~?OX2#ei|O0NCp2nhD6Vd$AZ`)jzw?Tmbsq;B8id+bJcc4W#_RyK?b?R10l z&>`86V!TQ2y6I*tUP8JP+i{K>e(E~LH$ERB0w@nd?UwL%^yPXG`!p0%PogO3^K(I4 z{}T(NUG3dp=jxBmniBJ!=5e{I0OsaT=zD#{E8}gW>SLLisec{MSzfk_p~)s!K8-eO z(Y%73&hIzH3X`rVr71s^V@G{UdC+b^hAI|ijyoo`AREAos%Ca+jxtetyx7F|OXh=W z9!@$gYwY!#Vw{D^?053tCskOpIzq@agQhOVb*X@F{ObUziXul}(M)hfGDf8}2!8~J zqIR?C9gg?~#Th^j9M>OhN}GLr{-7rrDM68O3H&P$9NU(0DmPO8&uEN}8Wd*AR;fdF zCJYyWt|A4#An6#s8 zRW0P;ppaleY}my3PvTGk;mrmHFdjFTxEfsmQHJ_tmYBY5C6X85fd?+}O=b*ItXEA8 zwKNaKDJx32twgq2>%M-XDFhA7OQMt%jgRLX^B)v(+ugE`nmX# zVG3(F+mDF{L-*F-!Sv*NHYm5qrMWg}KYEG7L{C4Chjv(`T@bF$OTuF|_ThmkYJ`ui z=v->Ao=PCe(Vmi-n9%i4`q~w99nk?ZqvB?Wu+?Xrwxmwu!4wgGMLD;e1!`urhQ*3! zxyHO<1SH-lH~kSF<(@cGl(%@^M<6I4EM zK*odtq@O|Neu4HfQtknJQk&uX^dwOmOjLYTu#t&$?gvws5dWs{F4XDzrvXR(FX8%& z;P8+74IO5_-vY^U-tUMqJ`cg--8euC$(q5Ajz^v(^ugh-h$#yX$5DfH{kj~kP5LIR z^Pt>pLnp`tYX*=|&pG}H87#0ofLWfTo1LVsAcF-1VM;b2QQ0)T$a4F7RaKu8Yaxni z>CjQ_6IgWPE<4A(ycK2rz5{@(RTF+!lWpVo%lJ$bU{o$jLU25(xTU#5sLrBsTFc;~ zc`P6)({Xh`s$?LmC^OYX*tH74kpXKs<(!+rLi11B8%i4NJ$bmqqfhEi`D>gk5Mqa6 zB5<2p3OsStfCNS3j+1^@GwW>FRcD~thY=4{^q&J8JI?Qk9EitOYgT~5L4}UwHGYghd_m%L<-JaqH`1YYCZRv}WXfCz z_H*Y7CoBzD@_nwYbbQ{>_)W>V#=l?x4pU;%YYDNZ_V5Dkx&tp8yl;JQ{B&E8r4>Sa zx|Bhc$}G0A85aythxAD?d8kP1e~+Fc^n#!GE!lWeM5VVVK4_NSgQVEa5)ssy!%4(1 z$tt@iG$TPCpR}A|?h(jo{k0QT;AZ$efgvGE;kVlMGr<+^va7YMw3MSy#7Vwwp&c1y zU1k|AC??}#Jz7K`?4f@hCj6?d4@A|$=1ybSMRrQzoWefE*=f@@7{SbDLIdC)b_V7Y zYm5h*I4y%d@1b--fU8pD|50yS z2Xo!K=N(~SIJO2V{4MVi185fspdz(eaUk+pc=ZR6Z$=uLeUbnihHc51$q`)*#$%zR z)Meo{;H#R^|A;+)%mt@bD~;}5oR363a1q(#SN7-5DVJVNgJI6go|z0Rz)w8 zp@0f>5z(ZfA(1pk%wg`KU`vy6+~bdS{{4Ud?b0F#9nFS702D1X|6Q+SMP_ff#+_U%J%PIngj1| z+ymaTck@LD0T|X`#3XxMKXa6q;yH%11g)OamLnUOn}EsFYgSPU)xS#WN8%CXRq==b z0S<(bk=(GzhIk=+^O0ONSw#b|YpfM$VOOQDC$UmJg`84?YOEw%OLziD3t%>xDIMfB8G1HvCQ$pan(v(L}T{Tvu7Hs zT5;<2g@6E!vPU|x=|AC&`+3}-YV4M@aRoAIlp)T!F*RNd>*J{a3Utb@8A~idj3yp(qh_Sg4;Rr^ENKo`hIrX zgR|0ts-ygD=AJyg;+M4CG~WB+>ThbU3LzH@+s)^uiuY*}+eg`mxQI%8A`HArwXGfF zZox+A-86L8N6;B~HuiQC^*r&A#;b`2rA>}IlX74xv(7$NAmO>rG`2K80@-nfcEZ2~ zbmbs5VE69t5ysv%;p6vBYYfWO|2g5SbC-eYtG45q(RR_M;9iyr*yQmC)}$fPJ8Ht4 z$EL$R+w*lwk0tEf(a){eiE)+AS%A=J4epmX$V~ zsFB|rkRYoA8m|W9wW{Ff;L(L&#koqcJ5kcWlsA>z;fi{$I1YeY!h@F5f_K7-gI(67lwSPgy2Fg`PtrSv6ql*dbEGN`7yokt&KOY&@z< zCS>@umBv9c*5vy+##n!_4=82Lc&f z&B<=PD2*v|q9d=1ti60}NCURU=N-%9l4B(`6~|Hl5f_d&TOxpSYP?FICiTagoTY;9 znY7^C{*89yav^0l;+ElqV z>%z4I)l9c*4x z>WEf#D*avayH@dx>&f8a27!)xN6>CIGszF`GwLoU!~Tk3%v?!lnE*#;hcRnTf;1;a zVuZrOh0DNbzid>}CHKQ01zXT$)-89ms;u*syF*GHxroT5R0*i)b>E-*y*>gFhBL=ae&x*=xl)E+A%iT}ETWqmnhSFvU|;g`Q$ zp?I=6&4JPlgGV`5S2!<#C8Ou~m-CMAjaSRRccZD08PH|9V#Xu=mp<9ZCmU$!Ppqm; z5f0V=(x&sJF>NYud;qNuu+we&j3urFGpBmuYBdBG_p1qwUaCeUC&}WX!2s-Ih1B5T zMMbkk-C9qeIJ8KFkjc`3|7u-}r+JAE86&F!C?Jxw*flZ+T~iv#YDoL>eM!A8(L?Vn zg#NKr{|X?aoe#Gw>rWK-sJh&0cHX^LJe5n*=pXH{))Wu)Nl1V&aN4(cJ&3Knllh(9y{iTbQ7UB>v!!V`9qruX(wn3Qav zpz_fS^xO7XV}=}sM$NmP{yO}|S166|%1GLcPlDsFI*mkH4G!b<#lnZWs1JyiQFe_|hvnD>;WVQGz2gzOJP9%Eo$XO7)%8H3{m6pNTO4 zJ?wQp(0Tw0dKd;Czr8A}K0JwMnUeV7B5cO={Jtci+y2L`s-yE6R}cRf zSUY#@sevf0OsTTLG7gFQTSbF`X7xZJYrGkr4@2tX6CFe1)@Ox`UK9K^)bz^5rB!D> zxGGWr3fDS09O^O#0#g&yVR9hL$9v}_Gu!IA*gg{2BtJQ^O?MYkvgPpg78oz5`P=x63(7E0Z)}z^5GL` zW}tt`8KdC;zW6WL4n_d?7lGpE(Ugm4U8^92FHfgxyZ2hN>b*JuS902@Bj05Q!*YJZ&f5(^KUD2#d!ZNB~E(!(DQUmE(@202Ii8t;%tf zk7w0Zz`$MbwKm>_kjqsFTM&9H5f~0eoXo|HI?|V6HmDAsSsaQgx-lC`$&jcX(1{62 zG@E&HaNe|NF4xxfK{}aRR7YB=!}!qxZgwPF*~Mt}(mDQx6-dK<{X{9or=4kx3IA7G zd9+))PWS=ae&eYC2#dz|*Fa}VYZf@_RPK=VJfm^sq|xwL>NPkmfBF#unW7*5rtj>6 z#_Do9TP<)DqDvkStXGZe!6lS?%CX8=^(3(29_l9hJO`YJg$L#muoQR33~9tTMJ!Qa zg#S}b$9xY)his8SE1MtN#U9YJx<&T=2sfc63BMERQ+wci&_d1Huw)Z))tdu(>W-KJ z653Evz{BCDQD1*Yl*smduo}(?HpPlVK*Es}@u(0PTgp^kX_q zv2zGCY)4A?7vyoKPHqMTQnSs`M&l0AU?Qw^C<;!x<0H7BjY&uXiT`Z|i`-w!mNjoF z?AWQzz0itK!TT%|9UiIMrQoaRy`%Nhm|$?8g`nU*x37+*2hIgH>oR?8YCr-dw3Wfu ztm?l&&ETaw4A^2j&l7CAnR>)SSsk~NWeX>sNez;%1gYZG#)2i?Qqs8f^N+}!88ql* zK3Gg(jpT;;Re%R9;Ezv<564mf5g6G1bQ_MkrKh+=UO4JQy#HUiDaL_K0v3NA6I+Ns znKOXC2L^%t1&avgcy?GP>e(*Hi^9t8ybV^lPd0KRh`r1s5cGa1&^vpzTKyTuzKuEX zxX8s{M@2SB%&EMv7r5A+a#;X{=Li}Tp`7+bh(u3BiyDjpdr~sGx2Qs&TXJy2~-7&GCZrZjJcpT|_EWx_r>)QdhTA9V`+ z(0Q&1O{MzsmK`q#iO&T@sH{l9w0^CMYm%RI7z4dLJGulg6Q`mt5`u0zk`CT<23|LK z9CB}yPv7?fI+K*6a@9Wa4vyB=RgJI{ZWbq{y+J&kK?#wfg5|9w% zGUmooG~@Z2KAO?XKbn|<#%(r6t%F6uC-ttB>9~Ugd6ZZVfp zOR9=|MCV|!csG6DrdvTihf+51NZfBR1n8=_yxAUzaC3(1Z2-3x+I-jnMc9h~rvj)L zuPlP%h#J=e7=2i{n>JCM?ve|fGqZUb^wuQgh~rIX63N*5b>^U)mB|}HQe5}TX|jmo zE?tNJGoj^}n>i+HJ)2?YvK4H970|B_If*A6re^w^5r(PizTl7icrX0Gv@Aq9@&Loa z`8@vJCZslv9SQ>c4)D;guD$w?i4V#r@d_a!KzIw1tk8dOq3YWiX-X%bEKMwgH2Fgx zXHq81k{AEc+raxiu}u3Q0bn$3f2+kQr(K2Q~lz0ILtdzBA{5om&ON zRvGaiZUb^zqXa-KCl`v0gagmlDo6k%JqS92JJq27FljzC0^5O-?h{Cj>Wx8+-MWf~ zF!^tJ&idr`?$s+5QoMu~&6aas*u-USX9&hhn&7i9{=CsxNsnnQY%^$UBcEGuP^g&d z!$Ggt^|3~w%%Ii8T^c9(D}F4WvX9#oLZ{qes#8RvUg=b(gN+M3=6{<1`uaP3z7tl0 zkN{axt6MT?0932fbbBg>6{H5vjBN^l1p;%d5)*w%9J7vEE#O{~-NRQ&J$j=ZiO_`# zJrz!<4bi{H0f~R_d=7b9DIyf>O&yB0}sl74fXJ~B8!001(=dWJ!P&ncgcnJL?rQx4R~r9#)e zrY2sBB5y+B)4$Mqvj~yHmSe1jk zSr3|N0kIM43;A=lco064Ou<*WVRIec(CtooN!?~Doc>7{v{UACmfSPuA@%{ZMyt>7 zgzzfGA001;at9m)(;&_=c!NUolBR<+rq6IH%wACJ7 zl>U|*teZ&+iqpDLZ~jCEg(|JV=_kkz3V26R|*F}G86Oa|2zUD z2Hf8$e;;@eS04*8(rLvFBJ=6I6eaWei7FR5PCc9`3Q0&eQ`R}>W(h86)x9VQ+3puo zKBWIR;3&x@|Eo;_@IhBwnrKV~ySx!;Mdljbufxse^Vln4>ss2>&tnr1|#A{^%(l3 zUtM2bS8r+YAQiE^rM>&dvE{~8)ve=Su{;NC{j(X z+{w&y7bzJdAy2jKO2_lQ%E}{|#=-{WhZ&tL?0W=_vn)ofJ`J5T9 zWQV37Q~pIcXBTkxn-@Pz*-Y3A9z7)}rH7M3g=M9t1T0Q0Bx~>dmxhR7W}FB;bseP! z6sp6PO>mzSxS}4lpd9Z>^?}PF>_&~_z&JvNu=yeKdV8w}5kt>WmfYVf6R<9Via)!M zh$#CdKuiyUb;u4Y9ZUcK14IA-05^kWKUI_@tt7%$q_CS@DAt-_Y2o0zy|vhKQfj+I z!e|G0sSJ*}U4+^y)Jxau7)VH(f|srE&;l4#U(1@a$A_iv38RJ5Qi&d24+L!N7|0d( z#i}RP;l25%YSkJnBUbwv1#PbU(4C5AwEf7+g>xWlD_f~_cjQ;8p_5_F=REhzC4Yc? z@BjszM=TCW)Q*IN2{~~%ci%?T+Hqe469+Z{_*~Lmi4|3dAYB>>i79-&Qy%U^i)Z9) zkW(Xcx%@0}=tHx^*W`4NSZUh<-3ncIY$<;Pp?iQbhNf!;jTAbm*2Xq~5K4Y%A(%fD zJ@h74k0ybjk!&VyTkL{S7bG}3%<+;MbSMY8WA00-52*BQ_M>93Kut7wW0000O>4IdB zrWPP<>kk{u)C%zrGd$QwlGWEU9>CrVhC(H78?ux5?=fR@5xu4{8hKThWeb%nn|Z_#U-rQq{97X=n# zLyMkmCLShZN;RRc$DYqmkp^s`_@NsED)s_B_i&fk*74%V31a{(Ucuo&C=-M=-~a#s z00HpH?A*X*J%L%1-dULN9ukvv!7mhWR>QC!|6BWcT~d^rYuqbjwpfzL!Wvc3yhS!S zT3xM&uv$6y5G&hVYQG!7NJ1f8+Z%A)Q8LrhOo!dDSrUhGjqGcn1St0+gUYiO z;JcO~@igzSJgnJx)4oE|z9*;O9?Q@#Af9|R7Zg7mA;AD;zm*htE0Ft;S)+x#)xa50 zXQ%)O+o^a;NX!5L06qjh*Og7DamQ4_gH~8v&jX8TQ8A2B&Q#LEA>gMSUgZQB^>fFO zN_=(~j;m2ZtOSaHwWSC`U0$ORz8*Y`@^Lr}cL;xCG)G^^jkuUGP0f%^2k7!g4^&LX z!M>zNKzU+V?;X0w)hYhR?gb`vLiaRu;3T32pG)v}|Mg6i78dR{Xdm|j_Z(2=8m4=M)85v0)p7MNVp+^ANA>%cm`&P2v3eTj^FapI($H?^{n!$O{`&15gNIY&cQx3a$te_kzWs zIByR3u1ymJSkui?)chGok71kwOZ4u@V^u&NbR(HhhW_wpa(j3yp0GYGCnGzIF>kvU%8^5``KVhh`JA z?S~zz!Ig#7pQ&yL@o-jx-?(=?Bw`e)aDCNBuGO5pVjG|m3_%-79538E653DMJE!7#*_Fwsp?_)V3>{YbdQq0_(BlfKLvZg z?(4;R&7())An?E+7bIrlYDWdK@Pnyt+l22*JwuFK^M33CvYCUpJEjGunV1^N*R%-S}(VclKx~#c>FiI^i z9v+~gL6=pcl{Yb?9L_^riAEuLs00r9y}!}ZyV+M8kM(Tf2#zyGLUDc(v;Y7A2nYf= zAt>i;;z@%*DZF4iX%|NW?Npsn zrCJoo19D+%89`4NTC4}fPyiVM3-Y5u@s#oKRZ660B|a|tzckArJ2Y;;6_y!>IzB#B zL>-+mCxs5-rIi}f1HgRxaANpja<{&6D;G8)QZ{cR*7y_iM37gfPp19P_W(ehcrpdJ zbPfpsA3*>J5CDxMn+2^&Km#V8Hh`AYHD!Bol=RzPNCISey7>ekv3(DsvXkX)e6cKB zK-^fPM=MCMFv^F*05zt?AO6>+G&f64pUdqJ*Ni#g+XmLxi69&kbXTe zLd9Z+p+GBw!TVbj-(7eXo0QXzqGI#}EC2vd1!0hYA?5Ycd}GCLfZ~7O0001eDF6pHI8Xo=@}(lBhYAmWpkbiLnfwP_@=?(ZIB8hZq(VjDr4a-G z0R(a`7 zmDCcQ>v$f(fBz5_|e48G(6>}Ht(8|JVu6ri1cK8b6^cV`9GIx02s^Rpa2Vy000>%0C8xbE8(qZE(QJ@lcY5B zG@ec6f?gI^z?(SEl{l)tT=@nwY~)D7zyME-=aH0nr$ta@puBU+>|*CUy~@QNxUw3{ zL0#}anhIk>Zl%lvhH>K%ILgbWCt;#o^McIf$$!vuxSTyj2Kr6aVBg>kA;FP{p;MeU zKmY*Z2th}M4(Xgld-pns!XWn7MiUjVsMA=`B7-F?qLU{(00Tz=ASkGa2fNTBabzLD zvYqxKxU_i;Q_eG$iIN)rh_b0tWZPs}oZ>&eFkA&+q)NRlNb*MJcWQdWQB+BI7ID>}nA;UcIm zA3OfFi4o%#dS?EbXI@TfZrDvqnfb!a)`dk!hrLrDp(?CGr4-OZO;^rlmL8EYZ#OT*Z(3|lrVr3`Uw}05?m?xHp&odEC+0}-}YHx@cK~JEEfHnXZde% z0R9W{B^m$#$Up!9f)%~;MDL1Ks-RrK1#gKZo%7Zcr$+;DSMSF+J-YG`ow!7=Lcf9F zAVQI`DCQg!OG?IExllZoneIgO5}3Q?@Gh;c?3$WkbiMCz*@1-X1ZlFAwkR$gKm9Tb z*j2KT2B%HeDX4+R(Y}EU@oX5~nFtmV-Fg%GD03xa8g2@CGzUGPlT%}Xs-YU)5uPtFSZ@45$ zdiEjdl1Jcoefly#-H5qxedISAXa(LN8&Gw zdLE~$=I2qCMf;s5GJGZeOq&=(lJc$mOKt!~PK@NXIvYAmS=qz_5%*essRT ztm)gyfV9z(o(pE|qw_KV&>#ej2f$y3n^uIBeAOv3AWF+W`R?5ZCAu5_??ia8(_bz} z|6r!=7#h=q`ia)k334zh9#3e=;gk&jM2)oc(_t2gl$Z?HO5_5p{%DA`;)k%3Cc0GA zEe!(xgJu8$Mo5}2T!5Sk%yW}0YZ(V9VYeKmiBV|ut%OFnQt?FqG*byU;SvZi1H%6q zFtnf;32GXFNMlxzSUh|d^ngRi#L*HS^pgj-2eRkgt>~-z4|Hv5XmDn&P;ek~MPyhr4t8@f15CiFx9&&@e%AFnMdV&jb4(}t&fos>Z zHJ=a$+k7QwC(^-0g~+6%pR?saKxbAcN!ywMd2&{)oH7o2PfKoMW0PDLI1R&fekRV$ zJqZxYirNBckluPG^jSWvtElo+iw|+pT}|#X`7dh;Vl5)Kmm7xg`*3iIZ&V|)l{tp7rb$WN`x`#ZJCa; zk$S5R^HePT+q9wBi9&xz+p+7k=gO3P{!n;AFv0of)5?`fr6n#Am6Oye)n5o50SyHT zHQ~=n)3}i&Nfc~&c45DXkejGzm1|4ev4s?fF5jxLO6mXr2lFpMK7kA5YeIr}1y1x~ zy%?JUrI?mAMW-HC8wFG;!$GfROU;8of!VV^CGExiuSGVwchwYEVupp-O&_;6P-{Rm zi{AdjY7HuC00XcfPt6;(aqioY_*Uh6JANA5b*bD;OxQdY1R&v+JOGcpChwLhjn};y zyz~O&TgSuQQ*-WjErGDSe-8f%4ihw}H`D!c{8^#wdZcU?)rv1mtB5TtMcXC9jxk4Z zLEZ*cnFs+900001X+Qu3sHmg>15dsvO!x*NvfC_WH7c;~0LhThJwHDKI`F@n+tEMH z#V=Z6XZcTQk?gr_l@V%jW-lKM4F99F)?d!w_n1YQ!AdKppl_sEX6_Olzr}lGnxl9O_y7mMub=<`1cbKj zj{%jDGFegf?{A%@?34^h{+sX}-+?>aN0fr#1f4+)hK{7djW;}nnsFpuxz7B`SqHvh zm~fHA1eK?@(xEBx?msw|N@bbJ_=kI>4izb;h+H-MG7jXUCzhNOxHXvbf;=K#7!qEH zMnZ0Fq$fb<3($!VQIGs(iQZ!xlZNF`9(xUR34!ncFsLKp&NNLkr(JVNV-UxYh%5j% zI-(B(M0-x`)6LO`?ODcJ}-Rac{t1!dhKKl!!< zNG|=Jh+WknjQ5wSvpQrS8$5~3Q^PfSeWfh4YS9%(_=@JYnuPp%>EQ8M3K^?zA|!<* za?0KM4OU{Z00000dY}YN=o>X^WoLtLfWgGBV2`}&nxFe=x5;)}D8e|;{f#~BcHF87PECAOs#7wZwxKlm-<50`VcB9kvL*pT=z#)%oggLJeLWL3*ar1lL9l za1fEkO#0mCqR#@WYt!WnSd;)79c~VON&emPDLp>s-%wmbn4I87*__Xrxx}8_FR}2z zJcAm?$_{Uh58b{pF#NqhQhLTk*SN8Eqj2;qw}Wc^|C2?)y8~It*wg7XQHb;aJ6d0z6u7s%IWu|HaVQB50t3x zM@f5c_B5hEf%zPp#nTqE&iP)}wlkipxQtou@s{u53umxkPQYWZ04hf|f(AlXPmv<# zr!npzf6D3Y=w(9>^lq9WGv%*zFA>0x!sIZq{IofW3;bpGi%XBz4} z#<-nh>Os#UC^3WqzVARi~@)@wc(rD5g7@ z#Aj0^2M#WpE&|8>%aag=tW2o43rfTry@$?i&50l>v7E^kdg#P@#Ghy*Y*2lTU7GNs z+!PKFI2R1=)nC^cd_hYoWLrH5#|DjGt+Mn0TbMxAh7>koAwV-IG!dpe8>`<@-38xZ znh^eiS`0aG4FDnO05YFFhcH0YV*j$lBF8VFs$JR57Ws4gmrG#f+kBtckL(Ml^hJ;ChA;s< z0)^(@NeU&B50B}uhpO75vIexI2c6DBtWfYmto#Cav z$VTRumBE(toS7X((QW#n)Vlb^0><}931k04P-?4#um8Y(^*0a013I-0&fQa%nrMR< z48qp*x~wpHtLpnb<%I#hp^z?JWneMp$m}`+kamwZSmHRe=2h;dj0&sZsc&z=3M*Q~ z4$yceGXP#;%ATMA00c*fQC;LH8~si@9Pv6C1LY6&@d1+t6b%KTk)^$;=VmwP@Ts+@ ztWeG|ULZ_BJT~CKV2+mJ3Z^?&q;fX-ij|4kLnAL5CsKdJIJ?|J2NXah*-%)X2Q32W zFDQ0Cu(7I&2Hi~unjTw6{@d@==Z9D7 zi%^mYL7(9gkw$7OIDsOCnW4{_f=Z=+KtzTt?BhRHVU{ zvY1-}ukW^Ke(x7o+}77s$n#aEMFX{hU|zSUW)iU6x42SqQElW_gxLz32uy{vmjGkK z+=Hh7+?R~P`>;tMiI;5o+Ox2e=nXJaLd6|iL$9v}BfczS&xBv=m=*->Fky>@U2}=i zx0wfS*hnG zgzcNewqF9(v-iilKY}Cj1=pbeT^ftgT9E58LwXe^RS-)!c9>n`zMC00c`g#I1sXBQ zO|%d;)Ur-Yvm+w&8q$0*jj1HQ`3sjoesHz-Vbvi{bc&h($~;3_>h+eyz=kZrI|A;0oIY?}L@6`4CS!05kSio45c0Q9vj(Crv8o0H{6q1C_XK z+>~vvc4we699C6tZlzmkt4UUk?u zTv^W^PUC!I>BYVF+Wx=|UlzYx#~`*{-^-h22t&i7WPY8)DjHyIa667UQ!7!4(rfHq zZ~mUpzehYL7|QX+@_)~pcv%jJRZENu>6l8`IuE8Efd@W^t&2|hSrq0D^s8(Edq91; zyY3ezqyPXn!!4SY9t4?j5}L(mcajwnM=$@gZM9G7vd^&})F-k%k*-HM7BK(-%05|7 zO=;r{PRpTyhy-UHDX_ai<3bg6#s-gC>2pNO9iBoA<9BS0=^<7|F(Yq6JUd0{#z`$N z3WF$?&x6UBXQh_p|1@?STy2f0Z&FdmW<Ocylo6zU`Jn z#bGYdc>-&8fx8f4>>8X(5CExmxU`+NF;+I-X6MAJ^$4A76EMafg=@Z4(X;%9O-|j+ zdXlj?B9$DB{RWrNMIG-UbwrOu)1|18#bS3s9<>88QQHv985ZFkXR|q}u#m6t%z;MwH?{^F;91IH$+pE76ffMcHXk!F$Uf&pq$wD6L6${a*_cFe0*S=N|ilP&`Fca}jt4{$o|H zUr+9EC~^V-o=+Tm9)-Hpk?h#+M!sEUClD(`06LdyI$!`KIxEEMXX|g20aA`t>j;uV z01TyZPRCYn$5Bf9X6}A*s$pL!f}su*a`s~kqP%Pi`FNmb52S_60C{$M#|#jAzU+U9b-Z}L zb!vLP`5GKy?-g#Z!M*7tb&==*01o&0-)LnUpbdDLuKY7nj>To7AP<}`F{h3p6hA;N zmIQsr6Z)&<$3F|$0dqVSTgO#@N_siP=Grm`!pP<;wQnC38!DKti+0~i0wq)3?e6)y z(uP@;a0{t)8GYmJL~+b@ietd?`*xJF{NjxPk=`sh`#euRUP#l3T}|4#7Tm|cinj?$ zeZWMRsP1sLyMMg`W*Z%AeuTMPTOM==&*d;i-n7wd8sZfI+Lb|Qhw5a%-?}8FVl-+3 z%(G*$o3Vr+MEt*I|L2ao;JFJfhic8KSwWp5P?U50>n%{K0ssI9AdYMMnn;)%lKIZD zDyh|g0Lf@IhJ47EMM;j?R0rXjlGLYsR0hsoGssA~;`QZ4@$d+B%X)Jqf2qJ&IN160 zxUqd7I{c!XoMt8vX42f?_UVTAH4NUtmH;M1H8Y1{(sk1cL9TaI9Opbb#Tsi7tj^NI zy>{yuSjK59Ur($2Qtw?dEdT|_y4*)OwmEA;PIf;~jx9*rQ`z5q&A;{Fu!LGE@t=q2 zG@!UY^!3HeJCY6a{q>r@o`pa-mU_E0r`otzEx)NKI6gc*Mx-Dj=}*}(xT~E?+`GYs zFEFh%HR{tKQd9#Z2JPjrYX_At`jEOCeG!NH>DxSq3^_it&%#7=5u_ZzXCj%aCqih- zQBL3h000A@-UjFM<(B!r1#9-+H2k2_-~a$1uYkY+2SCEOH_UE8`IndI{0RJj{nju; zy_lZo#FbJuaGdtsFOgg+X=pgzlN1ZfXQ>C~^RQ5}&d@-gt5XNy0N;&9L@T`{ub&hR)p@+;+ zy^PlL2$1jxA%r6#s4aT!)*-QN6bn{Tswl#O^ppxCDSQLWBYa(#f*On+G|IXYO? z>4{|Qc$XB!>2qH4>3v^5#WeY&F+E`UWXe!)mr~f5C#|cDykx&oIp2e;Hppq zw-^i}U{e9x&I%uznNi^?IbVRo*rE_#9|L2I)P**_?&6TNJ3YGOfS}^-a(-ckT`2yr z>yeu!9NKXExaaF)(!TD{X|+*chr=p*+=9agZ>dx!tR~W}cKUGV36i=RonQx*<2g9b zSqLV49i0Zil$W2}EJe#z@BDk8f*C2cyc;uD%oOWrRH9~KltX=IGXr%Y%+5N;1}iff zmCteTESwlO_NM1pdm0;DgdL*t029U1Iz_ET^=AZ_x3%mGA~IH{Z$G5dG@)-NuIF<9_p8{50 z_xKqP@ESsCSaNF!2``>Re9jWKF$L|QC4S{vNb@SGY6T`&+RQi&FEOcasOpLd0{^sf zG7;b#ZtN8sT`4Z@i!WT65dEw${ki@^s>1#qQvDzuFn?u_F7WKT?a0d8kxiC3*X9P~ zR~K-ZdV~N7K99^V0Lwst1r*1~P#XCf@p)UC{vBT0cZv>D<_=qo0OfQ! zsF(Fg#Sp<&=(}R}jABX@GAD;tJz7dJE=kV5mWS?4|AQ&#ctdgoqzVK8G?K#$C_j`- zfEet1uuF)JQ?ZA7flr9Hs?_QmK&i?~v^D`iniTBaNccnnT_ z7#?wO@N2VrNx$lpQx$69+025_1&El<3;PJx8S_6?EU3>G+CQ!bzjqxq9?E99jJ>+f z;AGK2UI}wcmeO7<^zTCNmvCjfjtpia%MX0mLW^X_v2&^er zo&xk#1Up>+eWWyRI_NjOTOu?LCE~7oV=z|}Y$;xDdd9f?$z*;~7Mrc3=wsBuNaX@p zO)+qJm9gGb2BUiY0*^ZolzDnpVe9k^9`xHa!JL?ta-C!(SlXj;w1ARyX5d|5)h4F` zwDL8@!RBZry7@j-`Z3`)pN?m_=bW@$_1XjGkth#2FWOeAZ_mV7@#dmZ6Vw8c}$e-6*E&-J3pDa4ra48i{t>r-vDD$f) z`wk^OQrN|ncFvbDg=L$R7;*}_;&NTa{^b76-ZblTez zw~q`zu-1ixO`2YNDLqQ33{-!FDShx;2(&bIO%;fc)r_mYQ9l$%F~ zWlGOc({)J$RsgYDj8wFE8aMB40uk8@`GLUnS9(<*4ngjvS~N|wtGhX8R|Bj|!e9Z4 zP_bFiQB^d|3GTrHYt{fKM04+A5JjP=uGKddc^&7wl_yxm& z3`(W-!;Y4UJy>6^rIs5%#EyGvy}c&aQ-PM!kQyO;!4Pp(lfpi;Nx@S7s+~n| z!Z9|>Weq$E(}TJUN00=mawQWf%x@<`JpUel)dIzEE%5eO-RrM;tDQz%nyL<*=3a#ll(qsM)!!4ipAK6;Y&` z&Xc>z)a64og^M6RJprWq<%wVTf*DVXz{Ly0=jNZ~)-8 zDPpHWTr-^&$=rhy;*xL!59phe3QUAG)!euB5DKU_SrKr2Bz%}LNL+6f;%cPqPjI#Y zdB*i}yj|8(21q~v5)MWcN>HxOuQ~Og%?4{rN-ee^}#lMjLGLVD7^ZBRc`iDbPyOOXwXrR@$ z1dnF74I`gy<4CE~U2~!z>OA00zV!76kZA2=_5E-*OtnhzqgWY4@bjSqHFe*oP4@fj zio!?ZC^3%>`4Gn}c596)b_1kblaADYx!mV*jM8w)Dbp8YcD=ty>oiVOe=`a`St!aJ ztH7MWKEZ+!lAshxKAky%{kUrr^?`(T4r87{xCK+DqH%FT=nj=LiD`A|nxcc-?A3@Y zX>@t+@(;>0lCMOlW7-RamrMtIVe3>yU25Ood@BwdKtZ7J*UD2M9JWBp!*}jQ@LBgJ z+u9#}^T516ZvLcya=KKvmp(jfL9m7{G9n%UFBrii3kRg1P|L9&)Z6|9w@n*&li!OG z$opk-Cw!TWe77G^zOlbcqn%(Yk|&RdE7)8O&Y;lTFIHDH-`R=_@i>JK4Fyl|{D%si z<_yg7eI3dB9saU%IfcucM8W)IOq5}dxTaMv1If|{!`K|_Bv2)#o#+u}U&??vuXMG|kB#qbnHUMilP z8Fio9Q^YkJq9#-(UX|ZA;mP{$5m?37mk+#k(388LXbH?zH7l87oUhDZLWUgrm5+d? zwCR`ffvOZg=&@``wMTtRdqbV?N2uX(jY&SLqD_C zrs~YxySLzKSxIZMo}^yvM`DLhF#Hns>r}c_ehi*kHwZ(4UFGH4Vol+YueeU3l6{uK zC=ab!PbZvh55F}j?{PrVA^7XDC2r3f$9`$*-0N?36g;r}ECB0qeMX?5C{WS?F@X+X zM|s4ZHEueo1_l5}h3>Y)8nH6G*r$|8{v<2US>;9FN&qAuz=vdOcmGtmt{q6&|8Lb4 z8ChtlP=Nq^3$Q>pg;9k}KsEcl0c`WT(ga;Ye~dG5Aj>GX4MJae-uAu6^jGyv{SxB9 zXUKV4QzR6q7;_#$PENA zP{J@{yib-0RsA3R9SNyX%bk>6pIQ}vSHIu%@SMZ~0o=~((*dWETv{-A;x4sO5oXU{ zF!D-k4|!8CMKUW-{fwsee}t@$-2GNkqA1A6th4C8RPhjr8v2rq(I5`0bZd~Ed1_>B z)#d6@FnRmU#uI9pgD!z!p9yjXfKS@8mYa`P`zP6-Ta|Qe40#Iw$}G zEWs|kLi4f^2Q3O^L+*z(3V>6qrrQG^5N79>HGIU~2oX3BrU`S3<<0QFXxmvkQr^d$ zqQqzpVUDJ%-#m=X_Cx1Wy7ue|kP0ZO7ajT5rkZ<_*w;*)7W#k&ycLSf7?Jhi{Pf(W zPzpzuUfsk3J)9EUl0H{9(CAC7gn?LFbg;dd_Y?Z+(;nC4fANC=ABYdNP1>G)H)#nP zx;vmF`{jBv_U17G$nFn9;4gq6sR;8V{>$u>k88_e9wBY`q-{jr=Oj2_&pv(ltO(in zg^im;9q_Y!P#1#{iDN{M3xwg;I-^AcBxR`+2clQzrL!0dIdV4}?+BRdKIog_b>E+u zHTY_z_fe|*(gXJ+qX7lzpb?PSc=sM{;KN12uFKP3;GR&x_&CCrcb4_5O zRA5_5VsYy^<`2KIsa9<^)@n@50-X};=swJyNq0@8Bjfq45Vm*2U zEZb9PjeT$?sNv0bCah9UkOO@GhAPswJ`Ss6GioIFuwg3r z%a}bKb+AB3tYqc{hQIv{8(vo1-gRIzeEVcsE(&MY44Q6iK*+e2v;c6W&l+?c@^yT| zseETY`6*Sea%~>ycFizS@EemDi=zI+6j`sbd=}tA%lG*60-^xzHUx;~=}c2=F;=C; zFO9dz93{2|+I9qDo3n0mjOwDOwmXBMzkV~x3j_2X^8|HqHRWgha-Z{0wb#&N;2)%( zu-g1L=($mI&)@LXwp{2Y@1yYL+yQH%%r_K z+EUgTF?5&uShJ>PA^> z6o>9l8=i%~M#k^qX-uqWM^`oEbQYy&)jwcNf1jF0o7ilWpc8;rfm4DR^TN3tq2L3P zQ8qhb>50Eak3*mK&;P57I0Zcc|mld!2RVtEWteE5y*cZ%YNi9r^d5wg0AbdZ(8r{MkFh=5?8jMsl&pw7qu5HJL+ zwV?N~g^M^2TZ;DdoKDz~);uXvC`j+bDYs|ztc-}r30fDXm(xHju!s*4b#k)6)Cpn| zcblmn5dRA3_GkcCA7YERsDwxmV+{^5a`0wmk&w<0{+7zVW1Okj9{rK+E$TOH;0@Nc zjv7>i?4RS9z2czWBq!;QvjHN%`|YUm?JAR-;vHBU?Mci6m34g#m{Sm$Q6j6FV%fcF z)3AqQ-eC zQsPZ11WQNZ3q2>1-|q$0*=R7pk4Apx4ma=DL!C;$&Xi$*@oqcnNJgg8bMIVmATntz ziB}uKVTtaRcT!J-xU@#LO&#b~xr^>@X^O;Gr>#LFL{k16&<(8eAT=J7tK#JQ^}hHG zC3Mc92Ie%7g@86@*iS~;2GJy@&}t7bzY&^b935MK4~SvqQ0`3bf4_+c2XjyUo1~ty zE`Z3JTO#35Kb!l~@CN_96@aSAx($XU+7j%`_Qw_DcE`CCJ3`UhL@5vF+`V;7yVkXE zc#cqVtlM1=y&m5D`vGiOpk>dYODkj~Q65yJ9$6m{7zLkjjvxZPhbGBGa@ z<+C7Yt}{}Tz(*s1G9S4-{x!x4!N#A8lCp1~WN^t7Cvf=fqmvyS9vHPQb`2 zfp?MCT66sDWOF z@$PsH3Y63skdCSGhcwV1Lj|?#`+p$61?2%stFCkkA)tNHuhm7COlW%+Z=bCy?q`|ze%l$yrJbZNC(zNRcsK0j>8Jl@~6Mcsss1m?^f17dElqHtalfJ8M}lVx z%rtl5egaIgRO~d8!nYL)JQ)`y;5y{r`ss-4iS#IL8Uzg;e1VN*%8vb6JP!ji zHhVyK8*NDAdOOgN9|oLZ_!q8%=L5t)K-q;yyxHD0WGTzhVZ+ejXZhf)e$&C3?gx!H zip)r?MQB3NbVTM`sKtElhTCw|gMAS&#LQAfH$p%M0(JlcI**~J`Sjk1)d`E+Cf47n z&`_|{b{Ac?U*KUbzRpppL8%8|k;`7^l# zZBipOdCe;)JR0eW4munf_io)tb8QGsMMk_zMvo$3NGa@4I)$m?z}kTmJDb@R-kd^5 zwsI3dgi1qhR>8MT1q~_+`T`j6oAN8b?g5kNoe6FzdUyY5gJKXvjDTa*a(DPc+O*I} zc+XqW-d%`u!{Qj|%Aq1Me)R3}ubmTMI~M8P-atwu<%KF^ zRDXSSooA?@7^l@VJV5=9blZ8X=_3+f^$478$SfMW>)IgbyKy$P+dcCqzk|afp{AeR zpSj)h7F3tKZgEQbFaQ7uSS3}}ZHs(|P0t6&f?<^VCS$7P9k5GXm@ zPFJ=&)Ijq<{|z+hCta>AiAoWe8U17rr<~3IjPnd0aYNU;xt)pwL4N(dp^X z-2+@pUFix+^V6KiTlX78gH{I|U)3E{k!-H<-LZ-(bG13J1pFKS!T2?BTP8gW?hra% zl(6KcW|=EIX6qt;=0>fjtmK~{0000B=&kSTqocdmiOgJZvvG$f(nNArs*A*hLl3&P z%2m}Xv2t>59#}sMjxPu3AtEV}Gcfa&mYqibPjO7Ib#>qnt*4h30aFQz zoTbuQS&e%F`pyfbCp3`mG%~&DkL<*3S&;A@t?&HEj=O z(fKG8(B%ISM=z6AJ1*C5oQ#cU3>2$B3>_;gS1C71kO~xlrsA;5gH6_0S~3+1095(7 zt&Zng7`m?&hOD%p93thRB=FJ#xhd3j9g)Am94IG403f<}_T~(v$QvQ?a>r8*z3f_$6MWJd-_@7m zbHWFz=FJkAv3SS;0eyUuXkE-QA*=F!hMaeV4m0XKfjupSd>NlrDT0>vMuS;oF`oN} z#ItmAz~kX6^1X3%@N1l^jq-RWp1GRMLT4w69@TT%;sYlsM5AX{M!*j1WSNjNJ5%YSteeQa&ywz!XQYnL#yWI%5Po z)YV1;P(=kQjUo!QrO9z&^si-rgM)oG$3INP4T*R{#Hj@<^p;86{SC*&byC936P;N> zmqKRQ1{gp=(Qup)2zeR301u#+s@Vi`Cnsu5;~ zmpy>HstfHNk&{Jq!-q@lDOKHI)PuCziNLUvAsQ4<mCDl-{VGw z;Fq3{w^^F(D}A=Wdy2RVb2r0td&MsRuF^Ol?h%a=!&ZnyRSkWM>so6J%wR7slU9iG zvA?b0S*f0X6(9w62J3GHQ&UNoo3dv5d|;NkTn`dnvx6-*IexNVVI_@dWM9Q|+fgFh z4?F}q)=Xwfo*#mv2n9EMxfVUn26o{X1gAd;1QNf3zLab}ppkSdt$k&C`myX3v~ca% z*Udke0u9Be1PlOhrR$0sYKgKp3^os!?ZRcU>>q{YDK2Bh;K5k) zxz~idCY@oB;FFi!Bvx{Ahusmu>Fyvf<*39;cfOg)wEIsmDiD5l`1iFG#ci_XIu4og56iQ%L*66n6io3x$B|{U^C_ zYtTz(i4FW1eC$NoX4BM`4JSjYBMhG|$LY34^D>g-@d%-u2G zCG%k9%PTNmw{=sAcIRwCfw1d zS4Qt_{4unD+s-oSJ?P;}95GR&*dlQ88Gh?Lij)ImK?t^9;N-s{*Ee7AOIJ><)Htkvl z{?h@E*zG77W%&(G$bmTgAxZ*$fZ?}k9uOaTX`8EL{Dd;wIwY$Kox-(`aW2rT^JHR4U4-+2 z`(IEQLglR@{MQ3SaouglJpDC8UOE~i1d&eiLX^rN00Li7HSuA6?l6VaSd$-@4W|h} ze$f+|N66>aH;y$D9CefRlg$LUj5h{?Rn}`&($}+PB$#zj@xXsAkmg!RTaUCg4^Po* z-uxMI|7Z;HeU1mjyDX0c!j={pmett)MU`%;}Ei=SpGhz$nOQ z_8uuaX{-PM6k~~W%h|JrJvf)&FHt~UTXmYZW?vV%h2h0@)K2VD_Ne9Hv+~y#^@Mrb zH)kD`%Y~%2XyOhqoxv9PyhCnmL z{@J2oUGqc(+$AvHq28th@6vJruLlj{pLE?O+YSyNVmO7@S-IaZL?$NxF4RNB)ReWH z`UpS(CnFIjV1k}I6wZ1_iP+;S={f2NgN%%Yvga-Ql(+!^Zu$!lM!`?1Cnvcmt{ExC zHSs6eI6j!tHo1TljQ2X?PVVlzB%8o_YjwKP243n~l~Sk4bKIRSaOUh99E>iff2B?m z9bo9FvoKVNcSUw+fdLRG_jATXV$-29=&Qs{V=X#=mW#5pi~7ddHLC<-<2_MfB2lKd%>I_NsV>EpL14=+9E zl-!ME{A&`ttJ?A0ay`w#su?%;9^D5tasAr~DJqKPL zefza>-S7chTlO5=S8&2qzmw$@?)MVNG`O7B6+X~tb@}&=tub=1EDwK7) zV?;`%x#pyT62r+*((xbzuo*YtOM-VmM9-7OkVVwVOVYTpX)J%a8dFJBtKWyO&6#jN zw<=r!<@Y$Dr1Ycmn<8UlN9T#AyIU;S2M||Cu2Vqqfxua|`00P{NQWvX<_ts)5F{>e}Cf^>vHPz(TPLhY^^d$+?Le z<5l6!|{h{9epAG<+K79UOXq8YQfGuIq zRAki_QmtORkt!XGy66*>0HIBw`OfmktGyOB>%LGQr*147D&iM>WOwN?gJp;Z>^+t<52fbePAHtguDDmC!CYC5DH4-JD&Ib z5bje*Mb-VTqO5O~o7RZAAUk0sGIseO@_ak~#xpE+vdt8r#A$G9uNB!W5 zj-%qWNZ><;4?3OXv*jFnQd2jB9#{+|h94!!w~)K>`g&4FK5CoWEePD0kU?mk#J%?T zzohU0XWor}&t`w>YusBkFYzmUARRI6Jcy@abp3w>(ADw47(JYD^JVTzrKhpk@#50m z3}%<1kdA2OQfY(>GNj~4AA`j@f+BH8p)vf%XM^ZlQ_r@$`bX(>-WA(4HfWpylmnCH z9w-Kx{;KcLJY(ZUH(h#K6ZqHQ7U118>Uh-5X+EWWU%l&2ge%&*wbnc{M9=1WH2O+4 zzH1^wK3T}4bJZ3bYo92j)i3n|#zOfv@8T?!gf0gw4B@r;;t+9QGthWUTUYA@EtvAv z{dEm;TACR0I$1C(CxVZBM=O4{$=jvSDdo(khOA@y5tIDBo#2gqNKBXQ~mwvy-5E%srXZ zCJxhi_40piGAuXOv!q^Ett@oR;+>BLaRZC0dy~}xffwl4Tt6_wm#tk_quyP5?K_iu znK>M?_d=;Kx0h9xOqTnt)2cpUlOJ<)Y!s=<Q@d#W6yQ7Xp-8 z7vmrZ=@iM28kiw%+*d?hzRTUZRH?{6MQbTZ1d~U-NsCZ3PVrGKO`&xYH1Im4Q`za# z$Y;LuLJp)PCN%J(dK;F;(5J`Thet+rQsf_KL{Q&fx`!%D%=dvxDRBihw)^_H;Z^Kpyskjgdk>+1arOB$&z_%& zhJ{0;T-(awy#|t4)pQHjlEU-)Jn(pfeb`i!lm^>3GI?OFX)FlYQ8s(*_}f)ub|!4Bn@fpGU7nxi@=BELt6~!5XoSisklO-@zo;4q78#P933aTk(0XKDbT!@ zSteCyFy&g=bMZd-gQ!^Ag267?@}P>zMuTR5%7bn5lw_gT*b`A{H1L(8HM6h{A#lCA z-IObx!uJRl;yEUPP6&FS!wh?e!Zng*0h%78EP-$=#-Ilx?ip|At{lt`6W(w<^lGGB zcosAFrG#2frN=Ek=H_NeFc-UhoScu}>6rVgC^%tB2X5wEItK|M_bd??mVO2WMK&AG zbw3E9P}}{38u67o^ztQmMr_(xHIoR zg1ygL@WDl$`Sb%$jHaW(vR_l82OAH>3OZMO z?3o-7bd(OA@xE&GoMfsS`?Zj&Q0`=>tW$Q1Td)>%ApjOERZL>aS*vzC}J zvpxB7WX54lRSpng+T^$-BMT3N2g!8tU3H#9f=nHMw0OE3Z$$KDplhS*+hYSt&U+rj%Q`K;4OKl~)VyRkAifYzK_$Wkf|2IQ!Mmv0@YW|I{mzk}A+XZ&idFX}*w_i)O!zDhY|Oo7?2t@U%BgBYi1;gaQV z^Bb+wAFn3_MIJx=JMAUJg@)O`olh4+z-}aiyHT}n&?7y|8h9G;Jk?xamq#~`R-!;} zwW^W6E48TeprFQJ*UEO<6hl-IM#gyteg+|ct<(M!MN)3(5A$dN9Bl{=D05=0fHrgb z*eYn3N=9aX?oz_O3^rl5(+$d-g}UBxi%sLa$10~Yw`+9>ScOvKKI8)yPS2e3sHk@p z-}fx)*AtLKJo16BE#u$A>k;r=AK?a%)BOBGjRY6#N*F@cgw3bMGCgN}7#x9<%5JF` zkHRFP4_EO}$y>8_v7AgFiH1 z%f4KBlEGR= z*;0<+uXa)0j#A%0s46UPnly0%gU4O!d(z9KB>LTKrR(SfP z)nP`1ux*f#qLQ4Q{9)B@>|23L@gb;+)QuRvYBs}%r-d9P+kuYe^gT(1o*w;^%dj~^%gY6Ce3Ge z@``-o5D2Zny&804?(X3Hs4lCyn)aF_-RoIh|BG;#i7PuN=EE;Y;t*wJAH{g?TD`%w z_1+cD?XM(ta^brhe0#zh7P1k6vjU^QyaWsyL)~1AwSuH_maF1+x0II>RdXuOneEs| z$m76ZQ^n7?8I8(G#W1os;PX)o)z^v)0ExOY!p8hX$vJ$Fw31O%PD zW@f^y=uD^HE(h6MLI`1q#)EoSizx09tQExtY3j7ALsJY}eY@b}AqRg&m17s?l>`Y{ zd?4;A%pbY&J^FgN!doS9_?;^IZk7$rG7?$vNkXCKi+Ao5_vEE$z+Ue*@wlK5v!8;h zCEB)x90ksUHoRbGA(9%oitls~RWu2X{&iT$T3&ZLExbT&6ELgE(V)|-7CXDHr`VNS zMX=O|=JcfW@pCjl!l71oC&M5uoz7dDe|CqPQ^q~b8E$TsyI(`|qjwh$Jdy_7;``?& z9JStaByWALy@^bau7;aKk7NKHw4jtFR>(2#sgGbwXp#Z_4+gEIC$?UI7R6nLa9#h4 zUF~CSxhJoZ(kggi(3;>VUGvVR)it%S#8>xEitWJoK*jIK4T0o;3*S>yZA4UdWx6OP zdrw2(iI#{ehRte)9mq2dC_#I4JC98U`3HQUZVKLA#xeGP>c3w13=RXES?In5f?rS%russW|$UnM;ZZ_0~ikx z{3xJJi^klu2^^MfYftF8SgeGMdmJM#FR^ewE)agFJdLyOq8mgly$nxa(Oicj%}bL1 zd7&W|HgxNFp;4t)iH&L~q-o!5`el20(8V|6iTwh~N7n3`jS&GeNuN^h?B<#OjdW2m z5^%~cq5bI!#6j`j)@i{%*3>3;g`47f{ClDALc5yuPT1+8b+=pfP*LT2rBN0N0=;@Ru7E{wCANDH3B;CD0U*4OSY&jUm)%K4+P}DHc8y2b zR;Cl6H*^s9hV27u=C*mYxrH3{7l?XFY!9CXx<3X0OrSOl9kR1uD~V=@sl%)VP3k;#{5_9h@f_|bMAgsT@K}OhQm*)zo&(ha>)9{X+A-D@gQc3!utTL8O zADs*r1OooSoHz~kTAGIW^cBA4MTUb`rP912Bqg5qdzTx1-s~+4VyF;J&40UWCnwtf zrig$7&#REGx#8JM5f4NU7-TO*m6Eky1K zk4ErTpeQu=UUIi-ad+<)CJNI$Iu+JverlR+Vt*}v2SWI33hs^-MtKaY+i@d-Y`fBp z;9a$jYwS6zSa@Oox@fMoY9|iaQgZq2A611xQaCBrjzV^z|$wx{I`FPFKTkxwetw^ zJzE?LY$4IwteKt=npA#0PT9<8ZOQTs&*KsedOU)v)t{q7a>}K{(-Dhd@>0Q)nZ55o z%LZicdRg?_aKCHv!l8sBCZcZNeA1RFY3;wbY*IM-KWy2~`VmeNQVw|| zqq#~wO>4dprA%#%8JERc$B$KKW+a<2{bO}oB!R4YJ>G)yBk}nv#|m9mAenQZY=Y+B z8rZ}yqZ^7YD<_2Oz$@p@Cir99X!~S$dW9{e0OG{-+|U4QZcz@t2Il_wmE1bUAm`gA z2XjL_*M#!I1?)aPv2VNP{MN4ce*N4^I>GbnIpAw+^PQ@|0Zp{4#8G&r&DqZ98&4yP z0{<_9h5}r!jMt`X?iNUGHw_}D$F!l3Q;=xb5@zE=w+;g!+@QV1@yCtdRJ^5UXr>7g z(MYx7=2WZ_cg_|RN4o3DiTv9Q(25mIHdmsB$}ph**g@C5tLnQf&-%K2yFMzYn&Pgk zUbvK$WDr>399Z>)w$}+tD^WB4ffH?#t&>Fugvol`UPmE@XHpN8(Amk?ec=AVQuSz z-tEkLFks=mPY3%HYsX!)-T%}x+2(#hV4f(KsJD+q2&GUX2a30=;Lhvj_ggJGQ3cznZhNxSW2nY<-3gNmpA4*A0b-@f;b_|`%2WMl4`(;h^|Wa-QXW|NnLYIpo1B6FnhWaT_wN z!u7#hvQr}RF-5p_c;kOh7L(AgnDWChU24YR4{{WXS(VTbHFIsh&Ps@tep z1u@sj;PIOJoLxjXN0(=VMdl!pWwTP-XP$f!RM6Zt{OQ^oau4Pe#-f0lJ=E{qTJM;d6t1kX1HbS+)@QvlI|x-E-G1xdWd z)GABi34KOP0Ddc_SV0d@sLzL-L|+yA8dlNdc7`i^b<^WJvJH*FVK7Bz{vDE%N;{Ge zekfXH$Q@4bkLT$X81Rd@D{p7WHIQ$YE)h$IZ`TnEifCP9y$${aunDF69-{11)}e}!zouybj_1K2X8`l+Xg%;??e&(8bE z_F)4mn#Pl|wc9+5oQ-6w3u@vu1jse!sQbQk5Fg#GKx|_~TRyU@ zJEI`)daaZan57BQ@)^z|T|~|u>pyCz>Z@1BI&{$VQWT}XaT)saIk-$`(^E6`GJVKd z&TCkkDu??tZ4Yp2JjAaX5qAN%X7^UYAJOYu;~egxUF}v`5x=QL3A7BtT zZi8WG&QIrzI65gixW&-7Czk!6+Nt=>IMICcYFmy?`u4I{c=o&@{J2E3wz?n4FMh@B zm7+lw;`J0(+9LMt(Fs7PsH`QOG@L?yvK>RIIhr7V;AyN9j%zp-N@qAUI{l@lx_R!B z<~&fV8R0O*{(TP_v_!MF#5kP9pSqe^PBt>x^I64%<}Du(@$v`PvgvjC0>B-n^fi#%f0_K+)L@T4sO5O zQ`yC|$F`Gc2*WR9K=CSkQIOtK7Q6*{*!qjNz}m_u4|ldy!E}r0BP?&pC|zJz@T#z{ z;*aNo)>5;XTl^#_6_g9n`{Ks01z_+G^(!AE5c~ubxEjnh6*&y?nvz*4j(SIkXrSh1 z*z7f4u`%m9rfgOph(=<`b|kto_28^g)YN|mqSyU7?Uhkq^M%=~;W{?GT0XpIHVls2 zQYG^$U|;YygeL?jhwJ21kH*X`jYzi+ps_ueW>>RO>HmSO6KRkI#(w=?2^=r2O zfw0n+Y*BK_nn5N!j#UP&?BVkH)`bEGYXb{p}Qv1kkZ?Xa$%d zJm`fPbS2@Qo6CRn6s6$clsgEy?|i1vqf#+LPwlJVTVu8TiYE1`EBXj%qKvn4+VUBs zYeExrO{41NUSXcy(|cyL;sf0vtY@Cz?PcxHHAZuY*;D)&34-mwZ=j1zAk8z`~9eS|!z(8FgB?jMpF^sGXdKJLkZ(qdL zp77ZU>r+BkGDlPW9~Y+d+05^#3<|cXR0fi|M(CFY!4Z-8g*iXLnAr{1n6JdzXhk&& zEKG$di0|JzHAUge%eVK5U0(T~TZ`|O?mxkcL)614=gOh%-zS|=bX&Ttp$yv=IJu%O z6XA*QaN2heMWn?-tF75n5L%Gk5d5+_PNBIRvbfl*}jQ15DpC`Mova`Sd zG$R{$>gq*_7Wabyyo0YMXS*5}&PIYD`W874K06bM<<;O3b0aYot)x2?(NMmW7U%1A z4OfK{A>$v9rz3vntn9RLseLraHHazfZOGHcxCgeA|McVGzS{fowV*W}ouUSJVL2!+ z#6JW=P;~0^{D<3HxfP7x9rVpA%W}|0qrYk9(T-Q>b5@E)*nRqO8f(SM1$#*Vw^TPq zWObF99zU&(-}8k88lmaC4zUB}R9zk?&&bxEO5;lAtCEj){Lwb7e}vuD+x;C;%3byD z88d4eyYh~Ts&(72s1Qd<*kn$pdUW@QgBycuu;79!+?f=K|NPr^i6pPLY0`%U9xF%k zZ|y8GicV1|`qRa`?E4L>)rs7|cB16?TfA)y~-|`H0JRmQ+WI@XP?8LA_rlga8cq z4iGI64~EF$L=L)*vzgFQLOh*F%*%Ax(Q9-Fta&(+NYNoHrV3arWO_Q;;JS1gpApK& z+AE0eVW0KfkBNFasL{>2$;9p&>x_op5;`Hn@|LsHwO%sR*zX*3;EZ!NVwcm{JsF9s z`Ge?wR?sv3heVwofgOTx-g7Iy{iaWk9k_Rgn=6mlXy=|1jT$gqCjdGM@hJUILhft9wOxedi9fRb}yGls!mn>l+f{#8rDHV)?CsPeH`^sMXSE8j|K5KhL zMs*dYV)Z#%F_u99obUuTfGBE$9lcb1*5jJta@{kQLBd`N-%0y~0j(*0CjtbyuCm31 z4d7Jd{&e5fYQ9aMzkCd;cH^HMMrDc6m?I$2xw27pXf|lUItupLV(K{eojRx0-uM`+rCYzR({e=A@hRZe?!E6-U~? zAdk^(LfJ>Rl>$cF~VqwyOkh>$4*UiVK!-fcS7oGzkv;mfP3 z3-wna31oS>_LCI~#a@^v2`JvB&6^w@(;}JGiEmq%&bh)*Q1MA)MFQz^AOAFNnyPmq z_935ST>`KD1oz`uQmCt`75xqFi$do-*FK4|p3iHC5bMqV^|fr$y+6_x18B>F+m6_@ z_yJP=!u7(6Bj0CZ;;D_Ec6{s}F##)f_a!e?TG~Gb%xdrisXH;Z5pZ6SS?{r%0iBH7 zSkB&S>lf1|4oAK8eG>I|)Q|V#oEy$5#173+s~SYpSlXgTCLXzy#kTbLKMBd6ZRBFc z(Cc*uSYwRtQ#2bnn7}!z-Um@FVLkt+9{j=JjVv9>JZJS|p8-ehgaAvg5<*Hn!875|uG1*dkwfOc`*7Nvu zva^tkLuD~{)Jbxoh`0!fS$f{3>#ykn}iUrT{;nLqw;hv#5uoleC0? zPkQor$RcI-s+ih2$xtyO;y>s!X#&Yh|*|K?; z5|;a#6l2-SWGE;Jf1)X%n#s8u+j-uy)PinPFv}*(W^tiJcAf#uxY)N;pAu?Xn*^@w zuJaC&77J`cCEt8(xWS2#CrpGhM4G5;OJ0^N)Zv%$J=6;17xY1cL&UH7y&t2tGo2!V zd=n0;oVDIl*eu+2(;~H6{U(=(Ze}(O;5yELizcgcEf|qN%Iq5bqXfsfL~Wp#YTjJY zq?;>fugyq3rWi;Pk|19*BafZv;IQ&qoJiZp6B)kV(S2)V6na% z?yXPXVCG%Xod&b6vYz{~kKiV`;&IfOEXbLrsdns+^utJlfT9M@W`T^dltgsKAYyH| zL_<#L+WbIy(J2LIjXMW4u!054TjVQozIvEuI}Lm4oe!&EqAk$ie2fn=k6F~Clje=irSdW-1c>(u11g*El$t-lYnSP+XRv=+POjM+mA zkStu3_T6Jt>L+10M79V0y(!glx38lV)hg}kNpo}%6$Qgdnonvr+W5MWFMJ~eV^r)< zKEyj>!$Y{xWNH!A$i;4QqYK_QFI)K>-DML|$F%db5oZ!0(5{$*I z_&RxQV9PS+BV#IkPd31UDky2L1xTkp5p&6!-VEnoj$pW5g|+b@*NMI43Lu@$A)Tw{;;%_q4@@?$&`* z4(h$hWms;|c|IPr@qJb%&DhzYdh1yH6u(MNBhGxQWw zERX|Pt!hI|iPhRz~|3k$i~apyBELXsK8HSB;6NOs1C=Q%&vMx0lOAjEu0MDyaSD48!obRy_r0y486kU|^c2eBIq1gPfYR#urNAuGR zX`v4{VtbJ(CuQIHKkoA&Mk+7W`;|0$sAeVr$uzkw$8_@V5 z+88X8edcy7j04AN2qM7kXUQsYAO0VEGamv2`#X?Xr$=J@#Y&NL_!470bv*UaYeZ(- zQ7X(r11I_14F1M#bT0q%j;5*ieBR@tAiVPr8QPxHN?tN6EiGp&0fG)LY7?yWt>%&gg`SVYrIhZ!m?c(BGcvF*!>!=6-)E7+^VrQBNc z{Rps#v}_eI_ut_tl0aYMt&KCF@L>*;UVNn{=yNxn#`CAYVeh<4Bjk=%xlR{F=i$f& z#fV3~j~`mF-V4ZQEHFQ&cymGes>+NNwXTv!Y6VwOOT#<>kV;oD10+HQ5HEj6;Fq?( zZ?w>zU?q`pJ5t~Px`{rCI5VVGnyPXD6&jNVm)fV?53FTddjcM`Zr^v&QF18I-Hgmc z*TsG@R$m?sMx$;<_GE`(rRQ4l$vn{%fAU>edoStXNEt34i2K0af!+-5s2hF1$=7OFK>~fzRnC^F7wb+XNyH_OvWIoNbu%kQ-b*!dd*3^H zWTS>WRg;}z=h|;6*CzrD*^+gMwTXcv=9SaJ`oNNW6)IJZcdF%5+?l37B*~YT zrrH%*`ooeK4SN@`kdBH-Wfv_4!pml7Gf+J5OhF(7ecaB%QcS8qN+$^^lAx@as!Kns z7D{)dR3Smz5*D#I+#OOA_I%=-2K2;Cu`SxEGKTi#k1QaRy>WsX8F+6Sode?WbHhg3 z!|I(ow0rVSvPc9RjnSi_DFS$b5!rN3eErIOo&FQp>ZJi6F8_PDO=~0hT^HXFspwuU z?Cx#V<@_^6vF0k!S)6D+vL}aYf>a6(yk=5^EnWg|0NS(h3_dPGJOaH$8I~I?$gq}t30ovz^yL)(^qs=8i;IX ze7f};$i>9AsvvZ1y~rKH*YTW4^OdDjUG()aTD0z2f73&PN_3+yvFHsBHr^6JQH*P_ zYjF266Fnsq1ERh*F0e^`XVH-gPTL`-x=I1k*Me}^03NH38t~;N!tp(8*=H;<6i>5y{ zitI2o4~ffgP0+>@d1=7#_Sbk~L%mo=VwhEJvhZf}H?e^nV9P(%226JdyplEeyPj}g5$ zR>PA!9p&_8rBexil0Oi=J3{|gJdHi*$+W_+ZoF6w33s!QtxHmy5mj~qR5}- z6Eo}(S!YJC)>;u;N38_CY(t@)O@5^>{3ceME6z9CM(QwbaU8lN%Lo~J3KA@%pH;ow zI-+dLINb4|#hwFH6Vx_c*9;A`Rg0~~+C=!UC7O26Y2!$*0Pe`V4YIe&xd`0uFK_*q zKiEzdE#&+)Au7~!Rx3VH;rmo%%RndbgakSYP#tcHffhTXuF?ekLUo>Wp!N0*q{!>gVs^uea~Lq~~hL;Onx?(d+zFS-ii| zpa%DfzY}!F?^^P24YJz(xTf_?z8|mb*QrSP7WY%A0jY1d(c?z#Ej6|3#gT}u_6Ok` zMy~`%VldGpUMv82#X^no9m~{}Z#T=t`9quc)LDBR7`2ccr!J{npvyE8W=`^!N3mPu zFiM6jTEl6t<>>;BSUYJ!o(=&#dPm4(_s3DV&yxrb-f?zemR1vb*bFlNsPTD#sVb+= ziI=jS{3U7~iQ@`qwR-E_yugtYje8a*7YZBQS7idC2Gq>HRq+$Ti!SrT`CoItiDSNj#9XC6fXe;yKQ z=_FsOEBt@>XT6)g-7llij1;8kk2GI~*St|1G9$e(3)|D-{DadUnlyYPz?z-=+JNIR z#yUN%07D8<+w(tnBfCH;p>6bbGwW>Q90X54=`$vZocsi)52$r8iZ?At4Rk%hj)~pX z_Zvlc%{t=UlOGhoqOh)-oY;RT8}cXD@+et;@c)eXlhj&k@||?V!OAf|W+<*qsy|kw zRp%X`b4u-}l%I>+(+@D9o?V42#&A{4(Re>^XhK>-ppmI6N@bu5ym3#d^EfzBG&%b7UU2G7bX7$VUGM!V9W^%Nw*HNfOFSn@}=O$_es!Lui`}VNM+0 zs+Si%E4|#IjIsq&ujm)vRr9oWb5!@Rfn6c9AhZF=Q#kn91b>y_RZz)x1jm9%q)b_J zzL)q?tMy_*YWfeW-DhRvI$#1q-f{Ws=J!tT=Ys3X3CmI>y~07|GK-h#-+VEHk3o5T z=F^pIfsT3dL?NQF%I+c5NB1Q{jFK0Xc$S;bZ=H)LeBz!|1bF8ZSxxAU%28v$F*HaT zswN`7jg4I3)<2F}|y09+Lv3Mzj^4dV22B%j(U+_5KN=T3e=| zm(8r^lUA@y{U%y(p7WL=1^e^-<*((&9BjV?UlmDy8*?ph$dvORS;l0M2Y$gA1Yc$Y z)v>nkQ0@6rqs*SI{=iwg# zo3dor4CvtwjNEh}(ok@E+U+SJKMfv?FzC2`PLZK!L$XX8NY8T(NvH+QPrZ*oOqh~n zlLfGsYwIf(pho&+ugAbj^8Ox!0V13g;2^6}mbNg>+OTgDaUuI-jaE%DyhFr9jh}8> z3zDHa*?U`cnqo^KN3sbB71>pXaia)^@$kQKz(w_t7^gKiirAm`ZKb|Ju<%22`X-ei zaFm&zX;%Ikmi9#sZ&y$Snbtu(=WXwuj%G8@Cdf!JM%5Hp)&s%cHF+em~bAM!cPTsi6wB*?-jCm|2nia!#SaHrkBO6K* zV5gqR(y*Mzb`@U)`w;gPK#ocs@pW3bcd*2=%I^>r9(unaLl)jMlZPz5{6crTc)x`7 zE)~1IOX!LW{(YL8JF;O^D`2)u&?RtE2#x}QbS#>dp%@7*Td>5OI{25m8o~wV6jC1er zOk;+b#1{_*o*+k;w5f7&DJDfr4Y`Ot>tnxm1W<73xRB>7+D3&3ga)lHhGj@J^aOs9 zbp^^r?rP$&z;dwzO(K^TI=y2gtE6Dp?-<&bEl@@Ldi2*}NVQ(PeU1tmbZ5eVo%m1i zd}=Or1GZFYzbD^=nO{pEw|=sbLLs)C3_)UcRO|Xz%84EMBm(!^^8z3kcQ6l#2hLZk?Lq)NsLK6yyh-;@*dQfx7t;}I_Q|((`%wYpY?OuRXU@Ql)ha!PlrE*K=?7@ z`3h$p-;s=Mw7RS%(kwD&E9caY4zHC}6t6bwRp}t1h}lN~2$P7+#+w0mq{aaO42r=b z;ulI#f#xotPgby&o$&gqZ-#SC`$$7wg2j6{`2YI^6Gv>_aJS6t3Z6sFooT=COGp{~ zHT_bE<+P=0Z&jRu8S6>ikC1^SVs?ZBj&NNPA}>B@Lh)TE-HI`X@+-C@VPolC3-cN1 z?z{Rvir)7PmXmqVj*MzxZrxH&%|n{ zhZW3?IdkPNd`)(xvH>3hJAH?}$7n1viH?qTqaQ>5kZlTxS2G7adrxQr`e8Pk>5%cO zc!bCFpa;oAQBP?MB4C}NsZW%mI)ky8ve)fjERbb*%Ne5NK`|6`au%BV&RB-XZNE$US83Ho zkv4z>Zo&$Mi^Y?VRP2=Ihf}*F*K{SZP4+UqJFK>Vdn>BdD!rq=bVEmhDlzk6_pz4m zVaPi9RXM3qG>!p!@H%PiOVC>nc&mqJ%@C`rvEJ-euUO(?D;>;=n*yJbe`6;js7e>~ zlspdh926~^aJSzmc1ExLR>I3gIr(?a$cVYL<&7#7fEVxqjl;n1MgkKR^G7IXyTmrm z1QVSY!)9FOf}^T@n12{AXjBi004kXJ^uhkHMgK~4KPT{Qp05CTVG1$EZJ`N^$nH07 zg05*MFGjv7sGFY6OnI{W*s{Cez2x8`tRhCH8iW6pcToD*mco1luxKGcC#pV>99Gmk zb}KW@#vXC!fJ)=%Qka9GV7I78wlGj8eRB|s2nkBR)x{VmzWG}YtW&U_hcXC6URw8O zXP7&to%Kl$R5_0L1WAC2u@*kru|U^5fp)p=ODld5orK_cC;7u8bJ*?xj2v*$$O)Tt z)pS=kNbC-WIG77?g)%#mCc5g6fF8%gR0S9G? zX_y?UaO|zRWpdfy0b$D7$}NXd>%6cl^P<4nn1T^cc;LlBQ9SrXse`7==b9M=Wk_hu zo4ly{me@C5H?xnm;(%YOd9zT#&GEuhbvkeR5K{*3=>zo=1i3u%S%Dk2e)#m?y*>6M zaP9;!56QYnwDXBx!+%l$Pb1It*z>@i>ZA1EN`yjQlL@|2=1-+aJKIhOPIZV_>OoiP zT~#lI*=ELf_r8skcG&ih=+BA?-7%C43Ds7j#T@->Ut83<&<~4YdovQ*Rj+-*5Ld`% zg(#4|G_hFsA|ur8x5P(}a7sUcqn0o0=7I4IRcwvP6d+Y*4~Rh0uV(uw4L^92li>+7 zKwb@gn$W_51f7`(6s}E17p_qX)Df!KQ{x{e*JL&3pV}_qSI&C_t#B{h9g^Ajco}qT z=Q1A<9x(6(%BV8Kojxfg3uKf<9@Ps#Ys9m{0#tmOB%Y*L8d?{7yczY@wWq6CE=P<< z>f!JPi}3i^N1QRv=6IlOaf@d|iPZQ=_)oE{Ae)U7?9z2f2Qq$@wPnX=S60+eT;~Dr zV40;_BziOF%FkIHQYoQGj{%K3JV@=%S~In&YXPI#kiqA{A8bnXzpnJ>q}9d6!%^Nx zTwwti_T|(4USXpX=ixil%v!^{0RjhD*W z>YXFv;+0%fPXOa`1|nwh@N8+ zeIkrPv}W=xdHH2Zfc+%h_1vd&$8ymMj?PTg)kWLsv8JHzmOg|}{Wquj!Ei*@5|8SD zw7qXXE4iA_ckKDyq5b%j$H?5)b8a&|EZ;s(!w|oEr<<_l()!mg31@(ig&wVWA6sCS z51fw?TL$_S$zM%sk_b3od&(&LDq3OunapQcjI#!QTyF6e;413;8Wcskn6I!On-tFh zg%8IlQG_;Y733-`VpLl}>^5U@aL!PwFb8 zF`m)3xo#ifH4Zh6k1JcBd8i_v6ypZ)k>}N#t!VQ`yOrIZZKsCUF_*=WW*~iMi#vzh zzN~@W=fVlmLoF|1R8dCC68WP&gxa8GJgDMC!kS1O`3G$^4g*Pv$5E^nnWt2>-BmOw z`7kO8k`j5New!}K9R5<0#Ip40ZxMdohxCKOcE=H9Kl~7IvfB5C-FRr~eX{oeiE)ym z*rb2QA+rmTD`AJBP@ktJi!Hxg*RB(MPes6pPXE$2Rq%@{)iQ+RQho!u$b7p zsrM*SV}Fr!;u!%7Yonyu#DL;2M=G4HioB?7Am#BbrYQezcfMkSi>B|YIEBbNI_wZJ zjeS>W4@+-1C6B_H7LGR&^NYL}myIMSZtF9lp-TXniKuGJjb`Nk8Y{9(KtP8|eXnM7 z<|9}UgnTQ@p;Dzal@qoZq$SINi;s_Icb}p$zQBnJ)XRklAa>xafdO%%!T8fuQi5>> z3v_@%U8og3+P^oMiWd&IzIPq{TL8oKKL=#|7ou-d(J5MLCv)SVFc;ncx$;`W+corO z#IA=DENhF19qu$Q?p~VEE}oWPrFL5>2{rH2UtnxBO4~jdRw71w@DD{asu1~Us=3i8 z&gMSpi+t1BIH>IaH!)uCd|sHESG2;3G#KAZ|1(Q}Bq26x1tEo&MNt=d<;yJ--Wr{+ zhtRL1wL(+Lc7&VMJN;D1{8CWEEh@%w5B)NYiw(MClxFBbjRRtC!NvIi5gN>p1D zq#eM&QHN+H338m+yjlZgiO;GZVI`V8biWD4dL-oC(wt3AKiu>3C_UMiRtauhOB}L6 zBCr{9f7W}!uWXM%H)ZEQqdC{CFn8Iz6*n2oZ^uys_3S{ zJ7A1%jg*6DU~f>w2MmEbQ(F4r_#3e+>Q9l_avp~UNtln~Cytgy;mxn||AZP*84DBJ zGBt;&Gn*edC-~)N;|99)CCp^y_#zFXehybyn+6)E}0tYFMr@~}3M81LP$)3+K2 zCbiulU9dA69kpT%w8N6zBUJg`f#~?a^sLa=>v<;c8pL0!D!fM_i?(5DSTaKFnQ$>d z6Iw(7O}UCSAmweJ@8`D3yu@rLT$-@$20FA^hTstf*+r{PEo#-}r?v3w2Lwpic8hrq zhoF+K`isjQ!4ZhFWdE@Y#Xujq{oR!-^3{Jn*ljeUwF1VgEpGF5dMMiVe_}3V2ZeHZ z6eictuq2i$K2!J=4^5HzzEJu&tjo8zs<7+W_}zbOL;u%Lt)tgY^`WuC@hEaEXN>0dxLM z0Im=6PPC`2c?|M8N7P4htW&^7E`wNY6Ghtn!PqQo|(867vbC8I$Nu+^z8gXdvp z%+8eSr%zM8AM^18%UyCP+GoHtb&1!!TB5AHG*?teR=F zVRKhZ;dTZgGX@8@_vGeab1rK6!RY2HB?W%#1Lnp)aOun z4Ov0G=32vxzut%0$o`eN*5RVvQ`y%07q8FmIAs?xKj^&`2dqp|B&IY@02besJq@o1 zojK16^gcdd#@ND{Si`$Rt_pw4HGwB?CEj9*N$9wU-F-7d)Gt+X7EFW#A&(JKz+5< zj?-vRoV1%XYqKXEf`i$i(sLKOmdbPouz4xU7r>_d=BYo<DgXQg*)SkS-$4$LA~Tc-wg3dC%4U**kYC zIyktG-C8#M&TQG(r(cUZ6aST6E7D>b4l(ubOcz^txo~hzb3B)Fk|-J(3;HEeyz{kw zMTRe@L@IQ{JPbhR0U$9vw3>Q}NQGXRlDQ9+wDd5`M@;$bth4gl<=6skZuf~X|Ir=S ztfu6)dAL6~Yq**TM&RXMvsFWMjF`5W&-5!LfxNnC1t8_}8sqQ1m!IHRG?zHZBf8rK za$*Y<*;$N&$bIvf;s!C0#3HZBkTDDB+Sw1fNfaL>+}A8m8Bw$E8z@{jyc7svZ{^Lm zX0-3T$PoD9L}E4<=ds@+*;Jy&*OD@twx1=I*b%%%n8l_fX$*ku5Q2D0e5$h`@toYo zOCsxqAsYi~z8Zzz=02C@){r(9IgXL6DlCTn#(|gGQIj-Y0{zaM8%&x*O)ERzE&)Pc zG3`#|D>uvb`X!lTCy(#G{If4W9x$SE`HYzvx;I^r;sz>31}|K%xM5wWJlOG2+hm{j zV=@fuLtgYp7E?&^exQVMEN@$Xoj$m-ROEVqGib?>c={>xA_F2P<(LijI6_FDi7a4E ztt-3E&Ap?UoU||C24tf*k-vD-#YMJMpu^)SycYm!PhG*^Go!&HW%1CqGgtbiiw>A_ z1R#c>R8zs;dAdIR43!1wz#bM=7FDLiTX%5F8C+PH3Qh+&)`|e5O2l$ss#iMx2 z6AcuEI_4#P$kt6d@zoLlKRB5#79q~iQC@~2cLnnXK{D2Ai?2uA4f}}f7mGR^)$xSA z?77$zgiA8&-s9ffdR~Bl25g3;<3X2j`+z9Lr(_WJoC(Zyo|L110M!-&WOlThRV?b{ z$!Aqjh&+9ZehffhvxgX!SCY6$0bv~p|3g9EhCyF0{^Z)B<$ z{b8!eMnBcZfFmxTO5S&th)Jkhl5R=@p6m4^*$wz`2TFw-&jDp3vV}#poS#`k!w9gA z7~CF379bLa5{gLz9kXbM9Rq9sZsz$_@^YbOYPOaeWBcvy-5_b7=w~%NRCh~;iKBK* zs=q82?1IF-iL(ei<3#`JB}(ty*xVPdOL?>6I7sT+Y{hC_*Kgo|$;k92)C#wJ0DUUG z@)@_S@w8ZAb-|iQgrhgX6e{Spz^A zF^$o*un7v`k<>vwy8gl5e-eMcs$Z=5ju>%LpV)=%M?2Yf#4)7IrfGPlNhl6@wd?}s}!ty>B zxEH7>Jpr~FO=BwxL%g5DY@e#>42AXL5>bVm6hjn>2aMo!F|uwk@n`*e@lu`!Kz1HHg3f z02j$iE3KRWqJQvX4@p%KtO(Lr27t7C2%stZ8Pen}ztZ)KXOz6eUxy~a+B3+ktfaUH z`jqusf(zNNM#%w>4U~FeLBBe}rr*qLaihWFQ5zu7X zP4eSEQSN$FF^CMq!w9a!MWTz=B0;OB?VmcL1fRhL#CGbjGo)iUppKXJ|<)pVS zUbW`d3WZqbqe$XU9o+Xarr$=a8g=OCynP#mR~lCo>(+|LK%L2WAPD-W!QoFb#!H1N zM_XhsF4a_8FnGgX^b2+U5dCnd0Vu3re$VJ_p)!@&RndKsG3xrn+ygW;u4Q{yqq9L5 zQrnjhQA5|d;BKSDNjn=1w6Ige+MYrOcC=Xh@${9XtfLOT0C04LN9kxsD%4v|Du(J# z@w=hdLc3w_Q;X(S*%$DKEmTg+V2qe{NKlj79s#s?$liqEM$gQB49o^LGs1WnZRH$w z6gs1gL2)&k0D;-B4v=qMh|A6*eekGwcxZcHAx2HaRyBqK8w#&UJKK{$#-eqpc^Gk1!z$anRNvuUAcyG6USdsH?#@YQ0Hhr?eRrnokOy1#Ndf-bYH^DCLq*u zPeM5_`saAY6Cm=N)90Sj-Qct?=QrT&{Ky}{`-NmpAvZ;qd|c>9k+LF-WMzKQ*Dl0$_@v6hRr-<%H!_odhkJz0 z={-x*WZ0ld*&s&a5XJssDXbl#iy>T|O~9bn0M#p*%Zqn1?&)aW`I*1t69z4n&XgV$ z1%VnKi?2@gm6BO^-rTnw4~oB!CKr=6u|i5%0tf9YoEKvCIuCgY^fKDZL-|YC zDKICb*uBC;EL?BbPn1T8ZM3w(t?~~sSMD@jQ}g$61wha0oG3s7p%tg`B&KGS9YpEY zSd&Lfe6V-);&58Deu(UEva0Q1PyjO*z$~YEQ%Nix%59yV|Dz(qxjQyRz~V7k-k6C| zbF&tEq6oZ^%lQYl2uww$mtrTd!xh|q^|*Ofujpd(QSJe-)%|GJWK?O#*RllhetM+1 zhp{Ms(&8nQ+HaNKL$qb>?6dnCPL9&rl=+#+s7)C`s5xH0l(%#&yG1l>a39E;Uk9HR z_9*C~f^|_)l0~lB#Ip;6IGZF?y@)ahe7{#Gst=U?oksIg!!VQdiFTR}ag%=0O<^|N zYy{N!i4-`6VEaCJ8v1bajpG8ZDpJSl3-KGV-;w^?5RV)S$n{yxcY-J4%U-m7rjR1zGxU7KW#gqLe#tITS9j{KK2 z@PR4fif7r)V$icvp)xy}J=3%J0*q^o+||$JqY>m`{wd(Nq(W2{a7Uu>##!MMx$TG% z)1y(!Xc?Zwc=`f~%w>!^rLllVGjpNfunVi-iwo-j}`XS|<$J`IkC z_h#gA19Ejq<+kX=I{(~;r95$H2XHU-!~{GEq(P@@#|?D9JT-TOqqC`xFRf7wig%(| z08Fwr1W)WLXC7;+W67hXr>AP`w-#TD+o10k7Z}?8m5v>|Sfhc(l8v1zQ(@e&b|e|f zGrErP>C_37@xON^eARyY3VlUAh}D6M6}w=8xRE)LDgtPGVOW>+TiqcyoxSx*5Z1i{ z%d8Kptp(75XHIIH-ZZUJ2EI#lliuN9h{VdN{8kAD@Omjb#!AX)zs+NyA)wB?HAT7n zd<%Imoc#y93}s>T4X0vj%X0pRHKu@tb+1}h`O7Xh!!Ubq2TZaTzG4y;MTzp&sQ8js ztpX2T`qJqxj_`$u1r4)@yFyD3La0ID`w#ASYyrqI5?o1VS0F^xai;vjO)>;Q0-U3% zM#cVQF@xfwPv47=3N#DtCDmACP)Xg^3%CGhC?Kq#VYCq9k>etZcjqDJK<~OVSy=vB zX~AG!#j|HF*?I6A8xo|%I8f~Hob z!2+YbA|t+|yW{A4ZXbVU zaOKxqap@PeJ{Z(3$W}vtc|gUj5(+`(Cd8LTI-l_!%D5 z31bN~<+6a3bNsH+K}D(ATZtE5%}O7Vw_Q9~eg-_%EW|>)(C0X<)dteiQ^;gh;}NO- z2q;)-7k9wKx5S(CX}s#P<2`s-Y!T!|V-@3ULpX5{di1+d#F^2vn|G~$82|wr&-i6X z;E=HQ$7C0S#Np}7f_H!2kRpG94#v~w)puecVqJ*L8&o-K z%bG^vy!~RfxN5>bTE`i#Rpi}C&jl2(8`oy7n#5tA+7>LqpS_q|)zc4^Yn(;CG9mKW zYT>8e2)!LRAu1&pO-@AoINbjdA)xoOTw{7Ti-ROj80WX;M8G~!$Qq2mCBSSK<{s*d z8%}tn0<)vWlX^pW+XK87qVRU@cNQL2hf{r1d}2syeMZu<{;+uCW>ql-;(a##u9Jug zToRBgg(mG%!I6{)IPwMc6Q^DN2j8!TmIp!o|EJD8jjyZS5}lEMbwkULVgJ#TrC{IO z|L7IxTWGHlcK`aYMrM4%_@oX);Li-SBANpbf=o6^%iij`8HqYPE6Z&L*)^g9jVJAK zTS(;QC+Pnb!IwA>02}t*Ca&Vw*Sd8K{X)!|i>Xd=?OFm@x(TP!cxp>j#Ux3=BB+o+ zxkqXe3nmum+Ne4_00S-o<@AHzG4($<(iuGuYgaZDyp+s?;4WwNch&ri`PaPlg8RpP zuABlMVR)u=vvrAhY|whk@jwJT^Mt6`y46WKs2LsjjG6k@QJ_2m|rN-o$m_F#iT6;b$@AY9zxZkNUOL@eVC@rtqrw1m?kdC2dm?vbv zbmhO$w@h1>cr~^}VrkGUnV*dj=M2*yc~oo2@~dlE6?Xu$8|1^6(;CP~{#;!ykuH_G z;U3Q6gy82L6%hQ@@;kD>0bB4Xm}MH34$#7tdiswUhIVL(1>JrGkhkR1s|fl z;rXW~*eWJa0MeMi^6_ccUX7{~gelbykG6J7zz2^Jrm1_c)wX$vn@q(-gP&q%pg+(c z%!;&?;eRMA{24WZjG~Dnssiu9`augG4kVa%f~=d_GAyzA?>gHW^uD4h%hglrg?%J1Il< zt0L_RGT%{Y$*CeNiE|)n-5a}CYprgYK`6&0+I&IlD@vI&=oyc^KMo2>uN1aoY|Ucz z-SH+NKPbj(#W67P0A`2c6Z^zHM1^1s3h{MzYnu)2sR#T7%X5GhA zMXi(Pl0=qlHQ0#xhP;-eYK^G&Gw@x@EyaReS{rK|2HISQ>PeZcB*vGLg?E`4m3fO6 z$Cn>3yfBcy5O>F~2?Jl7O8be8-t=ZGe+P+*=BZhEKXt8;xz82cp^=C zs4pT2yfmmJsXTvo_@Y2xQDoVqpZ%)8Wiaeyvv%OxR*Yn4Q9OVIK@p^^_Ca&2pFEB( z&o{IZ$%OaJ8Ei*&gkCY%ebObc5JI}9qT@0r7nEvFkR{X*Qi_QeJyg(kidDrdmxg5%Ef*02Yn8AR4oK>!bkY^-MCnC^Z@0+_`-wxR(Cie?zgw4p^ z8wb5&r5Q4#W!<@i5tg35w`~3@UqWjufS|qWi^BxCML4plpGy)oldFDTmFtm1xrMHQkUJ`w`5MNUJYKtQ>;TOS zodFP3Q=RpT=lu2TFElwzv~8r{lA!k>vkZCu-3yMm2PEtY=R!ZLHI+zOc-8WqGcKLfZuODBMnQ_mRcBPZ_{xQ4 zE8YkNnl1<@L!C-?ev%c`xp5lmd)94#elfIn zPAY>%sx34q7^yjNEJ8TL$;cbs=-nH8xW(8(JSXKgWdWl5 z(By`(DpFL+ehJF~PSz?p^abz>ysoB!F@=iDT~;;J^$U z=$cr^l~l0QYf_k>Lespwq=_;1HA&B(jb{z^APPGV#T*$0*IC%6I3#Q4nn*}^+LH4* z)1>BeBkOW(h&KY^sDS3Ha$$MUEs@v1D6r?+K>mmOK_>CB>wcc#pmL5j<}%Yr%tge9 z;^jinzmbXN&6Nr*VvDRGY!6z{V>xt9Eq=tMnVXZ2?x-}y5$*x*p{DPpPrZ-PDK2afPkyH{WAd7rm+Wa;8( z<|2{twGmw9kVah04Eq^ghl7g8WA$A)iX;o1Q&%WSfcf)sSukX|Kt&KC#QB{gVhOW^ zeTQP}UbQQA`Oe#{XkP!dY5P}~@VK9Vjq`fs+1G)jC8#F`H*fFETsEk*e8~i<=duD( zfDDpBsJIWK_0W`m0gUS@1fd{wiqMuF288*IOI|5jBz_+q82Bo_+o@6u(Ll5~hxd5B z&-$+vgQP@eKA}x^MT7cQcd0$_UQ7ZqR1!jsJlhW!aR&cp)I^tN6di&H&vZEclg`*h zMo8PTs|MiJ3o-oP(conytW1<;BVb9eXucx=JGBqXRAc4WeOEll`L{DYfY0dAEguK! z%}2tcl0rsx>hdIDL#AJD-B09teq~iGNwQy^Erzl76`%oU&9%xqV_;*=*`P7dcdt0Y z-^!^hhbe!oP8SzPVONC#TSBiVNxV>hqTb%1E2`c7xv!puv?8`T#FU^h-r#db$r&0eJKBKFTyaM^`#t!EC9M& z?2v;)S^AHbU%pAUP5_($rx@kl`OAnB&LAg1#iRTtK@>I9f&7t-*hZS4Y0}cr2b(ht zz)Pjl%#9Liv86RdO)&6ENuw2h@HrURHlsEt-#ET8rQe;sP5IQCyk95a-|%`DZ8$~< zWEyYBkOzinK#RLgiU$E!S1yHssGn)xYA;bbhvO*0S*95Hpg+0YA1I%YQ93uL9FR@d zn;k+fS^#3>rOV{#QV~Xt6EOjn5Gy@gH9eeR5%z`jtC~nu)7Hy}DU`ScWEA~8%K^$n z2MEU=j9aLchJ#_0;M`Kf6##V`Zsj)gD^&_;2C7qn&?EZcBbS^;%mj~4w-(H`^l?(s z40h2F5yZvnbOW5;ATrn$c!nhjPToHkXUQ{*MWovx>2w-xGIQ?eTlTlyaQ&60r$i63 z-|;p(`Jc*~Aw0My<&G(*Hc|0Go=NIY(Mqd~9Elpn zc9mW(L@32`B>;HCY98h*m;8G#2Wm%+PywnRDZ}c-aIZ|lFiO*{#!?^lP`vCEHgc-O zNOTbb?d!i0LPQDyKQpd%)cZ)o@jV~G23%Ho z)#37LAc|Iu2tP{Khh>RPn)7v)cQIC6#!$D3pUo~bLR~S?HZV_q&l^L3EUOL0%|se5 zQX(s_*|+K8Fc**TsY^y4M~vIvUy$L?K1%0TZ>LEJf!VE)zZqKz^P4|bZL)ycXtZo{ z<-1AQy!YvARbvB#!~~GMI{kU<53GPd@hip5I@Noe5CDhkC))kKcOINp~n zY{_7re8=llo@>kGkV;eIk!?0D2oJ&d6;rx^-M7v%CW{0^v|@$B5pjB}ZPgoyahB_V zlCQ%oG)}1z1hm8?jSsel3H&yKm>qm3jT8TaQM1hdahPtq9M#J3HQRvbP7?RziRtZr zhOR^8R2+Eg%n6Y33X3S6*lemM?xeUMSIeqSf=ZU%14yZcOl%gE5J2>&ciW#L zvRvU*C=mm^WbPLMBGkXoqobvq=GcgBH5p)o6u=2hCJ<7qI}sezw5UxO((x1lcgH*O zVU3cgjW#|zHfJ2ZW_PnzLK(U9n0|3M11s``niA*GlnkH=0WSkBK*fKbW!gY;G+@1# z=vaOGELC$I94FLNnHJL^IS;`kNUN4w?p+D*B%jyTC2|YHc6@_{A~aw_d3*SrhM5xd zgdE5_Oqpb=NO=6+(dU-3Rg`MGS1lPjX^}oh&%>1)Ri2AC3q*yeUXCr^?HKjA!R_HUpem6o2Hul8!YjP zs6*r5JJjkIUxh|zev%#ChMl0Wyl?m4hU>L>f}uiJfL_!@pTe4dczG;{9Y0Y+Ddf&P}+K& zpG(|#b%;ksz^w-=aNT*S^F%JF@~su^tAwUapyhlv17fQlJkd^voeV<~P0raq_eC?f zfvlH)ApsCpWyxPXg>q!?l=j@$<@~hIZw3RqBHwDQ@$=~TZO2Ozjd5(}G$7D_fxtLi!C%zn|#sQAC>fpu{UrH^$T4r1gKUZNxhYR3KYrX2RbUDxD{_ zr=P*FNeW;geKqsAj6(R>`pjNtRH>Z7LY;i31X!( zaGM({#_l(=_*R~WXSFAGEU~8hLtnN#xWtrIB2OrIPqy_u1@3DJPivPYePoA@Tuo-X z7&}R^;*9rq*ji+6p#GuMQ-oyJsz-(x7MzZ-IW;|O*#>nB+Qw5b*_HzNJ+g2LeuOwG)o02yLYF_*J zJODOVm%Gs)SO|-4mMR4l`&EJtMKk`Ae82+}RT6yKCVo5fuN7RmJ_gUbUvSmUL;r1| zk-~X$Ha+$}AnRZnf(afz+3*RcbtQ8u zivid%x;hmKW)bJqJ##sK#F+}v66D^du>sV?jnN00ddct0Z3thpOc56pNb%t_p$M|;I?cbiWzB$DNhq7BA%tGbbJKkdckF z6VDeS8NRDlE0{9SSub?4YelLy4Nb`2>tFLKqiXo21MZ&1q+aG-psHIoTAnWHAY5Dt zb>UZX#TTH0i2achipTTb5VM~ueW>Ch1F73cR3=HfhJZCAFhxJNYM^}3*k6Kj znl9KMa#dZZm1pFt^wv`*pM6^DPGcYh&r(RYKK&~bEkFUu@RwqB!ODP$o15t?PAwP( zT`2${COO@iflF!z&XvZ&o+Zd$HUwHUuGY5ThFA=RVIkMLh4XIh5dS*CO+G#Ju}K_z zCZ823>>d`cMeE2+xKtt~@ixcjpdDP^WjtrRe)BV3!aDEmp**3_us5DGganR)t~r$} zU(7rfMKDCO4S7E)Z42)e)k^{^jc5gSEqWCOBFA1PLnc~jT;=qFo_2JRO4ui8|mSD3$@kaGTfY{q`GYE=30-uFCk$|lQo2dmJW3bdNTVdCdDK@F6wHj|IMUjwlGRK9X3?&(WJ2LU|Kb;Jwg=b>j{j46&zl(Tu8s{UYoxQ_yL2t=k0 zXS1!{oqDxqy4H*JpedP)1`N8jbxJRRCp}aNcxdLn1Cfc|CV&Sva2IYHj4Mt#oDgRq zq~e5-E#CPMTed6Z$g6q(+!rNlc`;`QFXx_;kRfKF4$=ay7kxJ?khLgz!v z7I_$tT=KlhX|*qGrP-HEXEb3o6=nmpLpOj&$eghKJ6v z?vNE#?vItgush=izjlq;th5IZj#Zs!m~vkXw$Dv?*A>ioX&E8A9_vE^U!8u>6?B*s z{o3PcnNWA3qg4OF*abu5VG$k3-Lp#0k`rsALdHM+GJf)hR~a8(z|2wFJOZsizrK}W zpXClduvhas9NR9cV5Ba(+`Gg-4^{FDp9`)krB8e~if!%nIk`Hm+N|p93~-JOf?fIO;oP%as#f# zP$uVSh-hwv9*#a-| zv-}iW_6AX{?!nI9cQ0hrT|o3}!Px5~+)!+%EZ6m!X5%iMryJd>;NKqqP}WeY(>lKS zPr3k%GpLjzC1lr-R@7K~+F_x0DdA?W`V|tnv^*I_+$-pxnY`yCITCR~jrz7Vay5pM z=;dcZr5bZMSeb!1n7nBy@YdY3#7223HZYt{Tz`Nb3r}d7I(;MoB%=uTAUY$Gq~Yiw zb+q~q>FL+N3e!v19^G8;>`cpdA$09()3yx}yQ5z*7*ws@d*|gj9`Y4-AC4=bTbPg) z{*Qz8r|1U3X6nzggkf}$-I;J+5JY=Su4HBI{flVCbbuiW?s6N~piIsIiMwIgg#@sG z^Lv$7B^MuV`)%}rpiaDMC|_*NNk9OW<2U~@VzrMQ6C<*?Z44`DIx<*jh4_t(?H^(Z z5Vmf~yMP0`)PJK}!b%g11N;V_`y!~P8F#q|7R>j9`)0VfM$8%+7^Dpi$@_g)t&rgRZJw3~ynDx2uc6W)NF+K;r(DIRWQAKsq1 zn$`+T3TAL`4kxbV3=9leWQ2~I(+=yNIDk8e@jWbH`^gUc0In&TuRS4nK1bcm5AV+q zwtO61_x@y;=<{Jfnz3UBCYR)cag4=z<*$AD8rMv0`F+V89%R0yS?bz-y!DNe(dTr^ zNFqIh)JNpld&B=0UZyu2N1@Ga$SJ3;VFasx7I;2rcIfc~bI@C)Z_;2T0jSHX?EXhn z2vgcrWmv|u$_>C~C`QPJ|6`CP<^z8mE0)4`nECt=m6dc3j4 z_m&UkLc6B9k-8AT8xh-60tT~I>Lu!NY;WN#B4ix1X%omWS^sj;9y51Vw*&8e=I!4Y z$U}6gdMr#f%R$i|$EavtNr>s*6SC#1>M=@5d|x6=T__6;XPdlUqrb`H6_;8E8~k@0 z?)a;4wUT|#iCfUA(laL3-!cr&Ia&lVR$-M}ZnsoMYLs{T2|LB{m6%LefI>^~jREqZ%0GhI!iH z>_A)5+kUwH#WQ*<{lZMm!5Eia)ff7&ZNoyTp`P`FFgW@G9&Q92FZSZC8F%##{~bOM z4ZHz>UOaH6O2F2~@^d*j4znu9aJklICY=%mT-HxW`S<|P1yYkzMpf7Ic~aqpq=Gnj zc_GrepDQ7Mq)4R-u03PTZEm>Z-R9XrFr=vcs_?tpIzz!FV8i+ZrVOBmyWqpMsdvJi zmS$lHwYzjWnnMKLRzdqPt!EaFYVdYxZe0xjenH}w*t|+?X7vb5MUT`_=sJ{$aWx?H z_vPALyeJ9{dwXRxd92W4KWpfBc#sKSm6XVs9s@vtk)Je=Oj=;8HRL?$v-@B_l|GgH+h=hVOBDdS9o?ERD-ednoj9( z!;Q`;7;;K+f7Q{_S&!z+(imh_&fHN(IpH`3((({!J#u3%OiX{cQW%cU!^|eAU3${O zRX^T#X2~q7J~@N{KmfJ7N&Xkiysu{=v!~^1_ILDpQ997xQ&zyBe%|<+OYQ1Q2i}2F`pP z0U?UoUhwKyL{=H-ooE5_|Mm&X7HkDyHSSIrZxS_k{m{@Xw<}z|IwkOrs+-sW)|{Ssnw|no&!YcGVc@l%j$B75z5Zt;QmqX z_ZN8svs~9}F+Q>WH^AvC!_P&x3;#_!Hczc^iK`TF5$O)7nYxKrc|*H8k_}ZDqh{b1 zBewOQnO`>+Y^ZnSvO)si7-M~ucLeXrLnh%XaLsLAic+Tnqd!Z7w*1oy_!!31y|XGS zAv|f|Y)y^ch+t0mFmc&yOngX`FisM)p@G2`q~IV}MIG-xS{mZ#1PR0>5DEPVM7}9) zw^ziqt!{S2IeJu>fa2YurnM>GU`2GZmua6ggS^GaHaHYW!DweXF_u`yUj0o|-GaOg{6l>8aip1%wqA8|9B3n@|z#h7uN#P|LmoN@Ix%~G0CftR4L zkhwrRL}S=T!+pg0?~gl6A`)lJaq>uNl)~blzC_JA5aQ0&Jj*Uv?;K!od*zo++3+ek z>zX?0>6vk~aHd<-3AuzZBX048{Q5rStm%HA4Cx9si&pg>w)e8+VKI@%tK3LJnJ1+w z^ZR4nDg0Olp~nJ{O+5~h6pGia2$dH@q^xQv^LXyp`0zdoOs%i=R53m0mk*`X7^)(I z(aAMcEvth9A5p{|j$68WI*^~UqXX*TBQ*Hc5aJN+N>)q?`@0iQCqb!VMA21)rr%MW zi1hW03&AqtcTy%gGJ`Y@8W1+~ARTJ3;xY(l^Sgz}df+1NR@GS(wY_}! zZP@gEh)X_;i7Jp%oB)DXbBEIB>4W=qCy(xLd8}9UYPP_~OIwDj`JbbnQPbi!1}C`^ z(*;q4td%=5)F&$f0FBjgz7cy+*hpih3bw#8%zfYhB+o@aN7Q@h+9>E{is<^Go#vgQMz@qpq$XoapUEB1}+aRCuJ-r20u4R6;Y?2SC>8qE=E&s zsvP$e4DCsGBrm$;N(@J`4iN&Z=0lY69Cn)WF8D%0V`ssdi!(>A#V;EjL>X6cY+~rC zkj2S7Zadp8c;D6^$KJHDD9y&(T5pHe2}@aJ50`RU~aHT0dGJ<(q)=FI;P)Y618%} zE|aF5K?C?$c8=bU=F)ludH)~@Qs-|mGC7QFZ{)9JgiX@|)C?NZd=jY-cF)bJ#^VN_FmYwNxgye`1piE>+|; zE-afJGo$7%w8Z2uJhW0LPNAF$8d%fD037Mlip{9m`>R?e4quql7}7v~n|0{8C!l@N zw$P=sXT6QS`+0zoe92Ehl0H>D1nQuwiy86K9Y1a7hc^DN2Y^6S9a}$S6IAV`Y6=aL zJ%o?(`}%@ElixMFX_3XsvPK>zjmCiTG#6ffhGd9B>#0Kvc#m^%SwH+DV3w29c2FG) z4SYANAHEb69U&T1zLdu|#%&XcEq>VCsQ6N=HheI~ejnLcVUyOZ+-1t5Xx3v7^%Ubn z_Qt0`d_B$F+YtV_-f_2D!gC@>gtVm-0EDT!13xs|XgUwHPpktTW=A3P0z4+gAPA~A z!sDx5+uH_~VxB6UInQCd#~Dht5|^C=Yja&noN2F!@e&%fY5mJUhAvOk9uja)SYR(9 zfHmTJ0@{$BStY9X<{^1*rIctt=c4EyjW}pab|vwcwLI3AQC;(|B*I?v!bk$`)%Cvw;!l(0u`3*1QEr=FZ-hOqNk%3z z{KI4dTKBc;f#Zj%sh=vgecf!vMtST}`Q?Z_pzU$RZn!5;pmyt>q(-v&f5u?e27e8OLn4I2fyk{S7Y z)t>%qYQ-$ogg7r^(>Oj?&&2kE7fnUYm!!(Y##4siTRi*)ab>-Ml z^|G7zO-vIf;?A4@b6*_CnFB#frQlVgw>7JLbtM&aQ6qXB;1angFu`%Lb9O2BUem)hwB!zbYn8r*Z0y2yS zGxkjW?Ty1y3K=71Xm;2p>zvk$%`=>@uvIB;)f}XrFFpiaNY!Z`;k$_yCt^&ktV9ax zs3hwkiY@)kOZX~k`>m0|H2OR11U6EXpV*BttZFc_3qaO2*4F>3DD1nAfx2_eK|x11 z9j^*lZf3$DnLQg(lVlD4tYPKgT@kAmxNT%OP&4J2PBA4VX7Vp{-54LdP7ms+(D?BT zTv|dqlmxdiKe{YEA@t$7D2K>(U}VULu3rKwN?S0XH7ps4PO2}(c+v#{$`P8h@<+%8 zGdvw(2zqFD2H5|S8P806Us(RZ&A4&v^xUlVoNFVE4|~uL`q}f(fdN3p(W326EiSa? z=r+#&Jsyv6a8+*4S1wc|X`^j^l|Ll-e~wuBY?EKQFXfjWfcmaC00rKZW&3W=x7^Ks zblWZpwnWSLhzcdhzwCZ_ER298Iv#bF4I-HAm;P1}^V*sM zfJd)1?X785v{C(XBq^7{`ROr)X?LDJ*zp+$X z%|Ue{JHId@t(UKTdgH*q@11(7TbliWsf542i)^IWBj7&_>B=4s31RmQc5wkA{fN7t%b`04nP?snq{~ zk!1b{vEYML>0!fPCuF{M+wmSBb^! z?tW~L{X^9b_j@Nhfc12eHl0pIWbL!ca8hJ5<}z9XM|K8p0oj!Bimy@m(d_#K0Qkyj z(PzR}KZ|KMmanz1% z>`Q<-yEjjwNSl3Nb2ZbZ=X!ynr{Y{CG6WEkgCs)bpRWJ_G9_K^H>@oVUk5>{VM>q( zO*9M*x%i;VzOO|*Q5@rTxp@8II@?9u)#I6NFGFRNf|?(OPON3G^%+(=!WSp7@!*jU z3zer*x@YOrgnPHV8A&m5c>hSbyD?`YD`Vv>U1OC*vyF&wb;8K#lX1%0+GjnsR2y~x zVWL}k@LqI&av8(#uHF>OHIQ}f&uc`}{-Hf}Y?Lfcl#Ru7tjYyf2e^Zl+hvnE| zRoRtVd1E`rHao9$2{5WuSmO0ufARD^x$~VErL0_%<%j5ECKEBvYmjU&1$av96yrr< zS9@&BsYHe$a{l{TKdYlWgGg|nWe z4h_^0M2%Kk(&0?s1ghwxb?gpM8OAz7A~m_UrOmm@$ROC8_x)Dh=;BHVMnrn}Qz$TK z#6(_80+9WS)`{_=fyxu;kjExvM3zzgW94b-(~k!&4EhgCW2^~rO!DI?ZBpu<&;raa zSFJ4{QfHM~44Zbd6eU`Zm$RxLEcexq(Q0I1bqX{T^cJh+(do{G2gm8Jj#Cg7Fvg&gzdFBdJYu6lieo_{3<^GutWWJ#k6IL3J7pDUqP#?q;EKaFxtu9==r@id~BKYlY1waZfdAIGSwZJxFD-0 z1HK+nKSF1^Jbr-i905@B`?DKAVwr*n`Qqt#k#wDqjU^vROLo@j_PG+45p%d?{gXKg@3K2|oEKz|I1w@&7QG_Q5-)1aS zrmQMm%Pk)KvhPh{me+H@D5A#&3vM*8OZF+H#i-`O)IZmb5K|n^Tzu!i71BA(ZO3U) z=g7B#Os5mCQ7TmSp-1*GahgKg-5#9w5C1nOYE!%&aw-}8Y5mxD=Do4WSJ*WQjG}6Y zLN;cMK70?CVcnIONT$Ud-IorQUBCj&vD2h<6wm&&E=Am#^?L099(%8V!FYCzXo;4!UJM2%6LNm5hXtwS~!=0lafQhw;{2%`u$xXX_X4vE*&vjpEQIJgrk~DuooVk3l8cxUhVB- zzbaMgF`K^rJW0q>b6Zop^7J}(M}wu4v#cw+F6v>ZTe5Nd#Td0C@DBZIXy&-NQ>PtB zVZM6_B+~O#K=CxY>l4;-R_YaJ-5!A<7hz^tv6xa-n&-e z{OK&auP;5Fc*;`t0D}82%N5)17n!03gD5w++3qQ*TolemUTC7ZCJ08865*MD1QtV% zS<}WdkI49o@>rj!d&Rh@pHF3@4VPC_1eY}mrv{g5;e3O|#W6x7!Pb*Lr>K_q8>rS&=@$DGQh3;NR%` z1&~8l9(`2qWMxClxSb<1!Wut?EgLUQPL>&>L6|Gu(`Ogv!&*w^e&P9DwPiRisVwU>?sw{}BSJ#UX(|Ek`#qEF7nOMW{NZ z4W$HPV~4>QuWv%X95L6utEMl*3(06XC`Y?J@=e+R{scx%H^(92E&U@{JVeV+@QuuG|0 zm7yHCEaUX>I|ymxSPsrzS*o{r^(42H1uw}%yoHm*A6uFOK~JFK9Ck}?Vgf&LVqH9{ zL}k8u*0br0HH4W9@QHhV@f2k=jT?G(viM)`k!E0|0bhBCe*HE)zv&sNqW*{nWD7&u zI~V<*Fv?A|i{yRCzkfsmm?KnC`r|Hy3!pc`u~Rj!Y#IiI8HBSzlnyL$t3CbSDFqM}>1?+c3=mj561j9=6`ZqPT$C>G zxg>DVFC4%8{JVSr=Q58Q{Rdroh%G%|yYq%v8xRAGaiPPOK%j`HC%!mP{}Vu|JE1Y3BxQi$8Q# zi|0?^F4@|NE>M`rw*Pt{rY@*M%JV3N(kH^_Jd0@Ii@F>weP zFkfO%Q>Xmp2oKnWlj>xNWl&G;Fu!ZZGuH2K_@#eEuHF#O9LjY zq8M?oI>*J}U9LXYu%>+*pWiRuBWWmjMNB(T zY(qBc7jy9V>EBPl4J{-gpgAxgqy7vkdyf$m2!BHfKpNasPgq2Li)UJ7K7uhJ`OEncjz22i{ZbAc$wJP&*0l(9_qaMu-Rl<`g zv)n^BLOAP1ZP(VY<9f38|LX#z5!Xyk{RSEy=@lWg0;Tk-FP+nQC4q;6#lR%ZHqhvd zx2YO^@O#KZdX7k#SCG1mokwi5gjTWDT3JgSpqTAKoIl4?1Y7O4_aw4a(oyM7(eU4 zpX!)fI(bcltG(ycWEi49)w!ygCI{YiSioay>;{U+bk9IeRk;>je9H4G(6k?QmnXg92zAw`T@YI@TSD*k=I$?C`FbdaZPhFy za}qsQxDhRP!%*>5^>P5ed1A&xSD4ac%YSIg?H%5nS}ZZdiAHS1A8xaoH|wvWFTZ21 zo)dQXH4?3v@?78HNR{HZ~JQ#CLa`rAZ<5r5_ z);s_b^+k`pDh5eiyu(PrCAXU8wR^b~Cx}Q&8qbcTnKbPeF692FJ%ULHqWGYT zfc9*IK4NYdBmQOzAwyjFIFn8yX^l7}m=s5PbXuth%i^oEaYP?ni6%U{F>YH(G+XA~ zloh@lFfau4j(ps`=q;X+vh;1+N+d$x)%6H09n=};qJTwTP<@lnT-c;yAEjI!fgtn; z)6j+f56@01E@oI;Y*38|sJemFyMv`&I*E*Jns20#C*z$OW~!&_h1H^Hxp_5gAYTKK z{)$g}2HJ(=8y7Uva{g%i2HRYUS0#S-Z3PR}DxC2>_d1B(^f>`s&(IAlRojIUjt%MW(ghXiq4BkPHISt?!XoCm2ILP8^|9+_y;7Ec>!7r-o@@kr^6dDz zzQHA87md$iPFiqPmln-)7D!Xz_4aU?wnGg78>cH(v-F)SeT}tEdeH@UwWnlN+9IRm z_JtM)ItO3<*{4zZz{VIju3Rwn|5u*gGI_#va06h$WNix02B(8erUU)(bgF#vY)JKOkNZ(l?hr5H{47tJsw)z6VxQykHberf;5(Alv^}5s zzJekx@A+b$_1gH3;&4(#YC7@>6bnAWkY?UJ(iTcyjCjo90MR?`rp?FM;ppH9yy}Tl zFb8$>?+r?m9Hvc5*!3(oNsWfCCjRpVAkdAHBy;Y0UCjJYRSEgzlQV-~sa{CT1Qz2@ zMV%A!662z$N(Y=mnhJJuXE#+HoH(SCW^jj%`yk^ggEaJ?)X*M=bA9s#eW2=0LkXkG zU2ORM1Xx095^ty;H7!x$T0pU4HgplPOXuODzIz-M3g3iRXg;KZ#F1E&5qt!k>`P_9 z4rvm3>4_|m=3vzut~YU>#f|6rT}LQ62{|;r!p>)p#%0aFLwa^M?n+TF-++p~0S~a2 zkU=U^mX?b8y%Kv(kN?MfuAh^8qU-Vus3w-lbj;jtz3y(#Q8j$7#tAIhLAqovwHt%U z*m;<9Ju<~9o2f}^&|P2Fl#>mG>P)&au6l#~>rMxMp*a#74dA9bF3D#WX+n+IW;-f5 zdK+-fPOLY~g^|5wti$zv(M5JkBW&(%Edq~XaNG4M_@~3xin;}+Hkwv(C9F5u;%d*0 z?64I#yTTyL<{T?nIK(5{BH){(z68+WasPoG6I0q$F5sbT)nN?s73bHMTvC&6~0!h@?YH@ri(?2tP`t#g>nMnw*MGvJU z&{Q9MT0XuiPMy5SvE$fb}obuArPA%Uz6xY{5e*1O-);edbNq%dQqXMzz3V zWKafZE)Jk7FP(3Ec0gYTn_liFT(-voFl!3Xm6J+YvhJ*dF~_ED1GxL@&1K5y6d~#N znBhc+?xq{Bv@m9Vr3OFVNolb4&~rJpf9(`imayUnP9^@v`}UbDoO$0_2~!}- z_wsInMP)E4uc4H!7o~4tbA6M3g*M%m?fF|1i3+pUjx*vZ3%C~O8@AVeDOCJ{S7GaV zc-*mxn&MAJOile1U`h9NuLJ}@l{Y;NJn{%z0WqoP7Fxpo0H#w$4AKr<`3dCO=oCw?JJl$?9AYt)17G=AiOF2wsw*_y7fp~eIHwrB=iXMK? zl`YdfV!IkD%bdcxQ453DDYsj*KY^ktsT)1o8aHD*wCcogKrL@>3-U@WEb0KtEsqW; z05$u63`utHS|eG*EnRtZCKdMaL7os$TQqI&r<+^!3f|oCgaP3<+WbxJmD%S-@kUoI zm^;JVoiK|xz>Sz?W^E|1N`&3c1Ua7u3ZQUS|H(!|nFp9^6p*KLSd4r^mvfk^5KX*b zOKKX>9d>}_fvmM;tj3a$G#=@q9!<}=Qf6cLIIorCBiQaUA_I+ly6bxNa!8`FVbw+J zs1aB^1WMYsaD7AS6OX2?u9i8`Ugvo^#ka~KVdzS?x(k8!e(g&M28AXxboU=qy8#Z{ zVhrO#qf6p)G+~?JQkbmnjjtf|#5;C11R;oLB+LQ{6f|HNLf$L^egO9IO4Nb$XSO~^ zAy`z?dtE@W!A}WQT}0p+zYmjqjMBOhj#$*cTyLv9N7hpf5BTyBQj-^t8i@;M& zkjSbR3%FeTJeUv^7fhBP5mGoTf%2>}U|A7eKfGe&sqC9qm;=4$*Ym zzAS|^W5V-dtXid2wY$Ut?rbJXyAsg%?aN6HF5#8SVyINgafm<$R;9*7&`d1+ouKq0 zj8OL$v2D)TRvhz3Cxr3-=5ujLaOex8(G|YoV`NJd0^9nq^=uK6?Aju?PEF$QWd}`h zMR+|qmW&G_X`}&+`%eKFXi|xEI*HzRSg8lc^=BIDy+p-sjty9v$PprFVO57+Voh!& zV(P7jhyA?kLNl|4c#XFDc@?=4r+9UE^2Z@WUaN$Ad0oc>_atdXHft@(%)v21I8Q?D zHg{#(JnFIMF?z2kgiX+m@^I_^Um`HHLBJ0h%rnehFo?KjGr3V07)n@whzS#nyei)?4*9ZC3W6wmq-HJ$1 zZa8TJ_wbI6`~5Ee!)F`YP$+~|pV@I(tbn>P$`{c!4sHXY;iyUtx(Qf|42o>P>t=b; zk7MU{l`Z1Gqv2s?^tIw!>FYdsICG=HGD$UFY-_3SsV)@%0?2{=qMP3=Y`;c|;2z-F zDQ6S~&`40=q)K3=OTZNfakIQb^GY7b^;v7G$h=FL#}oAywLU7)*)8wgFa=i|`gz%v z&oh>f0j4Ak=uM)d&pwJ?WXF>U(0C~juEd-(SqHx*BulCGR`R!sQ$)wej1X@HE^G(W9)i|NAJ{97_0hPN#!@K{31wRf9C^6P<5GbuY~Lwi$o7L9!(M zI?D`u79BFVS{=Gv5HzS_IPC?FifMF+va%;P8*;x&m#PqMgo~p};BMZM2X*rHXu41Q zLNS-=0&A;WRcUjW0XPCnGzDzsk4;~K60RIu&&%N#RMAL9q9?UUR&jxOG?50g!UH?K zs@f91Zh214o;lq7((M^inpMHCVNxuVoCz+PP@()YPuC>gF`I+Z*!ffkV$HnDo%#Iu@Fo-dFa%FwkCfHRA+~3#;x{Z-?>e z5f$8T9KahTdPiY8E9xR4dn4v6jwEXWb_+&tG5a zax%_xf|qbY8Y?@P02TI089V^H{xK80C$GE_ZEdN2HA%ktZ#u9;vm|)=jU0e|7kGmu zJBag*TZPcP!4x$V}uz#i^xZENZ+i&v-iI-gg@(9qws*f)RU;>qN_6zg@R6y%c?_YWksH0%+s ztqQ94a)eQlciQ=pC&S&^vL;s+fn=jJR4B{e7afxd_t=G@dBx>h@bLZT6 zMcn!+4V5PJ=NY+P?n<{yn;Oc;D~u3N26Lv*#aCLwWOk^?mWW!n9b&Sv1Rw2^x=rtq z3bXvC&9(BQKnEGP77c}8C0?Bq(H|wI=|UyM?{-u32gs!^y2?2Zl8NJl6*aMJ+(8^9gZ0SKx=vQ;)i%^z_X|SQ3syHez2q?OFs0p3EJP=& zsrxb)C=TCtp2PobQILEEq=M^Os1yP)*Ng&%!!yoXw|`NeTSU1MG#hOg)i&8QaRRwp~Z^Wh9K}#OnrofTFDnx zc1`Y%o3B|Z=`j-h7nr$WRGJDj)(hMv=@#=uL=`A%IuO7;`p`@S7_`}5`4~##nRqg? zo@Qfn^Q0i`ON zrIgU?1Q|VY4jm}ONPR0Yp&bLh!1CtgO9-4_LZ5ZiO*M4-qV?)PzWp15|F3De0;_!s zTKp?q*q<1Q_{{z$W}O*_m+kMaJO$!O%OS<S;o?No&tGqi z#-k!pGo;zcg))Uveh73>Zn4W|I_?Y0V~s&w|-^>HzR;kCuHro@Sa(FlFsA* zgg!G{a>>(`rFwCN(@GVYuR4T;21Nk~$0MBEnvy7^j&-5BFV{L)CKrnCYBm>&(0)su z1)KUt{#*5#N@}Xqi;e3MteYhV$VNL0G@x+Zuod3#W$t^KWg`mhORqQiKkBJ2FfkMl z*lDp_GP0`(9jnNmuSAfQyt5GqozzQZZE3g@AgPgpus7J=WJ$cwd;7K`mMT%M_4dkb z)R}Xn?urJ5Q z!b`^B2c_)oOFO8(0bw-|X`OWrWE5^|VQyv#lF;ei;P(D1zJWRBP_-d!BEl|_?T%(4 z!%}X^?U;#B>|WUp1%-FVz-eGpnE3$RLdVq5xD%>8pIALlbDaM3ogW1|LVjBOrOIE_ zI*MfPPLfe1i#urql{3RSF9=d3aqAx{eXiQ!V=L8GT7P z)llW5e>HUqFQeLjxe4j0+OT;1cSO~KXEuN+plbUNXA zL3E0iUWTaJO^EE9B5)Yd+ps&NWF2jbYwd(v+Vm4HX&*9t^(rQ4nT$7`9y8@H8&9nv zIDZ!B6xCv_P{RFlI+Y>x3DbL)(KGQ?7<#zepa2pRVwzXdxan8YpaG9ux)K!%c0QR(?&fMU2K*CA{!fgUD{ZO!!NZjD*QoOix_@CitFxmcI9}EyOq?x+a=V2aL}^Y%#e^o! zI-c8-)DCdn|IBf<0@8<76`Mg%rYW&GywpA@KFADhn4g_p#ds)6`+&e1=@}4mJTApg z^FK6+qwzu$ZD6wMk1leZ$4-?^9{u1Q=(3!pSH$|T!-Cf2nMcjxKv903Z%B-2iynit z51Ld?0RRZmNT#Sz5`xOJb6_B3DqUrUJ;I@RBqVVTT4mGFcGBUmX0Q_c+5D z48v)p$Z&n#*x`&6bXsAMWFsgsum~ zif<5AS!$@=*6T>H(tgpZWDei6t8lDta10@>Z$VhjPYYpT6NhuXhY5ch#H9PHUeZM; z=GnU1KJDRZQ_FM_oTd|sZd z5k9-bo7jk2=)~cw=s`-!6wEudDyf&#jkTVJ zF#sH&VvtNy<@aw`E#pKZK9KV6yz$)oW3x*7SgLqTM*|r#$Uc(X@~oDxZtkP@I@(Hp#@ zf%PnO$#rJ7rP^pM?-;6N*)P65U5-~Poh#Ow2~=6xa={7TvjXB`c*{8)I%18_r&IFW@! z&|TN}KosUb0E&Zwm6aP{6YlMfc?N>3HZ^qKa`R+4giS;d?5;=o-|@X#49j`)UW!KU zDtxv#PF()Cfe&__bJs<0plVbl3;uPr!04!Yf&`N7G2izA^x6Q7JBkxo(UAT(SNgW5 zhDfi1H?RlI4Ao9nznifi%Ox zh+~~YuEQN&{nN#m0(0&aBt#3{#PLS%!@iD2)lQ~pt@WewhE@ohsA9%3v#W?U`w{R5 z-gKom<=>W&rL^rm(ANt9o7^4NKPX?H5p{OW1utGg_DaT&F~z|F@P#Bb#uEZid_Zwn z?L!92-Y7I|U1{0I7E{4UvHWSD_Qn1z!n%moBbJK8f;V0EuOPC$Rzj`T3)uSTk5ZGs zY9@jGNc&@KNca>^FN`{~AW}0I{?{eP-f>POp1&)jA9|x5P7El=jeoAWhnybde-!jg zS}YejopJgb$m9vH1jCk@&}UoU^$x1)%;m=-KHZgfKe85`tkktG^1}_Jm$#OMRwHE4 z$nzN-7se&X%aWmlxXsw;4Aresjtj65|F$~M?I=@Tt9 zVy!s5kR~?Bel|W&zx_LSv6Pw_gJb+p7;H@s00zt%PzUPJm>-u3LFNMjU~vf~{r}NY zk(uc;ODXz9WAP&T!Hz_Qn*~aMVTQq4*kL{@yaal;QFqt5+q_%Wm;S5!bF-2G%QHhLAX zDhWaai39oRLjUBW_&&m<`62dVbXa9IqcbB!DY&VeY)APF`5Z#hCyLk8J!%@QR(i3wy!V1 zva8IP#*8a22q{Y>JTAc85oQ6!Lw7p$ykEUH`8$(mNS0YHIH!kX)d+l5aLLO=(BpZ@xZJTCD16>^a;|XX@6bKI5jN@Kt4f zdqzj-1dWb{@yWv>$PiwK8E5MVo-h&)E|2|MJlyKRc4XH2XSTk~aMR_Xf+f>CqAmKb zajL9REMz6VdxGisy_G^rmim}%(#jXEU7)rl28axf5X4al)`tj=8jW{R8JqvUdWu2Z zV`9DdHk;PjC4ZRYRwcprp&yS-js4>z`bUoLI7jwgSyvD+%{>q2UB$5fWMWP?lS79J z0$D#21AEFz5_5)?(*dD$t|~jpCU~(L!hdJcd9*mx zO!pc@N6>DQG0dQBO=MJQ-2k(m%8z1vwj<6kg@tpyArlaa06xd!s;;#3h{8O}QY575 zp=X#*;aJkoALqMSH^6FWC0YI{Y(;h6%s!D7)Nquv54xzj^$JF}Pew@ZTB`aBTA4>2zQ4(eu+>h& zh6OqF>8hxEs(DnnlZZk>6tLZFszi_&t<#ERP>rJFJhq~eQXPXr-~#%8AVDFeMP_-J z8uK;EhvVHb|NAwc)*FE&sFeh&`=x2uLsxR}q6q(?Rd1Nh>}uW}*m{C^H#U}w+NhA2 zBivODUEdrr$>M|nl)Ej%U<7OdPPTVA7cV3-L(HnRo!_af9x1_85U|cl3O!c*)6+2*Ba()%|j9W{q4ULutiSzqV=Z-NTo%n z$>}G8&Lt=(_AAJ95y|V>q}IR4$^NORiDbp~ewX3D=+mgyzwz{t+=4rRw{HRNd{56y z$V-SeRIPgy)PGoTg^at4V;~b1nNZ-Hh^7J)|HCftOCw4*eM_&R%twg!KEW*G3IR16 zS?$uOoKR^WLIlWC`PbP4974W-btRzhBJ?+DDfudkp-bF#TEUBy1wrk-Cn`JQS4bNBs!h{wB~~eo>eT7Tgys;(!|{!BmoY)`fkE%z4k@S8RMQos zSw-VypKhaYx7&@fQ9OEs4SccKCpB4X+ORi|u?rUaP?X;N?w`WyL$nr$TmzGWVmaT2 zvKJ%@A^1A}DQAB?4*6>j` zhapKLKm_X-NA!9MTJ{qh(7}yf80_p&Q=4_nRicysf$~?qT?mkZBIN=fUf2?#-=o(>HtUv@{KPrBk#iwt2%NPVXmEc%5MS zr;X80&#vohd`YS|PZpPO&d|r>`r>5?-A|iAVR~*E=z_+HyP!{T9l^ASR7k2DccCO_ zRn~tC&&4&gIKqkCJmhD$FI1djfX@H}GY8-e3Ggvf%yTJS91H8qGVUX#FB7UX@w9Rl zxev)39L+_*gA$#KtwL563R#l;nVLlz2^OdUTA#~1&mQNZiKHSMZ3isZ8?Pvl^&2Wk zzgsEr{P4j?1a}ua+>8*5^!;1n>teP`CvK__Iw{R^5r42LEpi{d4bi@RZn!2tvNXjE z-GvyA^#3^&IWTneIjsCrxk&JZH&(y_v%q8V_u|ql6LeP7H)jMev0;V-5Rrgg2gX=(ug&_3LHd?lzqGjx6c`6w6}hJ?3y6MmS!;3vAdV2~=e5DM|Nb62++O)_CF$z7tcyj&x_yq@ z{~m)a>#Fo!!u$k$VkHWB(5u#a8|O{y2mJG?VDJ8seXQkdaB1v773|fW2t!JV4?w#! zb30JBJ^Cl2=mA&4yiNUKsKzVk6bo#t=iZz`mGa6PxhozXf)rjbuy0~WAK8j;LkyJI z5Kl4xc4yneB3RNP$PPR!X@NkX5Ha!Hw)h-L>@z*w--tMFmRi=b<_DEhjZUGC62afq zD#;k3d0*ID8zQ_e!S}}#vEx`CNKvZUnIcJudOrabZY0l?2OM_AnyOA3QA!ov5;`rn ztOJ6`D)zzF%&^>hnoT(z$4V9fo|c0R5^4bw;*y;oH)R8TZ(apKMRr++%p)AQd!(HO z;;|xg$s9I{!Lfw-zyOKc4gO-ZN|S8%rbR{-<|FlIiDp`l@(B2DSi07@3%Ac!;pt&n zy~EcTFXLo_g~fqz!_B?LWPs0`)Q~+#^5A4T;+W1#W<3Qbv+ko=gk$SmlXG(Wyz6}ZD7P3W(EnB!4h_)aqrZ4MxpcQz z$U}R1za8V0tYLinFXDZtaPSR_U7ifXuF3C!zxT4%^pKmrRf#Gc09O85YFT7gP{eEe zP0CiBTJ7WuuVF2>?dNSYm54s1`7pPAYGkh;BwkVAE<2d1tSas=@v%$cx)Np42GW24 z0tskV<|5DfcSnSE!6k%RF4eX zjQwvDGO?S`4|)Z6MDXpq-$tRm^KHE+#9Oc`W{AhoKju|5w}r6>wk;0Qzn|#A3!=X#kxE1F|Za zf|P_MfBhb?@MTfax@o-=n95iY!>nP|f@f`a#7w%m+^Ix38$PMM2?Du#rd$3J{pYm9 z^aQ7K$7mXyf0w#U1ZE3s+aG%V1_TB!g5u(yFQ;m@ufRN=oDmJ3IPk6lt@6^5%*MFGwL`4~Q7j z==4Vj@wJboTT5LsFKSn?XTufj`H8qQ{lo4wh+hWr;nh_whSb?q)5 z<`V&fFL#y?ER08;qTBKQUb&R8uJ9g)AWJDYs52Tc3!K_){&~cyJt=3zV9b?z(~E;Z zkOqW+wbUgC4~~ChDJ8n46#@Vgb;$Z(*-rVP06;*$zx5G8pH?8+ngIVPkMS>pHE6&| zLO;0RLifs>RYl(4^HV{`6kK%Lapd0U!=>L7gYabtQlB=;o7Qm}R{usHpJ!NAQ!aPM zgzBTns3@rl)zmK&1~z(@fYym#0FHhW@WlOx&+Q^3=5F6~TqVCeFR{gB_(%&Cj0IzI zr}DlJ&E>)g32O#`?2A^Dm1({->Om0Di>76BXo3ad39Xuez17T?(zy#u+{G8C?t?7$WHJ1+v zy7Fpo720|NYok{iJV=nwtk;UN^vvE!o1s@p)b~AvJ{o39G#T7PR0@*=_YXM0`SJv` zmskLBWH7MWetFL@>KX$b{4r5yb(t!zu9@y6 ztU67m=@3X;rflrR#JC%z3YPJIlA@XB{>J*5upjzvrhen@S@7GDiAkJGiV6FXvv||U z9)aF0<-pH8C9oLy6^g$rU;){0{|qAo9R_(zP@}w3Yvr4{XqJ9%X0A2`!00RG?c!xzgS1?`xo$|L&lEEUC}&Y1XzaA;xmUU3qjC{fd;d`*A%>T?J7?i&M*(tI`qus zsBOY`8irI5))`@UrE0)20ZS1!*7vzz>+1YbDQ zH}Fm)FVVF_9%~8fpdx>mPTHwa%BuFq`A{*b-cKrsG|7zbkvbnz6J=9cYKtg!P4hP* zF-O;-OOmLAD6Hb33n(pY-n9=ne|`?b9x5TrdnYTD*Rc4zk+Q$rl3Kc-5rSzbGc_+Q zG7jVr00+Rfghx`ox`IOqo$Q0mRxurAU+}~ZaOV>}<&GOw1N`9;2#J^Vo}P$hszzr9 zd>^1mEnfs)jurE6qoAda@r`fW48IYXZ#{|EU0KI0{anak!t77*vP){!fZfv~d=eFS zw2hPh1tW|@vN?9f`cArweG=dV9z?pJZ^V)69$ z_~7LwW@zUOI26SY=hy~h`=FsNMi>u|HLsV;#Pd|UU)4lJ&dV6DXJy!Zjjsvw-(P5l zhoa`gL%gvI(F=QB$4k^Jjguj6(&$1Qh0YNvs#f$z;(t&vY-9GK-`XQ`8Q$Sji$)Y# zCKK=iu*`TP`H^U%Zh+-n{urkapj08B0}3{RC4+{6m+M{|Ou2-^eR;wCadRnzrErcx zB;_4WrMgZ0kE!1ssIjXA_kv+oxQB|#bl`;qt2^%A-Q=bAM&jj)%Oyvzzvm)7dAHir zR#1C|vr{KUClGw^-sFw$Del)U&)s2+bGb-uk`RRy6$+^gO%x^PN>q*os1}^~4X-i; zmnKra+zdk3^XMx{554v`$RE?iU` z03eqO#P@eqGzP$z9`ca2l2V~-UlfL-v6LM{B?912dys^xr&%V958g$L-tymjBakRQ zXPaZGnPy>PMYOHurGlbnZowk+`zg_PiT&v%9qq>jehjcau(`&@YBeG4)vq_eext^`>pM-er^J)HJxs%|$L`C$(wVh@6)!JWi-WY4^7v<7q_5 zQ%~dIWqKIV)-_7TzBOvRtVvIhhA+t_U9FJT7CchuGGC!RtDnQiiCsSkbjxYt?;!9= zCRs$ksPr_74ML!L0WmiUfLZ zjnD$vK32h?b$9(qGV14meRq)q30-OmF6#LKx2qPvT!u&Mnm zE7XwJTwD{aXiOm{=H3mUCjtNX_2Azq=VG#{ul$|YrMn5ann7W?ubM;*CR6c#ao`EB zo&i-ao}xS%50aD#R;Vp|WZRdaecRSNlI0t}qn$dOdf4$$gX42i0PcEgt@sKPQ@p&b}-O&N;;eU2zd z*onOoP+_R>WjoeTnUPD%$61|2pgI$^y9>SEEEjy?vvB^U>9BLK30d1kI8*SADbE8I5#uYovT&s~79Ccya0scAwwwmBDJ zQlpR-VmU)PoOL+D3rl9z&A3Xt3tS@0+hFGGMsWE>$GBJCX_vfUnJOt5&aTx}7~c2< z%LQMx@A0&0h5f=T^rN&VHqgd~@2`syrdTOqNp6hkB$qtgGlM{L6)uXTz@s3yY9K8` zX^&vsMIgfghRqKb4c7?-kjZK9X|oB?ciRNTBV@otq_VK^$V3JSS;1N<;!A zcdY2U8v5woeVW*gAL~(!vANaO+$VN-D8UB(pw9P<8*_U%rk#k!@f)t0KjmUIMVBca z`6(gY<6qqG(~BIlVU8w)8M1=!)V=J2%)nODK9!TYo)sZ-m|m&=!u~z=!;wYU>Pb*| zXVC$J z#|^Jb?ZwJmFs5>QTdu-Bo4enXR&`NB0l3f8;yWbzhR(-eUz81niU#b2(8OM-6AV*F zP9wO^@u0~dlM$y;B+z%o>KgN&n#)do=zdb7EM$+tYX=DY@rEO>QoQ`VFqCMyE#jTj z*io+_MHUMZiN+Y7oVG<|b9@}06Lv4&>izNC$i8T}Kdzhk+%gqOA|8sS84$}Uy-M!k zeq}b@v!GBcZ4*?s;wI0DxtcLT^kfa7EQ{j*khLm3`zzrU7pdo% zP|usBHo{lY{r)E-fZ-gP8~{i!ia-DX+})|b1`h;fw>|s}jgAwrf58gQabIn`!D8%9 z(Huzye^V)lfFsok1avww@gXa^cPd$l#EdlLl3M8ATEqb1Qm(WWo)gvc#MlK#s#bJO zP^HGb$~m#B-pfPjthh#Zi;J z@{ar2yB#v>s-79D76Gkp=&}?v&r>%zr(rC!I9zXiAl&df5qZyTBo|(>FqXOd3&ZJ%dq3Srplg%rV@ zp1YAV+cW+~u6VeRFplkP=Y?csReROyx+xpt9}mMTa}rK zh;`Kl6%KNI2KpH|;H}`}ubI&s=q?*CyrZC3@CnelN%fas@bbP+K-GJ|<^p=G1MpdN zER=O$#cT_^W<{rZ=?m#H8dEj$=6xFdAnUNo52<}wd$=tz0mr)YMsELX>1&g1Ze|CK zp7{0F`bS=;F((69QKn{@zP|KL%=+AFWvZ6HXx!>(=m8mgTn*QYNlmqgOZm5CaBH5N z=5sLLZ6L{v2x7WYj~@hYynB`TOGF=*x;;DGMo&turR=MohK7|{T?zsZgC$e|M}q?b zYDH~GND3KZisUFs^nrGwdt7ju#9oIjrz2sIgQ)*^0uoBUytPT!EyoZJxe!F~2zf0dEvz0-QJkXrma^OIN~ELwdjz>I zTsC21kjKCobZA!j{$m4|h>vvYy$vmM-&Zn;~ulk6|YeZVI_u027x z*;vNW5lH?^2mz?KA6h9yb^;HVlaN|zrz-Mvgbs)TGFsQ!-6N>%P;8+EsJQt7Ntz}nh7G9$W`&mK1kg=qoVC@oobT+IsY16B(jNI>6q^QB@Bi>d4lSQ* z%?HABUbJ`bPUG+lA-4(Pi&)dMGjh_k6ZTdQ`cVS+0j*64v=(p0GhHkAy{a4?mYDNn z$M>P0&{rk!J3DiIbG6{|3G&Jvxl(E(39@D z?&ytv2OokR#`jbpvKsYg&@}iddj^UHOag zO}|9jmw6_H7(9&G2BX?6ce%hR!<**=+4*ts?-dS>Cp)LZub4L}u%x`tN zqvP4nJ;dU+*`(st3!CY+C%5?SaSQ<5y0-8~^;^gKF+Wtxo|d9k#;nJ9OUx%(f&E#| zKkG2$GWw{0OTZJOGurm}TZ%gasvYLKkdcTv8ZfzZxH>Vyv2*E0&Awqq090;DP@?v_ z$Te?<2S}GIg$6ZeNOOz4c%MTOUgxn+Q!}^wd}xI5mE)R}Q88Dl)#ChUlifK$J|_T6 z*mwH7h)R!ZI8$(ut4X!!pB}iXw7d&_cAoT&aOo^-k7iPIT6RQD9|>*%{3VrttqQE+ z+q*aKe7OdQ&(HNx8QuR#j~MCy$BX+F8@|o;7+fZkyq+O;*ggJzDBp``@65T1heEji z$RmiJ%&&{^xyml3Kas@;Wu$PRrC05hS3M#_4Z**WYDYX0KY?I{AaM>Oq9d8AhwqdY zAOVHyPm>@-rb>F*|5rHX!5?QegQ}l;@L~8)f{Kob+!*!4E9{jUOa|hwv3!640b7 zutfmjlr>S|c0AX10K#KYineLYV68O{NI?ex010J^v96$7Mrtatt74M}a6kK&uDHZ} z2NIFVu{DW0YW$hDU1e$iM)o=qxF=q4d&UYL)e(hP-%A3}bI={^udOI0QoAD2OU9rU z1(v#E8j7&6mm_!J@pBH1Y0!V3x{5ZsdrUN2o4cVAIO*yEXuQEsYjsz5Fq#}Nz#bO1 zb+_*`Rtu%$i)1ZLW2@7q2+K%OvKZfKeI&{%AEAtZ{drEE@-IC)Z$^74&zTTj6$>{Hp*Q`+$ zMXX3!DQQ&hB}1tKg`mxGqo_9NdfRXTGzoo~Uo?or7|;MZ?tQH> z@84)YihxvZ15YHR&TNflrR`3>ClvWr|5jWp&>yF8o-w<`!Bi3pXb$^c0e&OxTGrL6eZOC{Lv7S4@nFYT#PMSe0&RaR;@`<JR^rA2imdNtJp)2?6)R2n3iHz^=y7$K@tu5gHmD@`#lKkZ_tscCX0K@ z6p~X5uN8_wNn2V-X7d6RTKwz|a-H0DA<3E!kWXKCXTht&XDXz%2HgU-*83B}8Z_H_ z7*i!&pYziz1D$Xc)=*b42(&8WK6OLg2qYjllO2op&BJdJLZk$qtSkRbU@&&)O3Q?rBOu$$)TvmnJ**na9PYl3i0uH;yo30x(JBzVX5Tv+IL1qhLtsZiWfz1N2V=6xya=O7rW2m97Rhn>MD?5U% zFy3rp+;x!WE1=P_?=Z4k$Pn0@izbICT6~v{T&G}S1ay2=pfO8*0TFc>kN=BsbYeo< zT7Qo9^B!iawvY8xPpn1#yoawG96)G*d;o46fhJQ&WS-HxRzE%-1!?JQ*k}$eM&?dZJg`;$g$0zro3zOU8c|lVqt4E2#xJ< zuyz_O>%bmefFHpC+Un0_PmvT%xo7`xXSsrC=NW{{)rL{vyJ}8Gu8A+9FWd>F97Y2^ zPxtBdE8m-8XhD27joPy>kN4_K$fqi)4JZ9|J%SHE4DQ!$KA};ZmmbBp9`g*wY=Ryk z#HZm?SFF_`HaVGGx>+|ugQDim)_SOK?*Dw?gvb>Zf*c~|xU zE0VT-J^@mDN$@+8?M6Hb>=;@|cm@|})KQktp8GV_v*xN=o9@$^3eIMuM#Js2E=eB$ z6hLMSR3q^~L&c!5TJXtHOB$nXkgh`w^W2nGclfLBT6W#*Xf_ zSpH)V;hRe7TG-j1Pme9zNV0FfuJqj~B*p@R?^lNx5aL?k<2O5Hi5G;M3%y~h(wA;l z=$i9PiFAYPuSKa1Fxsb9y$YmIsK|XS%6=o?=2@7`Y(EDo(6SxN0b6(GfR34v88B5R zt)Qv2Qq)_QGc!b@Wc=v@do-fRvPHY^M8?9&8tcE!h%Av0msWqG$8OlYrU%k> zQ$AjmCFxJt`VZ5%T*+c#v>9Q`!!pY9w5%RC+dn^N@kbU&oWWnLW$2MH(A9l9v#Jr= zsTW8}-V69b=9IMTqEul5e&FXVS6N?oit^f{|3U5$6Q(r%E1NoF>*mNipL-_RXtr1} zuSnTdqWNBrxiie?72mGEHCJV!+!b~?2oz`z)vwgMOmaeeszI<~7 z9V`;|lSTboYlrQu!*{QM=K?axQOMV355Uxn#|0j!ATw=_Ek1UvI}@l%@Zq zH0^bTt`$>!Fex(Z(ljqeF?cnFgykfc6DquKfaev#%m;4D#G zQj(D@!xsSwIE4{b0abZQ8m|=yIQJO^E=_1(Pm9~&~N~>s@rNG2l%>!nvmok)-h;y|)9jWMR%PeE;C{y&d z^nP*a@KA7DjM4i;VjwLDOVuwr`$d@5<&~iun$W7)L@X4vNQ8X@&aOYemLw>?1D=&F zSmZ;jJ(eeuf$#e)Z-XAUw3fLW5fl&r(R5cP7|)%9rL3SZFx?F5cr!8yl8*I16KWBd zQ*QeRJmv0C%yz-1q zu^G0V;@ov1Xiqx#)N6uFu4O^>RP%90{xeYD!TF^~+C2BNy$`@J-Df#ax7e8AQ zb=^t;prJ=p``24aU)%BUr}(RDvPu*c(nym}xoJTuoI#r4%%oY+AEP5m%b#r~lN}F$ z775=)%soJv_^`OJD_$0GG?1rny z*;Nc*)l8W0Pt+!b>*<(BJ?z!GT;Gzo6hY6bO zBE<%ck=FK-8wL5%z87XNuOLL!@q#dqv+;^UKsn5f=oS~Vp2x|?MLIV^N&@f$zcm?p}y`L zU%rkWr2o@DuGp4DZn2|!T z;Ece;q4%S6HrHX4q2p&h*(q4(&|2P_hFQxb=iUc{dY5D5=1 zs=K_cQ&qC`j&wLhhU-!CN*;<})Vrw3#;Hb;o55>veONtoNEA9kIPHm@TGvw_rImkN zghN-lDMe5f$~^SK$tcH4JpSM>i5dgAAOh(e+K$>O8Vk8aG$y`OaM)=uZiq8}$Sg}| zc6M-;eHQWDwIee!50oQ$oN*{d5?vzx@02z!ayV^Rqj+ zJ|_BuDzo^Jf0$&Xm&aS(VB4c<>$@wFR-K}eX*Edz#SR%*x1GnBzrGK2yB8o=-+4#q zvc1F}ACeB*`zBj-Z!9qULg)w9OEaJSfC!9@t7S4FU5w8P8+WNnY5{UDYtDFU7{mAf z!wgz`sOwBxmnJu~8Za*h9U0fqL0*ftf43WrghHd=u6JiEP|(OOqcLQ@1F^sBO z4HBSQ?&?LzO*O^W5f~dxVrjq;3(Cp<8sTmdkOLn8OX?c-LtT%3TZWCa-0xaJKYA_I zO^G$d#1(V)EQPEKcMP2b#l*$~w)pgUudF)Pm3RuWz>9ct*M+cB!H}jWwXx-t>u(az zgk*aT{J|}zDWiL3;0^{s2VPvzMrYcRnrbAdvE7M2DWv>hp)D(JmZ(PTbynt{I%DmIqa{a zzHr3`|5bPgh%Lx@`e7aR9!Ie?q4d|(!Gg6r#@uxDEEjTbzOm{=G7a5}0*;*p?7;F1 z;J?T8XzLkCKjO*~Fi_H43N(Lspzr&H-oHOrEqBu~JZ>mC50FjcKHnq&ju1MbnVSR~*v6G@8Z6(=`|7`vm{Mf(pIgcv z9K!diHWzf54@FCx{oLyu&ewndFIXu47Gc^eIr#W$pVL)j?cN4)=1ckyN~E+ zhr!G~^n7#jTB3a^eH(4fJStqG!i?Bt5$Yf-A&+H zlEd%V4b5r;58{EbUDnY-MHS)tE>7{z#>yKQM{7_39;5 zQP9ynHWM15Dfz>J1wV{bD$1nkA z_Pa*-&?KuUyE%`{R{MLEu7@0pUGIchWxbyBEkH2d9b3QAQ8}90StqefL^1{#z?Cec z@tqmHU%ggNn2tC6o(Cz7s^9JqCH%QJj9h80)jP>lxMM|NVRiAcTv6%icPpPXK7;1K zXcW^3ZVR_|i6Z!_3utrk4iqfdSGDurNz4R#_N@r|k(^+eJ=VRUK@7!S%Js=;$RuPoMTc6(=OvSNrCN`BB|nXooQ|BOl2!#f1~^2HpxC_qIX>ftIe0wu9)q z8tCX9_h_lnrCb3w3G|F*FWGRSjTGv$lCi&`cs;Tog@14%E5rjYdN_0h2libmc}@f! z?LYa6ABtW0d|YyU(emx*-^X6(6U+Y4a%L#}*61C!6m1Tx1LJlJHHryWT)er{{6 z668p8mohtCX?IT~#vP3nJumX)m{v(`eYoY;4hs}WI3As>Tj+qlK zoQi%G>HO&i+g?eQA7wEkPcb`nGX|*Wr9xAUmlrLW3U^)}qf)j#KqQ;|>FuT1i3S7_ zX#AdioDh%+ZSkSq_9(+6i!R^&WQ}uPeCkRJ$Spq)JB!LVe{Bv_bqdp1uE*9VV|2btv3%=t!ejt&?2T z8eo(KG|;}69IE=tel5ss_<+3KIYM-e8Qa^BKJT}c0EE ze^xsN9rd*rK@SzL-o$seKz`=#=9tf@b{pGc8hno=V3G);VhQYMG^f$ee?7E_98-T7 z1m~hnbZL9nGNrImLD0qCI4Su?W~{Yu6Z?sePa1Ou;sw$7TGm#PqB>g2wN%wa`}8va z!cjq(AF;%#_bM47+qDw12q1_wx+oS0bD~vD?O2MrdT7rzXfx2q#TDi?-Y@9RF01`l zF3)a03EL#NP8WEvYW5?xIfpb*WNjnD%c+9w0@*&r9_ z_O`F&KUo)Z2G=g1J9*EUw; zU0ZEiOhL0BFk#-e+{ z-Z38a*ssnNy*$Gk!f`V??rMl@)AJ)tia^>t{6a#h54pcYY|b<7uNZJPh-G((tIQ7y zM4A7z>cYvUKBF1w-+c;n*o2L1C7BW*Qq*^d)bY|djQt_cloaP;f|*!|8S1uw3h-pc zD^({%!A@mCy2g2eB)rk4bQ4h-%8cHA8326Wcmiy00$Vr}u?ua$?WKkhBXUiO&!wJd z6+(Vo$1?G5W#DJ$`2ns-Iomcs)6Q23&p@tP6z&dswg>|Mx0e%H7!bghG*#C6p2Hce zIALd>IG(M#P933tN1L_AsGViW>JWz-vAGqd)tlHYU><~a^|1h!{mRSDn7*Cn+bDZ? zezrG}l8Z?A>pu^u2WlQQXaX(9Q;Ubq7xpKA;vjZ9#{n|@0Y(7E52cf5SZdxy= zBWq8O|JgTsHSw(w1e4XcX+s!hTyZtLD13}FR%*~?y!6T29CDT*{&+b}3J%Qb-KT`u`5kcjhp4D*VRPGDHn zW{H`e6#8@C(T3ceY{gMlj!R4~B$gkxMu$O7`Fb=i5^Z4(=LQoNpsa>;_&kw9;Pu8c|O$HZm z@tOwtA;MVF0>K-%Re3$n=R8K;ramEt67B{p_uXTSl3(hVx0_#dU268FtF~cBl%uwI zPVf6y!1Ktme6o;O6Udj{Td0==XoFS!R$1k2(1)vp0m-9;#5WZtDsB**3@0E0=K$C4 zupkkKc>VB(cFBfp@;v$K23(ZyJmGKow9`02cS4JdJC6V2XtW|m;}e9%PJ%$^jKfl==QLktS)|mT8;=TQ6_0FowTXUS>l*iq;)DV zxmOeCWMNq0(qE$@7gaJf%ZBuawnIS!5UP}F{5UUJefpab0n`CQ(rzgC#9nVVn0y6b zd+3}6xE~_zgeg9fN_}MD;C%t&@Yf%?O36)>_&(DV_X3m6#~iNv<}K@FBe2=TUY2h+ zQ{e(lh{(UH$roL-EA@RrRT{^?gA}bJZFUBIMQxxb%EP8f0HMgwuoh5{v`Ro?c zF3R?4Te`xKB+?O3>_BRK4&W87%xDm z(m}yERn9ja2F(2Erc1&_8LG$kx#hq>GD*Ayw)UER z__xA7348L!2itnhSL`R7sX@s-#rJ~+C8JtIgc=vxfmojmi!F{Lv_1H9T10;D?>d2$ z8))ludw?%DXhi^)|LGacH@=PBOeE>T5;B#PjuYnwDS&3&I`4;H2{E9&EUUGX)GqYQ zCCXk|aIRe%s~wJfkKFJYmB$~An-x-o`|OEm(tM?Q&8!}2Ei@iw{jK%%zN^;S&}h8` z?j%D%NV*7!0zx4$09cAFD|M)Hur&cC-)G_o3l{jW}Cv`2nCKN!u3 zt6dQP1B<~Si&jh@utIDRI`Ed-tUN=I7&r#X)78D7#1c;R2u^}lXZS%lKdrJ>l`eB2SHMe?N zArZtxwGc>CH?%=$Q17m8ktO{r(%7lIREq+I8;?Ce2S)Uh8(Jl>oD0)4`0gI~_ATyW zoN)rhG92(4>V2Ra8s8L8{$NO~KMc0m(IZ;s>!q6RC16~gM$_?SQXFAZ17XUHRh^d( z&8;ZfFHAvd*vg}k@Ij{({a)F{uaKH6lGggC}K@Di#+wMO3T#ZUO(35?*8c7 zlmhd6g>j8qQhhd@Q>gV_g>++A4}cU-`Fv1199f@E-a!YeKz7;~E#S(b>3IP1O$?e+ zT=`ljxZd%~?L#B4)kHNv8!I&0+osdMVTkA-Z$UPgHt9xQ(hs4n6ZiGcf1ayosozFx zqLc8}01LbVWnV{FiK+>0`fxlux{1Aq`_!@5KSW&2J4g`;*fgc@e2v#qoGfZIyV?K_ zd?o;^Bb66#tXK~z&=4%Z#efeL(M1j1MoY6uJOf9tb7k^qLZcub)0=!ClVdd2+qbo0 z(Wu6p3wY>OVCVoC^7DyNvm;nTp#wp^JCAtCXH$A|iq#8j>;O*V?U63By(u5Bfe0yN z4F&PeA#@F3`0k9JcGP z_eo8z%HuojDoIAL6|yDeb`^Fp5P6(Z+VKgp07G(qe=(YidEcoWF2 zK6fHe0LVt?Q?U6{vo><3;w(#ILM&nDrGr$Y&T$J34bK_?W=>r`A zJYo&&iT1eDgTYl*f}hwNw!!$0>P&V^dSoEq7Yf_=rjeW?*i&@sMsW5&qN9F@bM;H~<(_ zB?ReFMdU3`N*mmNglNlm(_+>Xz1wQPwDBAXb|&i*esv!CERmZZcEG0BNSItX_({h~ z$S$#9dM*X)JB2+l_43$^EcalEf4gXcco^}j?E&v@K3;-|XYw>MS z%dm)BbQ)1yE6>0Dd4Pys!?KWHmF=%D`)do%0|p)!7_TZ+Z7T${_R0@3uYD(pz83FP zVq=kf$G7^fxKTe?B0l=9xpI*QYK_}F+Qlc!U)HhUf)V%i63w zf;|>8u)Jw=<_V5C@CxZSbM9I-+6Ou|{!d3si*+%H3S1MVK@)ql2nd11(cJ)M?<%b1 zieZ6(A)o7U9X(>CQ(SIus=p;V350C!jgZ8XsGrenr=I*7uwAYaZyeQe3#KorlS(xj zK5|S~lj(A#Z1B@uqoO#~le5ZRq+D%97%m#9pKaP1Gs^L=lK*6&ZG=1uTL&~qyIZ%S zFP$a2-O(&jRr39NHX;cZfdO)wvfD<2b+^g;8bo~-j#0@x!+acJZ>{>rRHh;eSh?e= zvu{$e8cN5v+$G@!nqOxuqQw3D1izgIZlDp5(1@NRyG<4V0j4|8Ag7uEK_a~Xihu$J z00rbYIsyQ%s{x^3fDJb_Nl7iB*pfScYOs2%YMo_qcioJSp)_>`fKw5U^j~am> zaloyFrd1qBM>p0t#5mv)IGebE-V6uc1ht>Txeja9CY83|VRsG2_U8l{P34ViaE zI0viuPEAQ{UX3+fB6&(%z6I=WgGA^v*|vY;1+5@Z0KEYNZNfPBo{Cs^0n88pHfJzG zu?T=t9fBA{oN33NnYJY|NHO=;GkkK*zyX9^cI|UMt>A*CAR7c6prP30sAbUzWwfW= z?%`-_Z+atKMnuf3W<6miXI8R}uP_sA4I*_A-hMpnr@#R0cFELQohx7ttnxOz%HF`o zxK};4GFY}_-U>ZNMJr2YNlQ?R3s$`@%!~e_R0<)ZLcT*moO_A(`b14`zv7rE7$3)w z5)3{h*SSkU^Cxh9{WY)>P(rA5*moUT_O}~I(9O;AvbWTd##4f!B6$jn08U%8ZY%x z^FTsfLH{HoOfE{qG2dw0b_zzejQ2_$7z{iY)S-m{9uZHFFT4_f094C`Oq_U#0E`Nt z*&rkb4e(+M!5=e!BUQnGW8YD>BeLEZT){paS;@V*ZT&6TsQqp8OCF26rMy872~<+o z5LoyG1le6=JU${y)y{Je4lRZI_W)kxGGNWg$n)(2yxZJiJtk9cw^2j~*Yp0Cl$R*( zO~zfkfO7pAe%dpW2U~d!j{=jLN_sgl8Zg6 z<^cv#+W|s_d5~{M+Do&uMb2wKPK(UGh3))@4a>ZH!(N?hk0b+ySX$q%L(EqKL4W`x zvc-9@p*TK(0Kq5#005Ne04@UqRsbEE6}0l50|Qh{M;#Z)X|X@*v5ntId3PNihu0?5 z+}66h zT7KucKd8bW)s<^_OFQ`qC=@UkrBfq^hvB0D%U>kn6SXlOIzU($tRfnK7lZmtqyPnmFkt+33q2nb@whvp#FLS^YPx1KW{Hb=3~=)0O)ZnV9Qi|; zppj%`XWK>7NAO^}bn*}c1hAIk`G(*<2};5_R&vejF1=DC$YTvIDUlTZi-|5xa7$^w3L007=zb;VsK2nYeB0013j&;S4c z4?64*SU1gRCq{CTUK>q|>Bq#~@$d*0^?jEw6RdcoyC~r}xxu4+OkAo`Sr-tFwJLdR z&=g^#)N(P{RNy}W>;zTk43}pCAcK-3E__rqDzFNyNZO{gWdInS?eh29AgEqFUdpZTzCr=MPjvDQ|$wv${p3ifb#ZEHBV435(_)Zoc4c z1^Fylk$OGst~xZ|FIU1Ogn20Lii-kYYqrS<0ZaPas7|o@myMj$- z(#y8-ExHg1LWW*0zb*g)(1{jD<8kmkjNSCt5OaA^Z#J}+Ft6y3xWzIgMIT(ujmI5W$@if=)%qwm1#(#JznYQw&NH~9i=ri zVI(-w<|N`N%EgNT%>YQMO&Uz7(UoiFv9jmzi>r9k^^66xblU@(Ir>nvB$4djV+pwI z_h0R|6zlBP2)FUe2gSb%s}b>2PnW%B()Ia{`_MB@)4uFu=jSJ*fCs>U2=GPT2CJD; zw<>G45EbPSO)`ROzC%lZ68!pRlvFE`0Mymz?%n`oKmh8xAsz@(kI=j46tI!BkOjP{^B-F5Vs?#hHz^Mk9 zkSHn+`=XOut92v(ZZ38O3(Z~Sb|>BhWmeBdsJM7aMR^7BJ<$LFM+7XY)I-d{l&S$l zfB*qfV1bU703H|AA?@Zhl#4LD>Z((Z2}wS>T;$LNPS9ZE3w$CfmdYV00(N4gpS=j# zaDqrrWpJG#on6Lo>G_BstM&nFId>)}==X1{EdJdT#Kyfc_6*+y0Fk%ec~==_2a5FIl&wV(4X9!VLY<(hCghA=tM*+Mb_4^xi_=PuGKU5Pq28 z2BgdY4YbN}69$0sZ4y{%yE>kci(n|8jsfrq_{3z#eijo~wa$8SIL-s3(6si{!r9&R z%lLqnYKoq=#hqm2-1SBfmkS=*+G=a4u!-RBblJTogSnXQNuamTkrX>zoicCYUpwr_ z)H#s^zp*&BC0;&emQ?Qz2RpLE{&cDn3Ysa&1=v*2@KZrGlakY%5kZWy@3?mpj{f!M zk$hA+C-dMP?vEsG9?=9yvR4~emKz`#Ze1>f`3QoMSK@MyGy*IHI;_&PfN|&kG;5#$ zn?Eg4gGwX7*0+eQniNC$q&0>WBl>jR!yTWvAW^X6cshnnWQ|G2H1sbf1AK3snKR`- z(t6yv_zk*_K!|)%lL3DE=_de9Fl?fYuc;kt+m&U-jCuOCj>ll#2WUc2oouu2d7y}v zBz+TmI8Lp)H(=Lb9#IlrBn9l-g>$CzaSrRN7RE z+EAhFmsV<1Y1jA6WTt-K?|c2uod5iv%lo{~^Pcw|XMTsvd4|moszZA-^VVn%9QgUd zwuEnsv?-l7mJai}Ru$mtx3zj~K>>6B-Da}h>%zws+Y`MYk=$d=D|LcxH-_C^ z^uu`k$$L)x;dXveIH{MFwS-0<+f5TzrS*2@jM+ir^Y+KGhJ1jC( z2j=aU`;e$z@+4jLuQcLBCE*+^9M9d}vGe}cr)K9ea#Vx0mW31cyT(PskDvXigJB;>?GHC7$#*JOZFKu3|zOcL~X^U&-(X?s$lix$> zwX?Ko>3u$4%*U@17BN1=trK=>>*e>PtK67ADcAGa>A_pEJBQkgf*XIo{C_}xZDru5SDf&w#jSB+d8rT1zSW?pX_Z~9bu(|tCSv%PtgLx<-qnA2 zS2uW1yVhu?S!Ts2P8xJhvEs(My%@ZEdN=0}rMppf{ z&Y(JMao#{>EIVq0sH;`YD)*vx;C=olR!g+A$M-Dvvf$Li(*zICtZsX0)l$DP#hCf_ zdd9!J9HuE~w%?t9@!6qj-L-xh%F{OIb?hwlc{z8WZfNwNSzrJ0W7cP8Xv9!B)Ey&J znol)z3Zw7GRP^v~2F*Tm+@3G*YhvBsk;2H*W)Z%J{B#a1y<(sF=E&l|9h-udjP23I z`v-A389NH5mppqoP*0=hfN&uB{?)ozPEp{Yy!;u}+AB|ZAMTF(c4PO+8qSn?%SuZ! ze$q)O)8ASC9e3c0OX7I2rmAN5tdC`DkMo94oqDt0@6zi=3)8@;(|45UGkp)Iu5YT$ zncsBICLn6?b&kz~q0Hx@e`&wpa>71wF?Zy)VEkO3o&q~e`A*Ai@|V-fF+SDXdtDdM zT}!6z*w$ggPnLt$he;LQQw7B6>3LP&!bQ~=I$uO7t;;!eJI9PkDM`(IeY(v;#2aKh ziv3-9x@>denH9xTxTz0Adw1MDw8xs~{KD5DkRJF?Xw#f?+@T*1Y#ZWSi|2QoKlV<) zWtWBLEcFeSTD`(tdKJR#GbitV)47mwv9xKZkJ+c)|6zBVxxme^F!kV2T4bSrO4iKM zbC*ZU-(2JS@NLvqyb5{0)V|4(b+$xcGqN@_tN4u_+37@feFr6m?Z(3Ifa2Buhr++HJ)rbtqH883q<)$C-wv73uvc0CxbPS#xH}m0h!u?tA{Z(}#;jsLFMJrA3=`9#zWq+m?8s)zy{do9w{p z^w!hA#g$iCq}|e`9ueToIi`5Gu%JmnQ==1RT$!#C`^ul@pa%_(W;aS-X6Ze2ds^J+ zJy+8uy2z@=*u3{zQ^SbpgXO+pts9E97Z&au=6o!OviorO5;KUK^@0t#6h(`;L>+Fw z$J!pF?KW-75oU+Y!)ASC2iFy*so$JqW!qDc;Gh!OY|DOP4lUj9LC(K62f_dxlF-Lf!p)5bLj)44b8hBgla0AT`{6se$wA~bLoQe_&=9zTN+`q!9IaK z{xa+pv1MR#=Fd6p3QMAH&^KuRyXRuU<;0eu1#W7J-J5G>^F+N)`+ptXdcwfJIU*)- zvA4s=z3R4|q3Ps-T$34IE~-%lw6$*?uLfPF^lHETdv?ug-9x?E)V`@*dzv$UWmQ$o z*)Iy^ZGC4yPyNTbl$uL|Djd3=WrdqYDr2YYS1YAxRWkoS1YYrH%h zgFfZ=%E2tUBEXKE)#gG$;OwS#zp$S#Upaa*cgBfEgXNc>)(BnGm)L>Yze1(GJiVUt zj#WyY^8O2r@1zd2ZCZb)C23N9_yu>)KH}5qpw8EG)>~GdDGu4$q1f-4)OOo!mT9+^ z^KI`;-kL_f>4%fURriLhGgp+)sIEJv_byoB_iyZYs#`VFTrJ_qvDkOA*cb6anrt1$Yq%~hrMyY!O}vTCwgUR1pZUpb;T1hvoN!0bu+N>kP6%RvG7 zWEZpVPuE6}7u3#GJ~1|?88Ain#w;r`y9^fs&*0f!Y03a|=D-Yms|YHDI*^Fu@emOj z5{z=#PG|uI&jkJeVE}Rx46v6ll;K0f^a&mGKrke>_>3EzAea)YgSeiUDf4-2eJoHX z{B#ytNwE^%bO8_~C&x!atl!e4#As6nQ%rq}2loE?%y6{l+A{!{bSB%GL3d_yO&M%w z4%?Z{`P#}Xw_F+@8JAlj!^;ZIzrTE{fv(TRFcyCsy9|rq*&$lUcHIFux9%R z$=C^TlB>xHUW_SUVYvxxfIL$Y8^)tJT+Nd7i}OZFqna(jc8GPWzyIPNU5T66y||!w zd4b&jtKa|QZ0SsAIvwDD&j16h0Mq*coRR=+DgZW&0JvO4-{L0jYcd{k3O#bqm9*tj zB=gENc3uF=aMs(QhSG$d8b&RyBfcdqF>1uH6sLkEW=pC=;E1L8I9?@ET!-3HjQ>nP zQdhiQs6{YIg3&47kx`ZDSb&-gQ}M6Le6jsJpR7>-6zItKNuY;XlJQWxV2YGCCBZ-v zFy@{51WcqnYMM%Tv7hH)CY@(;lfXivgYn4efR)szoDo>dY$-5Jrf&(hQa^HbK$Gfd zwt&49V+I{$*ca$BTYq3lc`O`TiZO#68KwePiitDeD8-m@=dZAf3TZ;(ZFJ<;?$|doU4;jFdGxW1wI&p z8+7BqG*CwilV1xyL^s|riNGm6A3M$hH-bsLhd2nslzxwL0kH+j;3NdWGWY}wh}nca zK_wo+bi$R;LrV`L0eavGq=7l{4dF>lCCpLY1HPE13_)kyIh7h=s%}WV@jg&ckMm!je!# zxg~Ly?15*%M*ICx0P7$HV|2wyVJnem5;QU&>R>1A#&OKV!a4v0w+UmgCjP~EgWwE~ zEE_gJF!FqS9}daji*gm>4ay%tACV535Dh{Ig(Z*(sjwPTZ3IR*`d0itqX+pc*alIU zy=auD!x}_J7VAs@$( zj`o`f9`O(S25N-ZZz{^O(Q_8c3oxFkpigcjorqV&5^@M*j)&zaS&tfPAQ$beAR;+F zcKHfA{T@M5sB-cOih(il;Xf=7TooR_GJ4^P*o5fik>T;tfzioHkxMlQZBR&345T?k zX}OeN$BCh+sW){R&B4hPrxG^Faw-PmYy9ixHa^~01(Z$6foAVtNVaj-EUgjZ1eD(AX>vhbDCAxzpHQUMv=m;mBfmxl0@i{Y)W+N2e!( zkc~pNkVkW5Ik9MLfzX4-;|V-y0(VDuM<H3;JfEYfTF6prnau3 ziG>}<`SS?BWK&h5@#V!=S~V=dXI7SY@h0$f!;M-0=2cK1A468MJK$Mtgu5xO*LeP) zPamcc;gLU@My(8wH%*O=iZ+c5Pl#R?ZpyZ2CM1}~I56zFcz+uUg{vx%bMXa{*cSzh z{s~_tyr-C_N_k}+MB>0c2Zvuxe#XjnxJFIbDzh;fiLH;=R#m3si+Pst^ToWTjGvE7 z*B4%2#xKH2FXmMMl%sH$koJ`G{j9F4m@u0+<~AFOk?Y(*OVf diff --git a/media/so100/leader_zero.webp b/media/so100/leader_zero.webp index 5f8c235f98debf90712f1705fe582bd8b1d4d0f0..fa2963be1f2b1059c8e9fa81f17c950837024f25 100644 GIT binary patch literal 540388 zcmZ^}V|XS{@Gktsww;Y_+qSjg#YN+vfA`?|AA5t^Wsy{blNG@-Of6A2FFYIJp1-ApccV$=$`_KkV}lqdWbp)IXf?A2$DA z`0sz%_S?#W~?m#lMezf z0sug41Az||002}H0PvLn1b!3%fnS9H0N5q~&};YajUi^Ega$A*u;hTy%)-sW2_#Bn z%aRw?Gm4pk-9>Bb)REid7*0Te6?%LC}G3#aHx8@~Whl@-hBKzo_TY z!^EDkR`ZQWWasW}>J;Lb6KGzfc_aAv{u{V;BKQ{1WlKD%`0XLl?*(X0!(T4RzWM{K za)STnKj(ZOXe<1(FOU>T%>-7(-!Z;(Qvz9mYruzZ^U9e#|199bH&Glg&wI;X{>}Dd z@1^9M!|7Y`=HQ#C0=U)_d(!jWv*phPGz0PicRursYLB2MIi1G6{Biktp# z!1#-|uk8eXoO7hFn$NUK0byYO6EYCxj0hMHy!q5G2ZjQNK1yz>zp}nGuhLqfZh%0= zC}0l}@N3iG4hW1DmclAfe&9ymqn7z~bjvBubM|WklRHho_(4|JA6&_ddEtFw;YW8+ zeATrX8i*Vza@hWI7rKv8chmZqJXB*a7alRb^Y3VwA=3DKDxANqqWRz#Xy+xoYw5(Yy`ZF6NL{=h6C zqSJ9PK*(c+kWuhAaj0}-Xbmz}CS_G5ve}C;5 zjn<_vo4GXam|=X0Sg(q8N

*%aiI2u?2LrJ?0Qrz396d_M!8_SQ;5wn=o~x-sQD zO(6v7M73+0igPb8!fI!$UK}*`vk^9hMPHTz7@HJ+@lO2K<+QA@-dQyRxqBy?gePWY z3wLf`UCEeHe3w|EO3tHwQGHzpsbdsOoM73yoIH(lA6U_*7%@4v@wXjpoawr%%e@i@ zC!YHQu__L`b$*ccwmOv1Sg0H+>!_>3X;gaajRK)C8R4<;I=CvzQG#fg7}V+cd$)tj z%+r*`)P?*(p8eJz|h9(i0NrrEI~ z$4c_Mb5N#f8OJqB_5<% zPBGC>f`42iM0+uUAqJ|0Cth%V6UlWXV(L^-$4!7YH0E*985lNKqKBDKc$?MopE+RM zI8d0wP$MShgz93ewlcHv_nij}_AIDX$I1EScBCd5VozG4@7et>^sp%47NESo&8SQ*H;w*#nmhn@~~E#YMd&Nyno!Y_9ED0;IH(ymXvUEUBI zWG#v~J_uYnobMG;I&~Wbf2AYgDUqqj`Y;t43PFuLl|@$g3{#F%B2S(Z8@?^i(yHts||$zyVglA&VMO34I_)cJxu#~7P?y{9T~^L zbl$Gu54!18?=%Sr9l?@+bI%-K27E!`)0%$#S&=%Z3GwbvfeV1V1SgALBGlV!L-~35 zC{MEIXCKY9=m%2@JHepoxl#@~yc5A5)QEV~bP`Eo8wFwlD{oLQMUQ~J+Fl+X1&aJ2 z+7e~-H@&(f71oYPhr`A8E(A8|Ty9W7Lk)-RC|bGT0#udp9+-7L1II2{;(7pz4*sNx z$jeDF{6k_Xc6*DngIH)iiS{6E*}1Eq9tu)N8$XL)zNE)4LG~pmiq;w`3FTlXQhsB!nEpx zRI~#g77q7F1WoUfLSd%JOd!tKJPP3k8bP{KLH^x6RAG_Pbbc<|lded@YN#MttjUj>sy{kzBQjCR$VL&48(g zrXu%d7%-{CeU#{_*^R?6x--J)EHvf`X)!$9_~DE@mcIx!TbmbGdeU0=Q0!Nk zocB~{D71}wV}=~@cnD)8!rX*U6*QC(DVYVr#h8IP*Y?#%VBWo9c`za=9rwl9244E9 za7}oSV+KX1O|65{rH_y!i%lP28vkb7Yf9w`I#-9VRp< zrX?h(U+IL}dXU`I<1RXQjE%&k8}4C)hwap9$uxe=aHT&v*gi=6(zLi@+)WPN-??|3U5e8ur;1 z0nwK7RNc6Q+pr5t?k&n%9s!lqK{;VQDHQ6QNyFl9v{uvmZJfG_h%<&em{pM zSQ6!Zw=l~H-fn0lHv~j6`SBnkYqZ%PKTj$o~I zUS=5l^qYElxcx$~=?^<0!ie&#Hs{`0@A{SkOll%=;3b$jDC&9*OL=WxpEBuRXKV{z zXt+UDb-ziL0xpk%_|Euve#w|qA;<#Gh<%3XM;_m{BD8ea>ndKl!?K4HvlGvji!!HM z$;hoOViG}Vy64HAZ~wCwTHm4PX31juszId`m$O%5O1XCVtlZ^C%0slWc1*T8?(wXn zGBjwZ^LWojh(P@>Rwp0azQ7h+@aeFzK%=F1p++8W3OdX;GE9BqB?2WXdb z%MK%oy5!0rXcHJ_gh;B-@%dM&>V?3xTZ1&vgPH`Rkzp59ea>O9{jZT;ns zOfQ|({HMU%fG$w2<|G$;PVS6^>nFxhhK>#YM8-8jrnNq~^S`6K32I%C0tfnm*5#2M zrCz|xXNJBGsa$L_57JXsUZ_1xGyvG;GdYG_c{!u)vRaOl}_CqCP~u7a}oAlU9mk>0$nC-#QOB+M2bOm-$xM3r}|^C zBh#;%ATLiA(@xA)0<1&Y`a{g%y5ND! z?&C=ckN|)39Clz9z7#Dm`moj-HLW4npifla#)g`7J|ok?{kDSa4Ns4AgFmcdnp#gIYdM&9;7?lR+3xLf@05){U^0=?C`tgTP{6*2qUxxn2E89gw zjG4E(Q~wapZD*u@z#ZtH5H9%qx~Qj8=vSnr7chxN*y`m#&Y9Kx1??=UOLwfUuV5-t zV)(?&OeBR-+ux{ms8F&B5%!ZW3FqaHwYRKAlcmx~ZFZZ@+k)*KJrnFrNg>2iyz{5+ zl0*c?h$NYTJP3I+ip;Xy){CBy_rtCN^va3s>3IjFJ|6VJZwmfMl?{C)?#jUcNULop2wQam^b$g|R*iIHg&XOM}#&POCuzi}F7*nYChz_)Hvy$tyl*peVk z3%!oVs0kCFQkW?Q!ozMe=4c=3QloD^pkU1*q6NKeZs9ype-_WXKZz#ypbzA*V^ z>U*Rf6iKxSnMW^n;J767Z&kmgIM}`bEO+=Kj)d*hVMcX~vlSm#2@3UV^{V^s*^TI| zrc({o#Ulz@Xj?D~AF}upBUxeGP*PW_6dCg|2fHK(i`?U5coJ6KEcDA*)x}Xo%8)uz z;Vu+O5BM~X2e8YSI>SlD-K#VD&Ufkhy27u0RF;03rCytbiXfHLNEV9rH^WU7CBy>>Dqf=FEDXG% zGQ=xltPr8Nx(8}xpE49L)N|Y}(Z}$GN)wO1VJu#=htx!Wm~`X)vSs-e=HMCd*f~0E zcGHKZR_>li#e;rHWG{fVOTMK8{%vQ2NO~Daev-ym1%L-zzskMQccp(mEz1pVLr`GK zq744$unU|%WTbfxUjN9R8x?qA8K_Pe9O;kX{Z*G{DS@fUOw;{xzeKa(HZs)T(`Gwf zYbKovFP?HY=W@-8I^{+*$GJ7CQead&B@Aueq-$psY!F$m6lI$;Z&o@4C75LwKNF7& zD2Gu?g4P`X9X75`T%>ro+}+$u<~fiDWdNAhl*3OoPaGb&*iczXXqN2X>vqBGwrxL1 zT34Yotk>4rhj=Pdw{Hdnt#^6kSl(hZ;ME%jjH}qV$K}o=9#?odL zlts~in)PLw36tCRir~0;!MfGUp65%hm&Bs|qP{nM1Qk7a01t|Y@B9#T%70#G5yi3m zT;YVsG4Emu7%7GX137>{ge86IQ4JBQ?!uSeKg06&SfJsZw9V!>}h8d5{b*j{0NLIzAy2dX9CGthbYWhlmxWgKPzFagUkbmsAl6` z$9|K2Po-r!mcF|5%M=lCYq{*gIP#ND@DwOum|jGSf}Lbp3M62snh-TR?bjbdtaKzt zl!L>m_UA9^H$awOrM`F59>(=2IXL-S&0Jli89G^*xm^DRsKJ7LZMz9Rl4n+-O*m^j zvfo_Do`O*l1j8l_bG+|IIe5^jJhP9A2g{YqWS{En5i)i#%u5|ltuz1Z=kI3^+DfCc z*t}`C571c4%oB62td6XC#63ktuNXy+Fr5T_}MmpIqa_vOOb!2Xyz0u_77slNv1XrUd=HK5- zSXbs?$xmsfZBq=1ENMY24X)wHJvA5Tb^Q`pVD*4b>@7+a`0c{$vQEw##+FF&6J1&3 zb*}mPvDtZ1B2w#=jOJY5_q-T0p-zYIx_n$4bq*pfu2qkQB449qbp{%%8rw?vEqpp4 zWY#aRcXLC1;$1R{Wzh~UbImQ)6k{`X*#$W_N3NigXiT}~9b$&jZCPGX(;WvKM99xlqPbiwK&vD5!X3fncKZi}9 zyZJg;A|5uQ#hvOM#go)Kjo^@Shh3L{MLA(HM=m7Sn88D!-h-n>f3KoE=L_;im5M;d zTIoea?iuCu#NJ3;Jc!M;d9FdlUs^)GCKkuA;x<*>tI2S|qXg*2XE+xd6}3MXp+_G0 zu{dduuH_iMMh{WT=4f=|Sncj`3-WQKI93P#pHS{-Phy*|DE8!AEtG~X$0*l>FoDm{ zMD|p5Le=`)qm;hce%*$1D4(Y=i5&FY`tqtK`6^|83Up7T9tlkN@<`t!Z*tm>iVeC^ zwZ^{HFin$mk&+4mgg!V0@WRH8t>~|4wCQKu^!DH4xk(;~Ul*#51besF2kU`8Ptn)n zr4u93XBQt?T$eAvoKC|%n`XWWcTXBu{ct;vi+S?JSwh89o>XlE- z*z!4hg<)yO%DgU0lD2Gg=wrjiCAC^l4QRORgbCTxMjs1CV=G)X8^u9ZY)-=aBENxr zz5YlmBFDFv*T6YL6waD=`c0R`UioI~*D)YRU)z_ua1u(Jc@{A8Cs`VXPUMuE-GRk5cv({Nb;ym=V6Fi*e8YunwkG3p7v0`n`-|kRa)pfi?+gixiyo zP4`tC5)dvesRYc@-&=zf3R!Ojh^pk{|231hunZjdT#C@L?pv)UpEvZCxH%8|K`r&C zvlX_Oz)=8=g@XYHy|$BRYq*st9R>qf&ph~C1}7waF4GeY93 zw<{MB@?!q-ExFa1robQr2FeY}DG-K%CsNOcAK}KUBaMT2ugd{u(s0!D{a(pHDt@NF zISjeOQ^I9UZ9{&&!*~=3Z!cVdB46bQ+cY}0B3^Y3TGqp zxlHq$r=8Zz`4K-g7L9;cFhWr~jiQ$BV4QHgugLQtCb>T1J}=c$j_iyi(9OwmEC$02 z?b!{`gQGOQ+Rg%oD51+AhhqhuwqpBhi=)I_co9@sznVErt=MqbLdqRf2Fm=_^#hZFPvF3qi!TFf`Z>w3fxaP~D-6q_NS6^Aru^JkEa6<(i$Bp-bQ+_CL5S=CP_hd%F7o-xA?gx7jm@(sotIHFx65^e#i z!D+`?cbSuZ`mpus~actPqOmB}3n(%$_ zBdT@*tPHhxm_N{~ z&Y-^eLseFbj|ROpD5R&2;l>HSKPEgPl0U18rFkx|4NynA8u zFA0HPx^oa~OpSCgk~r*5FM{nU7lGp-{nh>~h1r=kb&4d!!uC2(p_G}LT7+!T?Y)<# zzFclBDT{@i?j-QZsbRVy65&@J9x1Wf%^DU?%O>&)fnCi`N&e<@ivZRDCfOhFAnnW- z{Q?ox$DhyM9qy1e5}}Zms@Fy!qs<5|6$x z?bDO^uC#g$Ub>D$+D9@jB8bq|@fJjPXm~QSS0clzd154_nLq`kqdy{}%e)Sl4~?^^ zmG<&C8NWnlq0OmrEBlTSI@{T4E^XpXm)DUW#rC;k#-*KbK=KnFWHoL#T<6`5K|$@#@@dze%Xj%P6tH+e_P9yH zRay7@6f__dfC9ZgwSV1V2kTj$bGcSg1sb?}uEIk^%I&oUUk|j)Wh|qTp?W_sA<*gn zoT#}={#e6=sJGrEBrK9&mRTCB>5n;R6nYG7%^A=9Eqwn_lT6!70<&A) z|5){jRIv+-B^5sxf-LSJXR=Wz%8*dF>JhUajj3!tgP5Gyxqb8ALvw!wns%wsv0Mz2 zL@6tzY^7LRcJ#!dJ>R9xYFjEi zFfraC1@NO=mydyvOj9wlXTF^3IIWQ%3@ts7;`(fZ{8dzw*woE-x+AoKHa2|w>5n@U zF508;lft_TMf!{CBpGS7vs5G<4X40ZfVxc zz8>V*wb&kkY3|IH{L5c*2?2URof)#s9sy5oMrQe)QCgP+TNsCZQzLJfINo|Ru6t80 zYDTEAy~M_)IR}GeNf&oG#_zj$Zf^_a)g^jVo5Pz9o7FpzRM+FO49(KC@356o-{S!|h4 zn%-ivwzGYKh8mKdDspG;%wuw-H0w-Kl)vc6&+jCNqhwg3=gQ#N&n`UfRZ!!-4&N49 zlHbGL62(J15`y6-p85d$(hxh;;}yerR2 zWBf=av)Of8$yDEt%K<7dI5M1AiP+7H z;w<_;AmGgIk!3&NZW6Zc7<$=_Tq+~fG9}`8Zf}wJ!60{Cz*v?QC&9E2cqI@T8VZLc zp_+_&UdnNh!vUuUmf$9C!>6PAy!?bIBHdLOKBV4Z?hmHHt0s=JhFiqB@qK*ZLLJYj z7Pu8uO`2>dt$x$-3&WB-W9s_!dA9$xNv)g~puLYtD!$0DR|2=E?MUyDfYe9_ceI+s z*PNDSwv8=8?~j9hHT{(&bp7%xEEg2V4L!Vra!e%` zB32&>&QSlTk2Ll|^8USxMEdKU$s8Uz-m)PVhVQvJE98wQZdt+6`Yq&CQmMaewz(4i zVM!P={70kqQ4VpuG@Ug>b@&UcQ7`0zGZx4g1{Q&~<}`%FXo>npEXE@2Uj@Ix9`O>q zhs@=K0w|YgBBg=w7w4sQEKIBj66)cL5~czVa}{65;J+QtpB5ezmK3Pi+X^0>UqjOx zUYg8Lfl0gVV6d;h10>4@4=Fc1!li`!5X!J}%G;4{Jn;ej^r2n=~{&vji$2DW5QExw@b4M7bpc&IZsiZni2z|-F zo$!;%QZcO;b_}fRj;kv?zgM0Xckiu*mf00i+y;3Y*mC`p4N*Oo#(4xkSnA49bs9sP3(5{Yb1Qj~I z|JAQev+ZbA@01=l=mndGcSj78N@W#kD4H-9!SgI}jumtuVWnHzRxa5Ri4=8iIQ4sw zFe{dzE911m@hj{fFg*n&8fT|v)~09x&9z@?G74EL?glOh>;0Y1w~PXILP7HQ!~~7& ze@lLD+ZBwJve}q|5wQOdn|9hVPU=Zn+pxvPQA_n$id=9|%vA`AmW6ep^7Rk+lrD^ zM?)I?o?zVyfi~ZgwJgHu=~3<_Lg)pf-wi`6a!ucj551EVq3u#zate!LUuI-mvl?!$ zh`6ctWI?Z|Q6NX*j50G`!BD2IBQ36|9uI~2@>PevCOsCs54SnJ zWO+m8BAj&&o}q_Q)8fz+Lm!+O4z|Cf@l$6 z=DC*Y4>Gr&BuoCMIhJ2cA_+-AtiIdm=)6023-P7O2jcGGcirgyG>f{DQ|T6d8qKTp z?hEfO@nK_G8*;Pb`yt*|k(+r|-3u#ZV`ubR(z`$%4sXWauO4LgAA*IPN@E*i0d{ww zrj(>~5EQ8q_$_1YansFTv~$E%i@N6ewsiX45X8{RSEb@L^t(q)S)PQq&Oh-`-4y=( zQulMh>xeQ84EUWlH*lcW2Wh9~0TGGj=Ia|WROtMBonzA&E>un?)W72L7W)IdP=PDL z1|I}|)j?c~_UqxA;ooNfr#0sCG?AU>5S9x85`O~c_Ff8Rv(5^mSZkRt(L>H#>?l@L zb~S!Yyt{1J+*UB>HMSyI8^E8);DnwgzwxMhlGMDQ@r7jfG9paYxH>H#&u|BgX0 zF=4Ldp%+_Ff7cbPlr6hmQ>o^4M{Ow%ZcmlNn;Z@!AJ<&}A=d z@yp<4FZHi%A2I2hwMnJ!JXdD!_~8oH^a+z=WGb_10+vc=#h>cjR>im7p@uzozlaG5jMU!1Q8$YYC|e zzv{a>Yih|?H8w|tt0T!a4*T8f+-tNqiNd`p3^}*PkrXd+4HI2& z_<<)<8Eds=SNIpdwHQk@evK8ZD~IZ@+>LN1r39Ew?}qK{Fwxq9wDHMK)=};4 z%@J;~i+p{!5s$X(`FJC3&8Mt+JPy9;X(Uo2mEJ>Pp#^4Ju2er)Q8uRt#q%25t4% zvZDN0A2~d89Lp|Q@@u#Mx81b)iY8Xj*=Q>ziZExuC#$8vF0C?-gVRkj+a&_uM&fTV zYY+AfclX=kP*1$X)an^6H6k$TAS~{sPFB1gok;W>iQdJPMj|EGh4j{xfta^dOzjV& z1yc1fU3V~YmT^#`Dp$fE)>CQ*cF4?3Ijwd9SRJ zTDRg#)eui{>^_Qq?t3j5@aKqLgPvOnq__B1&28LqUCb6n%XomrAeSGIKFOsr&Q;cZ zMMMkm<2J@FI__KOP;Dkqm7Ze`tjHdH;{ow^>q>06OZ?ZZzPHLph)c_-(;uT_25kQ0dP!3LVS}QscU@91l42vW;>F?DTO4B^ zL&a)6cn7Lkj|C(?E~I8RZ+q#G4k?2{2z$s5k9)j}v<*jGUq@P7LV}oPalJN4fG?w2cF)%4vIy;$4i*i)1z&}G3F5ov*R)vaLYY?tcuDAChDRyYIRNry#v z5PQ8Z?IEqBM)4$lAG-~1%h@Up$lQL=DvJml!WGes2J!XBGzvQ= zZ#9sO#A7ZoAG3afHM5CARoM5)%+P5^l<8YG47l=vKB+4XxH+hp)j3h&gphgDc!S`z z3w}9sU{9Asu>LUeaPY`LW*VgguY$Mw1A}eGtc@!4dDT!Ms_r-L)D0@ zm`f4t1n!0TQvxbiQF6rx1U%ci-TA4m1j~NEED-6x@i<6Xw$eZN>ysh1VItrO%pBf6 zC3b52P34}KOAgkGzsV;o9YuBQ4DGPc(%nO6Mh;P%9jt#z8!1evP$HBw*+jZW!Wzu} zCY!)*Tr)bq6fOgJp6!$a**8H8S_9H8=Pynt;m90ZKq0rwfm+e&{hVms>B;V)N9pLO zqW9(B7ggEV9bDbjM!~PA^po<|_m3OJ6`jo6+xLex_J*AViED-7VN-Bj0izqC5#kng2 zvQWG*-nN*rAZ**)d9wUb`#>~Vp`W^A`sZYIgSTd_p3e#XSwckse`Ox(Hvfr8Pvy-2 z!4FA3XQ8nHF&si}rNtK}L5BjL)M$&~`z-}PS9sypP*6UFXI6%gO_J$QYZ-|?>A5Cy zCYG%q3zJ0_PGYg~W-=qq&3Sn~6kTJ?Cq&qDfh*%46b?1Um^0V151*e+t@uP|XLvQ0 z&gdsO`$}KLX9km z0$7maHI@%URsbxM%_&9iqA(-Cdlg$3t|-_)%$Eq#+T4E0w|ElDVw*L2+H10mSYirp zw>25{yY8+Cw^9`fVkx+{C^F#8M0a1otB~IVy6zzqByPoRt~`fwoI*>c;H;kGb+B3M zg9U3wgg2&{@6Vxn!RcoN$s@iNcQk3s`sVx%9JhLi zkg|9EJ>^6q3_v0ehs<$u@4GFsL69>T{nI);F6o(K7sV@xeug^#(A-rDSQYxT2*?k( zE(3pvX&w(a_?=tak;H`)RF~yhUd$2N(N#0zTn_5RS?thq+H5I5_-DM^GqwsZL1XAA zwH}~AM!2Sfk7409QQX5g?hP4|bN%U%d67l9&hogR(v-PHNt|r~sB`6mv zmHFDsxA{;UWHdS~X!*vD_hhH5NS%oL_@CKycCo8G`BM02vh3IdI6TUzx+U>Q-%Tmd)sNU9PgH`~|G1|t& zvc1C6tIpb`dm&v2GQeKBYP}o>!@=zPG2>}^uS+G|5DKS=56P52U6DMTN|ipETlNQ$ zje3`xrTX0qR<=Q{xAG7-ll-7RMU|^%Ns6od z1!L_b@Ybw&A@h!Yd)`UXWMsjR29#Fo> zw5fcRT+2&X-GNenCY=ppbznIsYFoo9As8hLPe@8so^ww>%UveuClR6YfRYekK77JE zuu)l=rdVLOOlWUP5DrQ#3Qq*IlVw0Od#yEN3&w{<>{&td+5?UYHpY1dqVM^x){8u()Yc>W0jt_6MLVnXywc#w#6I+!J=)+ucZ1A5 zPqf)I244iomdEz1c_VvL1vaqR1T&=Hj4+a%*44ZGYmIzf&0u$gXD?499O~Y>qyQmC z2-jNEH1Uqvg^raA@is*wI{tw8xhipPd8LEm6rw+o(V2TCjnM}@o8zLV<)-<}l9Z~nSthPt%SYE`5sl817))uH z@7DaXwIO2ie-{4@?hQ=JU(FWN``QZk&dozaR^)&Wtu%iZkQBcEXt@@|J*m=b{>ivc zk0t3?*Ixl5V?&s_CjTIZfgutyphHT4M432c9@vr&EnDW`>Dwku@i!!=;H$-cdy<9H zS$-eGI?n#7So1mds)3XU$tzk7FKWX@X2~?&L)DX)q7x~q4@?IIdM3Z3#S1d5!8nU4 z1)_3%a$va6teqEuq&?;ruDSRpT%1v2)|m$F03RWdSLGKiB}Hq0mnB2`SfTRk;(Eox z?61y2YGK7LNfTtX&6P7%nZgV-)_u&*u%2-gp-_9DvOw)0=wF=AsO*#>f9OQ^#FkXs zLJmTB{pu25V;(9B7%|&Tjk+LTLg0iZ!K2?~30K#x)rTsHq>i}RCHaM~A|w7NEz5{X z0NFS491#9I8bjVSe52Q*%y9YEn9l4nZLV&2qZya768+vwYsd;}e^QfXy^#xP!BL1F z$E*HiK17qxddT^k(LhYa4`0uPxwo8Zl8b&$Lq4J+C+4>iFn^sNPArw2AW;#U$rT$D z|7TZ}rh@O3Qz48wp5-FN!6Jwy)!%xDO{09t6>A-RnYieQo-4wXV<{omV=ExPxKLYk zyn&Y7#~qID-gcp4LLb;BwtK#``)aR@8CO*;YZp&nPjNnof=luN;n$irsk4{E4MOIOA&= zq7a>7JMjZoX5YBX#iNsRh67)JiUiiH7CUhLH{RE@_y8t1V&!pdPPcU^B<6}PS?3uF zsymC)_C*4Ru5bdDk2?lMxityvo$Sw;!$DV~)#MH@c?(smSz9tsUfdZlA*wsI(l{oQ zM9FX)Ps=^W4Sp4Y_41`MnR0<%ijSW-PdRyBQ>djMFHVgl=p3})_O_(~lrkO-CE-)2 z>|&-TNcN3q+z#w_EqHaF^eztCj0!x*E6poMxv{lMvmlz>A&#j)dS|jVdJDL!y~9OS z^M)E1{u6Zzh&nJi2>+PNd!!RA;uEG_nODMnCQnb|e=dC^X%8*F>L@O5#93e~q$(#Y zaGtol4*3Lbu4pUjQ1`kmyu$BwA(g! z4i$?FBqqqfdSosB3JBOBwOjSu1i$2d3d<%!-oVd-J?o4CkR(ic-V6f;jrqG)Si|zNuh}NcRs%*kkfX<^;J`k|~Tt#<< zYXySzLy^;d;q;u0R^%I>{{|#w*TPB2=$(7*vz@$2L#^BT7nXNAdl?+Vj8=AqG=WzM zuO^6$x%UqgzxkC~j8y(`p@Gc172vcpYWuS}W53r-$K&AGh2JRKuBDGI!`VQk_ohj! zF80j$lcyE3d2&SNr$+b|?<9JZUO>j3;CGj+#)`v%_OiV6XZfV@m#whd^B4lrrF}Cv zYdsuajUOMxcsYD-Bw0zvXp1wrUG6pBM-GYy<^Ws^ViJIjRcJg|Lh8pZadN4U%jPeK z>57>b6ha)E_~#!~p6=A3kjLCgQcgubx^Yk$%N31ahcV0q(ye3JhBfG(6Rkj~ZwQ0~ zAYpS8gQZWJUYwmC|V~-NWDEFkRQF_#x?*coe^HY=f~#)yEbKgAiC!jOxj>H!vt#ZwbuuW8C_H!wA=A*rF^{7)#Wi zAlat@K*Ky=$v-%YQTTBA@1%ABo&sDphfQaOI-5{??{V*2$PU_E*lCh*be8`QU1Xe) zFlr7WdAmAgIo$-0ggp> z7IKDp3vYhA`?21WGOtH0pF>Ra{M*O)__>xpwnZ`yvfT%cS7SUjSRXZZDs++Znkj2A zXf6Gn^zK{KfAG*JMTUSabDzH_s)%!)eXE^Tq=l?(Tg6o@wFSGLY7Y$IRlVtGK$ffP zGd`Del79H6zuGjR2g&{k1QRlp=WXny~!vxd!PG^tRYOfKt>I#^0SXXOnslTq3 zI6q&gO$IFE2!qY2pGJ5lji`1ZK}fH^1yUhK^HnJU)QR)JY+>{JUsLORy9#v*xy~V5 zIe{PmU8@s`-e@IP=I7j%9v*>bpStvXRG&&L5q0;hVJO02tg^BbB5MU2M=X;BuH(SgiZ8iyR~0~rYHUb+eTom`Sw)mZ4?&pFlTLaJ>K z7Gvq%M`1}QehmUk#!Ijm3~lv5;7?bME)vilDG>%2!IvP`CMUy`h)FNP=H2gjsG=ZT zQJZs5^Trr(_7ZN?`qN=eqcz=4{v(~;N2lFi9#-qsAN<^(65&|oBr-T)Vj&g|Ld{m{1b zFfao#cX!oqB$8Erba z-;brbbpbO!Mnk4@O*Bxo(*`o!SLYh;6`xxsyp(wo;1c zu@#W)9*NcP)=em29rukq-5cbN+!(bRG(vmkKxG5*Hz~Tk$=fZ@td5t(gk`EdCZfuF z`k1wY%BCog19-d>GN@Qaf#B4i8IJ@Y>T%>Xw8%4Mg{mRe3+j1qh8R1w`9J7ko#iK0 z_@qb(K?cQue8`5|f|U^gprs7>ts~sXp#L8LGeFG0tN}ujp zp-sdi00tSAwAk(P!NHI$ljKOZ&z?#O-1UC6Bv?knyV`Js`jgxwy@$q>dAqV^U+B3f zl3}>BQlo4u%7r)VfH^lKDmXuH(;BA3;A14H`oiOQ@0qEYdqskC0Kj`bI{;n_Am`jc z3ifkciZ6#iq-+MGp!e6V_!-2C>0{!E%Q@<1%I`%!;V-ZP@~r&&Fi=?a(Q-H>6a1DE zGqi2Z5El4rl3LkyZ{@8W+{`f4`Q5|d|FKs3vekV84bm6?kOB3yeb#(7hKgUfcz_Ba z6aR!0o61?()+L&c0pH?l8$=mH$ov3NGan^Nij)8N3Fu+X&H|htq}t(V@KL89vM0vd z1zDmeUYc0|{{UZ$^Vn&e*X*^@^UBFvxXpzDXnKEznNp^c;@aA~aHHI`sJ&_L#su$8p(HO#!=L4s!b29Ufoxb#TUA@#4?&Bg#Jv0Bj z1RL=0obUfr6URSAJ93_4k4IbB_r?ow3VP3z7aXXLFk`P9a0-pI;Z)0JwzxIm?-E&KG~Dll}DDS=mC z7i=I*3(MM!MbasI^`Na5Ha17-^brLktUsI6Pu#k!ZnK73bVw7>RXLasJ;Pl}fL5c+ zy`+ptfP-i9nUYq#|DEP!?f9()@CJXA{v3~;%z=?R%; zuxQb;TZnj$Ee-r6S`1n|9WG04RvaV&0aoWbOymfUOezUV)2e?b>-Wma=WkqhteyP- zg7GFCx5najPl0x&@*n-REu&?4sIR4xU(BO-|p0j(O%|9VLiT>;}sMe zu9yy;-wA3Ng46?1M$_R?B+lV)`~d>+w+=G2Lhq=ZO!swwlf)!kXAb*S^`V$Xn!v&dtyxH_2VJhFu0)ZTJM8 zy?U3?@izcNg1j7HDZ!$%WNU{@G8eObUS(2R9S%4fsG94;SVY-g5x|T&HJHo}<(oI+ zY-zK7;5gfFt(|Jy0!Ie=P(#M zh1KAy)`=!6nEcU@Q)93xNxmb9lQ_@r;`^n`TD{S@RCv?BVJP3P+cz`3!-$HqoT1&< zdOLTXrkXB-)GshF%AxZdqjl(_YtbiRAs$_g!aKj&EmftUv=yo106nuVdDe@eq|EM* zg;A6GEr>Q<&?=+BxkNRd0R*E7@&|iFme$0$xi<*c%GjR^WsZW;`ymX$v)@z*bE!#( z&szjRFYwbA{^x(sb-)F-!$Yde0|b|W-zPC?)yp{<2>7AWzW6XvxlJV z$1TElVuP_;oW>jhi65t3;)zZ31-r}Zr*qT@l)2%!fJYD?xzf-Cdpkyz(8HWu#jQ#G zVmjYC%co&iySLP`nn~aa!CH_Cd(^diPSZM(cl3!1WoKL)5{xdZf%`M}uybhDM9=#%HYRc4Iz z8A_^|6$Qq47<+ri1{AwjgFW4N5>H6NWAlvPQ>(9rvJ2OD&k%|#^5~M^%DZ-0v*lv) z(9^WnhkHHJlb(a{$G=tIyD?Sli3?MkHVer#kL=Fx@LoyB)58{Qm?GFjqU&^Kf|Pl- zXquTgafkSSuV7nX|JLzASSeE^YHU}PNb0^%2)kX8v^=mAB%vH*tr0^;WS!Z>;YD1BMMuzlR3Q9l zD{wX%BTS5{$kEfixgrQ%=@Ovb#@FgJIHtyw@^r_>D8RYGYV2YQ)vBNQ06wq_mxcMy zdy|F&?mT}rLGiEX-B>{Z2-#YDah3U#-a2cY+0|1#k4&Ep{|9>LkB`P?nwc`95GPVN zWdB*g6RQ5-*Ys%Nxs~i0x+s3tBYYip&@)`Xac`(WA85E%%tTUj@ySb#H5bumk8@i4 zl{0&JZ+utqVx3i7u93n?JDsW*afLPH;b10qzK)FbNk&m~_|rKt50o8NwmB%pJWxlD z@Q5E=BH31D_JJmIb{kLX<@-*@=$V;o)M8?Kjyy{+hk(J;Z=-sEkpUnj{QAQj zpAk3|VEdl9*qzUwy_SGS?#V!z<7LG6jytJAh;1Z5LcxQx%B;}=eppsCOR+!PzAu~{ z!1?8ZDEZ9?7zAov9fSR$;CVS^xLaKwf ziR|8*i+=T$jx!oacvQ4#r#EnJEA;NY#u`d9XeeDP6EcHZJp&Km$mI zMX3``dHN~Zpt3WL?|w5~84nCFLbG}B*h^qF(_)LvRNiBIv&Mav2^ZDC<`{-Js8$;j zsdo$`3WlYJ+#0U2zlIcgyxUrIUO4-F#9%Q156cd2E`BGxg^DJ+=erJ@=6(W(J6+uA zd&A9Tld?li+K6%5vd8my$`A(;rMx`&|2MZ}B%vFFpK#Br6W_eNueg)J4<( zU|=a~nwEViR!pM_G!1=7+2@~6w`G(SMnPWOXvcfxO3KVKNW&~R(pIW1)OY$o#1TZe z+rPZ!|L!vWE8qJ=1&`DS6Py!#X*Hc5E)VJ^_KoPz>F80xQ3G$9is72>$WUf8gVPLv z?zVf=vXtybE4Z})QyDGy`OqQIR68e~_DH)LB~EU_5^+{@_gp-fCU(ZzQ>Uam@53Z9 zc5#+ixPk6!38+=KSRF1wHaJof#z@TM^??2o<|Gv5dX&tto9Eax z9~%mUAgKTdi2jhHU2-fL!!zrqWM_ZjcIECgeTvRpZcTf${k82~p?X;LW@{fWF0tK6 z%@9P;seodxlv*~lVkWY+<_|)WsM*&x+T@9S6v`$J(o5^I9TR9nXlD<_qp8|SWAtWE(4{R`}h`m&A5_;LHNe_3t3^F&m z{u|1wmSDppr3`PwNQSQH*Y~Q^Ok+TQZ1qnT@5AoUv+A{*1p)bw&MmeTIy?F4@=o2Q zjp)y}?aopPg!R-lb7!jbGQme)-9VYyG_!QqxTj}!zyGEhMt|apU&OnF^_7%p8j`zQ zph8CpTcR_;B)4^WZ5a@tE+oYp7~(W0N(ZF9Bht3Oi{T#Y8Pf`iDIdMIhi7q04q4z| zJe>J4So9pqk_E~#wsDdWHL0>^(D}v<{jUIBaYuO&0Crn#16*zV>^@2&UGjQ?3qD7; z;;e{-wnkV-mLkQn(cpMP-si)JlM(Wp!g#?U*8o?J1N5U3r_Gp$xWdayu z<^$pkTybSf3WnhSMIL%|->UMGY>ZAdBJid9q@4mdR0jV97fV$Run1$*0=NDn1rqrK;QyUv0(R(f zbf!5!hGh}TkX>-?rNc8!8twuC8kV5YMj3E1RbLsMtejel-ck#bnD&Ja%J~zSb*RF6 zL+XwS{tYPauIp1r-jE-T%={boK)Vht3wZx2bRB^mExH5-QTtd5xhCsx_CbrB&|>L(xUS|CWHENR~ixnY$!Ki$voYSdk`HbMxh?dZ=wUw3=`Iin3Hb zkopid4`MFOlkPKzob;_DU7eTy_fvnD|84&rxQ`C;>k+SIC&Q!-9G450`(knUxZp;N zUjf$skazso6tMY8oHr(h4#8%|TLOu+-~9*agSx+4{OK~g?`JOSWiw*k^l|ovbBIO) zmi47khNUiEQ=;;VWAYnjy^gR_80{j-G~fSbHKY<3{lGrDM5+~wf{JUozpJuddT*j%GH3Fz53GF-aCg=tBI4Dzp)*vRf3!_KRK$x8A{k_HEtr$gLdrez^4j zWDo@;mNIgXBZ8kFW51pTf8_ED^wc&!s{vXhF5N@}V@Zfj;KHqR|=c}G_ zi_xUDetLN2(w+2h<}R~cP~$b6$o9oe%Z_VbQTOC7vfV0m7vn_-*%k4Ik59U0}k#{j`+<|yjJ}`*4 zxC!xH$Zd_tuC=H9=U$TuO1{hU>&R%tH6_2PF-Z%1SxRm|#0>+)FR+1&SBtA=_zr$} z@Z5p_|NfOja;6(?DIR5OUg#f-sJ8sXtkP+z((n0$rvW+F zu|T1C45{N!`!+2`$M^f*kH_O~6b<>uM^Ny&A5S;le>C71KU{x!$><6>)0@6OMw8LY zd1)GKNUnoDR~<@`6O(ffKmhlMLdq_#Vo@(fu)hzoPH`fN)BHcS>MN?>ykO9J3 zU&uRjT_6(nJFFW~SZT5tM)}=$9U};e3k6x%(n){+_!(7@=;}DSbpAnPI2d{jBbI4E zKk3|#;1J}Ib(zKPk>T~D`A$iT;{QTYPy|*2m7<>e1}P-k;y;@ z^^=qUA!>NMor|$$x+YwXTHe>9$vnYLeU%QvsB~l9SefKCv+x^|M?;)C>ork33KXyYk&HDuhJ*^;-v#q_v zq3N#O47AFuI+)k2bksR=ay-q|o5onv2#VL^#)hFjBJ8aRDy;8u7@jZOkz^dpD7a~L z2Nxd$1qo$lVcG4Oa5Q+QP@@E@(%W7ZAv^E7Kvbr)#k*lVwisc0u0|23BQ5GtFTM39 zu_(WpV)m%l7D8ecwWO_FWj~dA5#3tX-uAjYao2ET@o##QH>H5FgCdi3V%av;|3Gc|#H^<_jA6-l{2k%q_A z%opyR6+WthWQ)kku-7a_1>UR#-c32&T!0@(EcTmVi>=r}DLef`D6&SA8;naie8$ zVC;U7@{Rqo6ZS}H+@^B>5OJGZ?DeP!a1zO9O&VnZJ1(;YRs?ZIEJ_!>>5A+SxOrfB z=KEGk&IOf0+fxrH2wcF_s#BxZ<0PCd;P)WM@=DjfM|1k&p(aK8ictevAN8}8CK@a!D8$Jt~AjHu>IVxEvUYp^BY1ew2jUg1_+py8^r zZ>X!^uJ{Sn_;;Mj$4la11UVPIUL)ms~ zIE$uO*=8m`7 z;t4Vu$ZuUES8IU%u2iqv+7#l$q?(h`XLDRiI;IHlL1k(hb37SLs!nzVN*)@#XsP50 z)b~g6pZ0bI;w$g58EVds`i~ALf_M4YeOyk~#S|Q`cOu~qTjG)R$3w|9X3J0Y1zfWV z+St8*Ll2Z4E`8I=;duc!XrS@MHiNKIZKwyax83Qa1z zUHNnjfExL91=rPx&RFuPg)4hAEX^LeECR#?yD028x?9Wsb z1H<$Yu<%%%IC!RgfC(_X#f8+sq~kkfXO4)kdi9E}V!60_hB-a!p*W;C%TR`0U}p5jxOt_it9dkxf;fkswZ~&mD2nr+ui3 zyYUFYrxW0Am)!g-hyuILa|%;|A2Ltmn|h=S@mMvc`Zt2cCZc+;EUb9P|5^Pn>H9l4y|RaPZV+EVeE z3FM4;>OD`;iB3rfTq1>Yf9l#}(hV>FpoI_Uj{mz~^$Zk6J^=Bu6YcP}k#; zlB2UzJtWXgqxQ8T{p`h83eV{Wz=#S}AnYX*3HW)X`lMn3ES znu*)reP|QC{C~TgrbxY0-C)?Jx`l?H)6X}5^-_OMWGWE;^$KKCVV-(WirPKRi?#h| z!;ujCE<&xL_&!U&ILol|2|@`D)tuos(acU}m7jQj21@*0g16dS7%x@T+3MuPq7Zw5fnU{j>~>4FVwQ`WBUvqkbqXBRZQtJZO308h0JugXF^-x zQ}lB`B0A>x#%@{WOnqlOg*p28z+Alio~~B!;R|dsGYH;qFdL5muejebOFo`%6e?!x}!} z9leE^wSWJ}h5ykkmb?0~P^NY=WfY-4`0fF0!_mOEXk_pIF=4ZHTw&~`re+5JSM%2! zPlq8HrpwM$?vSi|Ylbc1!papNdjji{NxND5 z+*rz+DzI@ATqN#|wsUQ9sUh25%cF^*QE@^QD-ERK)JgoduvVU-$RcswRNzmMLRz!{Q!N4^&g~zHV zo{uQoEx%!1GRzEfk>$(AiH0Ag+eD!h)eq5X&Qw96yk*H6hRGxb^WoQjbJ?psVj#wB zlcZ>%*H@>FN$EZSv%UC2i@CuTA7%VQ|Lw)U_F$2lZkWGu{!hLqG8~t?DHv&Z>XuOz zWM>3L7Bq8FieQA)}jy8421R5uF1Y+%c#5K1-mF+R0mTP<{m1-+`yQ5Ng;`Bb%Ft#mr zylqSPCB_VSKd1K7;d5NB=MMptB3K)0A+<)|*?qsI zew4&wcyr!|SllHOt`3*UGyn3x_QSud?z~Lfq?0zuf^On~>!ZrpY(Y8Q+D$iQ1=j`g z53}L4wk%_-O{eK=cea~Fw3-(WEvkX?=vf&F?P3$fI`I8ChzPgOxX=PA0d*$j;I<)V z5j};j(2Og=t1jop;vrN1>sqZ&>W(rhgHkGAU5&pvf2j#ji?G79Pun~GIq^zQD;A`j+9`)~o&6cWSC@)bp{uVA}pWqkv8`EMd<>O;+N z-&KO=4qH#hPfT}^-2N`7DgXvoi|x&9fz-FT#MvY28V`Y0@#_xf5-%m$gI(8ksU948 zkwiLt(~q=Y_#MUViv}6r*;P9LIN3c?l{Cut$GM`>0wt05eRxA4V75*Wdf=Ck_S&&3K`mu1@pKhWiIHuyt@G^qpSF3L^5Lp=yl5JM=mH18gS+9vwWTnDDjBW zk9+8oNQZ+MGAw73ae_Cj^qB>)@l@DQ$L zv)lqu;O3MBNd<1qo$S6;FlH(@O7&=A;Ia)xyfxMz#w{cr2oekEL?x7wvv<)S zv#BD?h~VD|e4=y904tOTYB$%KOqi~FayGH5*#LxvbxL@^Z7m6d6oa{|Jm@=TAt1Ms z?)&!5oQFJlfC*)0BIS5fl9Y?lyWeZ4h2Za{7;PZ5hPDGYIyB@fzmx|FKsV ziTVn27&^lj{Z~uaW^N|M;_}IJVu|EigYDCc44?IUSF+bF_6M$nk8@k9jD{^IC&UK(qr^(ob983}DI8|p^15Dh`R}%*3RFlzgTw$+~m+ehu^|r#qG0+q;u+o%x7}{M6<${q|k&r@6z@GKiPwY8c1n$2krhaO5*=?~R zBcC{bkPgP(s(xDT%cvRpn^C}vH1)j2DM+w3q(cZu5dl0`2hSn5KrEp^!8UF`EU{D- zRSA_fvC?olRLFit`tn#yh&&jP?>$D6@?uAfkZoP2kK`jCxAk$p9=#`z@5|t%3kV>5ltIzBkwqWSgU? z`Q)F4rV{I!Zr7NwTVf)LW5oMLk_NxK07%4Od z6Y>o`rmLfb?lo3mXnCc4pn_{Af`T`vCTTETTc6&|BIfAa^-b#ppV&xD(ot_~VWj_! zalyNy`1qYYV){Ic^q=6Z>yr2dJ%#g1zX$r^N7CIEl`Q{_YIPfW;=O6K@AI@xQ2!ZY zs1k*Z9HV=7ORJrfixhdZ08V0+Mm>`Zx%Z~*a@Q0)>9NM=eMU`jNMl($_W~MnDSBid zKh(@HuF%gLp>O!q{S||K`Rs-rsfk z!65ey7DR!21;7u}-#QFYj%7>xn>jVy$;S`UdXDuoA?G{!QWkOr@QUSiTxk1tbt*tM z^A7k)W^C0OKOoCrtN2$R$5F|dy}@A^sjQENCUNbRMW18gWV|xBq8N}T!p5DDL$K~w zmotM*1Z^r7nR8oZOHx_5eW!sgBM^!qzcgrKFr<5GrBBVg$bIf1XFNk4)pOmXvodQ8RzJYBSuq zxx-YF(j()(mAK#C#i9R;0@Y+_LN}EnnJcoWeB|u{V?`ZsYH3;_w{QK1z;s$Lr8Na> zg-Q7r4wPFqk1b&}Kue}alP2B`xi4wA>KFDLrMY^=psR~l9T4G_4*%l_>(*cJ6i}tjpqAk$N zNk#Nal9Ib?)=$Z_%{V;{EKil=XJyC(=p48%)j^(_i#M`;vJJ$459ry)Rl_;tyax8m zZtAYNC7)Rjfw3A(21mOpzlWEX_B5w&=BsF0HVi5zR_bZBc{gG_pwoON{(&Uq9lwbD z0$L3tQ!l5mORNhEoTX%CVc&%i*`KAhp0uYwj%CAAgVahxr{ zgTf`Oyz7zm6h^=o&nd>yTs)5l-+Y z&2{2^Jq4Vd2^nM1{!a3p{bP=enAcn-d@l|9ftS36Z-0X&8@fcoq@LY$DJJvowgJQf z7U!KBI(Iy2bzTKjDxS3!x~F< z5bHQ*eUoyYFRo!1jcx6si+ye@JnT+~h-nq{d zH&F2V3utk54?K#>x?o?PF%(Gefy+k+KiD#j_x(13K);E$E#!%vJ%PGykqTItC3|`5 zAAY`GqTI;VtI3(|jr)$rQt2v+Q|HCFo<@#@3754LyMHKofxpJyR@&!un{eUw_@F}c zBpe3b*b8-~q}K^qHryTqnYt;9Rjp;_g^J&x?t6|*4Hshs`3B|DeB@!?+<|IsSF$?o zWVROsR=fa}dWRTR$YnZc^k%?*O_$jbvehuV<#oV={x}$aMJ?UEmZb}QVyws7A1Lc- zZ*~TmXy|*_loiw2xfBY0l|#gMCFL-HVp|0+gh)<@v2H*mmR@8+7IsS%bS&@o?cJ7P zP4{r6HHRbOM@a3w6R2A9mO9+?mtHhfj{CKh7i4TLbQN~a3u_++@t2VpwtV|28^CzK z(3xW5wKJQDF{#kyXPVaktN5jfN7PV;CwfgqKiufVF zepia;vZO`JX2-D^MKy_y6XI>1_$YhYRW&gjsb^pH?Z=o{i=f~dnEzZ!AIt8_2O0X;}07Rq#KmrL+NX9`YnLHe` zOvER{4b4Z^3xpoxdPbB2Lr$l8%tQrZB`H|N!QM19`5}AR)L^3*)GnvJ`- zBUI1WzR;b$cbiy?F{X8G=C_=%kIQSI)UNJ|+Z!J@zv>sE{cS6{#qo4Vpjl9C%oy;- z`Mf{c7s{T_yTec$O_}z_(GtBgaj&u4hFAcOjC(G3#W2byW8lMRgk<_}jQ@rPDn>Pl zy2`~swAPquc=htYe_Qgnf;=}f-ptV`ydTtplTIihS^a7={~8cG0GZ$dJ~J14b*@BKnfs zbJh8!R$$3s85Tm#MX?b&Iv5oCbjST8&7qns9<4R`9QAcLL}EOka+<1dhVi1T9a!S6 zEdEBKaVX>sNzQ}`GJz+zkRl7Pt4em-aDWuZxitfS+fws!ne>WzQH>=MtD0JW=4e8x z#R}CaD-U~sSA3?z7mwhewub@n`Ty4Kzk@F#$hEXPMb{@X_If^rG=|ho8v3PB9Tgmg zc@>2?xEOSMcKOjcs>5N7AwBw2FeN&S#E_OyBp<@%2U z^5ZSTO6$yADiLR(C`UX8R9k<6>e!$!aN`{?*_e`2RRX;2N8HaTTs>*_l$9L*ui)R^ zRt0AsLNq(a76F`S<4_!&E9%N?ItRflkLbm;_gt%LZ5dyv*Qh$ZDCiDS9!ZVLO)laZ zT>1ZJIQbG$#=r1fub61nm_(r;x!!T7ldd^LfEAAg*cV?ooW1i) zSK)TT>p0a0n}3%z5>&EU(?DV9eRLt4QaMPF^pQy}syErC<1@D=IL4RTsn-GyI+8uf zIKS8FGPI~dKd=r+vSfN{GwO2LB;D&joX#`nWY0rbS4(8+ZeN{u3Z!W^0}us7R+o2fKeMOIRPfH<2YTegiv4z^ta zEs+OZVX-&kindC(`8}tn(ZfEqqqr`rA;e^Zs!V`=iU>LRVOy&Reg$~56xI(YL9?Cp zU9m0yLJg(=u3Z$m)5=%*Z$9W_uZ6?cKNK#Y$aNxY0onliD0>M0{LYgtvL(V`F7ENN zYHEQO;mlUMaeI=o2iGL3-0TPc(ufdZ{lwq>8NQI#gIhG@)M+<7ra_5FXu(?shYodq zRC7mpXQ9rSgMxH~n4ka=c@ye2sa-TxY>)M=gg4FO5YHld(K*hs z$cum1h^igpHmY}FQDVdbLNOjv%Pm(I2DD1mA)(B`tT1E1k5Xq^6hZoPr)fGAHKS>n zQbaEmsn@;@lGChU^NzZ)2CNpZDB|tFTE`E!{(n83`M}Uyz_Cl&ibVCwLE5c0< zmC-fl1NfdEi7g z(slZENwG)D$ja@Uo~$az{1_&PCQZE{!9QQer^*0TqchqnGjiuRWunTblqCduS3IMB zn)6?Uj$XiZ zGbKXvHL**!B}QnTA(#8cr={>^Sti>VV6@X6rAH#GyVVJzK{%_&D!GT5;xx>EVQRf} zJF4jOqiN;6+*>npZ(E`RF3)j8QGFS-pa=H1Q_nt++yhXiD5z+xhlzKu&u+07Gn{N1 z4D2A%7O{%ApOW~QYAKy!FO}Qw4f|fWiSA&K6EoJic*!HsgFxSPwqi}gn6HSB6ZII% z__Rq>w)&)Kir)dahT5X|F0~wg=%;$!*Y?WmS;_07?5i$j)+D~(q;OnFD)_UHy2H;E zr0L$2k}KA|ljE}b8!{?cmf0Z2=Ps31ys11!okRW`tWR%$+*B8?Eb-RANODT|+syVc z(+S#r6Cw5tZ$ol^#-8~KMvUt z{_z&ETyKsR5?IJJJ+AJ}>*CV4!fy<6%g$YI*X9$ng(9P5T!Q%cCn400iJJMznA^P* zs)Ew<06out!>+e<`PwlxZ@h`g--tPtuTqRBYqC4Vg%&H(rdETuIwQM=^m3~d(RR~X z1@4v`7j6KpNV`huvQL%eeK3crvN@;cj>z{vv4f+%qsh17%n@=+uzttP)z*vtZ&dp0 zY-`S-G}SUMa%7P4CG{}&HSyRqG!fE^!01;n~U!J>VVt1RCFIw{W;Db01FtvpMXj{C&R=4b#^pF$RlCCL%-$@pSQhBQuO7YzInm&6# z>?Dp)%1d>8KvH*)JR02?*Q`MpqK9Y5KYoA&raajl82U?ZB?5aPiFiw>>bcG(kZBYw zXKch&7UfFoqdBhq@$5spl28Rzy{IEeO=s7n>U(g>NL1BD%L)D=SLJQPK_&r%2_zhT zYFGBN!gFP%{<`|&;pYG-rKk*Axox#(C&oY;#Ab~skVe0@GiTW2^r+m$p#;4ja-2Cn zPbfr^e@W$%H=AR(a|zv|7g+8^<%n`Sgc)f{nZ@*vKczw9IppJOZh1S_Fi66SyWa9U z7*o;%nUYQ}jojWe=q@q1FfU}za?-PSa!4XhcGrg6^{_P<);~+vAL=&m{_jmuyscs- z3jcf6&4_&GnKyFqahmf85I4L(Vv_NZu%>2iG<&g)1?ALu{7jHKgHL@Hlzbv-A5RWWw-cv zp0CiiODv=iNxJV@bR_U)q~dZBBt!)-F#}N$J-k^OtiR-!%rHS6`2hy-WaKth%%*U;x%j$yp5qk;CmRFSl5u4xfyW-FFl|OnVyD z#wlhM!H`Xn-soeu$DUQ@->0f-`II~^kPXaMRn~^3-U+#`;q0IHS@VzQFzQB^ye?y3 z)k4XXYuj)guU1<`ykV6!(xBAUVrA-psymX?E&c1gm1#fqZ9Nd9a!?myx3}n0DfW>8$JJ5AxM5C4Eb!6FK z8?z0l=1!!{faU%VBfecZ!n^vWW3U_1t}Tv;?atam_?*mH-YVJK+-}{*hA>9ftxv+G z$TT(oJmP(l&{JXxros*yQD_t?7Q6qQklz$;uc|q%&Z2yO&n$+*fJbNb@7r0%N`j1e zMCM0-#yX-IraGgOXZ;U0UR!~h0~cR=)IFTgD{|jGJNNL%2A0%6@{batl*}_jWJ?Um za##e(;Ox`XEjpe`ElFO;pazGJgVFkCh(cYC>oTxvSJQ#7C}B*V+?h!A+j(%ngy zAG_S@Hz5Kuz!)gSY@kDBNJ1X+awMZGMEG%onlz0{g(K|+tkN{!D!64oKtMi%?Q&63 zdNV5Z3^({cotgwRu3K2@a3tZ(p7;$Hh{uTY*8YlU!uS@u^aq)3rdY2a#uRi07nm4D z#dh&HeE=T&48`{xWuzC9URKuB%QoW}VL%pLv&!D~A7lX<22J{qxe&5!>}R2CdqcJB zY2_1?^9BjDf5tSR7-ePq6(;u)@e<5*KeTMWVWgPl+lR*}#lCU6Ya!f(H zctnlU98wMKF4{(*#p&KRYQS8@_7ndP+gl)COz&u7jW-TgJ-l}#h$!VB+TiXKmL{}G zL>Dj(!@h6mwu6C!?UD{X-Z}^XUY-FL>4M`s>DXZ}53Dh^b7xNQSLPI5Nw@5F^cNWQ zHg5_EixPVJ2E@(fh3836E!|K?C0NLgNdm1JA(?7F1kf!GSzN`ys4pk&T>noBQpI0< z6sVw^z1iDxkYHQ z-lMQFwVb(az22ZlVhj};Jh#a|EF-hb`4c1LC2^g|(0G;^o=`~JzYPq? zi(Ar&eXb*0DC`)ne95$3^UpHX+AQTO zKKqwPG@$?U-p|{2)9MW0Wse|HJMr!MsQ+kcT3RaYO5glTpt{di6&GS@a|9e)ygfx$f}KRGM3jr0g~Wyj zT2!StT){JA5R=|F0%hD%tkDMzUfaesNdE=TIBjRTFooz^Qn%2zGyY}7(gE-de1ERx zA8I0lT<&!8S7l_>NrgV%?uSUvK-~9cAug$MtJiT{cn*u;O`bd$NqMO0mI?5<#9;VG z9o7a1xJS&Vpa7Bk>ON7Wi`W`i@x1tXyK#a(Bx#+Vm9}^^!lI*BTh2cNH556&55QN* z3vsBeKB)59H=LXC9kgQrY1!*bbaMp(PN3hNLeL&maM6C;MjoZ*(fzwZ+f_zBuY(Sl zr1!qi-w$iX&g+*W*=46U{459knX+i_48Q0oaPib+?YWDakUHTKhCpoCj*LGQmeGkh zKmfzL>HS&2jVwkwT^gkPo$%gE`y!p$*^C~4;^u7_bxyPW873tESS~sLAL;JQX3@wr z-0WNZazzIgefe4^W z$c|GCLaPt!tX z#7lhZvc;R`)>h-x0rRZt+0KVdkwemOX!v&l24{4xJ!%J_A0BWkusJr>&q$A(UsJZO zHbQybwKrd%kFgSK|9Pjh8}q$~+KvtEKMYz_n1~qxUP>!Q#UVbL@b=?y5O42ztZ2Io zTX9k2RBr@$DH9lFu$90Rm^TU~H)f2E)saVlFxa2W8fAMxB=`@d)dPveWT9~ZYze

lv4J`d=E8<*fN2!l? zEUW)6WxPbdR~?rK7|Pr#CMLSZ^1+P#%Hva@c}6?6grv>@KS030wDs#pL&n@pODYNi z`Pi@KXlkHaj-AYumE?e!!rQBAq&Z|`OWfnuS!|Pr<5%YUtep^t&C>5G`U`fo5qK+C zKv6`9hAwf3H5rbXup(ghu*=U7Hk7Ksfp!%Ym|0HnN)X` zx))HTvTCMNXnWw-0O~{L0PCVZ@qM62V972=g}vkS~di=R3={(BP3YEgLF%n^KX_E@+Jxy=fx zFEDWHz2@8Z;~i!ho~icE-{i=r*P=7Djg5EZOPX+PyYqFom)p&jR-z1Q?j z{RJR~;=`<_HdVx9P-~H{iP^FY0c^?;|4|+}$tR^iC?khr8h#2Pd-kCT-B+96KKeuJ za2f8}NMaO9(8#%2muS0rtC9F&aIha&~JG`QTnU{%+fgk)#)bElRTMhlL4(kHu7In($TlyQy4R)TjYSs5$?5 zAvLcXtzZ;I9Om|VcTj0)Widh++Sg@GLDR;S0PtD3c6x;P6Zh#Jpm914KauQ`f_-_GtuaMEI@xgdLdQeL-hIVlZ4Hb`3`rjKdjZ0?-=8gFx+FjX!P4Ae4NG?f|o=dK+2WN+wCaJ|hmtpuieBp|+gCIO{n)goLtEVj$L#2+2)!Wjo8u z8Qxo?_V+xh;bZC_aXz-(*fC7R#K=0=7tSAE5P}6fodgp?Q-(_LBDD!B~FFN-Oe@fmDoNtyP;$>e)0O?@ZG%hoSLWoH1$zFp7hAfq$VpsDQfH zPed2}7&3hevcmw;VIiCnK(%x7s*=b7of=OPz;kIl>s+yP_vuAITIH@IYKrw@qyds3 zsn*WoCIQ~3$VMmx~jFnPTefU%kE zJ0T(oM@ircHyN9xc0?+*>Z43b6N-~#nP7;-X%|p??lPMq8)pc~;DBF9A_Kq0s|fA$ z7>7M8$9kI#8-2GYPJAEBxaf5_^wvtXN=n6B^3t8HLoiGds1w7_I7Pro>1LUc`WI?O zsEZImkXG>&0amH`q_?ri4nBVHmHoKsJH7>nnoD++l%;4Z6q@*>ycpF=3*fHL9{I|k z9sz(qJ^)uu|9ISG)6z4a_Sw@=IU@K=%H;mjWh|WwhX_j&IijH^N?Jfb9s6*$Ke~?s zNd0dN1}_GSK$^8EI6pc|`Pl7tyu{!2lPw$PFt|sE2-v#=*f`ugIIS-^;4jjXXx&=&#L??&E*&?S)<6?0FR>rq-8$xa!k)Gd6tfYO z$qVY>PYYghz2l4{wt=S*{5dz%B;czP%%E^w7kogE$V!GtS?eZ6LIEpCV)14+X&Z;T8{q_$sbrT9mJFxxA+qmk)p)r z=7`%fT}=9zFP$6y9)TUx8O5L(Uij9glF{V4KkWgKr@QkZIdv|_l{}MR5<@uzK}g0u+^q3VzB(8g zFgnD;xzL*MX$H(TI=sGseDw$yssZ@ro^mEfp$YVO#8p*Lph7^e$#>fGkT#^(908Z4 z{lKsC;(ceE>bdkEYQKanTD3%}_awbDa-!Mr?lUz}9C(Yp>5cS%u6`Er`C9kuP5`++ zlPU59+U)JPdMBY0jwvr^`n1RF8>sK`HiRnZ47Ut%FIV^&7&}{Qs!c`mP{-7q67V8Y zpE8j&Lmd&^0ymcM|E+AG{_5P%_u}o~4VqSvNt`Cn$s8{qI%D8dw7p*!Qm-WORVTT8 zW&G2g(_HWDiFb6S|E>cOwwTPg9URHqcQzAs_%Z4&Yek-tbc3d|A+Z@Ov!!^-Z%9a8 zXVe|fr;S&4=Wjdk<9ml%9$6SbTY7IvPxIo+&4YWX-z&OUJrxx}ww9kFm5JErBR-kF z-iY0oU#sU-gL@rQHKe1#z_t*5&tNC(t}1FJe%_ZIEsoP`k778$sHTFJk>b6wCP5&* ztX*I8!)WcR_Y86&3U5*X57B_`GcIlS1>*xh+Hwgfyh5DP{lS9HJ6(>n`>AQg0^ij0 zRN+^UfM94*WMU}m(+~%n>MwgMQ9o^7)4(61i^PHu(l&2+RI^HsGCw1nnhf0k4 z8vnyXU}pqhcdum@rRUkJvJYo@u&=dT@(E90`Zh&dlN7bX{evOAa08VG3ITunigx>l zF2V7kpYSwL=JH2|8otW&{171@+W&Nd?~6fx znA4lCCX8gCTuCmrJ$)HU0RkWcA@*Ik7nd> z-KxpYMQ$^M`0OwB$d@JlH0npcl~UD@YlhS9oy z4nT!*$}9D*Ha_2cVonhF>d&p+@&E_<-dA>S*AHUzbB?4&v-29X3glVG1wbUQ`g20u zMzlg9NvWDPopNMtzfK=;jad%;2~a1rg#d@Gdk*4vqi057wR#pGrAajyGCE+#&_3DE zQ)Q(CVa^n8s4vd_}B>pODEt; zq;h=AtTUj5c`x~(LbQjqtD4@Awu?Lf!g~hj3&cf!19^QJP9{%5{Okcta@8{f1NdYL zYM6L>!)eqMI{hZR`<8fm!Qy2Rrn=E!7J>jw>Cu8p&N8aZpE?BKV)4#v6BibNb$YX1 zyfU{M-4t8naF7kBDdFq34pno>z~mt(kLN4sM@ep_*>~3zHmuUC0=keIhL zMpa#URQ2_RxtvKV;*u5t*&mtD3!eFS64qR)Gdkrd*?wJ9t9Y)xNtv~u6S1y#)}@YM z0F`cpqIx$d(*Qyo!iwb@RwJATdGt)%d|)AZPRFBq*JZ&}w*6&f` zAOt~pt?FmOGg^MHH3!wU_j6j?Y7lL0(DiOZ60{^ftev1438U3yY9i82 zgL#g5yfyH={eTQAlZ%}4kwzcT1vm1!yp~cz)a{g`XIn5_Gx%kqIispcx?WpmW}ZL= zN>kRVFci|t#l8d1=1yBjZw_ONy$S&Pd|(_zsQy@T^ih|gF!wZYz+1}zWa(VKl&p2g zTivY~ubJB-HKcfsNk5vy5$-OXAIY;)S~NYM+h3a~oB{YSKa?+m5cXth4c$cqLR)pK zo;7-Z>M-qL-%>VXTR@YO!ejY@313yg)n2K!U^=v7`3WVp`9@b#aOGJ6qus663o998 z*#`)ODi@v;%^`wq~=zK{5Pj) zh2EW2EJ|wf0F(6ptV3}mPao;tZdG)>|$G& zD=kYDy?t$llDzMo&%Nsr+Q<0aI02H12&85m^FT$MJe_0*e2q{(B1-j>vi@_Cng2+w zV-fZghCCy7gCWBKan!kOo%UZVn3yk|WP6JC4bSCHH{%304vf#;!#kmx)}PeBmaG)w zqpj|&kU>Q2$rlKDa&oJeh;nMp{70vk>qpEAwHj5e0)e2Byr!90Nk06F+v9^SS zq6c3feT*JsNtiH+w_?oxf36sqSTl2B;pIk(0jXm0ZN&~D&jhU4l01VWugV8uqY+BMii34w+H&{0$o& z{$81T9Zh_%YjV@>r=M?dtt|E5RCDsqYVH=ofK#J?S?^m6a=Y6PkO2O<`b9mY640nC ziMi2!xzI$sa-oSgz3$wuSUUa!E1%8u)QuKrXWMLOqf3yu?KrFzQug8Fk*cNK(j6(XtoQ|C47P}q&yjFEWbg1RtRON)6~|fcfMsMRhq5nf6Ox*9fK$op zrFVhOgPdkEzekh+v~xoGcN!0`!>nP!UMNnk{xq!E825bTrg)6X7)$Ly_%uGkmy3e* z&11ddiZFXhN-+@Vx7jqoG}pqhJ>x!Q=*5d9o^2_?p#o+|2KVMiJ|}X`DQYeWtuVST z(L=rYD^1+E(DGHEN$i1)=f*gm&4VugV0`t>Tff=(05$p4)QqE!fF^%B-<}D?mDkzN5g%!^#QUvPVi&nA*G1u^NI4`WGU`>qBX*3^ z&@Us{^`MDr^xk`N;SRR&FvB#%{hw?6w#bH+XW|9+nnIA(Dsq&cx$I9uN%8Dzni44_ z8o_$XlpPn_KB25JP$NeaY$aK%7ceK|+0Am!IKj6yIWt<#t_O21wQ|S=uLiGltqS@d zn32SLpMmsFlWucae)WZeY!~or48cM+4I?=Lnct8>*}At|#yh9h?N?uHQ$5HQ(~c-_l|RPKOho9m~96*ER33&P4s+QY>moSz4{V0%`#q-o*roaz0vjL+btC zxec_D>~aD!K_3xeyV{TRZ1dN^(8j60p}$O8Y-$DSCX~e4Vl2JNnOeHBv;@ET#*loil&@;7`r+`*+vf`hD>wYcOvDA%GJM^LH6nLdoLXScYC zg9;!|wB6V2OmV&-Ax9R)fM>pmk8DTUDwFrKX%PC=HM zTgE$pJ0~g6_+)xbeo6z%47`hCVBTGM6C#!!*JUGWPA8tzdqn6rtJBn?S~d|MuTDEx z`riYIi*g4#3TodP(bG(P`eCMyD!G2DACzMk6;s;TAF&+YZuAi#d|#n%n=%;;zI9n* zs|~r!J_Bk#4L*V#B_jq)cYl6Jl86_YX^tiz20*?`t_$333}IiFE5#=sr+qrW6U(Sk z=l;wcQIsdpGF+J_&VQ|Q3QgrBB@#*csobmi^KwJA6Ys=AzsC>&8fuqs`G?%aEAKEy zAsp|K_VL^M>)k&e%wLb`S?SAiJvDzt@lJpsY!45snaMTidTLlNI06%9J^hECTI{`Td3 z+~LXfBV5D!!#{UFnb_w>IB@!$A9jaR^U~-Op0pC2H1{YO<#+ zDqGsGJStAyvMg8$$a74KP-v@0JoolgcKgF>4IVh=c^CG~i*qQG83^iQeRj4JE6rX>8e=6#lop=L^~PXvCYG zST~J(h1>0*XNKFFNI=rBqRQmO=hc}ZfEmk*;+GsKo6hNdAdT;{s&NIo_S#$u z2$5~m+u35Vw_q9Rd{D|PhCuP>`b{tUw+&UoW$R8$3M&Q-0ehW8*rkqSxg?es3ULLU zuY|lZVp#Fed}A_O_)6^CST!1?|AdcSEkg9{d2I}yI$YbjV>i7*BTi+lLO{mS+9^Ep z4kcAVHVY)kj1tVfBVA385{R66h08vcPl(A7UTi7#w9)7ww>sv)Klo}9EVJot24R%N zwJb}+#p|6NtRJf6fusXQ8Dic2sB;8fbdy^z5XBazz*HGCw1Fti3LA>CYVRSY40yg9 zJwpZ>XP&jXv;t${>N@+n5z2Eohz2}eFXU2TIooeI64Y@33b}{?OKx0Z46iYW8EkhWkMk#bMZa`IYR zlANoh_Vb6|0o2;T%OJeb+}tON8y1XoQj#g zhTO7UBK)N>dvP`-PfPqOZcdOrrmrHklb1ZLCe5caqkcsks?iBkM=W zIGYR;g&2o@<%xW_98>F~;D~an@uYKY)zKmmjF~5?=b=`4r1+hpZUUl7wLG&M#c)TB zg=_q7_j;maZb`sBS->z#SAH9JJe~vCQufYrBTIQ&WzQr(PAZ}()!Rf~pT%Jg&g3~? zg06WdTZ+`ly*9oXLwuJ?NBgkAkf3gg@xo_P-p5!9CtLiIZuT0W({q?Ltj%JFElT5` zrSF>|_d*=l&j*&4?VQ}s6!{DsRR^boGFc9d=3yKM1I=|7wn^o-a=RCu2v z@pgYvb%!P9E-~1U@M09k)yFh?9OpMQ=ItMVKY9FfaR=K0Sg2L!lo*Yb5b+WGV& zf#Vom>0MvYiz}KI{3alJXG&r_XRRt1{ZmhsHadO-TTR;#nmO}ac7dwTIuJY-n!3P{ zM6TgDr5?ye(Gbr^Dk*#xSdYG-w_bfb0oK*gRz|85_Y{K8j8V*V6M;|9Gx=g#FETvF z>ZxQWC-J~tqcHJ!gww%;z)EhgT7Fj$>L1qEcR@{(T@rzO?hBAM6f!OXSMzPt`8^4d zH;-?mdwd562dn{0DXw$6zcDiTKRIhNckgdjW{zyQ`C1-;Gws<$f_V3{ImZ{3asBCf z5JGojnhSQ?cDcI(```S`W1)5oC9=U~9mc(615H%t$KsY)Sbl0jd6JF0ifauN`Q)f} zkbs4u{!{g`96AppnjoQ}Rs7PjErd{}PlQ4SP&#-l3%?H|^2n2vr)YL6tp5u$j)BN2 zQ_(|+Vv9}>m{F53rxaonqpMPz(J^;_sC!#UG}u{UQ0RgUZL<37OT{LNH{f|#U+}jU z!P&6UH)Df2gt8BH_e~of=qB~nbB?WsNqy0;(26KHi%)H=f!+k)%72fr?GR>Kj(}Pq zS?D9wGWie+`QrH@$9Pl;e z^6M#nXt3CI@80_fxiuy6zNUNCaJzFut;>x%WqTz5;<-8S2zNeolgZ!p>i1+XCgZ69 z2#h5_P0FA);L0u;b?t@F5&+<9O8%ug^O8E>#>{Z9bMQcoYCX$lLJkG5d zq#O-MF5bBu_VaV){)|@!HT7_hW5F)>$ubiU_w~nNGt7N0rj6W3A!%@nO9jINnE5&Q z?PI^s*J?|D2R#+s$7Ggy*Y%{2It?T9=G>3>4F$itm_6&WQhO5V6?cWz0_&&Y{7$PL z%cLa0;z&u?I0E(jR~e*k-{R7LKk)%?Dbh3RJyn@#22WMrfQFp=cTU4*@0Y^1uuMS& z%84_P%7+qRgaQHL3e5@X&h51>*y1)}@lcO8&BbYgsfS4+Y$Gzt9X*uWv z)QCF}#U>~|Vvg&CVg3GA4odoz360R>Q|^M3E#EQ`@k$L=@m)ZY+#GGMafqf_?bw3-z2f2r3BK49J!G-Hmh-y%nG+_#8bkt ze5mJ2PJ{J4Ia+J8y#e={1H;Tk@hxPbUT(*bq7~ZaRN+wBwW+b~VcHw(9v4h%7zpp= zYD?QUt%jZSUzGSJ5~^;R@3{`q;LT!W4nf~iplmkSZBw^SL-Pjk?$EoMOKXyMv{~5H zrt+4n*_5qb`q zS6g753LjxIQ1poE4;Cs!-yx^re0`_Von4r%r?&-GT}Mlt6t1e5-_6=?|K0#rq#GK& zd^S82GX)xKmR@wQR^}cKxTB-1@t~E)dcuhLp^R~DgNAY23O+EtN~CThDy@G3xeeX* zADPxO4j8#6$p9SX3SQh>`7~jOjA34g%lYl95_R==DLB^U)(eTjZzzrm z9l+njwHW|>>&rHha2#x=-NFwt&M`O7(@G^oZqSy z%RQlhn~tOZ%{ldO3nN?Jf9UFcWZilOvQ}sgIU!>r>)XVt->zlDj@GPJ#ybRC)6s&D zn8|uHbIy~wc~O#7iR0C~;*!9oVZofaCpvFPHm3HX*4Xy80ST3G)9$2G$RG{j7f8z>BElAA@H9W(^pX+bxqofr7c_3?te<$@0EuX@&=m{WKo|W|zFbh+6w-@~0m4%ulLvx#EBC~BLk)S5sn?pf@CNLz zacs`Ux99eZjZ+<0+nnf#)w`2`%7Q`oXA#3QBE*~T zTujf}>oC<8Rhd zZcv|g>YCm|mL8}XW`0o=&VfT-<>3*&5>t|rCVJECBcvPRQ7Ql4Y=1r?9O>XFF&qAV zB30#(dtowQa6x`PrLxNF*c<<$){`2Sm9liIlt#r(k01@2(QmT~v4~n$WcJ+B0^v?F zfntN%urodq5p<>4Y;P-wld2d+8PgFlvZQ89?D#A%)NatXQ_y?h1&jf9aCT-hWL4!% z94!PqxaY*$sXO8!S2t`7iG5FU^xZNE$rDgNA1Mw*M03{eTx9qMytPQdMe5eA4s6Hl zG$;!HbOWjvBMjWgkzNNpK0=>+lJBBmf;05KKXCp1Kg4uXE}i2vHn(?{i} z6MCy&U`|-c%BQyahQeQ}Tf@q~TE$}6X|=TseX<0&7-gXtc2J5{-b%MN~YTvG5fs~ z!g_8GfUI{}=RvsaiaLyh@QBlCrP%4k6V7O>2g;RvB^f#H-IlX+#Q;TJzb+&&z9?_) zUXKNh`IBt*y8yvBviIVYRfutD4JOVa8j;WLMq&pBizaj^@#-6sVS8Mt^xym6evK5I z7<#M}^2Qjx%2xePPp0yl_p^=IO^4+8L8yuJ*MHMay2H+*b$v5U&nr_A-y_}>4l2%? ztb34_T*`Mpy`(wnd+2_b2q(r3+2u}P#3F%u*W1mR0rC?75*VqPYTU(3Zj-yg zg~r8nrsES13_#oyTrUa+EfOK8IoT(L5G+Zg)HwxpM$P`%3Pv#07i}m7YW!lI`xB-F zC~`G{Ms&a+_9cqGiC?Tu!baw>zqy!1V9&|%w-%wY&@_xnGCg2q#PhDi^1E#NMl&V6i^bu)r${`!PxlQIk{KZI=v;&q=Z3Xx=r%$!A1B91glV&w zUXxNgKHUiNJd`s0?CpmHoT3$$EOFF;1TD`x6BWBG)%5_^1%EjpU==Dbw*9`QZDMqa z&xCz|2tS)wKV}}iAPFjIJr9~|TaK{2yfEcHAyr!&D6MBx&2yBPN8=5K-l;3~GM?L- zKPIoW`~VGwf?~rGVUzrEuYe+74I^`7@PZZ|L(f%z!7^Q=zV0wOPmP}{JkF}}41)!o ziQDc-G7!%(wC(ZC%jdD(xf%2$lQp87?hRi67Z9%0L&Ny3sJ7Imp$4w1Qr=I0LUX#x z&+&=gjsPq;6P6rIfjq&I3T72KS5HJZS2)$0x4;4UP)Hz{?!S}TO9EV?5yRCG!E*?j zzdnugatuQpES0d<7uH}JN>8C(k`q{ycvF8$dPpd{4c6Cnbahwea*&!hFPXkseXifP zR!v^^A%j>XBkON}=!UEMx~Gj>(Wyt0MtBj28A%LcIa1f$0LYLJzCx?cYszs3XxPMB z8ds32Ar4=TAO zo^%_I-6n_Nro73>UoIS-R#h!E3J7PnNw0|skNek!t{emB6uk5D&Up&P8{YG5t4U=1PN)J^X+ z5jzarib9iC1@&)NF6VN37_ zqW7AgtXXz?bl4eHuv!u@1G}>O43N`KAjbCi{OsnsDsI_xoFh>;KZY2`0)>;R}KGD`~Qse%UvL7K_ZP;#)cGJB}&XQPP zc(>Uc>IxYs(=&hI134Wis9&r9zpESf+v~If4uF+!pL8&oQDnDEkHgdy)1Y9;`j14t z0=g|I-6~WDf6^XPeXdM9q~ELlfi^c2k;lE-E}+G6UE_3g=tbAdy|t7J^$F%WH4eE~i>Bb<*@7dfBlY`s|k_M|o=)jZcke&!^A7uKN9$ zuTnaQsg0?MhNYSKy`o-f?I2pQ7F7S8CSWX3!6`ZNsdzK zYWTS`kVf{AIdU1!-C_qb{9wjkeOpsru!a0tfq@E((?fLdDX{ue(Dc_gdKgTw;qK;T zaq(!L&KDUj1AWNi@!PV#-3gh9DG$HPYa}jj!y|fB^0?o!Qw7>3<@dlSYf}@64ZS1I zA>lSF$=$wZ)k~LUR?2Fv%-Z!9NMc-FTyu{Mw3C_NN<1BD^^0{*UM<_sJVASUVARo1 zNrz%;%lJqcb!#RhKp!j819{m5k>;bgkv?6cY&?GTV}sae%DfRWInN1@=*F|=b?2^{ zyqy%2*Qv0qM6}KuA)*Skl>ktvg_BgnPL2X+g8v6#=a)KGO_kha=ag(_@BlGf6PPqG z0@e5dRqp#LEBf%gX)x55R*S>1dMV`K{R^06+^#OM*nkOA%x9-(73^W)KencxkdxW_ z87Aamg&%ENyFIV4FbM};sL!@Gx5h-oVZIPy6#v2r@lk$xmuoFs=ACJk5guMqH!dR) zvL)XO;0Lk{p$quNfYyxHtzdP^MuMx8j{>zCozvZfr(Hv86m_1dlKfGbbw zVO*N>;UC7=s^;3o!yBs4It|9ffTMA_dwI>E5#zmkYN^8P!t3@({d3!HudgTWufoky zRNWv?wSz0y_=)&B41mSe#@rZ;q@Ycz?WtZ@iAilVhXxAFJjs_VIwy+^K=Ul73JPp$ zmjx%yK0{&bPLxmJ2~94>>)d6mG|MHj^2W$zL#q=1HCvgfE6lfs>@ zB&kOI<(;kPXs8{Q4Yc8t;>iu&JAxMMKE*k3p2?Z`*?-1YL$c&B8eE7_<@Pvz+-J9J zxeQN%jRm^4H@AJc$n*3erI}-{heJ+-E=<-~$YodFJec!OZ|p=9d2+TVgxvzTFfqyM z;#?vg+#mGkM`}!KsyS$63Mj%93U=U+P#vtio_l~aPbad6+Rn8ei{}iV!|aCryWVr6 zs{l?o(JFVGs2se1X_=UN3c|J01T5oT76>3LUl&m0J)bPOQr506?U#P4@Vz}>J`!EV zUuQ=Iq??#AAs>@>p{t;Na|uK|^m`Ui)O{;GnV?!9yK%hh*ie~841`b(8j;17*VKRJ z0#HxEE+`SIcKzBuV`GHvd@qHr&N>apQUL;GnTMQ(Q>WoDfZU)O4cPv{PnZ2Nx7WyJ z6dEKMsn7p0J&0=zhp)<3uqRLSFxUxKP}Y$oz`fi2nrAzgHul8A0xD58-0vIFvOrQ| zpvR9TX76;7laysxyR;LO{G13xS+H(x$(D!SnbbLeM4OUtZ+B27XFK`Li+UTi7`qYc z1PcYRB(uq;Hx1t!XRTE3q|S3g?{-SnDR}s#JQ4h)J*KuCICYmGj(3?Xf z5I^sZ#(-g)TbZK%5%syt>hZe3jnb<9squMW@=D|k&YvJuw9La0s~sm-oNO50-*ceTtVV!GXlYFba441 z7<7Uv&iq{84e(6TspAAkE@NDEJeR+)V6tjFI>PNE)7y+`bHr*v6&7uJYihg7+X231 zg&mKP@Skq%M0qf@*+9u`(Vu1n74mtu?+S()zp&8#rto?SgO$U$r4OIO%Jn$Ro}Ao7 zt24^E#I_G98<9+dPrr8XxebCnYS+xIK!W)m}kqEF&ohl+(=cp zu-uZ=Z;WjoE#72?Q%Zt_Xx7m_Uhw)6_@}M(82y(UDYewZ8|PEwHF0sgU3<*exi8+{ z2%j#=pSdBM`)5e3B{59Dmf{hPO!0RyIePHpVmGDLr7V!zTKAFCfyq9quNeHV=6q3Y zz!07eupaw1I$jvbcsS6bP7atIN7qF*avvJEBiLpPME{%|j}h4p)g~2{q6Iorh6g8#s2nR8t>k^z z`+}Nh#`25)+K5qA?9H_jnj;+94Qh7D|G;Pcr78zqO?h8;H>Xkude`_i__~P8|6V7;(81SOl zL>RfTL`ne%vZjs{j@Hu8#am#%=7-oVLAmk!O?r43y1AFTF&-q7%UEJHqnw6ioiME2 zs+l9aS0Q5&T9NQsyqyPf20ORyGd@iz*?7!&ac+tONj@1yaBTox=K6Ov;qIjF*)0v9 zblTsj1rGDkl#zRo^t>yG{#90e9XA_3QeTh%V^OhEchpJGsHa~}EgrVAF#D8td@6W& z9GLRI@7j$0Z#OYFw0(xgR)_;aHgEH?YfUOO(B3+4B3-ieWC*kM!hFC-fgG4jgko;}s^dEV(#fL8#iOtzU z+O(20(o406f5*(|MGCTYlD1%%+#0+>U9(BsL8$P{wa=r9IKPqfYl63yx_aUq=rFBC zx`pE`HL`ZcmQLJEWbohS%n^FYKE12^3(;sfp`iGo;bly+jaV=5SPY>e?Tt7c-|Q`F zxBzXxJ*e%_nXN940Bc$m&7@H^sq&3bsLyG=_PtlOdTG%Qf((sH_m^jnuQ+gEP;GCN zf|U^w{fnfr4DUmSQ{C5I69WXEufjbPYo?M$YWz1zDK_l~0!X=*Yn7W;yNPPUeAoy_ zSup(J{S>>P@-Zy%JAF*-B~Mu)y@RtS?~6RzLfM0Gl2E$L$&IP(heas@J*~iho?uru zp_)(ZeRLg_#ui#j?{xzBMGB`qbSAdGkfGz()55%8?d_q)nnzZvG!}o#v55O=c*sHu z%vXt7G@Q`r46|@ki4kv-7vgh_LM}UAM8&1$eV#l7gH%a=&(%}s(@FI7Lyn|_x19## zsL^x&eXKVT-nf^$cwB?-o)`Zs|JqDUSETg@+~AWa8QNy~*}Q5r5xBzC&mXit2z z{%8d)xozkBIYmv}b6}BkGq2w^@}LGMzY{|=u_jp|b@*v;6X+E^H5Rs;;GKZH!}%xQ zDHzx<`=bP%47zIngw!0fg)rg|JsWOJ+qpl#`?v|AY#Tliz$s(8&c|RcCX7>Nx1*D1{nJ7C73^&8P9idc3^C#ym zMX?oUEA_8_)M+A!8`IC#qf{Xyqx%I`C((Zm=I!w>64&te9b=)Z8I3mG()2e zdIx4t$+a7Nm>~_R@gFzmdW-fTC%qF2pjL95NDSThls!Q3NLKy$>)RT#phR9c>OW*0 zB9wjZ=9T`lT}JU4TZ6Bl7VUL3rko5dTwT0tsY*?wUmYJ7G3j)*(k+1eYdJ0y`xww5HlmqfF?fB3sgp3@qj&BgR2<1jBSUEV;x6#3dihRd8CkR>6UUTG_527iUrn8sy6t0Pty#Dbh7qW(jAzK zRMYuY-iQYJ0s$n4in3Gh1A?5fiZ>pvG_GtzM#Q~E*dn@8iMof(-ED8dN`WBj8-;+S zfE=n@Vq%mSV;gI%hDb6VFs(pK9H8VgvWCt~NUC95fo)oOxt|0zsVXdsy_>Q}!}1lC z=TbvOeT)BFxyK5)K*m|`7DysZjEy1#0j%te5{x4cT50#EIB=xrL$57X72KJwl#u!9 zZVb@frm3ahdP7W$nTF+J!%Q!5jNe}r!i*IFb2JFSGYO?htZUpdphbw|ii-AVfT@$N zm_i=NpxUl-fZ7&!dkuj7(63mE98WNrvNuteDP`bP_)d;Clj~zr010l+ z&}%BK<>Ed2Q>%6B{a6$`*I6$>wI|5kNV(x;650LHtViuSO({tO)n(Cd>OuK`8-Z2_ zmU_$KtJ9#-{Y8KRTByOmi)^3IOfXy81ScCotl#3-XGE)g!0t>-Fp3jPL7P==pUv6ea65bQoQ@8^@T;GDUFMivR3@c8p^+c=bY|(g^<{ zP#w)*_(h2m6`U8*G;MTkm_%EcIp}?Q$;xlpnAH|xr-m|TmZ;+EhF;>pO$6?s-v#>-LfB00~T1i%cd7qN*M>{~nh)|*XqDSnfh5X(cks8oz zpL)jn@oetO#Hb%(8b=|(H1lizZQ5=mn)vuGpUjOrmQ-(hW_+;}W9=uPHH4+15qM17 zjK!hKNJW89MdJ(Fs{!14wYG?b9j^xU@!59NXYXy)e0ij7u?esc%)&xb`(jR*z2(7<#}khkFnfk}u8i;tn)gcMr9 zQF#A2^_}%@ad~qwa;2Y;3>5bSq)3YXk#K=Q6&)z5#7(0WrpYmJC*5vwG8B1Tf?;m5 zq51ehSM55oUBTB8DiKSwC-f1u+v=ap(!UE*To+l-dG=4LX-hmS!XBG0X)#=k6X{LA z7ulKmWK4!{_1jLr09*trPK`mdT?;(wDMj2PqEkHX_Y&I8PR>pm}Wn~hVjekck`^N<@5cm%^(6Wt@#9kC2^9%$ZWi~sTgaId zD0#e1?<&x01=cG&nqGdn0bXQEmFpt|F@|V!_F%F1mnBEpVnh3^$=@M+XnkM7dCqpFhb{NoX(MzdYv<@$ zW*w^sQW0+wbM)O&X3Hx2AH>_M*zzEbyZs>kJQT8QudtU0j<=p&??| zL4Ff=8&2-v(mXP{JA;yb?4S#U6_s=S8L0>Ff^5)4{|dx$QeX-&C$km-GO(99Eee3zFuDU}ukVFyZ$G>lMUHp2Y^>h}6I+&~2f$!@fdQseq|)bn24 z+?i;4r2PnB+`j^cCB@wo2zM)YESgy{HoA z_1#Dn@Yn#zU=0(!e725fm`TyP!%9iUUI$-tE@`(DtOh8Cc_*(8+>eLUtdAgLEpHVj zl7WQ$tiNnI=KiK0Qx~8HpwxW3`Eq9mCH==+nx1l~eUnvjBW`LxKSM z6f`hjsK0a|DX$3Hm^!Pt1?fn2b#m(3qcpmlZaQWv zQ{$;waq^92;t_{|=0N6i(Vy^Q20>hpX3she$5H>G0grUBt$}!Qfk_pM@fL*QEu6&& z&^eioB0|(U7)hBii#oDv`?47&?C9|!*Zk`|KfGxS=f@#Jk3p!S`b!p*;6U<7k4@R8 z_jQ;-gW0GhHat7wjJ0}RunxlA|8@=!T4^VP5Z zbib;%94~kH@`vH3sPq=PUmWq6R2M^u#xS|R5Fu2>CGzJRI8jIx zIK4F?jWCgog!qsMh*=vMPM-h3_IR6c&TdX;>i_sdCt@1XN^V zc%hbUsS3qXhqh^>)GE=qYd7vpFs1wmEa_r#f*ANM0%5HUW*)fXjCanjdoJuTJ{~t-4fs6j77Eg;sI*FUy&* zgc~yz7R(^HV;Hply5s_)`d4cflIp(@6r(OQ>VF1v+Q0DxHd)vvY{Oq4jg4R)@D{w- z6Fs}I0I?1kdCI_>X>X1i`WeZ3`IEfszq>3ZTgxvV7l8))JR1wTG1ThNvV*{@T=a7S zmEUT3ts(RlPPnwCr98O>ZG*4DRpX|=34rROJcKiW0`6S$-kU=vczhCuTOon|8n=`~$QsfJeMcW39 z_nlAeFzUy70>G80F#2EsBm!AG-jnTfd)8!K^P;OQcMMwEZs{+SY?8yPGw}74&C=Xk zGw4lhq9doCQ$*?B(mezJLUH3NMI%22HC}$JRFg35Lt>-Dv*$26|K^=UY(wA>W$v_R zf#KxBlGdvXfZH>?A8I^)T^8aBrRtfcHZv!+-Bs91f>+(Aq{FtYDUNy1v%?wrj^c1RKM;GlngC<)jHvBr}ZN4<+9>KlWU z03swX>-*bza2(mmP$0(bO5q2@$)+)PG9_ebGPB3f6(yv7zDx9`YFfIA5wl*Knhhwk z{F7zeNTAjBSGT45y!Z-;7`5!?nTKVfYx7|FTk3UBZar@m}+qunvhEexG zovuuF{tp%wL7}G>+gAc5Fm&Ua#$vu_7Jf_RcU@)6v88y+(3YRkJ-vp9eZIjc}kVrP{UBX7Ti1R&*aHnJ9xin{gq}@x& z0G!vGc%0^YzJShH#%B)MN4L7dC-@j8LuD6A6mBp?bB4`NX2<&(>@PNvF8!C)#O|BI zMK2OLWzM9;VevpZxdeR{y~_PSADtT3TT`z5I1KXZeOgtKd(If(=aBsqqM^IK>Y1+F z1vid1(9mdMakbG;_0@mmcuwXl@fgy}r}qN~q>pJ)s8Xh8k;S~@PohVC3z{x*;YuUm z{hGA7KVYU-$q2Mn#VxY=oLopKXk|U^^AM}HlD5$!OrqI_mlBR8;=*3#@@_UlXSDfq zWs+m)27ZWt1q$~mx%j)(sYoM*`*_t#f&#W%%KCKP>zDq|_q6i#gwCiZ(;>$d>i|DL zSk!fxz?85B;kgGGrZe(x&^rGB5f?WV3D^*p1-;J5U>Nh_e4i64!RN5HxXbh6KdZ(c zhiQALb5jx<1=`S0r!AtP?$Bl1NQ_^?cto=v6mgOes1%JPHw0S!5O;?vn9$J0@=?J@ z*-CDYh-ebPnr`44ks3kpw2qq)28IG|Svk@uw1beyfFwj3 zqLCTFL;rRWg3o7V8~ z1rUTdJz^l&{jd`qId{y$kP`ZgFhi*?OcTN$#ag9GWzr2`QV zmelBX);R7C?PBdBb$gJ47mzfnAc`RqoJ4=d0%p3H6I24iqYY+XZ;KdMT)O@byP_k$ zpdRM~LY&sSdRWVhp=^I-%5Xy?y(HsAe>czEHQH{s4|s}de9duJ{L0-NOrEwlT$vN1`nLxe_TstYV6L$5O&C*f!WO!=Se9}&>AR7BmYfZBglBQQo zoB-Q`t`N73nhEllGjfStF?@}EHQHZLuYnN{+{)I~QUCy1#EoO0j}(@Ysz2PUAImO~ zD^mxjLD8}@Ejqyw_R<$}qCwtuI{jwUs;u+J{!VzDjs61viKhO?*F?>5f1CEEzoDxs zP+3Su(%arU!}kHzjVOYr@OKoZs$>pbSIKVF@)tgRPP(1!kvplMpt&#y_uukR|LC>_e^$8o&F5YflvhC1G_rkj6n8)4| zQPHCg8`}LH?IVIs)|Vd9n-oGd@A7G-MB2@L5yEC?dkYwUigk}l5O+b9F>`vUIBOCC z*k67`+5qIKb24dw?R3HUK4-7xmDzfY1v~ql)KF>l!$GT1QGOZMCR+o!Eq+96cM1%L z?nIfY`&2;I7&0D&Dg^l<{PEJpki+=^kTuNpKqk83#OAli zN-Cl>;sXe>7vL@yTlT=%#3jYD^h9Al;!Q-u8#uFHGt)%O>QW|?Pr;RuZ#RqWOy0=N z-5#46t4_EEnpL(l1aqB#!KVrHL@U+?#uupaz(hj{^gh1#QbWHoEhNEfge21WZ~ zq9Y@OOL*9JE?^eAKI0EY@fHGp>>2rKcZv0KvgyNat=pMdi$UB8lCz}<#xqJj@`*H% zR_@4>$xR2yS5n7Rc2(+l%S<;-R}6XdGkBhVS0151z<`XQ;KNk_K4sRD!lq61N0A`* zsge1igl}zg4CTz~`nU-URNP6~^7ouTEz&JU~%mIHi1l(TTBq=U2!GlQn(ZbCqb!i zCY5lic4hs4T8}YCr6OfqQr7rWraWO6Avu!;(1szk6dk-))JrT-4H97z2ONLk0`W7C zO8cN}AjpXDP&X$>1+zieV}pLGLggZbe=`Xnf*Qj%V#7*MeeRV?Aa`QuO8_c7 z82`=uxyWAG%CeN%&TB~V;QCd(P5197 zuT}E@_w<8*WDI)~tFtp83Oy71J}64KKsM8KRRETZ|HDNtdSaGwS5r>py*|DM(@Pm` znpS=}MQFp=z1W@e@Z?3!x78WRypzkXVkk5H(|Rp^`ee5^t+_3c3yu?ns9LB$u zR+kv4-j&zeM4X;y(b zC9Xp0R}0SC2`ZnHMAbC%|9PEwIo!_`8zC@P zT;_GQ2F(fIlTW3N%a$LF&y9fgaf|8doR;}N&I027Ikh9;(v)K-gyn_s#eQ%0GL&U7 zg)Z~JB_nH(#YUNXTrMZOQSshu*(cig<+^d)->iF0PYhADqv)h~jU1mi`G;tm`GKCj zcwm1cGE`G2$Z)#UjbJI#FTtlTQM62{Ip-E52{jJ@wX^7v=-GLS`V4Uim_tw4MeiV- z-%sC&dyS3HM($UUv-PYG1davi-}3h$3|JvX&f!SvlSm6X57!|47 z#4(j_s}9OR%yb}iqw1AfucwFw#D|10c7gd1a&rC**F$+l*

    xDGVmb|Twz}GBRpk{#a2aYQKXSSJc=- zg8)fFMA99!$xtx@Z{QCUKolC%k>)q3&D>ZPmw9Wd;d&<=3!{z2GhRRRHaQ^u`V&tQ z5+l=6ah!?*-c|y=im5mY#b_Sj%BiP3xni}|(o_zu!$fMj|(f3-?79Ll) z-2qOpG9S!HGu@@<(Xl0!lqL~g`x(H>V+9=%WKfjSVhv_e(v#4kJ(pi(u2k~?s~%7U zz{UmlM|v%q@#$hhPW;eV_TjBqJfJf)|QYn9Xm}DI_fi`Ib+o(av^yv97m@=U-<< zo-pu$ipFl`*HMu-$@DiNr`dl~(KfGW>p?-fM|Dsz;kE2#jA_Pfl)c;l+?zAwHEf`i z66CR5VF5-Ux#tGpZRI>}0l2 zvWiEhX8!No7j1i?`jrFH%dt9bJdp=KkWD2=jmKCHZKrHFy38uoq`W3K#I+!PCI`aF}x6!Ao%})*{&c ze4X&Si}tZ`Hd)ATGlLQtnWe_7ab{+3Qt~Uz#NERusZV;A{>oyv4h5ymvtGgfp565Z zzy*&%*%O_CUk0Gib&`cio0@zuo6$QTg!THbls9;9j z2>yA+jb?L2zC$=4qo{?WXng2=>F|JpHpTbIkaruB^!a{hI;F`f_q+xF5+X3TStm|^ zEtgH}K(>oOXfhnL$DNe8N?;0{@z6#r7X6*$rKH~G10o%uKLXtv-^Hut4fLh&WC)`z zM)L9&Ag;*aOZ&2Sy2rnW7PU?^mmW)NwV<36APpk=9+y`XgNP^v!*^~_{<}?maoy;r zp*w2hr)7b2y(B?*4Zc5fLQc7ZchE36v|SF&jAc8(%;*{xy8dT@q`{{vh7;3v4lYK% zxq$7|&oFQZqiw&&n^-NUN+({FKh84*ycPmJi@L7ykEcT!VtuWQfYn11w#YbyOnVaR z*3aAroQWf7Q7S?n_<|L}m=@Oo<+ZdnfVnB=XDyzzamsbhGm=82n(xw!)3aK5SCx=t z_sdbr$~u_5wxqEMVLhJ0S7fT9e|c$QT&~-QJD@qu^4P zBOc^AG8y4g)acWP=Q5C+le)+1UcoSt}eK&6`d?G;Bs z)q+IF3kvpyJkOpTccIno7nF`_ylKN5KX%9AgL;>53>dvA&ErV$q$kgRlC`s%>#Yf- zl@I;- z&hVTcH>tpf^dXwR-AMMvfzK%1GJ(`=vlAMVH^G!b>k5d4aMhcOCnNz!(8zpNyDquZ zuHb{TbCAJ|sp--v0_x}ze48#r9W35`I_NJPK`$NPyS06YNdoG{?4EeM&_NOjExT;v zO+z-P*o!Ts>xw~{JZja&9%lV;USEeO0lW6hcjb$dFBM4`scpGNt(Lr6*P&N+um+#x z$c*>a2ILKYq8QGjsyq)XX~l$lQX9tr=82E{c*kEj5pcpaTa(O_f-CW6Q>6vsaurPZ z4AB03$R!muaD>x!u7F9jcjXZ$O)NCL%$YN=rjz7 z{+_8-PbAMJV#$&x{H$}g)QA3i=HDn_eF;=LB;`&YgGYWZVJ1a1TqH~tT@J@M39mWT zC1`&+H3tAJ9W5s*yJnyN*rjd`p#j@-$wB(Ed4Su9>$`*yAC2u*{DWw~lC3N{A`j}Q z5Hqn`!Ff)+Bb1r|h-+XY(8t-yP*9?NrXO7sqF>5G5xTFv;Oo@#6hhtd-dj$|=Bw+R zHF@+CWzDo)z_p^S|MHtmijapauKX;)%$UO1ptvw{4@s+00}a82vi*K$`~D+bc`V(e zYt20!yI_izO0R?}p8GAHnBUU@l)YpMXAtn4$jwUjiuRF$C4QtA1p zO(^{EbKK?`Y~GZ2ta0IN>b&m5j%DR|O>lu_)V%So_YKPTh)MJdiB7Q3@`?2`0{ktG z8EG^S@e&6)V-FT<#?*^GimOf$feSUT^6fYQ{UAj@7p<7A653a4WSW~oq(rNEwj!2;e=h8& zd;JBfwf#ozf*FB60Kw{NW{O*Nz@3FY*$fV-;z{r6bS<^)5a4hlLaFOLSy_k8geTfyOTy{KYF@jMplI6>2Q9y0{vO6$k|pR z*VSs8EZc(l5+zXxGZ=s+*b*Rrkb0*x=unz(h!(){YQYPqYvjJQ$yoRSCFv>D&ZtU3KV-Bq1hh zuLg{?5W=hF<+Qi;2PyFs-S}H1#t_6hk7#yHQ6E6wU+W3##+_cM;-dXXb|GXPuAQ8U z3nnPD8}Lcu%MDvSfile&yGQIvh8P*PkCmyYm4U=bR!OU)rB*oYEy&NBBD(U?Pgypn zez5QwpNe&R)^XHf2k0`J`@)(5lZmZ0ayEC)60!Aph)p4Gy2_Zpo$ap_KUz?AJB6ELaF3zDK;GvE{un0Wo52cq}T5TZH6` z$6Q9{!h5xU57D+PP-732#ij?SJW20|D!7f6&y4arAkvYOl~AmS%bp8TMX}vGud-`ZxahYE&fcOH7L<=ipJ-o+)7jLRXV@)TOtLeV#Ir_tY@l=JIybj{;8%FeFMx98%f6C~ zDJZ}%kv%yBN0rprg*2I2E+z5}xSv10p0riOmZ{+N)$*u`55+c7vMo3kB%;ZSHyVqV zgqONQo>AF2Ie9nTc+belcn^!A>;$*Ajm$|Mb+S5-BqnU|+vLFaLGu9@T!T&;?42T) z0`^YZGU1PF11d`kd)h-{QonaB{S`*) z>2rdPv4UeVDaLqYCis}IZUfgrr}F4JTJY}2p3Ri8)YIrpV1Cr8NzdC1Y&VO`rvSby z@yBc$g7S)+4P8Bui(mc@V&*s`{5wFQym5JRdz3iJBi~$03JpJ*i zrnX8Dpg;xPn$|o%(Ua7YJ!F$9@Qnyf(`&OXc{c9}Df!*?;jX zC8YK$0v;ULE4)pQkr{caIKmstrd8YLG&3d`F3}fpdM@gF;N5$p`TwpuGOSr+9Tt#% z!~bTd{jzppq7zusp*+h)Ql{bJoM+15IrA93bj66+QWqzHhT4Ey>T%CAf!ZLz#0b98 z4!HoaB<3<&dKKUR=HQ(<2NDvKe5nWxz$VSQv>zu|y%z1*JoG=>Zjg8ajfS+|%g=>J z2NNL1%>K)WKVt;2a_L0~*8y1qr22d0$7AAeeibYIA;{~Gpb zz_`eqwbZSR=Uc;2$;!OSY(yubIx-iy>>qn3bH92*CHt?8soQoJt*ZNFu;TDH;;0L_k*J)*@E*~H0&i2yE{|fvJ-gJszXnE{h5gFbDrB9P z8W2aJqr4;i208LvRtP2yW^?g%C9f&tSH%srI=55Ea3+-|W{;)e&rpi@?>*2_>ZP9u zBM>C-sh{XD@Yud#Bx3SaSHJ_ks^UF)OtLl_q!pXjJ9PgT_Z5B?zCo4-%L1L93X<>M ziphsmp~eFB6F7XvC+c3N1D>(2@c;4=v!d>&n<4dHOtWgj{6?2;T>exluOLySW2KKbiO*lkaD02x^+ub7qj_T?OquxXhcTDc*q87g|JwKe@XXn;pGz-nK z!_vB5GdNJZBiLxPp= zcsS!~2%E?G%uVJM44&sN_aCt(V6J9@GE#?um|#N(x4ET-lFxUp>!GO?ok`WBm=|_9 zL~Q1X%gi!tWg$C0f;MC0y37W0@6um#R`Of>0n= z>t9?_-$(O9stJ)Cj$Q}MfEx_vT;Wk}2{@VS4GH)hk0Dx2@9N1u9@84{{u7W(W*!;T zRe5E(@?hNEQ-7%Sa+W}ox>74A!`2PhGv=0_J~`olbKx_}DtL&%Oz?CQypb z#US&SV#Q8^!~Lim5q~5@s=K9s19M4N2jJGcHT>DNW@m>Zy>re0Oxj|r?BOjvysn7@ z(tja{t+}ah1Tzh#mUx$O{+w7;F%K7zQ&Ic7|bd>*^gIMWjg@68fS*duVY-o*D z+Mu|#vfWPQe*_K#3)pd#U*9mQS@s@k*7=>(u_UApm19@+MK?Umt3|7L&b)AV1|-9Y z5w`^O?Z4-b%6nKraq$K^`F^%XE$}Pn8}iVDTNO-Sv_3C)F?3bw1tS&%$G8z1<tmTa*>>q9}ZS(isk_r7sQlKCSSp-3Vvm+1`kUIo#S{$Z0sy zvnhByex)#g|Ao+Upd}!7#e+ECknwF#@`!fXX^ISxk*z!4o&5KxJb0PbD5LiQR%mp% zX^PZ(y`G$a*8#PdgoUtf#B2;hG#+aQ%Lc3o%^>p6F!<6C?Yv)B`7sfdx)264KMaV< zpxUt|9yc$+S)oGK!dbT`Zt4czv53RO?1aKqR8W3TbdBMKkSq?xWa}z`NM5>q-!<}f zg+`NM;hQH?s6WV_O}ajETQW&f8Bg1=2Z=;|WEY&^6ZBK8Uo{r*{fETu8@b)u&D2@T*Kf4*Pgv-ZF=5l_($7-t3`^ zS9;^>IM)sjBzOeXTyz+OQoDm&q<_;Qj=yrH;un}-t~kf{Tpl;Gblozg8S(WSEH@GL z8Fu(6PKP#3C+D#P@RXJm7v8_iReaF=!6c@o(TY8p-_;14$TMgV5)>_=gjG$HjUJVZ z6UnMJPW@pvXZsCmN1_f&g7)mku|LE_Ahs@#T^oMDCnTggDA>8hX!idK++ucNUm3Ee zM-|wmW)UVhtWPEO#DU`Y>`TTxIpP3d;$udbbe!s=ObyvfjR_0Q#dm*ZeFPmoKs4=!($l*mqH*^JsGGPD4e&HqIex>o`T`CiHdZP zaBiT@tM3&%W6%ouOpX;VK{ex4JdS|^WB;4qG)~T?E+k=mGT)`bnS~emcxiA)zQ2dp zWF8NP!qDGO4k`DQI z;{W^_(;hNQx}%!Xja<<)EA+!}#jR0c(V`%_J&AJgwfjw1b#Mr!xv+aS?k^M%0Lr%_ z2fU`60CB3G(vHcfV$9B|?>5!SEE7_<%RR)3(CxoJe@%P-6qJ~P%A8UTYdG% zOp}2+9pTQg#N+(X_UY@W%!}f^&(X4*rR;KZ0n~jleHAIatyY^}39X+Y`z=Tmqq&ly zagm+QZfGVir`TRKyN<%R-R0fSISXyPQ z8s~+Q9mzr`Qmc(vX{Gl+Vz(>86KZT$DwyT4DJ3zs_ILHO_(5Iz{mLVam?X~u8k!EIfEhTk4i7upcXb?Vy{k)8Gpz;ag5H)MC(w-l zs-#i*iE32E&!`I4RSM1Fg|$D$wA=SirCva}hxPtY0zSw~K8=^XTQgmRs|k8Lmo{#< zhu16S);b;;LW1melBl~-I{9a;6Cp8Rx_%h$cjiMug#YR=$=V0kAFt;KH{i%=@~FbK zWTyL)Zy=VNi1Yqun*xD3tPk1YCj{)jUhSZ4Z#gKSz&Vu_ z+Q>51LnSCKa^w=eD*>uNp{+?goX4y!O69bc)@v5_Fw=_!#?qu^fC=9X_-5Im7)1An3Wwv{4MY95RR@~44X$1tkV6qbDE0lT=DWM<$ti7bE#e9tungXH zhNv3ZH}{Q1j?jpQ%WDBy$uhPi8`NU1W62g^l96R~Kt_dH>N}RJFCQk@?W3>h%^F;5 z+=XmvLAGt-$eUo;aXH<2j3^-Vw|H zMBu!V#LX;E{{)znep!oNgiajLZlm0i=*g(rH&G%bAyYjh73Ao#P(0pE7Mrh7a%11O zphay-wknTZ3ts6b^c9Hq^j4oiTz6A{d-3P))WXi_(HRI=`jTwZ0`z7K_6~u-gW0h( z_NWH!xtD{96590kAg06w%fU<7|DJz#H(0;4=N(Kx**7^sdiGP6HY>k~LyN?nJfrj< z10R{4oDPCX^=Ku7btQJWrmxh6vwT844#<&te?Rb}V>j;cn;sOoNGDvVSHO!bY|W4K zSV1%M(9b;GUN-|ok4Sf|WXT(38%-mkxUImt3kV!1%PR0|DVc<-&-Y*mK{cm*w`#Ll zpln@S;je}UnMiV`-g`cGx|20Jg%^`uC?}pa5g14EB&A3GSyMy6ww)LcwazH(kN^>L z&g00pyGd84JCt#D4t|pH{L@slH_r|!3j^rX#*$pdVza(sXmHfa(L6offbU=sD`=s+ zVHk^{@alvi_e#4$G5jhHeb@TRDDDiG=accd2g=Hp;IeKS@%1~|;0mIOGPL#7f;ieU z$|zqkO{;DyHgdQ5o3NEA{cD>SDn@g=4nD@C+Uf6Sbcnx!U*VR;5+jaVNLZu zy*kOWNnc<&@q6ajNmW+h2pVv9!X%Cn-Q|ma$&A$)Iq|b!>-C7a*?=P0rl39s0Ep(CGI}`X10D{2Xse z?=hl8;ekuaYD-(xS#l^wqnw7pZw9MmvVWk5P6%?F(}@bx>0{W3I){uDYr{jZSh7wyK3a{ zV+_3LDMQ(h#eT-&Wj{0uO!~Vt%gBdNUeE|4=@ipRx6if)iM2z5bH_tu6=rek9zbSHFvffGQQ*_YC|tK*50hc112cmxNh=hgi#ih_)67 z!_FD2FNl=cnjkrOjj5zvDGFro{5JfiQyw3@%3Y>xdaGog3)>fRBys>*=t}-Y*3jeH zgz|jaW9+nVQAwL+KoCj-JGN+&Ghs`4TG`Fbfd1hxyf@l4BGs)`akplibwaUN2oOTI zF4z5n18v$Q5Cl?nGan}=JwQm#+chtwHSh*){5eTyR^k)fWiR;92#^tmFu{!Y}_VLt`N zDM{JxpvG2!@{)AeCVb~qTInLG^2M?RN}3PhE&KTp=f*uM{u?N;JsZgn@JpB>Rt92y z$U3YD`6-Z?@}XHM1K;q6I)bvo>(9WSZF`!!DZ(r3|30%P|C4^1inz&M{o{VsMG4{Y z-VOVor5PP_LCOdtFKt$yib}YhSQT%bFa0-&rpZcuI(-`*@hUxfK~tF+@ewi0b*x7=()=fY0Lw4j;ArWwi)y|mrX-)$D;noDoxJ@D zSgZJio;|pT#w&d_YUu;`w|0`d>jb@2Y>BuEfXMMl+-Fssq>r0s#fa;#w*hJ!S#=1{ z@`ck5L3)Q9c#(MJv|^kjQHM#b&lpP%f@>uHNS&v|OmV%{W|>UjqyQX_uZvrv!<>Pm z!bpGNkmoVU{ZM#81f&=OCG<<>#mvCJ&*vx_Q*$*)us<~X6U9NxVEQ0T_gOL+m0_wH zU=ZnrT*G>!Alg1gAQ*aHplP5b7+Cgs}TY8?a%3Nte>sGzYhdvQ79Oij3DH z%M0zVRs}x%;`F0U2FeghH%hm~`eY`Ivnt^?MjL{B1e^M41Y1t-G(Kd-O52XQ*%3+4 zsq~i^T`Fok`Mouhf=C4kx(I&L7MGwEvfKEd zxdq&2MJ^$dG8)lX)bN9!2nZ#58-tB8eSt{~D(KzxxOwhD8?7w>&v4JGAcdBKwQ|AC z2)x&pP?U>jf{}nSD8kTUmmLn9%qbKT@==*7TnM}|EhSt9qmDh|H`o6giVP@$YE;n7 zQEaUd`@LS(kI3t81BK#ova)NOW?9J{Vz5$z9mY#~3>@f?pEnQmcO8I!~ ze~wp>qc2@2M?_-l4qbWYbG^QINu8P3sNSm{+5@5#&%ruAOS ziS0G!4*$b~xGSIY==xJ1rOCw4Nf~p6S2e_^zb_`KPXNT*8rxQN?b35!5CW?+xHzeD zi8D`~v1EWeRcV3wmw z3UjqHp=k=;>^v3tHUl5Ra{L;D$^wD6d>QO1DkdVyzMd=ZLwbBw8T)9!`~B|tqXW7H zp$3q?^d|xKsl{#or(<$IHC4Hb<;0jYjc4M#o3h#}vdCYX9+>jQ3Emfg*2Zns7QVtk zxWi9^R0=9bN_OCZHlfG)3U|Z~z|L@gVz%?5 zR0henc?TV3#l!!XNAuwPBrudQ&kTCt1T7@O+e4NLkCDT>OZ$Xhe!|5gmQb`maE`c< zlpF6**U7>&X_Lt6IwC1K&eQam82!A$1$>m~&x9z|n&sw8qp4SmvA?&y}e?AV%*=UidB6Xu!e_3UwKCc~)L4kmd(k+zWq z(1zzhORe?VOcElO&KUD6f0d0l_T}YFHI91!>7OriU%PIR3}Y;>DF@4$4rb*H7Zn^u zujo(4K4t@#xAp;#6*Yd1y}GlK2vHaXKQZutSJ$tF4_8P|kGSd#{mj$%l6=7~d=J#u zuIV^@;^`Qp7B9l^_b!qQLfg$FE(OQz$LF2eArCrQRMW7jknO%c?gJ$B90%9}sg4po z^SH{$+O3YPWrfZ}HojyqIzVRWjvn=AKYc;E-AFxY)@#eYzUuU8Jm2nEOS(>!bI`NWWJ5Um$iAT z6BmIcm&SHJriS9XtqXG@sZIaCOgG&23@G zajG`VVV(`3ZZTkXVPF!jThvA=4K`KufOk^Fy6 zyb%vgx?D+N&*b!p%USr8ea057&TgrYD!P`X%~aG^0knA*Z1l83-!Kd~da3&NmQDnm zJ6)hTJ3rg*&20>FwF*!2PqL#=1tUSA57#D_b-z`j;RD_vIT0QfTpGbz+k@UqRIh5Q z$q3B_8sB$5UXeaFJ%a$tB#fthH9AC&@#`x^%MAyeIUTjst-vbW2;di-pDMhB!kTX_ zQ`yONc!;vvfce83Z)U~|?g0Z8#~x)A+^{PYhgTvh-1I~KqQtoc1~DVG&HI_oYr7HKhc z?IlMwBH1d!`1gY&y>&!w!hnu{xc6$0Cl-7vWWTOU8eio6RR-NT%vmWEgv(!%kbfXh zY7#frWh()(S2BGe0V1cqVN)c*?;@rQAs5ruYYHSdZk}cR%o*-$zSH$u6Rx&409$el z!_s&}hfQe(WATL@C}G?59H&7FQ)M49k@GoX!L|VxaH`p<&PsAx)1ybUI%`9d!p`)c7|ogh>#*f50SD~z z{;HnM5s=C$&5dAC^jKAhKw95~bal?-Drh>@69EWR-9{{R^kAG+qRzIu-r69X1;9I( z)T#LEpIvDj`d^EkFq6)hawr}@%bt25N#5T+85%$-pxt>v9raN@EkQ2UK?H zLyu1U=qz>wdhF9$390kzTil<#eMUSzj9zLv2Z(`k#SFT@ULGEE+W zgHX{>-v(_XR7vBT3StKoCb1658lIpFM^oMrw7w1O%TM2J?A4yo(Ewf81R^PXae;(k zxAE-b=nGz{MAInl2m;R4^_C~Is^q@e1=Y2-=KwQ6%)hUlZX4>8`hd?en)~x$^=B!# ze!aJ4-LX|d=6xt@*|v!s;3Ry`+ek7OWt{_(eQ|e|Zl&iHKdFczpog~`{I=Qp-CasB zmyjn356YMRdBcrV0q-DJw@4nz18)ohp>>HLkH;rL(vI|8h_bR64jlZ&Es1J#`k~tP z)HDH=47%4QMMS%^fbfdh9?ZUFT_L`5%+ z1YDckWaf^$>lsJ_c;6XtC1Ra8H7iaayW*fXCXEm?kQ7*(MI(6j0^;L^23#^a=`$lZ ztmOBC#11wPOdU_1y6RbzsU50}z&`oqT7L6uBz~sAVJ2;9>|GR&Xl6fvn8T`TS$WpL zviRqyfj?WN-!5&AJh!t?p>Tu{;@RcmY+-k%0|DuYe@TRM2zV?(Z95Rs?Zv&sjCK{A zGkOOFNr|g4EEYWWGD+uN7tNTya2+{{)JJfbb#t(5 zr*5|;13x!ym1tWIrJB?d(6T>wRxTZzCGZ*{zeuU?Tx{w^7kiT8pD6e8>t{I#^~7=! z=)22=Uu=|yVgYs*hY@I6?o`5oAHnIvH5wNSOS}FK*^18(Oc6)e`q#@+PSPIvNjWb;n=ffPImZ;S z{N<9hz2xwf7y^kXSkl(FcyT$sbs3pca}J&d2+2Y-X}kghm#+)-XQE@=6x>tl@N%Tj z%8V=3Ce(K$Cxq-`v|#^t;CZu5>P;qaUFP&E@YM$(^(UfTXO-lUkTrQVbM6a)0ih&< z)|bcns0K-kQB)mt4Jj8kImr-a@` zhJ8~`e;?`?i8D6;QfTJ)!Mp5Qlhg+-$aG(JEpXi!)k^UN+G(L}q)wY2`Gv zv-?Dm(iJ|G+{z&&tSzAlBtjFfLK(L|YXpvrI7l678ZqQTbb*z4t(&#?xy1_=Lk9z} zeT~R$*C0o)?!E6CW}^rH3#`EC2%%V|es8EW?4McFUv5CBO_2aVWN?!q5B{i8$(7;j zlfF3bHs)WGm0J`g?#ondUMGfKt)6N0y*T@mlzG@MSZj4$n1iz1O)8t+FIF)T`+Ms) zXw!uvxHSY(W>;7G#8V5rvtogu^>z^J5wrrHX3$k(mXjwr55d{~3`M=j zt^hKiNO-d2Cc*W8MB~zvr(VpSmAQw2nh(tTN#w1_|rkxL;^Lu3v@fC=Qv2`5W#g3vWALzZbX3hJ^(y;$i+E-eSN z@TQ`g{~pmGnfu9ruMehuwWJINJp^hD&xCL0fm>1B=H>$OA ztgv1)pI%U_Q0e{Z?!!v`(jxJ$asb4=14VR#;+<)w)MTF$aX0-HB_(cchC@A%f^h*Jd6;=<)bFs~RDV_h87 z<-8_Q}>DV%HVmY+|xiJLYzYar>srX>WBMWV?BzA;S(V0%j7oPArmsJ{yvck`*nqWZ^`hseJP^ zhFEW|_Zs6H*~nLI-W`%`7h1e5B#rJ>kLr9DK8}dH{f`Y0iLitt0VBQ$m!<<)8cGbC zfR@pgOKLOxLKCbvzCj~@7u=f*?PBxz4lh;-{XP(rhAV!TuLzQNQm&`VUHwi|P=^u(yDGS&x=#o6V2EfPTj2TeK}&HY)^c##GE^Mejl4>7LS zr#JnJ$3FhXFY4&6sZq|EPV0_utc41}pH^NBnRxZj<^AYYqk4js*bU3a#oB%99r3}T z6J^ofop$6s-WFv`yx@HCA}6>3MPB@;f)+1;U%7=-{8UatpXmUsTN-swVay6? zyO&F5Zv;X)=)A>!=gJn9z8k7HeucpJr!Iq>=!~!?Fz0Yl#`STEf>~4JwnILv9G?Gk`cz;vi9#)WZxY~0FwtMw zISAG){KSh{HwkJCKP9a|@L|UOsm%RYdz^sTKm(`9XGs&$L$Y^q!B{EE);j!aH7-y? znK?2}LNwEU0SllG{0yBA!{^z53?C<~NQ9_E&p_C830yf;64V2Kq%H0`Wh&`Mv6@1f z049O!d+)WgQ_a63J-aoWLEO2@yJq4E)lsw}v4>Q?@bKu8oJbWy%;++zC`U~$5+Rx9UEKGlGY!@_|?AkXvW_8$`X)rHm~$%q+xkP01=gaIn?y2AhFOI;SiG4z?c zLvi*^P*fBcf25B>dcb6_(vuw zI^p;mRBxNAfb+$#j33niVmNNjg=1r8J9v#s=Hcv^45HKTxpilmQB0k|)rbwtN**n# zLBIU0MATTvb!i|6A%t93>o~SJxivMivD?YKwrJ{4(>L?wso$5P_Rd*$xoAG`rOxZW zC^qM;+S~L{^{(!+jH(g;A7u3VO5Cw~#ayK_XMN03U$D{$p6)7+WJY`9ce}3cnY7Wh)Ypf2N!Z3%aGN!d(@d zeD&0OK?Q}m3dQ0#IjD-NZ0++WLTsXhu{0;`jBS#SfJWSPiZ4jF{|m_=2VecYXztEo z-)8yvp<{wn6G{bZH5g?SoDt;V_J0xs$x`Nf_hW(B?EYSfOm!KTf7FS4QFsXpr5QYH znlgzjZ#8W~UEzFQgG{vyoKvba?=id*ih?quDjiowRY zf_@c?a?_|fsKo~jW^eY~Uh>mqJzAjYRnrbiLAHyOhtC2+E`W zB{k==WF9fkxekK(@Ztn#h|Nm=bxjebMtka5+E3<=G6&GLspAyaWtDCl$gLM&DGCDXrQN~n}*5q z!Qao`sq(i#f5emX!?pj_%k<6Q4SCsNMIEac$5^8tPB{u%*GG9vboc6(%y=*q^R#QB zz>>85!NApKq~>T7B0c9=OF{5IdLJ0HU@Q}NUO22_Y6gLObC-3VU^*b(?r=F%8=1X^ z^JK-&mhjkGrVY^Pp?JBCco#GYM~X!f_)uGZZ2Kc&)5g>29#d-!Rkz2{zZNhBvcDhE z_5A<#X-by2Mmn*yaE-v5%n2EFV+tPwjEx?dNxNT^!ReMax#um>@5nLIr(vlp(E$P> z3Suptq$4OH*&u0XW-tjVuGIMCUF@D5tG)B8VXT^7Dn4;aMwiq7`-YEO(lT_8cP#1M4AJ?URR4e;IR=#WLdy41WS93$Xdg@SRY@@nW?%Hb@dlfkVWx zlB$zr9D=j$yg@i}v2@%n6c(5%it~XL*%FSJJC7j`F)!0XUrdjz6`0AT%*N5Aj`&^z zpX#A~IO6ZNyfmhqEGgcr>Fb!Y{KMIwyR(g*a!@U@-?hrEdsVlx901Ly+wbb=Eb<-c z9=RR-!yI_(Vo_*OwlqepvIgS(g-9LolLm{KqH_liCArJ+k_Q)iJ>`kocs21}ba=v( zgRS>P&k8QY`9nZdeAy|I zHF*&&?wFcl<>e@mn-u8zHq5c`ZJ<)CcwsaGJ4x<;76a9-Baxk9N@?h$d}!_5lMK~& z)w<3Z$OnC~Zg8NrwiiwTXCuH5mgam+3S>WRW?DMCtkbQ$^e{d)bI5!e(*4OgE%0`6 zJ_uG4085jAs(G?g7Ir1|Fp{%<;5r5CJXl3$gUAFRP5Sam>&Q=a17Uy3# z|I60yVl~kZFo^;fa%i`HF^5^Uun(jgD4q7ToGV}59mYH% z`!rJxg1pkh_jyORdOtRVloZO^NoUB!VSQ()de+z@vylK#g4SYI=IvQa#0}Q(&bcgr z%JQAdT0=!$rC=g*m=Q7CaFK-;i((#3Cm9y5Rg$^pgP%2qcA28bK1yPm@8|F=61W=# z_~MU;Q{%?xxlhVW)-gg5Efcm=zRKWH)ZwCf&~sRbML%30|J<^U{fGLaDvlAYWk-C6 ziGKlY2j|+cuEOqzf~rJV$+o7)9qgw;IMBtjOnp97W1ngW-oo2ouImBGx;Rod1DF;T z_Qj%joiYxm0l+&wsG1I+B4g%`$NOLL>DzwN5yidEe*t&jOwn2Br5Mn7YFd7ApSL}CSkTwunbh(Z7n2=vzS;vECnmSvwt(zZ2&_$*A+E6j@*!Lv*=gtaJyDW7OrXXgzYK_nu#Eem2irp{dhv zc(wW>YUXlY*98~iwK4~HwtYm98}d0YxkROH>`(cPJ$UATU{1a~;GPaX>9O;km`gYK zZw$xr!9oyV)q~f9NG>9sACFqM)duvj{cfMGOsgRLc-M@d3e-V7 z>8ZK0v9t&_Wd(LS@0q`=OU@kNU=eu=Z?GRCNWJF9C@u2!OhCQ=vmx}pYW*itBhIeI zZqujt&CNqli8F4e4&1tB(dD!~tO#hfMBnx43&P~S_uL(`>)poVUPB2*VS;@cypGNJ z=9y6b^4uPRqTXWB>;78AN7)>~o@WgzHRQJ3$D$FJzJ@`XI%tN@Dk1ZOLml;-RAj0) z<}$-HTGLyYmfZ$~^W$oXg7fjHN?}YdCmAFZN=V-aV5flJBvwi{Cu**(cfz$FX4Aa^h;S?^&O z>~x07ocN!@&GE$H+*q;3FI;FZBKDtW$>2Eo^zx4d0mhZ6d1~%VFp8cp=)_&!?l=G2 z9q-%%b%wnMM8u4daEEfTJtbL)Fz;Umga1Hqr3kK&InldOTAYiTF#p7zLm77{Wor$? zVCmn?Nh6OZ<-SWzF>zU-Hy6NUuoEpp{E>@{v7mER6r|i?Hpm^m7K_xf4`w;Hr1cJD zS`;hHXFTEK;6Vyl94kkd23Dx}Ck0;{&4ZSIR4YoPFkO?t?&L2ViP9eV^?Te?sW&?HwA?gVWcQjuA)9Q;SoDL=<(@(MP@AZ7xhaFO3#DM_%_ zzq&NjAqFF-q^FA(MRT>9W#^qOmRCImmTCu5F|*ee`N{^jQl<(UuC050G;h$TX0tf8 zhdqSe25VX5)IaR@nn#`n8>0cH)LjFW2mtK^&7HI0kKWB^Bru7z0HyA1 ze&6CtFtmB{cddJdT7ODuZ;(ASk@tKhjS>URq1Yo~h4PGs)NCFX@05nlQKnsbjZl7% z38Q_nCNzZFB1WO7r?U^ou0pd`5P+s*UZqAXFhr^4oYQFnDJL}`Y}3w^)7yMJY=?g{ z!QA;gJAruZ_lV@Yd?I;2AW*L0+L)p9;|KfN+vM;|Vu^_L1^7)P7LmjKt*kwidZuAM z&AVB+wXAlmFeBlroy)bDp^9Yw+T@E&wyxG0hTA))aGyUE83LkpPpL$;)=(5tp15cX zUMff0lB*I-QRditv1RNI2xeOfunTnZEAmhBv)oZ^s%(Jf!}85JHVzozaoA39L#|0| zGwxC67O?F#D#^!PRZ_p&Li2PENu$Lex~{fiZnDG`6j=pJ=jtNHHuM)hH2L!sEdHfE zns84KTPnO`2OmT3eAPEl1ysXviNgmCJl4nZDDW3@$er5&x)05G3^@8<47XOUQ_e!m zMMW5UwE-#NS8l)5ceNJu&)atatmVOqucH7|GVTEb5n{uEfstykH4=VxL;J6hpRB8iUVRyVJONQt+tyaOC?rr*a=M8&-opMLX$9@YBQ3ph*aZmMo2zN9oYYq7rMc_U0ZZheufcdVcLx znH-`z2RQ=;a&ma@w8+O+_`>Bv4sYw%XJhZ9nU%7v<=^-TUsPSOyD@n`vt|yv!LkM7 z(Y7P2hA~bu2!`@SoW^D?%`N_a2t@qP#4_c7^#~-nzYFWnbR@J?pY#G++$8oc%MK&V zc2Fo;G)<-id$xLNI(S~LBCGS1O*fdB#7bvY1KFM`6PS=86JF<81fX0R$X;)rBw!@X zpL#bZ{4SrSR;_-bZ8CylMybn8V6A#XHvtsg3Hm@4WF4c;QODr|PCWy^IY!+$zPgu43gX>V6q&~P!_c@|^*90wgW&)PlCH-k@uR8o_$Su4 zk*H-?s0T1~lHo;^`0XVr3k%kcC`xxAl`)cyaCYXf zk{QKS%&5GOwTfu;Q=K~Wf>jxy;*6-H{c}!h0Oz-_VAm=V_di=r4HMQsS92pvCn!JV z=#hMAggjG!oZ+VfM?(KjrRz#lh%z(`i{LnpLFy$`NPafU5~SHdB-3ZZ$hq9;6_M8`sd^3 zq@K#^xm~uypBIQKXPL25nFB6+OJun#K(lN*^8rlPjyOx(qs2j6RU#IpZmMTOdW0BA z#RwmRD+QByMth=6XZ-HF_bT!Vo@~0m@P~<2KrOxkd>EpFd1o_6OdIF4v6Ybq-cgqY zoyW9>4oRzXti74ic~!zPf5y}QSpoM=ivC{7b*I34J#pb?lRL`M+c3o4ftO5JW@Ggd zOS4e?2*g!H(f2tsPP#D;Wrm-+i2Oikz|9qqWug9@7i0&4$3qEG$&JK0TRHRBM>OLz zNj0I=UFy@UwN=C@|G|qzO{uZFY7So!XX!oz@xV*s9zU6W-;Symhx~#IR4T1k_wA19 z^7)ZHFYVS34<%Oymz1THbD-W-O1xO?p122C*0kxnrFBl-DO`6FMm|K=|29xaJT$Fq zQ5HfVf0$9BZu;iy(+{g?G>3W=ig7?S&$D>IsB>6$`> zyp_jBDKqTJ%62=@La~^KJ}_s?LVy7@l)FtsIOYj%gxZ_xVNs=~g?WlDhp~iJAjUU% zJpuFSN4DF@G)q}O=+8v0Bo9ovW1vREMDjX>{Gzd620k0Bwc@Olf>1x$uNEMyQWAEO z;N07U?k{*S!-Uai0<{m&^Hf9XD{Q=;2A41}t7l4Cd&28%{dB&!HR@az`7r#jL12N@ zv+LvUlSy8CT^;$*o4$h4W2)kkJQN5}xP22cn`U9_LZdX-k=R3^W)e5bw9`cIILAGh zJ~*}-_%maEO(t0eWSO{!?~(mGb+$eYHZxwG&}#Ml%cUM9Uc%>`f)iNe_g+LC0?Bty zPbl$B{6avfpS2$&h*SQi#&)txqxGlp!qx$;sWWIN!eyr1#ylRqAWtJCPHYU?#D-7| zC3Te2y2#2Fij~g}8zz1Xkm`AWu)x3c3LMG7$hrYaQZyz}<*p3S}iM=Gm4=!%m-)dkcyjYgZn6OhuX z+F}iH(qTmQhw);`Rm=7U5crb>m!}n(%paXqfNiks5#w%P3>(HJ5*g6zpti>hKnXK$ zoC>JFjMkQlHWWbVoH9>y8g~-D1vOHqy1kW!@neMuav_Nwfh@zvK*br6c;X8?ev!_~ z&gUxR>>Ug59rNY2#o2k$MnbG9Life=Q=hR{@q&Srwv5_W=b|eoT*hAi7nje_bxfiC zafm`uFp;k2n{-WP?S2Hdt#fPV(*50eGT!lc{(w&;cL(yb0_BZgo5A`r%vkbjly-~i zpRH@*bgC_{(a-IIz^pCHGO$>Z-o%b(8B>kaPVVBT!Mx>%Yfro>V*#1s`p&;Q2zDnm zf~;FD-nf}o-?oZvkT;p*VOD^>-9LTo?2ce>l`%DHX=1L7xJMmkRpMHscUMfDoU5+Z zs_(ZLb@7+_t*lj#fXnOSk;z?kV^GF_9}4Lg7{LoRh@bZeCL+xC?`o7ah5Te`Se$X= z=shZqs$90J<=TY#LR=A~9`vh(DVL3-*#%&n6Wv3-<4t|7vCzZin)`Ho`;nY zt6t3gR^RuL@Bpjb@u=w7mM}lEh#Li%Dy<2Pl?n^KB=M(4?m&=sBSv5BAqhj7U@w9F zN`?KJ&EEDd`vRF%un>Q=U{+AiAA|@;q*6}?V~*oA-yP=54aKKI`j(dHngLb~zSVOI zR5$6{!OAul(%qR0@7BxVPDr%gFB91sl5PLsTHdr>*1RJl2N`sAKxa&-0h-meL+ce? zSni$EtCXL);_Ikjh|KYFJM$>#1j4<;f{#&zFLxy6Qq7B z8N_i=0~HL}x=&+^MNW19_?qjEUt;aGya5CHe#;tENa(r6A*>x~cu=q#oea(H+MHZi zub!w(vWB~~3a4HA)_w=!n|(3PEtF(xhwP)2Osj^P%f?<8DUe-p)k+{eaLtgDfDsY| zFm^wQSd%5`q3^Paw2`IR=``nf84-vK8i}A#n0IEaih_4&ws{IUj<)a(eloOT z^1p{=N==t%oU-%QoIZ>Dn+?gw}N)9vj|bm~WrsX3-ZAI*af z7?Pp6@m@KWtUOEFElN`F`IdaX#j(|)4ztAgW0HhB=KoBBN(}a$QJIi*;elfYQxhq$ z>)kgi>Av&0yynpo8;XwZK_C5BVqei;0mR8qQ#Y2~F;v}F9-Sb?q`SCIRdi4=7)#=|m8g_XVaC-UD_|*N7dU(V&{hvNM zh9iulu=Z_t1k#uu?t55!@g@4;>GK&;Vy9Qq32|`=eh+FoZD< zMhjZqUqnVXemMg}Hti62m5z6H^$K{wZrwcnRmsLokFp7||9Ql0c(TsK7ACQx;1<7o z8H!Fd^TJmgxm~5*)mhv66hsjbHgNJY5|r z&L|=(DL8g8CFPp~DD(_n>*S1~P(Lntw`1Gzp$jD+N%<_I!UZHChTVh!CmHr(z-I1u z(9#daY;%J=`eS?RQ@r9NVZ}TCdqFHzF{gSNJbzGvScTEYUcqECCKZ?7)7l$AL(Dd0 z4u)&dH*z%EgfEA|b)QiL9#ft!6;`sP-tAazE63dnizv&0WJi>!61pki+ufLequTTHs<$SbgYP8Nwg3N6#q0+%ly}keR$;zt4*=j+55Ni#uz}B zK`|koOQRopyq5Kaxc1XGk&{w%!wRCL+(0zwZCQadhlAW`sS5g?U$PbqMr~0<-pjQV zNZ?8S3Jzf4py{Biyv+);XEbS^(S;WQj&w9a)TRxpBO35TvfUjhdULN9sX`q)N&)z8 zYYOt$S2u=YMU~N%O5#8|_^+FofO4w4AjDI8(?3A{QjJMeg!~oqjqBU}awfuxs)D2! zG-xAZ>Yn;x6Hh~qkQ~{k_Xq1i7u&%`dEm}mL5%Z``Wh?5;AnPGUzE}V}ER&5o=_N^) zLOrTOiCE3Yf~{ty;EI$z9g7Nz_Tx#EPeTibxFHfbStTluZ|9ITGzCTY6p0_S;&F=%3LL>(~})-m8-z+k0Af^&Q9`UOeD+dH=9V z67Th2JbcNm#84oVr!_q@Omce$UFI8q|D{SPypGYt(*M(kBq77uB>bN8IYAU`(XDmc zsn$%?ZzTE}xNr$75VNEsb>y|k&pjwX_`NdXihy0C@D-xo7p?J&|imy;aA?|17iB$_z2S7(H2jZZP&@Ny`w$B!I%Nhe1M zj(+rQtyhr7)W3<7gqKg2qHUOg?yk7$I5Mf`+Ew|sl~scV-!L(2!N7)`(>BY?hV-rq zdE?@>f-i@mv@5O*kXo)ykLOGe<*bA@`WegOm?9Y$-UY; zo1n$x{L}`Rb$s&yX)7{t0n=*?9G();MZqMZ&{r0190IrV;ul+cfxin8ow0*m5~+n$ zzF4hky~*N&TwDqNZ;G&h<}LN8Fx30D3yYv|j;n;14|6*8zrCyO4$uM!9qJqZ45aC> z36nnZU4x!r5_RLT!xev&q2qEK`CbWqL{Cp<*%u?2 zJPAZ5_*oSDgp{$Uv75XcyEGqeX}n#sQilk)pG^_4lredr9|E7Ei??L65!|44wJatR z;NHJgb?9|e!oQsUF$(v|P53j)3Vm23G<=M8{%uF7Ctsv819YZ?;=XqTd!;56vP zYe_O#_TWkMs%1 z*!dV)>~}}|6#J0pFA5cua2sd z(n#~5EpOh*YI$vX3VOJgU`wq|Nk0Tp%BEiz{3b06Y!6AGDgxQ&gqZtgk>U_O5gT3* z=;79yiwe)_`P*5(vT<%5h;qDgVrG&q1)opo;wfM_f1DIsDN%fBbK(+J2s#p6yc+Rk z#L#iIYL-}_?LBH3%Us13TsHf#?pM&7Sq;r$*B#+G6Hi8s22 zJbUu8*B)?mFcmE(C)H~F;94j~tyC3#zbpjzOPOh#>aLD6DAr+in=FiU*_EfeSgJr~ z9(YQAk!WGyT_!g9<VUpP$-332eFg#l9&*PLgZxq}QzF;Lk#PO?^(ZePMD?ZOqhdQD6g#o+#rC5XN5d zQ&xfKp;~tBjDr5`LRW*}D+Ge(Q|@?ew2=oY&pYX6>p8|ArF&QZvue#?Z?5vuW9azb z0fVQsEEw6!hkUnBRilTXUX(TS#i!9dKJYW=IyE4-8ocXRiBfPU{wu|+P0x1sxPVQG zY7uXYM-`GZTKmstzh~b=Z|cC*G@H>ICJlpwuFaE?u2c z+%o+M`uo+?0+M@wp3Stm`v<9TrW_zlviRXPDx5H3e6!F|aLzM6qAYMBugoV-SXj=( z#L*ViNs716bqo~}#AyEP1UP;+MfD%}t8Pqg@13Ptz-5zgG*-XcUx)^nY+9R&xc~kG z_5~0;cxTYn7CKs@+zD{|K1xhF>qoM}x$G-gP;=q>yVyl$gd?#NjH5`)=D}THyUX!X z&p_j%N1k!#P|RR8FBm!FKR>I--4rg(v~0afn^_1~#h4Nx>*w3j!SRL%cf36a55aOc z24jsRLi}{K#3HKZ5eo6p1vdF*7Z98$glyAC?Y{I@>C6a))(jKmZ7erPu335q|1WQy zDnnCjfyIVSD!0dI98_6H@YOtEJ6r$y$PK_MQf-_0@xqhaD0GeMkHQnq82f*;#AuL_B2d^lFP~B#?bU~-q^kB ziiNNz+C1&HSCvdRR*;8FT+}q1FC95if|nnJ;I3#xpyrkPTH4S2<9Mw9GRb$z#uWoK zW;lNik6=e8JU0HT1p|QGG`Kx`c6B3;=O2KV`cER`db}T@YqG8!8IjBTJPI zWgNAuv-r2rR+a4;5H8*SWv1n9o}wcC!3H2E_f|Rl;ho{D5u>S1Hd;26IH>q@Nd`xF ze7m=z}l{F z4#3FVWA9K~RO1J(^WNcQl|tCmskSvB0rfQm2WQZ3Owh`k-yG)mzV!({PK4|X=fcvj z3lH+|^&tMT+tU38tV|Ke%%g+qoYNOdjWql}0iXg?pew&D-JMHw))dBSpJBmD3;Ji_ zlz1upV|g>9?8InP@Rr3h?~$=#cecgz5p|l=#=YKxcq<|b_fx9i1h*JB@p;B%=?i>< zUg0#+KMZ?f@l8Dr1hT8i4IBd`FF;iqy2WqvS_sTAvg-I(d^r-IZ?s<+bVL5g^d$5U z@ZXKetd+6@Fe7aPn$J+BYG2b_!r9a4e+q<%BREFe-ALv2C_j~t;V*q(>=0KRWp~(c zuc-2(2tUscsu~9<+Y_WU+g<;ywU+YX;jaoUYTw10-~(4k!6fI@(=x0Sn}VD-P6tH0 zGAX7giD3BBr<^odttg2b3F`^(piimBD;HZz8wx0c@{9{rEVcu|ZcqzRZtCGEF}63a=KCcpb3dpVLV((Mf=)p0<2KU!64`*evJ2 zbOuC!o7zKFVS&j62!;+@wY^`Mz&wrAS4iM9p-rVcq+^l|1zlw|D}DAX8dkqf_-?`} z5RPByBdp@(l4|P{9gW7v1P62~U0!ImlDq{O{DmMlGC<-4(+nNN$A%lj%{x`c#{E-YV%^+;f7 zv_1hhz+#D6*kp36eKcY3^n?shfHKLlQJHNO_eus#kbmQRfhV3Rq>PsfMqf5fQV0rRdZEH>!YpTehKl85 zpcnsCf>fP9Vc_l8hiXJL@l{|_csDaNAH4eL=l>A)woBy;@9fN|Jas{<4m=z|ExFQ! z!F7V_K%wLD*{hEYZ6+dP&Yi45wv%uxo6DIWLAdIOi2ihM8*`U~Z+&Y$n>Np8%|Sh{ z{Su7cnv>Kn_EWdrF9hy#U(e6*cVluqHc@HC@)}V3&M{-lK(`D-%KROnNrAC2QFym1 zUF#OdpD-K+=I2={u0~kYEeCZ)FOMzGW=$@Y(bu4cT?Cx zFmzOP(Ax<5=!=~JlXVta{(CT-2e@JqU&};PYHybjxLd<@d;e#EOzmzdhoW>6oG}rJ z{JYeTZ`6fu!acKyqec4sQ75oDrB_$-istbN?nKxeF-vgD?vQ zwr+1N$1Ogzt2C@1#RB&_^`xl#s0V$PrM1%WB#Xhj-P*FnQ&?<=GMFvR>(47V_fCHh z{0i4V#s-D|IFgtLxU>`T=Bl{$A@9lb`Vg|&KxiqBB5_L>^x&qJIEyoe++vlf|^ z|Jx*%a$Y9ow-i-TlVM%gFGVCT5=3PwGoXC!9CcywQSexC1-ucHD4B9E628N9zrMh; zs&9`2)(|eWaP+rzMfLA=NXr0d#{u~i$KX4-QfA;uJmnm3CpCzefW`6iYuLcMSFg;6 z4xqG*t<3RKtltDoglZi8^L3M=6yW6HQ`#TdqY?;co`x4brdsVMC!P53_u_C)7b0la>q#P-4z!*)= zQ+GCW=pp2^OAf$pwXgP8xP$c?=Fq6VO(}={n(j4x z(d13301927`a-kLgGvdxho6Kt5RFh3U&^Y_Iuh+bDN;fj)T|P7F6=MBVy`BW>)85v+N8jhvC)mkl5e=?f;_h`zWB>PDsLnK1wyp z&fs+NbdMvHb6f9Sdeicj=)gZPlQWK#Y%e#aP(QT<`{?D~P$pI%5-VXHau1`Vp*09b0Q0csv3u%}6sLkGrxExHyP4N5Q-EpEJZ7P=og$qWU6C=HBsOyL zP3W%ff({P#rs-(|Si&(`6Zw7sFyiQSheT9Hg5BY~g!>;XoT@K$3$Zz?7xO6SZ$966 zAr@G}zCB(8n_((ZZTYB64~G$z4*lf-BX|k(1mp^);vs(80qqM1atW`lWk=;UGGaoa zl?MhuKqn|Yu?zF{s+}P6lBZ}Wx3n+qi8Q6ym1V3S4f5iNWY@XLnPgb*^Km|I9V)CA z4fG5#eq0g@I*b#uIPS@$7)2yb^!=)whByVA5Xz!-H|OiLfm1(;a3bi~Sx|a47*f7N z4w@XR#y`6L3fLPyQ?2NA1nBC{>~8+ma`;`afiZ>C6$>UptZ`U6Am5R#fpPFaV(NAJ=0=~C3ZI1`;8#+(183XY;^q9 zyW6qESKsUwfgB6qqZ_8rz~XZ_K(LrupnZc z$?&m=%ZFR|>JsKU!R-I!CLFaJpL?#+iyiB~Z4xF}5EoSAhioyZ$EH|+^+>gcvW=>t zxL$1bZp^;f*uhDlAJq;8);-7fn*HK+PK#l9Fs&X@oETq`xpnJ*l%%T5ZARP{2BSx_b8(f z`hHKnr2_rD%65kKE30juzArM-I;0urSzHhF1Xm~|iaZI3acR&mx&c$Y1mc|d<9nJK znV<;#2m@nH(0x<1Q;)*B>g++sb}PuKPHzI_B`~|%640ibhr{LegvEpGD3=VZd&}`0 z+_yte3LFTefKD3;X9*#}=#9PH;H9b~_n%u)H4r76^((IHZpwK(qR?T^MO}HfWnDqt za^XKnj3pOu93um4XG#sjXP4mP{f5IXrLG^fh4!sL#>AoaX*|M$as=pb-AN?GT9e>^ zCki9SLP0*hEu-S!sza{mvmZ^|qh!n=QoNSe%KqrcS(q7})*98EZy`%0mXj%WQ8Op#8BRPpB2?_v?^- zLIG%(U%$TK`+5k`N~bM%nd1~}MFqJ{C9W#+fw0l1HUl6Qtq=oQAg((~4 zU%1WE{z&mf9c{~`1c`9{m@v85qYT|v6(r$+DA&#Gh2jYUGaQ(?q9;J}AB6GqtAhPM zb!%ff?q2p=a^92-1fu(i>3i7{IBFpc6U5&@Ad~Nr2jLrQ$?Z@TU>NbK-+^AZ>4}hW zs4uC+NWNoK5J?_{v(AHY)PQdSBJsy%xm&+~&K9OmVSf3l@w=NQ*%49j1V^O={AnsW z-8LIsso*0Zme4SmdzvM*?_r>ulSM6*@!EXpo%Z*tJ>u^Yntow?-2rP<(PjMkTblpX zNRl`3KB0dgM_DVF8x|WO?I>Z!;Qm3f4{U35vU)^V_-(N zdp+%X{%%;dsSHq5xTM2cuNWgYkJ_R+(0_@}M9%d6>9A?_^TEzi7{*@+=85y=a=I+87jsp0pZ2?th>_%+0eaezql0w%l** zQJgaLJ_P8kGQmPW6z)W)w-|Z;_M|?K`TMJ4l={x^q!|?<9eD{T^QaK7A`DN^EHjUl zxK!d$E(elMtwj0p_6Of#Rwja{lwF=K)%k6~kj9Cfe_*5veGirpd&z!U5-xNrO}c;2 z-7XXd8mRS_gk}Hnxg@{de(`O>7u;Z1J^k65F#xH~5Fi85E-y7(#4P%M4>LO)S(F+` zJToq!uB)P>SKSQnjWvMbG*U!{sunmx!nV=#j#CR+0R~?jDPa7arDi*zdYYzvg+HMK zO)Y<`q`9JC^5KHw?kMJ5fYuAbvGhyBUyp9rm)hiXbR$hW&(j+fg?(!oh}>n2cbNO7 zdw`7z{zTz8Q6l|?s4R8m5oR@q1x3Q;BY&>0^{wF`BD%g^%hZ#u$5?&{^y2doeCCt` z zy`NZTQV9rL<`29|m9w^(vVAEo2_i-EU-TPOUfI@R*)Q(W_yCBx%09*_V9efhZt=%a zgKvCBo$vt@!(b}Zu`N+*L6;;0zvxuK*ewJEO6uGA7ia9*=s-3`y}-imV1yj18C{+) zf1eM2iQPC}yI3JUa>km9PK4G*lF|gnz#`HhMzhir6 zz8-xyeYGPOrfyNaOU4T3J0_hzmPcQvzQihtmL^tgo#QU~35rr$wF-l?>qhp4X>%F*=NlQH3%5o1Xuskw*Pi<^NuF?(6Eh4V`cTJuSNAYmr^d zUO{l(R?OxXFHM~RZuhVBhp!k;7h`fA5a^V!<;Q_9Q&NU~A=(2Rxl}3~8eq~ul^A~? z6#C9s|7ygk(&3b^eKzh}%_cj<5x9Wg6*gi5U3)U>J{Yen_RRM0mzjbc5NJvsY|)14 z`6>_2aHiJ6RQmh?ZI$6XYKqrtq^5G-z_J(>*J{a2#%GT79;_bs;n3`^dt_X zU^lc%(_evlKvK~a#E}ur3lXGIkerxr8r%U#UwPkK7(XNK+8W;H+~Qm(I3TL?UBQ-4 zwZVWBt~X43opK+Yb>f7Car>9AfawU#+O&+2+{8bJ;w*WQ!k!O8j6Y`Ahe7}gfNZPd z7epCCiL>>1bS!27`)`ct>mVD*FbNcnbMI+Lh|-Uil=~F#rZtRX?ru6D_&uwj*k#sH zI0wdrL5oX>xJKs$lzF_r74bL;7c)?I242Tu5vmF< zy2;K^bMB>NsOI4&a`Z6(l zZO!dfD#c8V#_u%y?N>WP%!(>Yzdt2yT@=p0A-w!JKe4|gi-5KwYu&3S1YqPj(#0g^ z^tCV6Tl`I1@pE5P!$V|~*qB-Vy5ap0i!#zfqm$7d;%ze^`f&?a6FKm>-$pgYHpwWK zyaLfrT^~K>(}qOc6r;GndW~kge$-uQ1-Nepq^))13+%bN@od1oGd1um)Qsc#qD=%6M$b3b?fhPblNNx{3(YZ{MM##+%nF~$ zN!cZ`?)!JFu_?bcy3F+w8A?vYpxkvI`q8biPNN9}sSb5mKmkudl=GnALppZnn%ZtD zVIdhofmZ4B6YOHO=HCgJmbuiaTRrSk4X-sNyHmv=wOEQBnyoopBr+G8Y&0RwSX^E2 z6&|?#l`a-`Y(ue(z;K1!H5rD!3_9ETQ6TYn*_IFoSVE%r5Cg_)*85}@8G^zzH|Qx` ze1x%!z`utXPwTNy>+FU}tD*ob#xMArrdD5QbMT~`AZLa|_(p!8rE0Jp00L)Dvrp8wXmn!{|X2zbUrD}Anv0uruc>y4B|r`7gd$wR{7$Fphs=( zX9z;hz=(j0t8kl9IgHeM4u z3ubS~6?Kbu7$qnW)Rv88Eiel0t79BH>i*aY)u{(c&4u?9|1)BT?GV7}b$yG%AMA&0;iT`-TcD&l(!%f<#Mi?JBXyNL(StyN|xH>T*ay z)#|TmYyla42ienk8#7QW+nW$Y<dyv~F2%;YZG}eh4+gA9ln-m|B_X}d0 z1+$8o-tQm>M3SlLMom-bHd_O9HySdI8dS<0;gb+2_uR?$`m@q9Kd&s)*29IBhtFkF z+VyBgeK?a>!#b zP8ZCst+}l)DVAvs<%G>nlZU6AR^@2==e_=QcN*)FpFPinke8JOU{)>(>2pHmgTPQ+ zo2t_-H4hOEuM&z-VOEcV7RyQw{V7St3imFLfB~)w2f2GO9}Z8UBcV=cp;DTZl!pmr z;iA8{`e4Ug1Xm@>uhlJZJCPF=z`< zeN;%KMd0InC#riAQGe^M2X5ulv@EjML-6B!Tp(qE1W_pDC!+k@^w{d?H12uWMcOe@ zi%Z}(`)RH{sV~NJNV&dy-mrlTX89E`g25kReJ`pLUtrqeg^p{CG?r$Cw7tSjc!R|% zwFzDUJMr)rFTgh9-knRm;{6l|GYo?}V?_#l>0~~R`tad^Bu9iv4vjqWh7u7@eDVu*OYWzdc)ouqevML`DD=aZ z*_rn2c~d|wnwg9ZJ6Vd>ZDV9$IY_9r3ZPubOu~Z>6=DfZ>)~0V?4w%vFyQ|7!KY*( z7av$F8xvqGfz4S>mbD9zPC3U0v-Wek1vbfd403+iiGToK_0;ZgBTU@NN0JYQi!E?C z=*`U+kOFp8$JJUBR6`#NVg{hAzof|Qbf$0bX#=Q7GOYGXEAz)oxV`%@Z|~;M$1PQ3 zSZWToPvhfW{-cA>$@5thu5;GyUeEjhT&Y@JZdWaX;U_uWFuMCD#=0SwgbxNP-uO|@ zt30+9oZL@AGV`F^bszx|bC{6&Es+Zvw+OP)|5051@b1`*4-DwMA{ECo!s)~U1r+pA-oI#orwQRd6C3@`4nlJldv|;Of`o<;ABYSk@Kb=4fC=KXxD|@plFjk#@zoafY zVdRN4YUOKd|4FZ{sZC8&Lsdv$YDWUnC8Jog9?tYhRR!s1$EHerTPUiu`NiaEh-V45 zQ)ZjM|Il!X=afo}58xf@RB+62lQ23PPV`>eWOf8p#n`z{@D5a3mcab`betPykR1wU zhHK9kWtB{G`tkW;fUm7V@N85H>$FlYdN4qpL=cspJJ+TVTRi1M(O{(qhgN)HTm09k z?;YISx&g)Ii@Y!m*@-Y%@;5fJeX6M)HM3fG+c{QDg29!v;wsA47mp_j1nYe{a0&{* zGSe>z^gDbzw~!`4Kz-(RVyV{i@-7NREAvi7bN@f(xmM{P@i!c(6TJ$Pu%bxk3}oiM zkX`ZUvA}#LGHoH4z_&VUubpcJ^9O{7Hl2fBT0o;+ea&el%*DE`VT6Jqz2V$sVV~eK zjxWxxMxD>y^V-GA-0jinmEoVhu}wO7)1KMHaf5SHE%UUxW(&ym^j4K9)MNkH2Z}*+ z{RyPj%zmnjrhAogaEh5(BM}-wdS(F^@sbzdyz0}XkI1rOUGJC|P=0#tWhBqJabQ3WM&_7!OU*S>Jfy-Q~2?n48%D%9PP(szwh&td@m}x_##+j?^V`{KAc-*fmvP8hRp?y`J`cYd#N8%yPm23VRuZ!U$N{X_WJz+^QB1>Xs?X3Dl*E zJi$$-4#phtBCqY6?rd^7v}`4s&9I;er$Y1OnK?yA{Q1CVt}AoTzXP$+>yQ0bl#P=0 zM?a3@&Y{yWoHIMG5{+oIa_W0anOC{w2jtQ2DdJ*mR?H)m*>Co`h712g#ji8gEQLbM z53DGZp^J_&ghwn2uT&lFLJfcA21tD;?qpQ?$f~D4LKbI3SOD>e zH4AOzQx)^O2O>+%N|5UyY)P{Ei5iFB_DMVM68=mxXtSdJAU?0M_1{#9EM@)-dALos zrCH(3=S%T@Ak!ZSQ3qPOLbV zEd(Fd*t~S!n{73qdzQUl&m5*^WAZ%T*qn3;V7_mKX{!)DU&rjDg-PSMzD_}ez+EqB zH_q?n5+&Cn{+Xe1e|8`YyfA$nROxo3Yc?y;OE8LvKNZ0n*brax!yEn4hWSUY_}hgp z#G@!Jt5)c6fK>AowU4CImgp0!c8l^6UwaGtwkk?6=vq)=vDim&B;U6KBbmgbj ziwS&ShTuq)qf*YC(UtLRWIGJ|0X+bv~ zN8>jvAOR70<6p63j-&@x&~u-270@J0A~sEtJ%PeBdv-!hM|GJwLP=r79C}vH{ro4T zEFp)C@n?5y;ck^TH@%R1UdgVY?;~Dx5UO|%9U42zt1FQ|NXkg+WLfd{ue_QpwYa4^ zIDFFW_Hg#le&vaY7HxF}d??=*`%>zD{(n(=ON9alRH#e zSv$c%u_WbeBZ}t|)3^P({N9&x@#?yJx{hNDg`0yB-vTOUEUw+~6Hd2}lgUt$(Q3bR zj}nNMMWwYFk;zG3`MpTcY-%FLo+Z8MXFe4dNvymZOMjg_TC!@f<+~+EBQRuh4=l4h zZ^{6)!5^ZIH1yif<(IWIREIgM@lCRx^dSQ$-KvLOE<>zZR9qo@4f8ah%qs9ib>{3u z07YM)_2}t_kvb=H@eHoz?f>!Z8`<}|U&#JT-+FF1N)6$MV8&5>uU-vzIBNO&&x;us55rtM+k zUnt8?psi6uj@@4*1mx>Xq%A73!=QJiGU2L0`g`F>8BZ9r0?f8tK+{y}AXnYkk`2qv z2sE_XAi8eDW9xM-?c-tB_CD879Nk`8_8EMNF!C006d{RQlp;_4&V$qd*&Bm5z_8>S zT+vN`OPyuvJ_vPBNG-nIT*LqkMtj+%dquRwV_n;_4k$=PA_z?9jbVK}atEv9c}5XR zAhwlNo^%_huw)(HIO=?$0TFoPsQf4ZoKGjkkI?0OZg=90Ne9yo>3CH`;vb6q_*R5Q zmx6NeqWKE8{t8$L-D(pdPr$f-UcdOyB-8|q92VrveUNa##~r*}K?g<=eWi^J@{BZ1 zkx2y4b{>K^=i5uOq$Nir%qtIOOqso$84HqOle*?wCalISbjfnYXzwL(#Zl^@&xCAF z?;sU{qd44)KX}f>S62%{AusE{<}V6YHf#fZSib~sQjWj6?xBpzAy{n*zpX3C@v!6g zwR-m!Ik$KIR&|26XwdVesmzA4N{a!*X6|T`fB5$N@SaL$X-twM9AP>NeR5QPKo!g~ zcwQ`{>lpct_sdWfNqZ2ywb&Ii5TG0Ierb#$+7HL~nEH>>4d9LqK(>LD9;l`p) zuE)CQdLFW>EaPgO05_3b%5j$*6y~#QBt9Kuj*F z2ZFff=N8gF6JDaMgd0@Gj+KfQOUMk&q*nXM>0E+e!0$Tc?bc=&5KJkwk0P@|x8V{f zQulg077BK#1I9l54(#tG;u=E;lv?qkNbkRRoO&-UDlJbgt&0K)s7>uZGT>e2@UR9X zA&kKpXn#5%J>rXC;Uv`=V2#T;%-(bxxA^3feBMXUZaR(kQR36-izkh3vg)4l5EbyKfu6q=Wo;gO^oxoh53oi30{+ z5gCY@ZtGlpmxZNv0eXk_2ed?d9N@b#71?lXw$d?JW89!UjHL7jnK~SxZ0HR4wd`ao zH-;}T!-SSf4-7!P_sAT0j?!YxV7YPrEgbr@)o@5opGj_fRWjpY%PywggAtH%5gEX@}oiyd`!|whj=vqo@vHR7T)lXNJpaI`gPw zY(YZz5#&9`jXhIx6EWikVmEN^(ozH7BA}oJK|d&gTV|&d`rPc`C-jUtKKv82jue?X z z@9l{+@D*|*7_X(@q!l6+@R5+^00p{3xUxuxaji?m$Tcq4(WT47 zfgOXV^$ikTE1g^(pWuHZ0OhDhoCmK4-ul?ofCNNx9O|>rFp!U++;t!TsEA;QjK%Tg z=}2^9Qt~ulDXvUL@ly&%^0OoJAQEGzt~5A)MbwvX8eMzZBPdEI zB7A_1cLIVSd~q<+qKg?=$n~TM$0CUY=Wu@%__2`MHUheP^T&@+1aX#(HH3#A3Qz~h+MaD^w4>Pnawq3)a+ z(MdnlnEFe|xjDrLlgl1!>`py@f!M&o4UOH4YV4k&06==G$ZD?kb5MR**j8Ou0FGxN zIN{p`_!?mNl?mI-E*@S*FUjG)r|?P{)mI4Wta~U;z5uI>4>aq>U!V__-`HE*GhH% z&@y`VY+}UFR@a0VXWjG^*olh`JtsJq(?tF>ci;S_b0hd8hXzXxht~Kk8&5=WFv-zz zK(O`7z5=%C<`?1$12KY?H@ybm01*-V=r;HS-3H$J*wlaoMd-f9DbA#oc&8D&3C(UF z8fSIeCBdhOQp2MPBTEFNIv|AEL`TtVw_I2pO&d2_AwYd|#J=cEs?Zyy5l5`dm)CJZEQG1Pb%Z>||+ z-&=ZQ_l|KikJ1ZEOc0N(4wrFQv(=74+WzSc|tjg z7oZo`mF)s=*3#O)O1J0PpkTClWGJLnn^ZEQ>>g zKcsEq1SC^nH03!D@N65WXQQ=g<@i0qS~4;nq%W^ZVs^{8)X}-k`@Ji=q(JPmn#h-@ zPPJ6h0hBiM{3FP@>@Y3H5d`~H6+HCfVBN`KDNtdi7yPnzh+<3tN_spmOAF%48V?cI92rRfigXC(yObs{NFUNI+5 zo$vt>AIq5^KxPb?dF#D}c7}AZqhz7HXRhGu5o5L}(qhQDj}J_s`Uid=P*m)2dH-O0U|v7?uQG;8KYa zQaN^k57y9`i!D=928XDEqTd3e*ial}zMu0=!JrNT0$Jh(FTxj}*-n;0ZU5+t4pOWo z4S>LBgKJ($Rr5TMQ!`83G$DsOfF#eGbiXBU4o(!dG#$aMRH>SS(G&vx)aKLip+^Y>~Sj0iJssvHC54%+% zQv#3dNc0zYn0sWpidopjc5K8vi7Xyd?fd>VswsQ+PiRAim&}kK;rF{jEIQ)^DVqr^ zir<|CY)7c##JvCs1x~AK6kI?QR`2$R3eypoX__6yHK18*%HIkO$F*}U+BS6gf#KOz zW1at<4#p$+sV8$u{OGeU?@-P(i!=8#-94~Sez&sY-N~yu^r~`HI`|*WdxYA)5WGH) zGvPPG-`!7JN=yRo{mWMOk;m;T0!p6EIkN|n=J6C9bDA+Dte1 zg%8W=w$}X0&G%%E;8lNWSXBt9MHqa8DqEO>7F>*9f(A3r-uyBD{1G%Vz<&u&2sQe# z7pZY2H;HIQz2xrnVtL~e0vj_t>h5C{;e@cV9ZjCT(15jW=YH;SKSIhxN$h82$B%uP zAIEZXtR}Aq2Xl_303t6OYxdoPVwmN0fCV8#|GZdlPu+AjhSqBr#D3Zef{wqNLUNQH z6lf2^Txdg%^P>y9->PsegYsx{|t6yk#vZaLI50LGRgULt<34ott#BsA;@nTqO zBX07egd;6Vd4!aRlO8A)9q7c+2lI1C-#80GtW&!7=Dm5Gy&jP#K8M5-jo>^?7FEam+h~ zY||bh9w6+l*4%(Co;y@K#=Ovg?mZ^fBjAs{Hv|W&YJr4a;Ky5`;l37qo>dhK85CNW z2#&uBnne}zypj_rswnD3$+LU1&=>-%nNNEKi(AA}u^0mB=3YSO9`b0X|2-td`I@0e zn=V0pyVL5OS&gXL)lmRbN2|f0jz2=7D7mJC@I(Yh!8BVap8gc_?AD8W89Ooq@dG-yw-@Fpxt|%o zG_PYaNn+L|2h)5n<0*vSzBSq}-J1jMRS8OmK-tj&1(e?_S!Ax;_5TEri2N|diZE;!$0Wrt!sEv?A;zZgm^Yq z>4FG1Kbe}Vj*mYatH9tA<{*eIqgzjpVUBXwjG``mtH{m%Xlzli>F-?O%zgMLI1TQo z_@b03xLjMwj~$uV6peQkK^v$Ixi!Cst%OX?I@KD^OX`if^3@pIUeUiL6k+Lc#A2sv zHg7o#p38FPqK6jQN7PSnr$4o#qwLOh&tr1!5JH+81cK|7EdN!5RsTODhr)e+NoTVE zJjk|2{h*Mva^9j$)?UT^I(5bTyKO7b&96FY@$^213O_4g#|X@2;#3VFQ{e6`hLSWF z5_!~IC8oQz(F!5$da67!wu1oaYJ@vp z1}CF`acj14<5iw?8;+y#(8zSH6^wC>5`;RP1q*V1mMsDo==l9ouY1)M!R}>;u=B|` zZl!c?;%z0i0*nGk$ZIz~#NN^NFzN9^Ff!J;vt5OVpw}FBZe&AuG6&Ivmm7yS0h&U} zaRa#_fxxb_3i7m?Y>TKEuqXa2GP-C1a^8O#X^C!w97qcdhKX9qyY9ZAjL%q--}LfT zdHZf3y47L`S6E>i56e|%AOu8O&c0l6lr(WquCNVF^7Oi9@1I@?`tfPHsC)R4##G%2 z)e(&^YtL7@`-fye-ZcGI15&3|gPdQ{n}M+Ow!`Ys(@ro=*gulcUKrqv`s^(ol$f$e)ag}g_pfVHX%yng$2}VQm4Bk+ZYBckq->l>7J(J#RGENKO{b%1 z|7R#d)%!hcm%S$=rWUwP03>Q@y~XEE`;|1**eZn!j4Ld@<>B~Gh>*Eg5S5ZfRpSJ+ zIq6uP)kMcoznqi~X8(JsArPrXEnnf%4p=77<7UP84%cm$%(&au4#{gj{50Hkj0%D{ zHnFYR06C~x?fzwkjQDh?D20`R!P7WIKmV>XAhM%;N&vOJ4v@ms(4mPNUd05g(5LQS zf==N|5PIDp=7z~eOL~zV?96gy&OjS@Vpan$M% zW3;aGsptVuujR{Yz=1QxH#o6+u;|-odol%1CX|OheQxMjWQInB*|AVF&sB9dx0a4y z7>YWitj$lf>sjP*KW9836n7s7-Ie9g7Rs^JD%acR2(2Hebr?%*gz`AnWJ`vUsPiU}&KqdH7i?d+%!8`D`f0z3 zGeSz-ZPWx=-XZQiL9^V1J)mWZ-EPjfbnlsXYvi%fmYnIKHf7viY}!(zRd#PJNHc`3Fu-XCa{PPknpL^?o6NzwO?UNUXke1_!2s za0sd&$vKS~0kRRZ-jW5#a+YFh|IcIgQT3*zzj=W0n?hN>=!jlAq;m*FD!W(er|7-# z3ihDa{lQ??16mJ7^K`wS*qCHF)nrpeBRJ{m3)%v354f*QaYVldh0Myg?nwfgvC&x-d<&XuE&~q!z=RbT856$}Y6qz7HUQPIbD*N7cHRfyKD$ zFJltVIyZA=F_4ftkN}9hanyhWL~+*G3F?dDyhd)AabuAEvB^F^7vv8oc<3Mqc%<>g zujM5Ruj8@)p^vM~vzl4yNF$auVP>EVdLo+8>CGfc)3&7`Q;y7{!PtBbQEXgT#NX5= z@B4qn_lurZC6nGYiPE6+PtpUL=Gc6a?_xzjYM>x?3Ig7GR~4xO)o6>J{33;64+6@(vLzq|lf5M@m`#q9o@Y?Q1{={=u}jRh_an@LoRFnYi3gNU&@{m~P5mVTgI z6UUR&c%1Hg4y5FN(8e(m^5NUYr2-$I3g2@BA6xZ98y&JTqcl>B+WY7H{{3X0UIQbJe`I ze2RI^*oE?r2KQZP6Lw9@6hl^uH7?8QL!;aZ@=Oe%AMgQcU89Q+$6i2i<-|1XMu*uY zqS~1U=1h#^r|NFPld)BLf4P>6$1lHpZt6e+BU32(RaxgsV$p6okN}0bIWoVsLU+?2 zF|tYyvXZ7sn01A=^2VGYR+A8PCv3w>jS@r-+bL*H#cQ0i(IH)7WV)|;QO`PGVJ?df zDN@TU*8)4noq)MZQ(f85=F;U+5uGG!Y-#X;mF|V90YIz^F511pl$0-!a+fke?A;*G zoQ=_#M8p_F5WQcdsAk+VQSB>Kgijx10ea}QfpsEq0k^0Eo@N?obS^aq9*zcz=(-YmgKHQ2y9KowMr z2@4jD1d)b&3d84DW?t@El=LA9rY6DLklwTmX0~OKfI`PBu0ERw$M}h8sajoBdirN9 znypUp9(tnL7h66}6pDC!;iV&1P6Hgs5SpGG2 z^|gOHkwRmi2hA6U-4i!5c*hYCcgt2e+sukAj-y#Y!HQHOzL;+uTudNu1a5K=vibjI zMZr}9(_L;)O*0QL%!M9P z!E?I^Sv=}#DlIvbZ`07?c-j(iO7?pj1Ix^!&tGrc=Uz5_VRO+>riL~!DW?se8E;>J zvmYcOSBpix_FoRl{mvUFs_G}?rp*fCZkB{E(Gh2l7x%0hE)vcf6RYPVhgZ`hRUkX zIt|BC04iI~fXrDDA%_ie)XLPow|I6Bq_-uWSBoD!{)fDqsmkP;GLfgp!v1A$WZ8 zBvMHK1TxBY_1}m)BAM_Z^!y*j`t`D_gW{1!fIYuTs?Ck(MtkH6j~nx@IaKydHUp(f=}=0Z0nQZ1W9P0+LCFm{jBr@FvgH0~&HWFJtHMhvuq za(RK2Cd)+N+}eIR0tU|o`K>Ju&Y7w|Wx7LRF2Q;kCFi@2tNv7l%oXylRuZde z=oJ=UqLA*~{9hJWH%yC&-^`jwoc@Bv6TYM%Djin#vY?Ei5v#s=^RFDHao&8PIp?7? z9lGoCZnUOqrmQ+x(h4D~IMM7%RA;+o8N4&}*A;ehaNsnYxBtm07O(MEOoRm>KQY>N zYEg6~HjL+D372ES>AbI4`5#1RU@SmoRcD@L6K{MGGkMT%S4ZPEJ@L+~Jn2-EeI?1e zI3BAHQ8X`>|6J13dJ5HgK>n}K^FOoR3a%x5y}1l;d_Hq#L;G@JXwsVCHqBB1V6|uW zlMFmIgt>Us?)QT>2w(=o zXC=eNIm3Ms98bhlVs?r5% z6I0-LY)O@DQQf~(R9M^IRk+ExHO1HoWNJ^91BN0)ndlnx5O;2iIgqC^+bZu-{Z8(f z2}7nakyVSL6hUWCg;X9=7K$SXcaq;Qwlt)M$S~6I`Ij9>34WkvbCeG%fh)4k|*p+UmNhI$^8z z=K!T}=Qat&(YC=L_S*9F1F6h6?1)vg?;D;kXnRvi+h^DavZBdkRab}rfXM>z$LYJ= zd^EWl58yQ6OU765yc#?J_dTA@!Lq#X5-(&KZGGX&wjGfxgjmR%ot?OdHLBATKv-#A z+TZK4U!-OxOJ5ob{|j~Xpa#%<(TFv7&z$n~&xVDBjUQ3*sqfW~sOMc@E6H=|j9BfJ z=v)p4Z5tb8^N7?*G^NJtQ~PWzvnoIk6Ami%jNHVd|Pksokz+U#F zQX9-)cVz*=j`EEmC8#3feEqra3ZL8)2tz&qS%_EUQ3oAULpU|f+waeb|gn{2y8_APv}bd2wPy{Mgj8iI0=AT(c zwS&C|^d)VrL9k0!`qB;np+(8HcJ=lHw8=eIMEQ9ROT48d^n!Km0=Qv=Bv23x)t8S; zrKS3wqEjW3&ye@O`hi9@1IR6@D0;qkKbWG!JT`==+IbW2yKkYS$6=HaC$H8`UQn}i zC@D#ujX=GYlDnjrU}dN(GJN#|da*VY|Hm%cdsDuktN!c_k9w~v0)N1db{d|fVa3%* z{7K{bub@|dMjbz4C!k6iL=NrUtpH4qM>6fU2D0NtdC*YDwpDvwE(B72#*Bd+QXRdg z>3!Frcre$@?FRxO<8q&Yc8uUJ?*M4_DeMvf%Y`Y0SL!OO$`Xz#=`VAx8~vtrJ9Rsf zP@+m4oYE-j1C?mG9R3X5%m{eMEBR?dEQRyPZwcTZm+cwqEt6GK7O4qA#>+pHLzDrX zS{+$2Cc2o5MEwh)BgPM$dD5935VHS{jSjWB0NM-UFLMxVG{MKYB}dm|OTjbx77i1=pXOXk8b4=+ z2bLbNwDJ4LpU*}-mHYpEvH#X-R?jgZIoMy_rcTaE7B6CDEDL5w_NBe^_l)5*Mjjg) zd#P6*rqF6D8LJGUf)F4N+O)Lv0_dI#yAdoPY{jiIs%YwyO4aPH#)I+F<46dRr_#)9 z^aD)qW@LTsR_j?@9H)g_EYlR9g1Q{g&^H0Nkf+t{fv6)KPK^=7D$)1AB_S7%I*`3sZVs04Lcd9&zr5LaxbA!}}PI4!xXcWXLe`A#k;2^g6k+VO z=loMeCIRo}o@YqXN6%^y^ z_!gl2wCKfbjjy|+<8r)-k`zVw(eKe^Xl0oXXCqgO1X6Q;LbjPPcGz0>~}H6QvY{VTbcTo2Z1jf zO;`Vc)EkQRC4K;RoLjU8>@s{b(Bf2(Q@z>+nci}iLFRq|qT(-)uC@xGnWcaaFkGoF zmhM6Y5~D5&#L?uOFaVe7CE!pAwzm%9%8EvXiMS`IdZYrV>td4RF{+?U#xTiRN?D+* zdHI3<7{ymNLz85We|1S>$dW$ zdq4#wzgrrN8+`|MU!zt&nN)c34(-b+x9EL9(6uK!DNeQifNQFk(7NFK9!s`@twg{xjhA6 zEH0g*T(?aySL;sX+3ZQ{k3Hy2v`>Pf8PH5!JM8M>51{*fX*8R*GnR(lBe5AzjC-_~ z|Ls3Hy$B3|0QjWer}0W&?vge-Zn`Os>J05a`szZqez3lFkc1!!yH77jRA9PT-Y5Fr z_6_{b4FRO1=52<|?9>R07Pb%lUql!We0K3i78477ESh|ll-eX!RL(=#M zN59auPAi&bQd@{fam!e4tu9}yvvYpO7j4e$Bg5@v_E#${&+E1te09IK0%Cg67t&PI*-&>ySjf|(3UcqGJA=un zr^ryAQl~XEOgK$d1qNmQrOk;uoKU^kP!lQI1xxwQ`1V!uJxOCaMWL$w$X=JC^};&C z1ZIc^%#has`4LS!9iH)IIBCNxLY-z+y16S6A4L4#11olh?HF(bb1c6N4~zpPKk_rZ zNa1|P`b1lx&CCBdYEe*eJ#pA>pUO>B{gBM35_6t>yCBmeDb!!WWYptqh6E1o!O(W1 znNbrPN^Bry@}=qoy>fp$+ELB1QE=mGZ!9zxzAPNqN|Lb79NTLNN33QtROMGQr9KZ7N|MsP`cx(oGHBoutS5b4oLHK-|peB{D7TrP0`YXWlr zU8pxY7s1YuE*f= z5VHv%d`qA4AUi8NG_u4%bu?P#$+bak56&Oc!^gH+eskImLAK^GnbQAkWzU&O#A9eb zc%6nN>ipaRG3f8r^H>?lf|(OCacT0EgIamhTb)gcP3RR;NVc(HL$X z2}aK17jeBdxw^#hYlMPa_sRmb<^Os&#a!h1VG~<8>+7?%$|}XlXwM&qr%0h zMSM;jo^mN zxi)w3V{b`h>0{BcEUBP<&>yP*Prr~ONt>M=`7i>pARB+|3ooAysq`#c`H$@V!?8bs zazhd3;O17-5z?VUqU`z{7)Cq}j{CF5@q$AceQy6IAPlz#qx*TYl7o%DfxCkOZ@H31 zvm{PzaV%dli^l66HdWxKC17yJ@mmcWHjfyj7p=|{2h)F?8d0~hm#0O&xO6ePTh;=0-KA5#b+3P!-gYOY;gSJWOdH$y z#FKBNK-bZ;J&YiFh_j#4?Nd_@qqPhrOE=*m=LOTGIE^4Jo}sZyXKlb*Y`F?eE(m^q6j0si zeJ4@F+iR|>o^j`W3WKKR5+iQlFCocl((@kK9D(v2w7_G@^6v3^x|Qv3K^Ju!6#C*7 zq9VU));HbE6rL*9_CxCNsYnnbL1mkXV7F7FNNq<%HOcN<4IzS9xa%Y9fLZpPaStai zffVh0hMzCd15)KQTLSbSUl^T&!d|l6$Fd08OY*8K24}`Pppk7+68i#fictbajm*wI zvP#514oi;f3!^oPaGtHE?n*?#;W(o?u>Af%pN03aDf9oU?R+q|3M4y!(2* z2i#RGdo|1O_hn9F0FaoV8ayc7k6JOP6W+bg%jTi}*+cKC76245(bHe-Yfj2SJ}a`Q z`rhw4n`1G;X}j&`5LzD2XQq^1iTAsC3i%kSzwWxvihU&bzOU9=L8&a8WFvCX&AvRz z)o!2~yc?!XVWT6CKMRS!o<&%{&)CVA9(*Sm(JfvPD@pR0w&V33SD+TH)lp09%+qSq zVK_O9Xm>0r2$bE0&OYt0pWCdtMpc(x#(@Hla$fhs_na?bK0Fx41klxL18>MUFAN}0 z^s6t%$aF;J6XGL9P^I^QVN`f71f>H>6c@yxZ(v>ns%K#ex@E@xt}~|^A#)3x=loLA ze^~tnDXO&c!C2IKYl%zuGHt>e+6L2nv{uwnT4R$G^Im6q-zdB!oMgRwv1V-ByJGWh z(a6g{gD?T49Yx)EoNksHMr%g&eVz>(I2t)o7Ksvf(3yGWg_95U1KTXJU}x7BIUB82 zfz@`_;^avl6`gd+nHMUhy1@YQIwJU3u#@gSxFqzrfT#@5RinyFnE$t-G;!$eFPfNv z6=%|=kVBK7=Q@oMlISrD;kPVCkAPTDO&IVA?(6!sAHz(b45C@nUmal$2ZECnwBxuT z2@4>dh*xK&y#tcfG%-9a4oj8uX@UiVpm;FQ!}ruH6&*%rzJ`x;%237dU93l2AIu;d zGss>#h36lQZQ1DWQ3ZMI--b98E8Xk25zcx$|GCoEnzl7n%Q;hEDwu(wC6`a|&MmmF z9}SU8(ZT?7a-V>FlRPp8&jeFSYdE^~8NJ|aQ>T>yLZRJDxT%$RVoE3R%;QD-z1c7y zW|D7$m(a9`26CTsDo#O|?^+_c&g04c*h&DdXzX9LMUr4fyTtpcY^M`Pm{QO_%1zaM z@Oe|tpWr`lC3U)l{^6PBM^r#{IwGP+(W|Eh6(KUP$C_H6sTPu=tV@>0$`NML#nPL& zy!^CZiULjS{`Hw*w(c#{dRyvfn-U&cmob$OS6RWp^M`nKq%Epr#lq(x3hWL&(hd>t zT&HdQWa2pSl?MoxZ1-U^smcYAq@>uG|7mR=NifaST3-M>1Cn~e z{jz~tsLo6Vcr16H^TToYTm?dx8qeNduPtzpHyR`=?j)|j93lh{3Sz86-IvZJn|Zdn zC-lkwki3iW$QG^`{z_$-@DXG>Qf90ob*pmsx8TNu`H?%;;fNRuwmcqDu<`G~gFMa} z_4P|QpvJZ@4Xv{T!`_BKsg*T8A3*5TqNK+mn0?6*%rj`PeKkMCo~}7I8SAm>5n!| zK6Q_UDOYzSdy2&nP2Au^l~gqr1MZ%MAxi8>mC#$hc}Q=M!JKc~e7t*t*ViR3cfj4A z_j7ug&If1@h|iEb-_9@7C%NJV8h=@2(6k^D-+}!UbPmMy47T83*R$_mbnQRkR}fzO zDOz{Lbn$+5j)8N$v4V!QW^jHbJ(gp5agK@>e=LybQpC@+PTRw!&ORX%K}qjiwMID1 zYt(U04?s(e2NZW5d$+w{3fVH+Y#h=ZPhQMXQ6(HVT<_)x8QZMm5X)JvkN%FQyUIr~ z4Fu&>!BjVJCjD8(y_*8&V$7e8rDQ!uWhK*_>e50vPeXI|zF908zbQwjc#im0JezB; z-4wGu4hEAp_4TK~#ZjmOS0`e)o2r;Cou?DAO&I%M%5TD(`noa@R`L2M9WC5pl*+sk zENnfFn!O1J(tsby$o@f}^S0`Jg^wwN`wrptG9FNY#i!Viu0vR}wKgCr zSK-srQB#oBfrUjdkhFJprz<-Mv1z3*kWc;-!depvqj2GIQpUHF5x09d{HQ^r;)#q& z)#a7JL9=cmX}d*N-Wc@Wg|?^$f2wx45bvqQ8w#M+{GL0&r48wy6KtK}mzS(&E0v(4 zwCHc04Jde60OIa!s&GMmX-vz9mWUXYA`usHP^6FFH7n3m6yjo(Ue8H>86mK$T+T*o z)UQS7!no>zW3CaAxrv zmD14^u%xJskV*eD3^X^>I#a z%&klbpBH(=jeZdKPx)AjfwPcu^PXb!G@UW0Ozx`^B>lAN*VN6&g~Z!OEespR(K9q2 zqE2ot{xns}dk`BxbeOdGn|E>kY->ymXYYm9mhC~Om~=()%-T56eT?3Dk7+b!;1kyj zPTYv{HM$CkEhGhGVph(_D`7RWLpXcUdP?IOVK>JJ9>GtmwjNjf zf@Nk+x2s!ZJ&{5?l2f2ff0Sgd@0#cT(EHw=uv@7_LD5_=6%UFHlz-nlC00W$G%Q7} zk?C`yk-a++5k~^8TE|-02ZTiwrAl%&W>kWvg=9kYD$I4$e};00e&tE_%(z~K^xXd9 zn-diw2$c2h>Xle~hVZd-hNQ_(R zGR+Kj?D~zHb9`1Gw^`2*0Pt}IU&IDy&&&|zI{1ApZS0xcga@V6&yaD3Ta{9o7KPPf z<97uLV+sTy6?_Z{Av|zGcU(xKD@dX=(sB5^vTElYy(_ydLBV4O@41n~J<}B{27M!Q ztN6y+9gtPkD-c-iQ-3k}$|rsz(L$_VjBxntLb(2x%cuE)GTch;V{ECGA(wKIRwn34 zEvV6Aj|AtNm)~`isK^Of$|uiIHAQTQ<5z{r7hR?!?YkGgE}1kpmpo6?b(Mk5(M#PJ&sZwAp^uT6{QApeFjOwD5B`UpgsTeez&t;g3 z!AeN8h(5WQv$^Df>PE3~1P+Dt3hPv73#ahUgO2wafm|h?QcD^&KllgNBl3g2(KF*I zv;*Qqd>$q%<&A?!JI7j46Vv$ODjb*bLp~@TD5y+AgWa^RM5EBBzWqK@q7c1tk3A5a zi{d0zRsjWVxdhRnAJaLTq6L{L(AoZ=|5ax@0ls}wS5|zs#_4r;O3s*!ClMUdaLnAm znuh{ywxG&|n}J#kt&#y0P@68%c+_yu$A9fioG*q#z-rMPYzUJ~H^-X~N{793jC&}x zXJbG!Kejbm!c;`y1sfg;``K|4P11)u3JjXljEf z@@jexuHC+EWoma6M-#)Tcp9k>)dwZ^2`9zBIk2!Gl+f*1mFsi4bJ|37nzp&J$R`X! zoQ878dVxOOYhP^&r4$qSr=;fXvf`!5WhO{RpiwD=QvtqrFIyjXYhL4`Rk z++kIloYTpP$hl%jUUO9@kL(ca+V@Zm-e*ev_M2=MpdX_zB4P%o7vsN{Q#$sP8|9LX zMZ<%zrj%UP%xC&e?XSUSC8d+yKrZ3u^N3o7%10OGLnVy8V>7&IC6b_zx}Z0 zmHV;1j2qt&nF544(XoyoP)>R!EjkX}+JlD}eDGxm3yHDmIhtDsRKW&zKi^AcuB*xK z^I%HosVfkM2cbdl));km3#44+IFX11@M&}^X(pnncMz5-Ib2IQD7Q0C_PdGKI@EbU z8v2wRodyF)!;C?W{TgpAr#nubZ6?ICe>2r}bfOJH%cR*R5S(DP z;u;aa0bMNk{$N7{k4`eX-tP6IaU5>Ze;4+DBj){j_M1RYG>@AlOJ)vL0M6;P%?Hg? z4ZdF<(HVXGjbmPKZjTV^tzN~8{V4*xD3aMtw+jiSJ~A@ZdY5V|9iOr-%azY2k&aDT76XoKvaUSPOJu#K2eOHb3EEOM&sVkVg)?7+5$E zlUFNo(>2OdvG3TZw>FH{KCy2@D-?H+Ilq+zCc#}5?FxhJMV6dl<4dEX8d{%WM`QPN zQqru+_w_R`K(G8fdT=1z^jh5az<&a;YQY93)%~0gPR}X_b29FvX(A+;h)=9|E27Xwxj$d};)H#%4~##;L3c?$Iv@|&IDJ1ivcI`W<}Qa? zeeaE@Z-#Q*W?OiSkm7s*SyM@d*4fgl?99n+8jLcnsw<=qu6{Hh<~#zDhJEsum_-8D z)HC44r~3R8%9RUYBzY)7@=fXMEe7Bs&y z+*hDOa^q)kBIuKN8Q`0l<6X6aYo=>rmpY1W+qfA86W5NdkS`Enc8atp0IrxOBvp-z z6rSOrxMZA~fZDDbdGUk;bUwVb?@J`rQMpW@GAcFkEtTIYK|NZV!dc6zMoW*$nfm7T+2YqaN$c&sN6FtTh*GEcZq zD6sLHgFvwI@;nyV7cQ=)lh<|>cecv2;j=v6Aj@d9$E}7ZT?P;#-bJ#(W8LM?$;kl^ zlv78cug*z6WZE81v}MjwVCR09<%yImp*8USzgHk9I}uk(DhVF;uVx{Z$^%y7fCqzv zEC9h>B)({Nq>07CxW@q2d+Q7hBa|i8+3=N;5sS=Y^J~&4^|NFZ(00xWJz2+#KD`uO zcR?x+@q8QG;{wMJbV0!0%p{nMqzY+@X?Gf!OR2^I!h16(#Al2Y(@U^X0IaiMvOX2+ zQg8Wy?ODXGg--C?e2-UXUbRd@4%ugNY9Z?X&`Yn4IrG{7-=+V*aE9I_6m=TUDjslD zYiY8rO;l)V72Em^4fpxJNr%Yw4txF>4vC2{9Z^^|)x^I5qAO_aeqtO&`-?1}9a}4a z)sQ^$30>BnydaAZ9bNp^)(>4YcMibGIFUr_AV7V@{#T%+)ayTj7?Z@U_mp+={jlV3 z#1LK|pzeE1X}5$Zn!*%fdlN=VqeFi~95(m5-j?++o3D9YiOA%D;RhgAR!2^Y zEn`f%s5k%YQ8SFLI>Aw9#}@drOFjue<3G+?H#6G=)CglJ{i%d9%lz*Zjx zbBi47GsO|^wrowOn;-6M2vXspD@Ye(KJldzD0^N5{Bx~_pi%r;*A7h>MDoPonJ}lv z2&yECP(QA5;xQSNrd!o|)lU>d*lnY}`>!QMk2JBfssEOJM;;qG_b48HI{(VSnLes5 zFQUFZ`X;%WPaJ3(rbS8Rz{A?Kcs@YAw6z%G>^|)_>%m84byv0PN#I@0MnT)S0Y*20 zu}J8Re7!8Es761Se|^G2|-L3;Y?ZX zWf0|S8>!c=I$k0_bp9tk88sHkzKTRj>}1d~mYI{JGMn?Pm>y|9?7GhEBm`jb%g8SL zjbp!x77pwuD4Q1*3?M!#M_-s%OGVA3Bi>W+SAf5X;fx$SQQBPuNP;uer>m2FGBF zc8_f2`$k%mCY+Ky1LjCl83L!f`*B$`8!x864Y$^sK%y634*oKbPA(9V{zJA24eO4Y z1B?b3Kmz*L9JoLrSU#Q)I)mM+R`}yRHj}1_#@+7wM~ZeU^Nq}lVgjLe!N4<~HDcZR2@ZN1$l0ABB9?SM^ ztIu+HJXw<+sFDbkaAsaMN*&S?3)%2?BUm%@RN-rBcQ{^4w78!G z>Mc~_tv{Gb)}D`L;q%)hH43}7vy!MzLkQy&vEn-dNuG+`<%re)pkpZmdNbLyBdUil zKvMGGm~X-d#hXM#zPDs+jpNx&(gql0l9_IgR{#?m%k~I_mJynEmKTGu?j_W1t~!x2 z1-w1W@Ukb?Ioe7Ql6@K}3u%3?L`uu#0{#mooP7^MMZ;WIvRmfgHbTLwp%p1KO`?_4 z!!$C-HrdtPFO#Nlnku0CW!aqxr-DRw@rV@+bsr1MFeu|aAQEdv1bF%8pw1TEZ1GvH z;Gpy53@9%B?2ffb*yWeXSf0)$qO3^WuJEIL;bKHohr&a>PvUOtm`Rv5aLBZa2&P@S zf@5h(upb+A##vBfpE2gkxH?}hk#Lj~+w{0CHp%da}fl(k%D{mkLz3&ALO*>lypCa zcV(?zw3Z1~jd$C6XM^lLnhx;Z`J4#9=C#~d!iJ+ncd#aqPFC2LgO+2O@;)wCx3By9 zJ-sjmQ2$baR3);^0vEMb3x12`$t&>+xNC%Ildtb&=_uO**fy$&CRzxas!I>?wbv*N z-7-~Gw76a2RU`|MpebGZ!duB$XVBy#;Wv6`i9S3aa;m;7=235%T<0zBX%N8-Ir%8Xl&PGTDqgUoZUl$YnPoy63^QaaSfMU)4D3`1FsqGU zbe;*98aiKJNS%fn0>NL;;n!ayGV+C7p43}|yr!uA#rApfiXa#%wuRk4L=HkpHIr&Pk(Oru5OCw3Si2*Ce%&~V>Q)3>WQ z!6X8w-2wy3K1)@mp6B3DrHc1+K0IZ!$`|O4wk$Z-rgS6I`n;89@mY&5{MH>P`;(MjN3naD4^K_lBfIsO9$M;9d*7L&`3wnsD*M@#@>@^7CnxHcL@2)$qdY|!=`Zf zJ{Pg(87WZ1^0bN~=R+?P7$E(8H<$cmAA^U{i&OHPmc zz{drx(p9m5qE@FLp#-s2HT2*+;e7g2QagJF9W>Y-Im6{ z;HZF8Nfl_IdP)tTc%{y{-NETXqD0tNK|zI62Bi&-k+v%k5(kUCJ861~^>BFtCpb_I z{ZI-30E#NhncqnBZ}wO$Pf)If6dAxf2_*HR0(K?I%`w#f-G6Y}Cy#ScTm(6pTF9@@ zFt|FK9wJ%4m4>MQ#jysj(9HKsxvXZ}syNM+J)fW^nz^=M@PM~U7Drcd1geNH^BlNZ zZtqSM3AX;idGkQ^XzPs`HcUI-Zv5C@1av3;&a4$ChM)_{G3|1W`4tBFj4?8zSwO{k zvCRAW*+;C}x^p%pPdwxK8gK0hU9;B@eVY?Mljx~IsSvX-y3!oT8pFAbU-%b<)4eUZ zps3{_)jl#hd?8RY`0_H3f4YnhFerF`enS0XEvyeR@0BxL(T%8PPb;;p@N-9*;mz5e z3A<%ILkjg_@-t(0V*^3!R+&m$4#HCs;Q1DLfyv0SUi@kdFz+;iwGW|JfTv@fHj?(E zJj2GHpriIwBad=fgX22$s4?9Vw!iO}IvHKCSsb^4@B$GVju|O3g~n&qb*Cu>%i04^ ziu|=(Oi~y<{(01=pey&Z&f$n?1c38g=Cg#<HBHBgK*9r#f3gx`-MD8ej9v63Z@YuK7=6>d$Es2n|6c)#!TNT zwq2K%pP4WE4o?LdIv|P)9`~NrQ>iR)IidBDre-clhu_fvav~yYp4tl&KUK4I!m}HO zN3V4u>1V!PeM-xWjV5{WOoj8>B|>SP0kFc$dE?4t&$1gMq?S?+pY0IXlpUR34r;1Y zgq4|1GH2)n1t&*sKumU}1a5 zRl07O>ddh_(vF#?STNlEM>FjsP11R8kT*QXA9g6q*j%HkX=z7b@PR3uMlDY#0OD0?sx_6m%)9 zz$1VfI)LP)H!LG}{J}U!zc-x33)R8=W-X3KEd^x6juEATXfRI)s?SnVNmCduV)~TJ ze0ShITc9WyCWsq_a>pu@Klk{O%B#a8RHmM5M@Mk#RQ-TqHK#-8^Hq;A{uI_U1=>nb z@1PF&w}KEnRijr-Wh4e>>C2A>CN!Uv&`pV;qp6^IJipC) z8;1|#AJ5RoN*Ch+NCNwmBnnfd@YJHSx;7g6?9@syATupIxzS?SjqG&jYT_QkE= zH(_x@IL*FfJS)I`ZZR1Swku%@hMu+G1^H?{p1>RlShr;z2X8xglB#ij>%!;gO2W4uz$dl%!duJ6jd-) z?QOrUW9#6;vdTcK_6tXADhe$)EFs4QBq^2~jj0<1CNn`;?HE(Zd+2RvZ@0aT+v<8KPimIjAsM?_d0<5V1@9gR_D0*HXG+V6uN|qsXiw2{UEP! zmbOIlcl8KC9c}=}0xDnSqc5B9rLrR31)Qr`j{WC!#c~m9FlDF!GLt-8qZ>G>w7RP=cPfgqUU?cF# zV$xw5df94$O*k1|>Y}!NNu3|aC7p6?8Obr@f6~bFs*GV;f|$`IN%IwnrXAc$!y4ak zm!XoQL?6iVg(RZeZc}DTs1p{6_e>3E#P^LfpgI0^wd2nqcILDPi~ik8rceWuEM2hg zA@Z($uOn6G!!+cz<~i0s_*B%O+4taO=`C4mGW3?eL(<$S&eU3v1GUDrMEqsO6w~AK zVC7ygTBq+|+VX?o`NErwiGm@9QECZGiYxRq?Q|PleB*Tn{N#i>EJdC`Qk~`h=muaf zqygr98SkSirofDR?-KP0S9Y;Lv?%N5_>l!)RC)T6_OxIM{zZ5X_Znncdmr-*Z1;n=8}*{=EK^P( z))n~wp|UEl`aCRqi_~spB!to5`6$0Q& zw_N}Sf_KWkS(a}ZyFOj>)8}2B3JsYGwMAJO6H9oU5vsUIcXeQ~1sk6S@KO5&WiqV) z_yff&g*?Ig)}MBTjkV5-eIxPn}oy6yVaOg5bZf7dUXtqa8u`b`Bn zx|s$4&E^}OyLbR{A_;F{1(9+|Nje^=Gdo|#kG5Bz*X0o-KVhz*pPIHXt5~j$V`0eq zj*fiYm8z4jB;)UNFz1+(+`*!qM+KF6E|?6T%Ma-DDwovcrnU9 z!+B%>B}8!ubuygHg{T}>V~zGQr9)QoQ_O=3_Gt`dM&gXh+y8k)3@E@d^(BcPX>Ry_KA^M`ed zC7bteg9N*sV^(UBF^(GM7FpEt=D4h*=#72OrgmkY45^;zr5IFHodmEm&I`JuR_=u) zmI4cI3e0rah@wU4xUq5ny5R*?iCdslSCXLsEY=$_5R=0szMRx;fEK1gb4)!HmUem) zkFaKHvtVYzvVq;!Yih2ge4FouTb5gpCGU%)_nmRj)1}Y|lY^l2im=gTlX${-)_T}e zME#K2t$yI*#?RQ5e>?W0=Z_nnuPA5g>9NfPs#E&5CW0w)<;c@iK=>7_m!*!eziC7j zKV=oJoKohI(7h84&qI#R?kSe*x0}PPTOhUSz>vCiX|1Hmqa)ZTzCP6`WYE^y67w1x zd_z!^ke_;pz53FZ*_!(4pq#TM4e~56M2Zs$Uli-yFc_|}uc!ebq8F3f;7En%5KhK1 zOUn`)R{g&yxgIC510k5+Xg(J4L{R^(Z>oyeC{{ucHexO{tRP}VLc;xFa*=}iwixm& zA7nzyKyk#OJU*65qe0>bhi zQX%jG5P(v@X@+Nnrhj4DP^qFoj!%r}9?o62X_O3HMot7(C1`eVD$l&*uB|re+b~iF z>T#QyFy`1k+J`+`mRViv z9Bj$Puw9yTO$2$dp~q4X2$ohk9wP7v7A#N9BHJm1bwY?2WzN3Ljv#8mkOP8bjFTV9 zic9X05*CAJrRzeN8=#RK%tr}F>yzg`J$33=X{>Kib-^-mn!D03*4b~Ra=N4@ zUKyQ=!G&h!o2O;9W4qX ztOojt#0HL!%zz*nb)t#7(3x$mW~|6=f7EXyaw@^JQZk@P&PqGA27FV>s&})-=i;$Im|4_S`UN3MJ%GJFqFZ(rCYd9 zuM!#Z2D#{81*48e`_W%qLNQWRn+c&T3j>}}0N_I&yI4{Ah9S+1p5uen+{ zCbfMzJe5tZRXMHRtgaz>e|ioAZ0N`LN6rUsvFFx8YQp%uhRucW)xR#UMjOC&Lyra@ z7Q}pp1GImpiuuE6M_p#g+lSkYzU+Y2VdsB88wN?Z7(i9zH&-x?YFnR2%PcOaYZ{b{Aw7~xG zf3Lx*=o9~S9|>lh?NMw7i-*fL0J+U1y*X_3vW7Uu;Fjo=QK+h4PBX_w$aZEZn2eML z^wwdp5a29@(L@*kxDNcP_Nn6L8=95^v?l85){Dt#M)62Mfq8A&O~amaGn#TE)+1!Z$eLT zAfsqTY}r*vi#fxk?&MJj!X8sFf3QqoFM)Xz_aZxwq8RW~mI!51=V{v?-V51ObTAMJ z^IFONjWwqW8SGW*f0lB9wX7UYK!l;$xY*8PdwaG^$uAON3$SOSkS=%YGpwuhNxelH zp48L8)-8e+G{210k;gKwmzutmH}Z5jgZndb(DKDlwd;)VpvN5^ zqG5DmvW@gGu*3iyG8hxgdlp>w1#jZ@n`RZs%8g{xH5i8E#w2L-2f9Xt((?Dd0!HpD zfbN&NFD~W67hM!MFBnCTk*)Ng;f9vmdyu}25#~c&+mSmX7U*RlSq_Jb?eFf8Lwk_R zPSbRhp4ufme3ykm^8~)@*D;nULEO6+%Q(BBS0R9yWY`7SYhlbiNT$_I3r0N#KA04OM0N>=l* z51|GP^rbYNSlWz(5c7>^TLD|8W2s8$dmI@7Sx&*-W;v9(Os9kTV5yaFKaa3&3x+Qf zB!FJ1x|v$aBAom~_Ck|av+9w#JB2OfIT6GibFT%nJclnJKht#W=B6GXdupcw23v7! zT)HuEs8vL0`)`MQf z($B6q-k2$&NDJK3*DxHU!hG*2joEjtdt(XkKsC4t4C{b#S-*=Vk+QP{9o%@S;5I_x`Ibn%1a`pi}w~+V6K9n}o!Qpax z^4c4PR~m$b`<}sa0Ls>k53EDROG2<)Vs%ip<{_61?kc_|2D^a03(SBX{^L9qcDee? zEmzb(B=zlu~Gsn=&Moh7nKlzH7paqqSq|LusqiqWf>wKxO zoCHh9WF=}tZe2FR!Lvm=EeV)H`QI0|1EvGq5a^4iY*$9RVE(V;y2WNSmf6-|e*S5n z@Ggc<%{;Tqp07JRw?HyzQ5fqWfJPnTEjJ&E=|o7<~Xl zYyrZmZ9zfqHsquoqa59COdW<8f}G0bU;`A8f0#%qay;crAV6(s)%qj7&_&ycBgVOl zgb;WiSeQjM$}3>qsDPsemunq@GyuP)1!ylGpdm5f1x*?lzdB032{6$_KJW?MpYD@V z4xo$o;Q@e(Gh$p{Ub8_FDg;uFu>ZC2`S`38NV+Jv&B${M>=nKlW-4m>5RrA{c{&rx z-Qp8#KKgw2J3}5V)$_fP>?jpaQZY*4uE%Hy^rSW1W8U>o9#X|i2=AgBu+D3#5U);t zq$Rf+U;0nsQ^7Y$@1ekHuO#tQ9jiC;q%}UH23`)%LDwf!HO|o(wyp~_vEqa*8LtrHaqL)elYUD-^s@#LBH_rws{82>?NVKP*XVKYW32Nt@1%B~D+h z7B8G)jY^AfibJYrg(LHBm51gFOcbc`mtk2I#NQ6wGgsfgJM{;ZodVgEA9^$TQG^*T z0X0azliJy!s|^vMs3QbxGrMJh1_*dO%4+~d`oNOu!PaEK6Yo-s%2n#Me4>2g=NY_2 z_{oqFU_2+h2S=8veP90jtcl6u3)Lwur4f+Zsb^x}H9!3O%+Me`6gy?3nn{305)jY} zG0{}0gZZu@#Al-OTk?Xg5?Y$lFXz}1^a9FUd#qdI^WWcE%EC32#T}_;Rd&Mk$+=(J zGzrJ3_YPsWOxUGkqi*XA#3={em{yGZ&lwfit|@a0e7KN#158@0JaW$F0Mq~g0A6DF z^^j6fxsVjE-8lgIr0(Q z+Z1nHF#)omWI`ZSKJ;kv#IQuFuZ4h062lZF`Bt8g;_Sk>a=tgxGisP)5b@q1l$A3c z68<#!fu%df#bT-I2y0Z%7h?25D8-cnZ4#2G`LR?jY1Sng2OGIG=I{b;2GP z`kzC_q8hYz$oM|J?pnHD|3a7t+FiOA{FDsJp%M`bG!Aot-EoPN$;O0zN4*?2wg0KFHe9iwDce;S0>N+0x*m~7!0xd0;fOX#HhTxK6;gGw>w zYe8ZHJ9(%vl>DPn_!V3%#7)~VBHepGGwyBm-d|1VqVfPecD_Xf1_TR$2kEozsRh^M zHqZnf1rki_5n;e+yW^I37H`Ih*iu7m3mPvGXVgo zjLOc*EJb|O;q*-sf$R+`=H zUuP@nuIJfi1j5d>7Y3UxGwC7%V!gNkp-y1E7j4+E6nnX|t3Tl{im-tu72_~+S;uT@ zz05j$ElnO~&#fIzZ(q1@!zKJTfCou@ogCR+er;P&Lx~(e4jI3+)8*?6OqO87Yrj$| zOtAU*rWqV7_&bpqKisBLt5?KQWbOxagt{GoT!9eaWyLz{5>*uNGmePRu}yWM8lht? zOSl2q`L9H*H^L8_NqR}IGveZ%SFdmRs7)fwvh7pG9=Q-o7LXDkhhXTR4Pa)t3=39E zea-l|Urh-UmZ61r#G9D#OzTyUe_1Jju8$T0b0*PRHo1JX8O$YcD!2tSg{;6VsHkZ-kH`i_=qD%%h1G(f^&|^y2+IG&i zOH>x0581fXYti2LhyJ4S|8$*++q)0!T>yaKVPO#lq$Kl6*8!t1Sr8OJP;!?6M*HjE z)T3eOrSve%v&m0)ovjF(_ks#C;mr!t?ie62CB=?ZG9Ft$*KTJ;uCYK6(raOADmzfyRK)oAbuynToC(tN2dqK&1-5?=wv3T6sL>>hgpnVGTPXblb`Z##Ln$;bCZTn zZewDd@BvYF#q?t`itzdYa&=^%l}$vTu(*~6T|-P&a{Mw64s)hA4N4=N?0kG+@Eex& zcuQ%wsJ;Rx^3l4}YX_m8(KXLab*k4X03tE8yyw;>zVGql`J8I+-pSIjM2wtZZ;MH0 zRD~|+%2e%TEwxh?_yumaN-0cfw@ju+>!Nf-+kr>e$m+6a@cstVb}vR?-4QWzUrzE_ zLR32jFKfu#z8zsz9+{c;gD|T&?)N%nr5;IJd=nbmtWHMM$E4@CS?EHc47(t` zz_&K*$JNo*OG0&#ISMlmSCBr=;0YJV{R+Fp23V%%|05f}Z%cumk2+jGJjGqRF$jC@ z-fQ`E(3*1(ZwaF<<#iS?0FCCyk(p2_3MLfGcLKef_=c2a{xv-Y&%t`GB-HN-fQ<^87htv-1-B;w8rQ{oJwZO5^8i_QX zr*~bTnD1Bc#24LR4gPO#-BM%a0YRn?u?a=f@r|5)?ndHr02xo~613`&0NoT~NlAR$ z$!A61MF>)JbEFw!*-_l+#|BF(0r4c-MM|j=a?@8oDBLyrvihY4=FpA`UP18Ep)dC% zH%p8$%Hk`YP0;0o1<`SI+5lu6u)ZpH@UDG>HWP|7iKb{(rt6M4x=}JOl0!%~K2K(^ zl~3*Qs-PCzXvt;8UX;Y@4yfX6%U$+mL#`F>!)QWL@8z0v&tj*QY>+ktmBS$gK>2i-RLojla}LydSJEK?=80F)Fu|`-cn6#Otg!Dr1e<275AyhDDiwU zr;vnc#+%8+k0`9&4~SK1Nj~D#=9*Vs&dCL7cX8MXBv09{jS%dt(B5J}ydW!ni$!!j zsE|lL4R) zNG&+kSLy&$K&-#&WC<{JFqg@%`fHQI4e0XMC_w3_I06pd#LwNs`Dwcc|W`DUb(=V+(l-KoKmI#N;2>iU^U5O{<<1n;U zGieG=ep%3?_NGs$ucLUrKrjKC*B zXa?dvlmUXq9kc(@_-)2O@L~=A9cF|Vnf~am(OBpun={0JS5T2#@r3_iu|xXjQ}Cff zG-T09Lj1RtcY8n<0jS+=Y>6B60000001(J|p+#-}lm?Ys0fdArIi3!#*!WQ(%3=rr zb4j;I@t}vFQgw@=CqX7zAh`vKa{ir|i!~IAK>sx&bRT%M4dX21ZBr@X&LQ_oK!n`1 zbc}ibxrNVLAf|VovqM>rarE3TK?Bv$eZD;fA7riPFzF~TWRnzPKv3C{3Bk7q>ukKUbJJv@?T9vK`mI*(WxYA|5v%6Pl{q z{sK529h_SMGXc4*`F9**_LRVj%im?^=_Ao(qfe#R>7LslvJFzu0$Hp(B7MWiosc0u zV?>EMZ4W}agHM{)g1$1V5Jw(FgTy91kq6ZxLwLPMOf@P;2pYubt7FLY>>+nkc}S@q zCu87JOGwS&hJRLzptznL2Xo{e+y>mL1l;z8AY1du679N5IGBUTNOF?yh~m-l)C_kC z)%;NU?p1rB+<`GLgr2Yf;?}R7ES+*^P14b3?#M=Dn4A~tzAIORo5AWOQa<)aqb3)s zZ>e`qQo2zSwp3!nZruqVA3w2JP4|ac)Vf5k9+q{g@Y+@-E&1KG1X;6XLl|oXhBYO( zf`{VcH>0`4}uACAb-t3bmRuX3-ZdZIg-L0ZBQ8b1p z(+H(qn1V~*)(FPGmn*jq@G%rH6DZ3s8oZq7i?NQ55ju)fGC6k%&@nYb6+mC5NE+|k z+OPH@J#%SX$dXI#dh~`rm;`yE(8-Fr$DM!HeqF>HHvoY}?VHYL&eH5V!7r$Nk+!tY zIMEV=ChY6djcKD>r2%NjxK2M~l^g|h4qmU34gIJNS`-U0ns?gH(bW>j8I0yu$b&?k zBCcc4i?nzv{z{|yycN_q$2!1&##~Aajp)~rJdAsX*9c2!APf}G`3Tu;?bgYr^SA^q z-Qz474~^G~+rNu|WSI`Q48C(X-d(1hf!g0W?k1iexk|PmgUi)F6Kn?#SVh|C^IM+l zLG8b5;nyW1s?&&rj%`h6l}NXg7VlwXK-1+#JV>q=N>&doY|qc7<1Y zs0p5#@Rd}{F~uBZyo=U!9$l^q#fMS}{16F7H4KzO2AUCo9xM&mw3*N%2vV3+g=YPn z0{vq4m@oyX?h2@f2ZdkPnvYSnIiR~2I+&L2iGwQR!8E>J@0(g)(kCBiTAXCFM-#USqf$BcL;z)D-ru#i z}ds!dZG|uy>^39;gYQDO^8h99uV14!~>;^YVoa4L8qUkA>MY+nvI%E_=>_n&or8xszOajkLJ(W0ojnZx;OMj17&bdaE*1@H<&*;uz zt75W2zmp$}6~_k@?{aC;g|r?`PJHi)9Oci2=vlQ8tXBi-`P3s^qkCh2s+#F%BF07! zd*Z0`LqDZ?yh^E^AiT0Mi}~x6EubVA`k|DAo_;DBE+TM@HS)tw?(R9&W;pv$3e2Ko zzUT!#Ikx{?+;2t{Uzd(}2HJ#Yo6`$d72#^9L!s7iW^&jMAAy<)+P{Vcb9Rxz)>clm zbCc$LHQSLb4gmZ$QYdl>Y8D?nSV>393^V;4>lFte05qg|vdoi#rNB>IwqZYE%H`C2 zSiEN+I_7P_=6zl#26$qx->6>9I%u;EysLgFBRY3l1Tqs1!6oIwt?n>e$~;6PL0Age z*SxK%T`|QE@fccejZ!NLUcv(s**!8*W263Cyj4XkBg^zGxyq2xag*gKQTqSNa~Vzj z4mQHZjwN+zgAt&H4ew8+(x+_-P*hw@@g0lZER(u2Hkwu3G~9tI#ae?n1cwte1GXcl=bI{XSqUhj zPoXG=I25MK@TzN5B|@G%G|1Cu)cmwT17%=Wac|y>Un%^(mH6OZ>BIiHG-wB+A+n{$3i6_-9 zIIA|e;`0Gu&9dJ*`27qX8tn9&Ah~R;dA&r#F-W~wNVLmWzypqk4|~-bP0Iig5lXfI zI5vo{cWqKlo0HzE2ry|?CWso@1*VvEleb=q&F2$-Dym-qA)ZNd`>N6oq$>lo2CtPS zzKpqJRv&p4FfOOHY1#3xVvotc=CEbk3uBI1Q6RpNNJ;AVq^`nmt2S2f~x!+Eyct4>2&^I&N=6t(cDO5WkjCTgG9%4nzCc zXZ2*MGXWFpHFuAVsljV(D+=)pfI&sJijglYC&tZ|;eB+)Qo1DU8Ekd#AtFwN)f4%R z{4O}g?Q@;rE3!r7c~%YbmHBcS_EdcYWf7W809#$+^;r{{feVlXaWRB9T;wu{n0yB( z%mWn`PE3{gFn2PCr0_g9z;iZ> zw4>op6VRUfhV3FGvcJ|j2v813#tRlkA5E>Vu)(uF0&3*;)-~kuVF%q4dvd*_0w|8Y zU^gak0o4nR8UnWanrco<`kB>9VF!k9zgYsiUnlr|%jY@nQz7x&=hG*Ji} zcxPl*VH>toR7hwT_XAz_8GVHd7R4j6LBbI_vd(=zaVAY1MRnykR+<3$8GSOHP1NkBalF{v#W@YJ##D zMCkJ56m1=p?xQv?y6^A=iJ+PH!91f|S0KXgO5CD;;IdWT7MoLhIuSVTG&k8lASQ1A z0wS64hB2h|NxRzUq9Pt^Zy0n++cAR3OHHUx@iWtbE|x2u=Yp+?|I)|b2J2D6x0(@0 z8;GFYGw1FERs2J}zB*oYjbRGo8!3&0${{d8yBKaH*FALyPOhI=uFdFv5E%JObZa}% z6$nrtMB`$z5MTM93rd+m;z54&&Pd|g>VY%5SH|REWzUxx5T_Xwy9brH@yf(!YS}|< zs^bxX(b87oALF&w=&!vCa1IChBuX?Vc*tykROGuX0MU+&Ge^nA@Zv{yuA)VclHK)} z4m(hu^kBO)bBN?ijl~1+gu^<^Z@k>#FOu>$PMSvXwD%145tMgNc+U)x#ks3(OrD_t z+oY)(75h(qcGL>P^wpJ{<9AXFvy$5~oJSK78Voa}=HOM}1O1Q>^^=@)fzQm?l5>H= zpC0s_D@6>(nx5T=R&$m9h({pXo`a!Km~0}tiAK38_)A&Z^yJ2|#foS2^BaU8Xv4ZN zToy?d>W>f(fmC2dfFdAcz#3%WndVl`N)HWoOe>u6dN(j&Y(2Qiz`5K|m^-(J+`9o1ij;xtwS3L9yw-LT{dqWECAzcfoXJYf^yk=|$rm z2V6mr939!DvBA{KnjC>5BYYoFgDnM|9tZg`g4o?8o*FrUXbp+QoMUlJLe71;UZvMI zN0+({6q4!esAZQ@L`g-2Ll_6R1{+=x3kDMSEw&~~%_{^BkL0E)yGhNKCN+eKdDf`S zr2jg*69TQRYWjPxEhH*xtVl|suH?I&`bz(=#B@2R4zQ7Nh9r&k8O*B`5pT>SH-72M z3v-~*9dUp0E=O&RwaqrF%*(We75y!?(@0&V!nb*sE$$Evp&lr(`$N4 z9xf8|nuS_5NmlCLO^Pw$5p>Q?7}DUDm?06fO&?GHeNPlQV^fP41t7=CJed&NWb!0q z4|82=Q)z#M!4$ee+B47so;;d;5gxiw!h&_g5Xk3*TE6KRI$439EMXI|B%|fAkxwA9 z3$X!SZHjgCkrYuBF(Wyz$uhpIL?88nPPZUvtD|*h=%`jNm=Rc567$AgWAJUGoJs?a zkGDwq1!{NDVF3DEZ&n!oq9f%z2=$k(R&yzlnZM!cac=Rb?^%bKxI`A!-w6WIz9!65 z(?F1z1NF~fU^Ls5Isr5!CD@nXeQZ&lE?L54nGs+DK?J$%5pE%rgN~Zhwl@QJW9r}_ z8eIYx4H*F1s94mK@{`ev>I5Ui11XJ3{b?=8R~{2q#|+v4tYRkxmb*feAbZBR38O9I zH?}IhPuj*ft@OnL9mXfqcDJ(LXQ5eER#G}Vc^;hiif32*oFiQ!746%$zgv~y6a|;x z)|wR0YN1I_hWPf-CK>Uk=BWtFPL>k1DzpQD;XAue7I;WBlR56N|9P5 z*6KVY;RaAvyxWSeNA!55gk#bBKgBo{Ai%g4W$j$;p8JU-I+5c16tD3hZisc@W=7V4!OU16BC%(3nNhsW$|mmDx|pQi#?J%PG#4u)j4RYqH^$pEtFT2}hcF67 zozOoJV|Snf`+T;jh>$NhH)AWuKZs1oy|KzduUH8D*q2T+BDekt$$jOH;I=SkdgPf5 z00091Z}?L$P+?dA2tX{NmQ)ej@_?_;&nwHTEcBVs>6?9kDDa46L`f`!SjlT*z4FM3 zepGwyA`ndzgXXB^B0=dHsuqg}?uY9%Fhj+cDN7-bfoKNud_>?O;fs` z=-3)GUCR6qL->qUSRexNwW;`F}r0bjPpFU;bO9QKPjp`yVjGHCoHn`%S z@(FHmBLNpH(QG6ox4L}c88hHHp3TW@mncs{0^*&v8cLYkmKD)4n8(}y2S)Q6@ja7F zwe-5rtod~S*YBu)(Whjyw>5FK;pr-HO$UwDdoxky0S+-(;4vKtBStQP2cLq{hA(rp zWe!r{W)fLP%&~w#QtsnG6~ie1RauF67WRcb8)+NtsnMCF( za|Bdze?qD)0dHwtnuh6%{9(yRsSLwi=Tv98EG2UEU2wN z<`2)@jR32b7B1bL)S*0KWRs6Uv`7J&6XAVrFJ$P0o2>AJq)1Y-jGL{Nd!-~cMb<$0 zCH_Fuf?agW@ZFWpzy-F#B~?=%d@UHw?hsZz?s5$9AwlPfZU8OBLwuprw_UjCHr$@1 z^Y@n{w}|gAu`FHLC5b=S5ZB&QOlMoXaJ>;=F0~BKV;Pzr^mglf=~wIy^#ixBqb)RS z*!^MvF?d|**KbWIl~7^8tG5b$EsP&6jM~JqA1azU4pG#bV|+f*P8RJIVgRw3+TMxR za(2pLf~j8>wYLRUMO*hqT+WVOXIYEo8YDGgj9ofO0r2|`3twG}lHTtm-Ao?lb?eL^ zMM~q4ar&N{FSWDk;e*DBzn(8jMoGs>7c7JQr>TuOk=f^J>F$Xv=_SPl4(2EhKiRG& z1~7`xxCwIHe3rY#rjajKgT4RTGIc*>b9|U)bDs{MZqWSD_|%?Au#5RX6P}mJvEhNb zSi5dV-~2b(vD(?7&F*B4Js1G8 zaviXn)Mw@mJB=_09bs`l?DNJw>I;@SLvnEk675K*suCNmTahLD+3;?sC{B*`5~mLYx{F(3a(<-VId5vCGNRT@$3T{`W((Zv3BC#S!CDC;Eb$W|0F%H;efGL7j!S@BAF*+!dM&=@c~{e&Wn`Vo{YkP?R&} z-#`C#6c1~M|%MV8-!q}6P z?s#F?In_9{k$noy*}8yyU!e@ z^zT)jS>7Xn1m4nerJAu!%PanAr236l9A{twb8b+0=rPDwA0+1SfE@0DqwEW{V|0@7p$Lw%d)K7PBLchgAe|`p!H{!2ihRJ2co_xD}`c6j~#S_*ob}PYjgyl z{QrO3iEAm+UQZZ}^m}EuY21O1vblR`nXNHM)>5)1nHn_0gS_bu~qvPD+$TzGW z_=}@nnbnOVPfx?SBgXfOsC@5t$|Z2#6nT+GlPGA~nSRaM9Y`fkSX7GIYTrigXLJ_Q zw}jDl4z@E;C(B7;MS~>0WdG?|wMC~lrpfqA1e#zxXv+;Ad}Pq+UvnKAOl1LChdo&5 zzM+!o6n!L6Ch=WY17H6=3&1x1(-{-s=8vBrIb@Mc=dsu;l(=!N0&7GnU@8 z&Exr!K1yCY0N%i;@vPh5v z@Vh^>G)H=pe4rmslb>-NH0?v@f!DiJuU6K$Gn2P+kOEXT1`q%Mmf@K1zo?E53neK& zy?}`dm>}(-g`SI2|#}RH4^aEaNcpSL-vihlC79`fB4Vt zrUN$ZUfROatk@xixKzfsY)~&7j?2bEmg8c(0!4I4?FSxr}mX zEV^Y_@Q23yMloy;2JKu*p}9R7(j+^QwO??C_yUOv9e+_J8ChlA5*duCFTq;`z%9a; zn93mv?1=&z$QFVre0YH1JG}f6@g&^5iD@DrD!TWLrZ2adLHQ*z;nphVpQRFaOU)uk*vs{nK2-u%xqt}DY)WksxI{mRah z;o(oW@b;aP)-VA9N%I!#8~w-rzoX;!G(LMz)OsQV~lRpl^7&*#)V&<3<%7%=uM2uS;=@48`~=~*FZqriRy7- zz^`#b1Ro}5!M%|;;DY$x2APvGQ$jA6G-mhmtqW;;dznJLCkjsS!q?x<<5U|4en zq)+HepbQ`SRsx`YI{W266wo?00s{Dmxr65Lo08l$F<-Ujl<3p$)YagHtb)dHsP3>g zqMTAI7{D#1hP>2@Q)mH{u!D)dXqsQN`gldekpH9NZ-!2cn-2pkRt42dvErPWd%aM& zY{}h#S5maREbzX^xhZI_!N+ z_b}g;@5C!tG#0FSoWJD6*$~~{?uX<$g#ljcrT5&h(mrv;ENjHEW4Jolzx-20`^u*1Z>nJGtGLjC_AYQe1X@5t9uXT^@?q(hAkn-!6~&K?mvGkYDQK) z3U1j9w2(F`XOrw!AhH#-@dRr}-^Q1B83`5HhY`huG?Z1-lA=~4%sE6$u{}G=22+XQ zPu#qX&UPhsB3bq3R;lT5?}nbRH{x`c1^~A6(9oknh9Bu;CO{j9L0MTznmUc+&PKby zUJneF`r9TNdSnt(CLRYB{OyG@Q7%He#H(P900kjO$K<|?8u-R%Tcn`S6j`s8HZ!_U+fHN?OuPVYwEln^uwe0#Fr>Egtp<-7 zsoN@^EO{{J11w$|^?fb59n@fMs+u0!V?~3?LuTC7+@k*v&TrH zbchnnlQvGx0_{LX)*8miqYFENmGi(UEe8zO&j{t?Qhigve+P8Dv6RnY=-OMlRfolW z(Pr3mzRZ*42DTM*SW_5 zXCWHCFs8DT$pk6DP|TTlAoD|b`E&DMiw?S(8GOMBCVQ2qJz%fI2=$1gpU^P41`p`T z`Sa>yjQgQM=&nkTE&j~kk}##EfrA!2LnT(%-|u{bW}t`kdBpfkFu$=1Ux^b1cH^!$ zXy78H>4+*ePbLJ&vC65MDAxOD8*AldUe1aEkT=&Zr+&2|;=j1`Rd)5N)xo+sk^6e4 zFKhfvYr*uH@@ZjC&tf+ZQGMMCf?V zRQQc^yvERS#$9GsRZ{I%aXvOo!DgZsnDj)DMc*wUA(l=^~6aA-(}OYWh~$l^N} z(E8AO+`l`(W}oX~My{#?O}r`97aPQ!35fv~5?|@(SNRZZTlXYf1Zsw|21)`OptOBc z{RQM`_)`1UPPrpIE8224evca4p$fV@-R>tpcbv9ybJBLJ5rm()0l}u3mzSavuq|k6 zo11NgI-}QGolrthQ4dd)v652t`Oeq=EJB+c%Hi57bG9n;9C06@vW@wPUC!^>yH8tjtX807o3`t^$R-?E#)}_N^0S%=)tA3Z}1# zOZ;Y%RI`!3`}fwRGSI%Mu?W=JUX#gEV@FMi$ajtkO4QzPDkF^I1g4^j7k$^&NFy?b zX>vO~Uz_~C-yFZv<4c>aRwdz2Yz zRKjcjg_U|d8&l@vQ)iFD^vu=~cM#E?!5?&OQQJm>( z5V7gfe^5`nIGpVjlc*IaKo0g40f0y>f}8y#{$dfC$!gt6U8-&W>j)}W_AmYnLvk-i z4(~gYE9wUaX}}KoaeJf0J1c?(i^&F+UYQ|#2PIV;>$DTgRGxa^VIdI4bJZX#y+EO@ z-fwEtP}qz~e1cNBb8L1oJi`g9iUP2N1LlKbV?BGU()iwOL3!-UzIV~-yzHDdS6ktAe$h&qIwy&7%G(_#|8B2xkYotAX(P;JDW(k1z>(_Y zn7cAIse9tg0g(Q&^*u`M#-332F8u~)F^p4CON?}L|I#8&i!fy@-MEgn_ZFoMd-fD? z6B$E=rs+&jj0b|1(QnL(;r|r9;S;yUQ@gy!ed4av&C0c2O|Hmfe)_(_iV*^@bo;{c zX}L3?Owrw%P)LWM!wu*uEAsW?b9ERBL8S&IOD(tw%nhn9aQ9m7ww~%quBYa`&z+k{ zZrXE|DIB&HwpgvkReGqcI%?czbmhVc#g5=q$96#9AoA}*rwzEYziK+OOBqD+^FZ^b zB0&;a>hXB#kHg*t+j28E8@uc(9T2(v#An6lR(9Cy-_P3>)QvPwPHooiN%t6g;-*B# zrGH47Q9>;M$#BQ>2~FM0nje18$ds6;-A34Q3fi^Z6y6N_^tuw;ya^O#9kUH~BK%++ z>bzN>Y=TXB=%z14aiIvZ3K&zWC;r7qNN>L1IOH7xMWb^1Pfk99B&&I6pn_01w`Zg` zU5i2&Yp?y`{w=XjL^>fB4HuZ*_`tXa^?@)!f7LaUmP&gqlT+_iccE}#e*cv|!z0Rv zzU*A*%cam~a{fKSW55PlDM0J?UKS*1lfKj?YVv=x0~Tn?PyyPr&GnPLdydFr!GScT~D@E2*;1{P5VT?;5gve+Ej*wBq#p}Mo|F=P4EpK67B8*aYS2!*a2m@ZXP{^HpeKI@xo!p%lI^$omNnO`d<#X*j#tBq zM||lf)x(qRF6W7pSH{dE)NHsT+_upCvGqtjOrZ@eDFIwqIER+MX{28(kcyC4cw@;w z2H_H6?W+86$sQeR?@r3j$BbL_`Gk0~^yumxLs#0NrQ8gI)H|-p!jCT*TM`cLUNu^y z{!S^!)sBB3N9|oUn*q z{|GO~GP%-dx)w>}_l!u<01pI4k>z6gl~k@e0032hYt5D_oa;8!Wn38WIVBLGxHv32 zC!oMVfOb;@fj5!ojp<0W<+eaALSla0VN2i`XSK_=o10HzQ*G0QI^dA*;3JFs^Hk(J zpy4B9zBiWnf|e2_9OV?3BM!T0jYyIjQYMlVbNOqw9Z#7kMm63=v|%$f2@MTxtT0jk z5}n)%tLTwqA;98%vLBYAtls(kGT|-zC}42Dj&tr6(=;oRg%{MRih=9}CCwgO=4$}X7t2J| zW%5mD3qvXy>E}*Uw$VjFd473~&}KG7vn9d@F6qskt%-)^(oaEhbe2|mMS7#r$tj}b zcKH3u!LIp8Nocj8N&Zw28t;9+S%Q{T=8&-eqiKc#a%RAOHGS{fKk%<96u$q|gR3|3YhE(4SE~+ ze_}tU(pB&2bm_^~{@WO2=z#9C6rr*}F_|&Ts+EeRck)>mVv6lj*_*C*T_7hrE#&Si zuK1nhr}NgaHD)!++05OU2m|`y_0$5O1Egv7Gk}N?m<_OOK{67N0MjVxxl|0y<}v^P znKXmSxg|kpa5!E0`z*~P*wTW#V z!6<#CkHi>n?5-@ZaqvnnQ|>;}jdlA!^5|raULln&L)@kq#`efFM~I3^his5ET{717 z683ZM9gDp$IZToe)SM5WDYrXSz3kA5YnvLP9)Q4N)bZ3uUva%v|nSK+}efHTOs#uiuLG5kB6-W zLza6q!l#vP`OmPk8BssGHvntz;~RXM#s*hUGGyk*7e`Vr2|&K-*hLdG%{3R_`@k!;I~}~LPQbLfKYY8T)5EN;_xbC ziAofa)e*0jG=5s1wqRWr1awAj8BM_yrBzy==)85X8)a9Xz?+xgo~=Fu?8-W4-LO`B zgtoj#Q8ZnH=oZJ@mhaog$E0zCO`VeAnJ(+%s|DLu+%adc%^JKk((@vRIF1Q!o~(SQ zEP{zBh-QwGvMU(hS77PgxhN?z44RV78F4PSk=K^}xRpZB>(Yg2+yCm?`+608J06U? zOGbU44;;SZkDZ4PZ_3r=qABR~GoTRFBT^g(tHNJlxP-tzpmMq>8r+sb)@PPU-bZ`E98Z(7~nK=3`E&!uv&Q86#*abo@s&o z9yY@(CS!el-~k_=g5Ju8Yr#fJD9>NAtTowDP(yj*NdC^p%b`>h^ESj2>+yI)idGPf zG{VbNLpNisi;LX+e_%0jFrn5Mlgj| z;-RY)x23EFCHhTY;@*FOk)yxWmdN@YBNmzseaFSp8c?B$NRRakuSCx!%W9?3lK`)sJGZq@GtO4qxeS=#?B_fjvPr